├── .catkin_workspace ├── LICENSE ├── README.md └── src ├── CMakeLists.txt ├── mpc_controller ├── CMakeLists.txt ├── README.md ├── cmake_modules │ └── FindCASADI.cmake ├── include │ ├── mpc │ │ └── mpc.h │ └── utils │ │ ├── dptraj.hpp │ │ ├── minco_traj.hpp │ │ └── traj_anal.hpp ├── launch │ └── test_mpc.launch ├── msg │ ├── DPtrajContainer.msg │ ├── PolyTraj.msg │ ├── PolyTrajAC.msg │ ├── SE2Traj.msg │ ├── SinglePoly.msg │ ├── SinglePolyAC.msg │ └── desiredState.msg ├── package.xml ├── params │ └── controller.yaml ├── rviz │ └── test.rviz └── src │ ├── mpc.cpp │ └── mpc_node.cpp ├── plan_debug.launch ├── planner ├── arc_planner │ ├── path_search │ │ ├── CMakeLists.txt │ │ ├── include │ │ │ └── path_searching │ │ │ │ ├── astar.h │ │ │ │ ├── kino_astar.h │ │ │ │ └── kino_model.hpp │ │ ├── package.xml │ │ └── src │ │ │ ├── astar.cpp │ │ │ └── kino_astar.cpp │ └── plan_manage │ │ ├── CMakeLists.txt │ │ ├── config │ │ └── planning.yaml │ │ ├── include │ │ ├── arcPlan │ │ │ ├── Polytraj.hpp │ │ │ ├── Trajopt_alm.hpp │ │ │ ├── geoutils2d.hpp │ │ │ ├── lbfgs.hpp │ │ │ ├── quickhull.hpp │ │ │ ├── root_finder.hpp │ │ │ └── sdlp.hpp │ │ └── plan_manage │ │ │ ├── plan_manage.h │ │ │ └── replan_fsm.h │ │ ├── launch │ │ ├── advanced_param.xml │ │ ├── multi_sim.launch │ │ ├── multi_sim.rviz │ │ └── write.py │ │ ├── package.xml │ │ ├── rviz │ │ └── default.rviz │ │ └── src │ │ ├── plan_manage.cpp │ │ ├── plan_node.cpp │ │ ├── replan_fsm.cpp │ │ └── test.cpp ├── decomp_rviz_plugin │ ├── DecompROS │ │ ├── LICENSE │ │ ├── decomp_ros_msgs │ │ │ ├── CMakeLists.txt │ │ │ ├── msg │ │ │ │ ├── Ellipsoid.msg │ │ │ │ ├── EllipsoidArray.msg │ │ │ │ ├── Polyhedron.msg │ │ │ │ └── PolyhedronArray.msg │ │ │ └── package.xml │ │ └── decomp_ros_utils │ │ │ ├── CMakeLists.txt │ │ │ ├── icons │ │ │ └── classes │ │ │ │ ├── EllipsoidArray.png │ │ │ │ └── PolyhedronArray.png │ │ │ ├── include │ │ │ ├── decomp_basis │ │ │ │ ├── data_type.h │ │ │ │ └── data_utils.h │ │ │ ├── decomp_geometry │ │ │ │ ├── ellipsoid.h │ │ │ │ ├── geometric_utils.h │ │ │ │ └── polyhedron.h │ │ │ ├── decomp_ros_utils │ │ │ │ └── data_ros_utils.h │ │ │ └── decomp_util │ │ │ │ ├── decomp_base.h │ │ │ │ ├── ellipsoid_decomp.h │ │ │ │ ├── iterative_decomp.h │ │ │ │ ├── line_segment.h │ │ │ │ └── seed_decomp.h │ │ │ ├── package.xml │ │ │ ├── plugin_description.xml │ │ │ └── src │ │ │ ├── bound_visual.cpp │ │ │ ├── bound_visual.h │ │ │ ├── ellipsoid_array_display.cpp │ │ │ ├── ellipsoid_array_display.h │ │ │ ├── ellipsoid_array_visual.cpp │ │ │ ├── ellipsoid_array_visual.h │ │ │ ├── mesh_visual.cpp │ │ │ ├── mesh_visual.h │ │ │ ├── polyhedron_array_display.cpp │ │ │ ├── polyhedron_array_display.h │ │ │ ├── vector_visual.cpp │ │ │ └── vector_visual.h │ ├── catkin_simple │ │ ├── CMakeLists.txt │ │ ├── cmake │ │ │ └── catkin_simple-extras.cmake.em │ │ ├── package.xml │ │ └── test │ │ │ └── scenarios │ │ │ └── hello_world │ │ │ ├── bar │ │ │ ├── include │ │ │ │ └── bar │ │ │ │ │ └── hello.h │ │ │ ├── msg │ │ │ │ └── HeaderString.msg │ │ │ ├── package.xml │ │ │ └── src │ │ │ │ └── hello.cpp │ │ │ ├── baz │ │ │ ├── include │ │ │ │ └── baz │ │ │ │ │ └── world.h │ │ │ └── package.xml │ │ │ └── foo │ │ │ ├── package.xml │ │ │ └── src │ │ │ └── main.cpp │ └── tools │ │ ├── CMakeLists.txt │ │ ├── include │ │ └── tools │ │ │ ├── config.hpp │ │ │ ├── gridmap.hpp │ │ │ ├── tic_toc.hpp │ │ │ └── visualization.hpp │ │ └── package.xml ├── grad_test │ ├── CMakeLists.txt │ ├── latGrad_test.cpp │ ├── lonGrad_test.cpp │ └── velGrad_test.cpp └── traj_planner │ └── launch │ └── multi_tail.launch ├── simulator ├── fake_ugv │ ├── CMakeLists.txt │ ├── maps │ │ ├── RockyDesertMesh.pcd │ │ └── processed_map_1.pcd │ ├── meshes │ │ ├── car.dae │ │ └── diff.dae │ ├── package.xml │ ├── scripts │ │ └── keyboard_ctrl.py │ └── src │ │ └── poscmd_2_odom.cpp ├── laser_simulator │ ├── CMakeLists.txt │ ├── README.md │ ├── launch │ │ ├── default.rviz │ │ ├── laser_sim.launch │ │ ├── params.yaml │ │ ├── play_bag.launch │ │ ├── rviz.launch │ │ ├── rviz_sim.rviz │ │ ├── simulator.launch │ │ └── test_0.launch │ ├── misc │ │ ├── demo.gif │ │ └── demo.png │ ├── package.xml │ └── src │ │ ├── .clang-format │ │ ├── laser_sim_node.cpp │ │ └── transmit_odom.cpp └── map_generator │ ├── CMakeLists.txt │ ├── package.xml │ └── src │ ├── map_generator_easy.py │ └── random_forest_sensing.cpp ├── tank_sdk ├── CMakeLists.txt ├── config │ └── config.yaml ├── include │ ├── serial.h │ └── tank_send.h ├── launch │ ├── tank_acc_test.launch │ ├── tank_sdk.launch │ └── tank_udp.launch ├── meshes │ └── differential_model.STL ├── msg │ ├── TankCMD.msg │ └── TankFeedback.msg ├── package.xml ├── params │ ├── simulator.yaml │ └── udp.yaml └── src │ ├── acc_test_node.cpp │ ├── kinematics_sim.cpp │ ├── main.cpp │ ├── serial.cpp │ ├── tank_send.cpp │ └── udp_send.cpp ├── tank_slam ├── FAST_LIO │ ├── Log │ │ ├── dbg.txt │ │ ├── imu.txt │ │ ├── mat_out.txt │ │ ├── mat_pre.txt │ │ └── pos_log.txt │ └── PCD │ │ ├── new.pcd │ │ └── scans.pcd ├── ekf_quat_pose │ ├── CMakeLists.txt │ ├── cmake │ │ ├── FindEigen3.cmake │ │ ├── FindGLIB2.cmake │ │ └── FindGTHREAD2.cmake │ ├── config │ │ ├── TA-camera.yml │ │ ├── ekf_pose.rviz │ │ └── tag_1.yml │ ├── include │ │ ├── conversion.h │ │ └── ekf.h │ ├── launch │ │ ├── PX4_vio_drone.yaml │ │ ├── ekf.rviz │ │ └── ekf_quat_lidar.launch │ ├── package.xml │ └── src │ │ ├── conversion.cpp │ │ ├── ekf_node_vio_timesync_with_acc_pub.cpp │ │ └── imu_add_noise.cpp ├── livox_ros_driver │ ├── .gitignore │ ├── LICENSE.txt │ ├── README.md │ ├── README_CN.md │ ├── images │ │ └── broadcast_code.png │ └── livox_ros_driver │ │ ├── CMakeLists.txt │ │ ├── cmake │ │ └── version.cmake │ │ ├── common │ │ ├── FastCRC │ │ │ ├── FastCRC.h │ │ │ ├── FastCRC_tables.hpp │ │ │ ├── FastCRCsw.cpp │ │ │ ├── LICENSE.md │ │ │ └── README.md │ │ ├── comm │ │ │ ├── comm_device.h │ │ │ ├── comm_protocol.cpp │ │ │ ├── comm_protocol.h │ │ │ ├── gps_protocol.cpp │ │ │ ├── gps_protocol.h │ │ │ ├── protocol.h │ │ │ ├── sdk_protocol.cpp │ │ │ └── sdk_protocol.h │ │ ├── rapidjson │ │ │ ├── allocators.h │ │ │ ├── cursorstreamwrapper.h │ │ │ ├── document.h │ │ │ ├── encodedstream.h │ │ │ ├── encodings.h │ │ │ ├── error │ │ │ │ ├── en.h │ │ │ │ └── error.h │ │ │ ├── filereadstream.h │ │ │ ├── filewritestream.h │ │ │ ├── fwd.h │ │ │ ├── internal │ │ │ │ ├── biginteger.h │ │ │ │ ├── clzll.h │ │ │ │ ├── diyfp.h │ │ │ │ ├── dtoa.h │ │ │ │ ├── ieee754.h │ │ │ │ ├── itoa.h │ │ │ │ ├── meta.h │ │ │ │ ├── pow10.h │ │ │ │ ├── regex.h │ │ │ │ ├── stack.h │ │ │ │ ├── strfunc.h │ │ │ │ ├── strtod.h │ │ │ │ └── swap.h │ │ │ ├── istreamwrapper.h │ │ │ ├── memorybuffer.h │ │ │ ├── memorystream.h │ │ │ ├── msinttypes │ │ │ │ ├── inttypes.h │ │ │ │ └── stdint.h │ │ │ ├── ostreamwrapper.h │ │ │ ├── pointer.h │ │ │ ├── prettywriter.h │ │ │ ├── rapidjson.h │ │ │ ├── reader.h │ │ │ ├── schema.h │ │ │ ├── stream.h │ │ │ ├── stringbuffer.h │ │ │ └── writer.h │ │ └── rapidxml │ │ │ ├── rapidxml.hpp │ │ │ ├── rapidxml_iterators.hpp │ │ │ ├── rapidxml_print.hpp │ │ │ └── rapidxml_utils.hpp │ │ ├── config │ │ ├── display_hub_points.rviz │ │ ├── display_lidar_points.rviz │ │ ├── livox_hub_config.json │ │ └── livox_lidar_config.json │ │ ├── launch │ │ ├── livox_hub.launch │ │ ├── livox_hub_msg.launch │ │ ├── livox_hub_rviz.launch │ │ ├── livox_lidar.launch │ │ ├── livox_lidar_msg.launch │ │ ├── livox_lidar_rviz.launch │ │ ├── livox_template.launch │ │ ├── lvx_to_rosbag.launch │ │ └── lvx_to_rosbag_rviz.launch │ │ ├── livox_ros_driver │ │ ├── include │ │ │ └── livox_ros_driver.h │ │ ├── lddc.cpp │ │ ├── lddc.h │ │ ├── ldq.cpp │ │ ├── ldq.h │ │ ├── lds.cpp │ │ ├── lds.h │ │ ├── lds_hub.cpp │ │ ├── lds_hub.h │ │ ├── lds_lidar.cpp │ │ ├── lds_lidar.h │ │ ├── lds_lvx.cpp │ │ ├── lds_lvx.h │ │ ├── livox_ros_driver.cpp │ │ ├── lvx_file.cpp │ │ └── lvx_file.h │ │ ├── msg │ │ ├── CustomMsg.msg │ │ └── CustomPoint.msg │ │ ├── package.xml │ │ └── timesync │ │ ├── timesync.cpp │ │ ├── timesync.h │ │ └── user_uart │ │ ├── user_uart.cpp │ │ └── user_uart.h ├── livox_ros_driver2 │ ├── .gitignore │ ├── 3rdparty │ │ └── rapidjson │ │ │ ├── allocators.h │ │ │ ├── cursorstreamwrapper.h │ │ │ ├── document.h │ │ │ ├── encodedstream.h │ │ │ ├── encodings.h │ │ │ ├── error │ │ │ ├── en.h │ │ │ └── error.h │ │ │ ├── filereadstream.h │ │ │ ├── filewritestream.h │ │ │ ├── fwd.h │ │ │ ├── internal │ │ │ ├── biginteger.h │ │ │ ├── clzll.h │ │ │ ├── diyfp.h │ │ │ ├── dtoa.h │ │ │ ├── ieee754.h │ │ │ ├── itoa.h │ │ │ ├── meta.h │ │ │ ├── pow10.h │ │ │ ├── regex.h │ │ │ ├── stack.h │ │ │ ├── strfunc.h │ │ │ ├── strtod.h │ │ │ └── swap.h │ │ │ ├── istreamwrapper.h │ │ │ ├── license.txt │ │ │ ├── memorybuffer.h │ │ │ ├── memorystream.h │ │ │ ├── msinttypes │ │ │ ├── inttypes.h │ │ │ └── stdint.h │ │ │ ├── ostreamwrapper.h │ │ │ ├── pointer.h │ │ │ ├── prettywriter.h │ │ │ ├── rapidjson.h │ │ │ ├── reader.h │ │ │ ├── schema.h │ │ │ ├── stream.h │ │ │ ├── stringbuffer.h │ │ │ └── writer.h │ ├── CHANGELOG.md │ ├── CMakeLists.txt │ ├── LICENSE.txt │ ├── README.md │ ├── build.sh │ ├── cmake │ │ └── version.cmake │ ├── config │ │ ├── HAP_config.json │ │ ├── MID360_config.json │ │ ├── display_point_cloud_ROS1.rviz │ │ ├── display_point_cloud_ROS2.rviz │ │ └── mixed_HAP_MID360_config.json │ ├── launch_ROS1 │ │ ├── msg_HAP.launch │ │ ├── msg_MID360.launch │ │ ├── msg_mixed.launch │ │ ├── rviz_HAP.launch │ │ ├── rviz_MID360.launch │ │ └── rviz_mixed.launch │ ├── launch_ROS2 │ │ ├── msg_HAP_launch.py │ │ ├── msg_MID360_launch.py │ │ ├── rviz_HAP_launch.py │ │ ├── rviz_MID360_launch.py │ │ └── rviz_mixed.py │ ├── msg │ │ ├── CustomMsg.msg │ │ └── CustomPoint.msg │ ├── package.xml │ └── src │ │ ├── call_back │ │ ├── lidar_common_callback.cpp │ │ ├── lidar_common_callback.h │ │ ├── livox_lidar_callback.cpp │ │ └── livox_lidar_callback.h │ │ ├── comm │ │ ├── cache_index.cpp │ │ ├── cache_index.h │ │ ├── comm.cpp │ │ ├── comm.h │ │ ├── ldq.cpp │ │ ├── ldq.h │ │ ├── lidar_imu_data_queue.cpp │ │ ├── lidar_imu_data_queue.h │ │ ├── pub_handler.cpp │ │ ├── pub_handler.h │ │ ├── semaphore.cpp │ │ └── semaphore.h │ │ ├── driver_node.cpp │ │ ├── driver_node.h │ │ ├── include │ │ ├── livox_ros_driver2.h │ │ ├── ros1_headers.h │ │ ├── ros2_headers.h │ │ └── ros_headers.h │ │ ├── lddc.cpp │ │ ├── lddc.h │ │ ├── lds.cpp │ │ ├── lds.h │ │ ├── lds_lidar.cpp │ │ ├── lds_lidar.h │ │ ├── livox_ros_driver2.cpp │ │ ├── package_ROS1.xml │ │ └── parse_cfg_file │ │ ├── parse_cfg_file.cpp │ │ ├── parse_cfg_file.h │ │ ├── parse_livox_lidar_cfg.cpp │ │ └── parse_livox_lidar_cfg.h └── readme ├── uneven_mapping.zip └── uneven_mapping ├── se2_grid ├── se2_grid_core │ ├── CMakeLists.txt │ ├── cmake │ │ └── se2_grid_core-extras.cmake │ ├── include │ │ └── se2_grid_core │ │ │ ├── SE2Grid.hpp │ │ │ ├── eigen_plugins │ │ │ ├── DenseBasePlugin.hpp │ │ │ ├── Functors.hpp │ │ │ └── FunctorsPlugin.hpp │ │ │ ├── iterators │ │ │ ├── CircleIterator.hpp │ │ │ ├── EllipseIterator.hpp │ │ │ ├── SE2GridIterator.hpp │ │ │ ├── SpiralIterator.hpp │ │ │ ├── SubmapIterator.hpp │ │ │ └── iterators.hpp │ │ │ └── utils │ │ │ ├── Polygon.hpp │ │ │ └── untils.hpp │ ├── package.xml │ └── src │ │ └── SE2Grid.cpp ├── se2_grid_msgs │ ├── CMakeLists.txt │ ├── msg │ │ ├── SE2Grid.msg │ │ └── SE2GridInfo.msg │ └── package.xml ├── se2_grid_ros │ ├── CMakeLists.txt │ ├── include │ │ └── se2_grid_ros │ │ │ ├── SE2GridMsgHelpers.hpp │ │ │ ├── SE2GridRosConverter.hpp │ │ │ ├── message_traits.hpp │ │ │ └── se2_grid_ros.hpp │ ├── package.xml │ └── src │ │ ├── SE2GridMsgHelpers.cpp │ │ └── SE2GridRosConverter.cpp ├── se2_grid_rviz_plugin │ ├── CMakeLists.txt │ ├── icons │ │ └── classes │ │ │ └── SE2Grid.png │ ├── include │ │ └── se2_grid_rviz_plugin │ │ │ ├── SE2GridColorMaps.hpp │ │ │ ├── SE2GridDisplay.hpp │ │ │ ├── SE2GridVisual.hpp │ │ │ └── modified │ │ │ ├── frame_manager.h │ │ │ └── message_filter_display.h │ ├── package.xml │ ├── plugin_description.xml │ └── src │ │ ├── SE2GridDisplay.cpp │ │ └── SE2GridVisual.cpp └── se2_grid_tests │ ├── CMakeLists.txt │ ├── launch │ ├── interpolation_test.launch │ ├── iterators_test.launch │ └── move_test.launch │ ├── package.xml │ ├── rviz │ └── test.rviz │ └── src │ ├── interpolation_test_node.cpp │ ├── iterators_test_node.cpp │ └── move_test_node.cpp └── terrain_analyzer ├── CMakeLists.txt ├── include └── terrain_analyzer │ ├── TerrainAnalyzer.hpp │ ├── post_processors │ ├── CurvatureComputer.hpp │ ├── InpaintProcessor.hpp │ ├── MathProcessor.hpp │ ├── MeanInRadiusFilter.hpp │ ├── NormalComputer.hpp │ ├── PostProcessorBase.hpp │ ├── SignedDistanceField.hpp │ └── post_processors.hpp │ ├── sensor_processors │ ├── OusterLidarProcessor.hpp │ ├── SensorProcessorVirtual.hpp │ └── sensor_processors.hpp │ └── utils │ ├── EigenLab.hpp │ ├── WeightedEmpiricalCumulativeDistributionFunction.hpp │ └── utils.hpp ├── launch └── terrain_analyzer.launch ├── package.xml ├── params ├── elevation_map.yaml └── elevation_map_gpu.yaml ├── post_processors.xml └── src ├── R2_terrain ├── TerrainAnalyzerR2.cpp └── TerrainBankR2.cu ├── TerrainAnalyzer.cpp ├── TerrainBank.cu ├── TerrainBank_huawei.cu ├── helper_math.h ├── post_processors.cpp └── terrain_analyzer_node.cpp /.catkin_workspace: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/.catkin_workspace -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/LICENSE -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/README.md -------------------------------------------------------------------------------- /src/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | /opt/ros/noetic/share/catkin/cmake/toplevel.cmake -------------------------------------------------------------------------------- /src/mpc_controller/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/mpc_controller/CMakeLists.txt -------------------------------------------------------------------------------- /src/mpc_controller/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/mpc_controller/README.md -------------------------------------------------------------------------------- /src/mpc_controller/cmake_modules/FindCASADI.cmake: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/mpc_controller/cmake_modules/FindCASADI.cmake -------------------------------------------------------------------------------- /src/mpc_controller/include/mpc/mpc.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/mpc_controller/include/mpc/mpc.h -------------------------------------------------------------------------------- /src/mpc_controller/include/utils/dptraj.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/mpc_controller/include/utils/dptraj.hpp -------------------------------------------------------------------------------- /src/mpc_controller/include/utils/minco_traj.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/mpc_controller/include/utils/minco_traj.hpp -------------------------------------------------------------------------------- /src/mpc_controller/include/utils/traj_anal.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/mpc_controller/include/utils/traj_anal.hpp -------------------------------------------------------------------------------- /src/mpc_controller/launch/test_mpc.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/mpc_controller/launch/test_mpc.launch -------------------------------------------------------------------------------- /src/mpc_controller/msg/DPtrajContainer.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/mpc_controller/msg/DPtrajContainer.msg -------------------------------------------------------------------------------- /src/mpc_controller/msg/PolyTraj.msg: -------------------------------------------------------------------------------- 1 | time start_time 2 | 3 | mpc_controller/SinglePoly[] trajs -------------------------------------------------------------------------------- /src/mpc_controller/msg/PolyTrajAC.msg: -------------------------------------------------------------------------------- 1 | mpc_controller/SinglePolyAC[] trajs -------------------------------------------------------------------------------- /src/mpc_controller/msg/SE2Traj.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/mpc_controller/msg/SE2Traj.msg -------------------------------------------------------------------------------- /src/mpc_controller/msg/SinglePoly.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/mpc_controller/msg/SinglePoly.msg -------------------------------------------------------------------------------- /src/mpc_controller/msg/SinglePolyAC.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/mpc_controller/msg/SinglePolyAC.msg -------------------------------------------------------------------------------- /src/mpc_controller/msg/desiredState.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/mpc_controller/msg/desiredState.msg -------------------------------------------------------------------------------- /src/mpc_controller/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/mpc_controller/package.xml -------------------------------------------------------------------------------- /src/mpc_controller/params/controller.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/mpc_controller/params/controller.yaml -------------------------------------------------------------------------------- /src/mpc_controller/rviz/test.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/mpc_controller/rviz/test.rviz -------------------------------------------------------------------------------- /src/mpc_controller/src/mpc.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/mpc_controller/src/mpc.cpp -------------------------------------------------------------------------------- /src/mpc_controller/src/mpc_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/mpc_controller/src/mpc_node.cpp -------------------------------------------------------------------------------- /src/plan_debug.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/plan_debug.launch -------------------------------------------------------------------------------- /src/planner/arc_planner/path_search/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/path_search/CMakeLists.txt -------------------------------------------------------------------------------- /src/planner/arc_planner/path_search/include/path_searching/astar.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/path_search/include/path_searching/astar.h -------------------------------------------------------------------------------- /src/planner/arc_planner/path_search/include/path_searching/kino_astar.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/path_search/include/path_searching/kino_astar.h -------------------------------------------------------------------------------- /src/planner/arc_planner/path_search/include/path_searching/kino_model.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/path_search/include/path_searching/kino_model.hpp -------------------------------------------------------------------------------- /src/planner/arc_planner/path_search/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/path_search/package.xml -------------------------------------------------------------------------------- /src/planner/arc_planner/path_search/src/astar.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/path_search/src/astar.cpp -------------------------------------------------------------------------------- /src/planner/arc_planner/path_search/src/kino_astar.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/path_search/src/kino_astar.cpp -------------------------------------------------------------------------------- /src/planner/arc_planner/plan_manage/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/plan_manage/CMakeLists.txt -------------------------------------------------------------------------------- /src/planner/arc_planner/plan_manage/config/planning.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/plan_manage/config/planning.yaml -------------------------------------------------------------------------------- /src/planner/arc_planner/plan_manage/include/arcPlan/Polytraj.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/plan_manage/include/arcPlan/Polytraj.hpp -------------------------------------------------------------------------------- /src/planner/arc_planner/plan_manage/include/arcPlan/Trajopt_alm.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/plan_manage/include/arcPlan/Trajopt_alm.hpp -------------------------------------------------------------------------------- /src/planner/arc_planner/plan_manage/include/arcPlan/geoutils2d.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/plan_manage/include/arcPlan/geoutils2d.hpp -------------------------------------------------------------------------------- /src/planner/arc_planner/plan_manage/include/arcPlan/lbfgs.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/plan_manage/include/arcPlan/lbfgs.hpp -------------------------------------------------------------------------------- /src/planner/arc_planner/plan_manage/include/arcPlan/quickhull.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/plan_manage/include/arcPlan/quickhull.hpp -------------------------------------------------------------------------------- /src/planner/arc_planner/plan_manage/include/arcPlan/root_finder.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/plan_manage/include/arcPlan/root_finder.hpp -------------------------------------------------------------------------------- /src/planner/arc_planner/plan_manage/include/arcPlan/sdlp.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/plan_manage/include/arcPlan/sdlp.hpp -------------------------------------------------------------------------------- /src/planner/arc_planner/plan_manage/include/plan_manage/plan_manage.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/plan_manage/include/plan_manage/plan_manage.h -------------------------------------------------------------------------------- /src/planner/arc_planner/plan_manage/include/plan_manage/replan_fsm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/plan_manage/include/plan_manage/replan_fsm.h -------------------------------------------------------------------------------- /src/planner/arc_planner/plan_manage/launch/advanced_param.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/plan_manage/launch/advanced_param.xml -------------------------------------------------------------------------------- /src/planner/arc_planner/plan_manage/launch/multi_sim.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/plan_manage/launch/multi_sim.launch -------------------------------------------------------------------------------- /src/planner/arc_planner/plan_manage/launch/multi_sim.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/plan_manage/launch/multi_sim.rviz -------------------------------------------------------------------------------- /src/planner/arc_planner/plan_manage/launch/write.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/plan_manage/launch/write.py -------------------------------------------------------------------------------- /src/planner/arc_planner/plan_manage/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/plan_manage/package.xml -------------------------------------------------------------------------------- /src/planner/arc_planner/plan_manage/rviz/default.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/plan_manage/rviz/default.rviz -------------------------------------------------------------------------------- /src/planner/arc_planner/plan_manage/src/plan_manage.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/plan_manage/src/plan_manage.cpp -------------------------------------------------------------------------------- /src/planner/arc_planner/plan_manage/src/plan_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/plan_manage/src/plan_node.cpp -------------------------------------------------------------------------------- /src/planner/arc_planner/plan_manage/src/replan_fsm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/plan_manage/src/replan_fsm.cpp -------------------------------------------------------------------------------- /src/planner/arc_planner/plan_manage/src/test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/arc_planner/plan_manage/src/test.cpp -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/LICENSE -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_msgs/msg/Ellipsoid.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_msgs/msg/Ellipsoid.msg -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_msgs/msg/EllipsoidArray.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_msgs/msg/EllipsoidArray.msg -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_msgs/msg/Polyhedron.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_msgs/msg/Polyhedron.msg -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_msgs/msg/PolyhedronArray.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_msgs/msg/PolyhedronArray.msg -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_msgs/package.xml -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/CMakeLists.txt -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/icons/classes/EllipsoidArray.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/icons/classes/EllipsoidArray.png -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/icons/classes/PolyhedronArray.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/icons/classes/PolyhedronArray.png -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_basis/data_type.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_basis/data_type.h -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_basis/data_utils.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_basis/data_utils.h -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_geometry/ellipsoid.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_geometry/ellipsoid.h -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_geometry/geometric_utils.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_geometry/geometric_utils.h -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_geometry/polyhedron.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_geometry/polyhedron.h -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_ros_utils/data_ros_utils.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_ros_utils/data_ros_utils.h -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_util/decomp_base.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_util/decomp_base.h -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_util/ellipsoid_decomp.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_util/ellipsoid_decomp.h -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_util/iterative_decomp.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_util/iterative_decomp.h -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_util/line_segment.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_util/line_segment.h -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_util/seed_decomp.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/include/decomp_util/seed_decomp.h -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/package.xml -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/plugin_description.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/plugin_description.xml -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/bound_visual.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/bound_visual.cpp -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/bound_visual.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/bound_visual.h -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/ellipsoid_array_display.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/ellipsoid_array_display.cpp -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/ellipsoid_array_display.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/ellipsoid_array_display.h -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/ellipsoid_array_visual.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/ellipsoid_array_visual.cpp -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/ellipsoid_array_visual.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/ellipsoid_array_visual.h -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/mesh_visual.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/mesh_visual.cpp -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/mesh_visual.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/mesh_visual.h -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/polyhedron_array_display.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/polyhedron_array_display.cpp -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/polyhedron_array_display.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/polyhedron_array_display.h -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/vector_visual.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/vector_visual.cpp -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/vector_visual.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/DecompROS/decomp_ros_utils/src/vector_visual.h -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/catkin_simple/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/catkin_simple/CMakeLists.txt -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/catkin_simple/cmake/catkin_simple-extras.cmake.em: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/catkin_simple/cmake/catkin_simple-extras.cmake.em -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/catkin_simple/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/catkin_simple/package.xml -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/catkin_simple/test/scenarios/hello_world/bar/include/bar/hello.h: -------------------------------------------------------------------------------- 1 | void hello(); 2 | -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/catkin_simple/test/scenarios/hello_world/bar/msg/HeaderString.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/catkin_simple/test/scenarios/hello_world/bar/msg/HeaderString.msg -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/catkin_simple/test/scenarios/hello_world/bar/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/catkin_simple/test/scenarios/hello_world/bar/package.xml -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/catkin_simple/test/scenarios/hello_world/bar/src/hello.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/catkin_simple/test/scenarios/hello_world/bar/src/hello.cpp -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/catkin_simple/test/scenarios/hello_world/baz/include/baz/world.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/catkin_simple/test/scenarios/hello_world/baz/include/baz/world.h -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/catkin_simple/test/scenarios/hello_world/baz/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/catkin_simple/test/scenarios/hello_world/baz/package.xml -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/catkin_simple/test/scenarios/hello_world/foo/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/catkin_simple/test/scenarios/hello_world/foo/package.xml -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/catkin_simple/test/scenarios/hello_world/foo/src/main.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/catkin_simple/test/scenarios/hello_world/foo/src/main.cpp -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/tools/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/tools/CMakeLists.txt -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/tools/include/tools/config.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/tools/include/tools/config.hpp -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/tools/include/tools/gridmap.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/tools/include/tools/gridmap.hpp -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/tools/include/tools/tic_toc.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/tools/include/tools/tic_toc.hpp -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/tools/include/tools/visualization.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/tools/include/tools/visualization.hpp -------------------------------------------------------------------------------- /src/planner/decomp_rviz_plugin/tools/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/decomp_rviz_plugin/tools/package.xml -------------------------------------------------------------------------------- /src/planner/grad_test/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/grad_test/CMakeLists.txt -------------------------------------------------------------------------------- /src/planner/grad_test/latGrad_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/grad_test/latGrad_test.cpp -------------------------------------------------------------------------------- /src/planner/grad_test/lonGrad_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/grad_test/lonGrad_test.cpp -------------------------------------------------------------------------------- /src/planner/grad_test/velGrad_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/grad_test/velGrad_test.cpp -------------------------------------------------------------------------------- /src/planner/traj_planner/launch/multi_tail.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/planner/traj_planner/launch/multi_tail.launch -------------------------------------------------------------------------------- /src/simulator/fake_ugv/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/fake_ugv/CMakeLists.txt -------------------------------------------------------------------------------- /src/simulator/fake_ugv/maps/RockyDesertMesh.pcd: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/fake_ugv/maps/RockyDesertMesh.pcd -------------------------------------------------------------------------------- /src/simulator/fake_ugv/maps/processed_map_1.pcd: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/fake_ugv/maps/processed_map_1.pcd -------------------------------------------------------------------------------- /src/simulator/fake_ugv/meshes/car.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/fake_ugv/meshes/car.dae -------------------------------------------------------------------------------- /src/simulator/fake_ugv/meshes/diff.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/fake_ugv/meshes/diff.dae -------------------------------------------------------------------------------- /src/simulator/fake_ugv/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/fake_ugv/package.xml -------------------------------------------------------------------------------- /src/simulator/fake_ugv/scripts/keyboard_ctrl.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/fake_ugv/scripts/keyboard_ctrl.py -------------------------------------------------------------------------------- /src/simulator/fake_ugv/src/poscmd_2_odom.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/fake_ugv/src/poscmd_2_odom.cpp -------------------------------------------------------------------------------- /src/simulator/laser_simulator/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/laser_simulator/CMakeLists.txt -------------------------------------------------------------------------------- /src/simulator/laser_simulator/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/laser_simulator/README.md -------------------------------------------------------------------------------- /src/simulator/laser_simulator/launch/default.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/laser_simulator/launch/default.rviz -------------------------------------------------------------------------------- /src/simulator/laser_simulator/launch/laser_sim.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/laser_simulator/launch/laser_sim.launch -------------------------------------------------------------------------------- /src/simulator/laser_simulator/launch/params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/laser_simulator/launch/params.yaml -------------------------------------------------------------------------------- /src/simulator/laser_simulator/launch/play_bag.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/laser_simulator/launch/play_bag.launch -------------------------------------------------------------------------------- /src/simulator/laser_simulator/launch/rviz.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/laser_simulator/launch/rviz.launch -------------------------------------------------------------------------------- /src/simulator/laser_simulator/launch/rviz_sim.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/laser_simulator/launch/rviz_sim.rviz -------------------------------------------------------------------------------- /src/simulator/laser_simulator/launch/simulator.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/laser_simulator/launch/simulator.launch -------------------------------------------------------------------------------- /src/simulator/laser_simulator/launch/test_0.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/laser_simulator/launch/test_0.launch -------------------------------------------------------------------------------- /src/simulator/laser_simulator/misc/demo.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/laser_simulator/misc/demo.gif -------------------------------------------------------------------------------- /src/simulator/laser_simulator/misc/demo.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/laser_simulator/misc/demo.png -------------------------------------------------------------------------------- /src/simulator/laser_simulator/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/laser_simulator/package.xml -------------------------------------------------------------------------------- /src/simulator/laser_simulator/src/.clang-format: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/laser_simulator/src/.clang-format -------------------------------------------------------------------------------- /src/simulator/laser_simulator/src/laser_sim_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/laser_simulator/src/laser_sim_node.cpp -------------------------------------------------------------------------------- /src/simulator/laser_simulator/src/transmit_odom.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/laser_simulator/src/transmit_odom.cpp -------------------------------------------------------------------------------- /src/simulator/map_generator/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/map_generator/CMakeLists.txt -------------------------------------------------------------------------------- /src/simulator/map_generator/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/map_generator/package.xml -------------------------------------------------------------------------------- /src/simulator/map_generator/src/map_generator_easy.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/map_generator/src/map_generator_easy.py -------------------------------------------------------------------------------- /src/simulator/map_generator/src/random_forest_sensing.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/simulator/map_generator/src/random_forest_sensing.cpp -------------------------------------------------------------------------------- /src/tank_sdk/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_sdk/CMakeLists.txt -------------------------------------------------------------------------------- /src/tank_sdk/config/config.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_sdk/config/config.yaml -------------------------------------------------------------------------------- /src/tank_sdk/include/serial.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_sdk/include/serial.h -------------------------------------------------------------------------------- /src/tank_sdk/include/tank_send.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_sdk/include/tank_send.h -------------------------------------------------------------------------------- /src/tank_sdk/launch/tank_acc_test.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_sdk/launch/tank_acc_test.launch -------------------------------------------------------------------------------- /src/tank_sdk/launch/tank_sdk.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_sdk/launch/tank_sdk.launch -------------------------------------------------------------------------------- /src/tank_sdk/launch/tank_udp.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_sdk/launch/tank_udp.launch -------------------------------------------------------------------------------- /src/tank_sdk/meshes/differential_model.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_sdk/meshes/differential_model.STL -------------------------------------------------------------------------------- /src/tank_sdk/msg/TankCMD.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_sdk/msg/TankCMD.msg -------------------------------------------------------------------------------- /src/tank_sdk/msg/TankFeedback.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_sdk/msg/TankFeedback.msg -------------------------------------------------------------------------------- /src/tank_sdk/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_sdk/package.xml -------------------------------------------------------------------------------- /src/tank_sdk/params/simulator.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_sdk/params/simulator.yaml -------------------------------------------------------------------------------- /src/tank_sdk/params/udp.yaml: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/tank_sdk/src/acc_test_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_sdk/src/acc_test_node.cpp -------------------------------------------------------------------------------- /src/tank_sdk/src/kinematics_sim.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_sdk/src/kinematics_sim.cpp -------------------------------------------------------------------------------- /src/tank_sdk/src/main.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_sdk/src/main.cpp -------------------------------------------------------------------------------- /src/tank_sdk/src/serial.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_sdk/src/serial.cpp -------------------------------------------------------------------------------- /src/tank_sdk/src/tank_send.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_sdk/src/tank_send.cpp -------------------------------------------------------------------------------- /src/tank_sdk/src/udp_send.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_sdk/src/udp_send.cpp -------------------------------------------------------------------------------- /src/tank_slam/FAST_LIO/Log/dbg.txt: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/tank_slam/FAST_LIO/Log/imu.txt: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/tank_slam/FAST_LIO/Log/mat_out.txt: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/tank_slam/FAST_LIO/Log/mat_pre.txt: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/tank_slam/FAST_LIO/Log/pos_log.txt: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /src/tank_slam/FAST_LIO/PCD/new.pcd: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/FAST_LIO/PCD/new.pcd -------------------------------------------------------------------------------- /src/tank_slam/FAST_LIO/PCD/scans.pcd: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/FAST_LIO/PCD/scans.pcd -------------------------------------------------------------------------------- /src/tank_slam/ekf_quat_pose/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/ekf_quat_pose/CMakeLists.txt -------------------------------------------------------------------------------- /src/tank_slam/ekf_quat_pose/cmake/FindEigen3.cmake: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/ekf_quat_pose/cmake/FindEigen3.cmake -------------------------------------------------------------------------------- /src/tank_slam/ekf_quat_pose/cmake/FindGLIB2.cmake: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/ekf_quat_pose/cmake/FindGLIB2.cmake -------------------------------------------------------------------------------- /src/tank_slam/ekf_quat_pose/cmake/FindGTHREAD2.cmake: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/ekf_quat_pose/cmake/FindGTHREAD2.cmake -------------------------------------------------------------------------------- /src/tank_slam/ekf_quat_pose/config/TA-camera.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/ekf_quat_pose/config/TA-camera.yml -------------------------------------------------------------------------------- /src/tank_slam/ekf_quat_pose/config/ekf_pose.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/ekf_quat_pose/config/ekf_pose.rviz -------------------------------------------------------------------------------- /src/tank_slam/ekf_quat_pose/config/tag_1.yml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/ekf_quat_pose/config/tag_1.yml -------------------------------------------------------------------------------- /src/tank_slam/ekf_quat_pose/include/conversion.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/ekf_quat_pose/include/conversion.h -------------------------------------------------------------------------------- /src/tank_slam/ekf_quat_pose/include/ekf.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/ekf_quat_pose/include/ekf.h -------------------------------------------------------------------------------- /src/tank_slam/ekf_quat_pose/launch/PX4_vio_drone.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/ekf_quat_pose/launch/PX4_vio_drone.yaml -------------------------------------------------------------------------------- /src/tank_slam/ekf_quat_pose/launch/ekf.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/ekf_quat_pose/launch/ekf.rviz -------------------------------------------------------------------------------- /src/tank_slam/ekf_quat_pose/launch/ekf_quat_lidar.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/ekf_quat_pose/launch/ekf_quat_lidar.launch -------------------------------------------------------------------------------- /src/tank_slam/ekf_quat_pose/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/ekf_quat_pose/package.xml -------------------------------------------------------------------------------- /src/tank_slam/ekf_quat_pose/src/conversion.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/ekf_quat_pose/src/conversion.cpp -------------------------------------------------------------------------------- /src/tank_slam/ekf_quat_pose/src/ekf_node_vio_timesync_with_acc_pub.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/ekf_quat_pose/src/ekf_node_vio_timesync_with_acc_pub.cpp -------------------------------------------------------------------------------- /src/tank_slam/ekf_quat_pose/src/imu_add_noise.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/ekf_quat_pose/src/imu_add_noise.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/.gitignore: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/.gitignore -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/LICENSE.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/LICENSE.txt -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/README.md -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/README_CN.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/README_CN.md -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/images/broadcast_code.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/images/broadcast_code.png -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/CMakeLists.txt -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/cmake/version.cmake: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/cmake/version.cmake -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/FastCRC/FastCRC.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/FastCRC/FastCRC.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/FastCRC/FastCRC_tables.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/FastCRC/FastCRC_tables.hpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/FastCRC/FastCRCsw.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/FastCRC/FastCRCsw.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/FastCRC/LICENSE.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/FastCRC/LICENSE.md -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/FastCRC/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/FastCRC/README.md -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/comm/comm_device.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/comm/comm_device.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/comm/comm_protocol.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/comm/comm_protocol.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/comm/comm_protocol.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/comm/comm_protocol.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/comm/gps_protocol.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/comm/gps_protocol.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/comm/gps_protocol.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/comm/gps_protocol.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/comm/protocol.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/comm/protocol.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/comm/sdk_protocol.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/comm/sdk_protocol.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/comm/sdk_protocol.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/comm/sdk_protocol.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/allocators.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/allocators.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/cursorstreamwrapper.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/cursorstreamwrapper.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/document.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/document.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/encodedstream.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/encodedstream.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/encodings.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/encodings.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/error/en.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/error/en.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/error/error.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/error/error.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/filereadstream.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/filereadstream.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/filewritestream.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/filewritestream.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/fwd.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/fwd.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/biginteger.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/biginteger.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/clzll.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/clzll.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/diyfp.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/diyfp.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/dtoa.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/dtoa.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/ieee754.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/ieee754.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/itoa.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/itoa.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/meta.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/meta.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/pow10.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/pow10.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/regex.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/regex.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/stack.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/stack.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/strfunc.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/strfunc.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/strtod.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/strtod.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/swap.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/internal/swap.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/istreamwrapper.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/istreamwrapper.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/memorybuffer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/memorybuffer.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/memorystream.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/memorystream.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/msinttypes/inttypes.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/msinttypes/inttypes.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/msinttypes/stdint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/msinttypes/stdint.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/ostreamwrapper.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/ostreamwrapper.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/pointer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/pointer.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/prettywriter.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/prettywriter.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/rapidjson.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/rapidjson.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/reader.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/reader.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/schema.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/schema.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/stream.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/stream.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/stringbuffer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/stringbuffer.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/writer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidjson/writer.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidxml/rapidxml.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidxml/rapidxml.hpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidxml/rapidxml_iterators.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidxml/rapidxml_iterators.hpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidxml/rapidxml_print.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidxml/rapidxml_print.hpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidxml/rapidxml_utils.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/common/rapidxml/rapidxml_utils.hpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/config/display_hub_points.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/config/display_hub_points.rviz -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/config/display_lidar_points.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/config/display_lidar_points.rviz -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/config/livox_hub_config.json: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/config/livox_hub_config.json -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/config/livox_lidar_config.json: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/config/livox_lidar_config.json -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/launch/livox_hub.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/launch/livox_hub.launch -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/launch/livox_hub_msg.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/launch/livox_hub_msg.launch -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/launch/livox_hub_rviz.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/launch/livox_hub_rviz.launch -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/launch/livox_lidar.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/launch/livox_lidar.launch -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/launch/livox_lidar_msg.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/launch/livox_lidar_msg.launch -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/launch/livox_lidar_rviz.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/launch/livox_lidar_rviz.launch -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/launch/livox_template.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/launch/livox_template.launch -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/launch/lvx_to_rosbag.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/launch/lvx_to_rosbag.launch -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/launch/lvx_to_rosbag_rviz.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/launch/lvx_to_rosbag_rviz.launch -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/include/livox_ros_driver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/include/livox_ros_driver.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lddc.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lddc.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lddc.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lddc.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/ldq.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/ldq.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/ldq.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/ldq.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lds.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lds.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lds.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lds.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lds_hub.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lds_hub.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lds_hub.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lds_hub.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lds_lidar.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lds_lidar.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lds_lidar.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lds_lidar.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lds_lvx.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lds_lvx.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lds_lvx.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lds_lvx.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/livox_ros_driver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/livox_ros_driver.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lvx_file.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lvx_file.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lvx_file.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/livox_ros_driver/lvx_file.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/msg/CustomMsg.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/msg/CustomMsg.msg -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/msg/CustomPoint.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/msg/CustomPoint.msg -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/package.xml -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/timesync/timesync.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/timesync/timesync.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/timesync/timesync.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/timesync/timesync.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/timesync/user_uart/user_uart.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/timesync/user_uart/user_uart.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver/livox_ros_driver/timesync/user_uart/user_uart.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver/livox_ros_driver/timesync/user_uart/user_uart.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/.gitignore: -------------------------------------------------------------------------------- 1 | .vscode 2 | build 3 | __pycache__ -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/allocators.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/allocators.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/cursorstreamwrapper.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/cursorstreamwrapper.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/document.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/document.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/encodedstream.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/encodedstream.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/encodings.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/encodings.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/error/en.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/error/en.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/error/error.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/error/error.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/filereadstream.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/filereadstream.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/filewritestream.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/filewritestream.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/fwd.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/fwd.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/biginteger.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/biginteger.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/clzll.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/clzll.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/diyfp.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/diyfp.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/dtoa.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/dtoa.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/ieee754.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/ieee754.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/itoa.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/itoa.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/meta.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/meta.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/pow10.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/pow10.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/regex.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/regex.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/stack.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/stack.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/strfunc.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/strfunc.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/strtod.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/strtod.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/swap.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/internal/swap.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/istreamwrapper.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/istreamwrapper.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/license.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/license.txt -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/memorybuffer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/memorybuffer.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/memorystream.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/memorystream.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/msinttypes/inttypes.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/msinttypes/inttypes.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/msinttypes/stdint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/msinttypes/stdint.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/ostreamwrapper.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/ostreamwrapper.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/pointer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/pointer.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/prettywriter.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/prettywriter.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/rapidjson.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/rapidjson.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/reader.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/reader.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/schema.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/schema.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/stream.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/stream.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/stringbuffer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/stringbuffer.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/writer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/3rdparty/rapidjson/writer.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/CHANGELOG.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/CHANGELOG.md -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/CMakeLists.txt -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/LICENSE.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/LICENSE.txt -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/README.md -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/build.sh: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/build.sh -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/cmake/version.cmake: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/cmake/version.cmake -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/config/HAP_config.json: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/config/HAP_config.json -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/config/MID360_config.json: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/config/MID360_config.json -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/config/display_point_cloud_ROS1.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/config/display_point_cloud_ROS1.rviz -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/config/display_point_cloud_ROS2.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/config/display_point_cloud_ROS2.rviz -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/config/mixed_HAP_MID360_config.json: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/config/mixed_HAP_MID360_config.json -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/launch_ROS1/msg_HAP.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/launch_ROS1/msg_HAP.launch -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/launch_ROS1/msg_MID360.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/launch_ROS1/msg_MID360.launch -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/launch_ROS1/msg_mixed.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/launch_ROS1/msg_mixed.launch -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/launch_ROS1/rviz_HAP.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/launch_ROS1/rviz_HAP.launch -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/launch_ROS1/rviz_MID360.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/launch_ROS1/rviz_MID360.launch -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/launch_ROS1/rviz_mixed.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/launch_ROS1/rviz_mixed.launch -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/launch_ROS2/msg_HAP_launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/launch_ROS2/msg_HAP_launch.py -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/launch_ROS2/msg_MID360_launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/launch_ROS2/msg_MID360_launch.py -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/launch_ROS2/rviz_HAP_launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/launch_ROS2/rviz_HAP_launch.py -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/launch_ROS2/rviz_MID360_launch.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/launch_ROS2/rviz_MID360_launch.py -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/launch_ROS2/rviz_mixed.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/launch_ROS2/rviz_mixed.py -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/msg/CustomMsg.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/msg/CustomMsg.msg -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/msg/CustomPoint.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/msg/CustomPoint.msg -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/package.xml -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/call_back/lidar_common_callback.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/call_back/lidar_common_callback.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/call_back/lidar_common_callback.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/call_back/lidar_common_callback.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/call_back/livox_lidar_callback.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/call_back/livox_lidar_callback.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/call_back/livox_lidar_callback.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/call_back/livox_lidar_callback.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/comm/cache_index.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/comm/cache_index.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/comm/cache_index.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/comm/cache_index.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/comm/comm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/comm/comm.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/comm/comm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/comm/comm.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/comm/ldq.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/comm/ldq.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/comm/ldq.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/comm/ldq.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/comm/lidar_imu_data_queue.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/comm/lidar_imu_data_queue.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/comm/lidar_imu_data_queue.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/comm/lidar_imu_data_queue.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/comm/pub_handler.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/comm/pub_handler.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/comm/pub_handler.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/comm/pub_handler.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/comm/semaphore.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/comm/semaphore.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/comm/semaphore.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/comm/semaphore.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/driver_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/driver_node.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/driver_node.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/driver_node.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/include/livox_ros_driver2.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/include/livox_ros_driver2.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/include/ros1_headers.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/include/ros1_headers.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/include/ros2_headers.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/include/ros2_headers.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/include/ros_headers.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/include/ros_headers.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/lddc.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/lddc.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/lddc.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/lddc.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/lds.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/lds.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/lds.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/lds.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/lds_lidar.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/lds_lidar.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/lds_lidar.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/lds_lidar.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/livox_ros_driver2.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/livox_ros_driver2.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/package_ROS1.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/package_ROS1.xml -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/parse_cfg_file/parse_cfg_file.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/parse_cfg_file/parse_cfg_file.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/parse_cfg_file/parse_cfg_file.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/parse_cfg_file/parse_cfg_file.h -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/parse_cfg_file/parse_livox_lidar_cfg.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/parse_cfg_file/parse_livox_lidar_cfg.cpp -------------------------------------------------------------------------------- /src/tank_slam/livox_ros_driver2/src/parse_cfg_file/parse_livox_lidar_cfg.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/tank_slam/livox_ros_driver2/src/parse_cfg_file/parse_livox_lidar_cfg.h -------------------------------------------------------------------------------- /src/tank_slam/readme: -------------------------------------------------------------------------------- 1 | in future wxx will make it as a submodule -------------------------------------------------------------------------------- /src/uneven_mapping.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping.zip -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_core/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_core/CMakeLists.txt -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_core/cmake/se2_grid_core-extras.cmake: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_core/cmake/se2_grid_core-extras.cmake -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/SE2Grid.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/SE2Grid.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/eigen_plugins/DenseBasePlugin.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/eigen_plugins/DenseBasePlugin.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/eigen_plugins/Functors.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/eigen_plugins/Functors.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/eigen_plugins/FunctorsPlugin.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/eigen_plugins/FunctorsPlugin.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/iterators/CircleIterator.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/iterators/CircleIterator.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/iterators/EllipseIterator.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/iterators/EllipseIterator.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/iterators/SE2GridIterator.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/iterators/SE2GridIterator.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/iterators/SpiralIterator.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/iterators/SpiralIterator.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/iterators/SubmapIterator.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/iterators/SubmapIterator.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/iterators/iterators.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/iterators/iterators.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/utils/Polygon.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/utils/Polygon.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/utils/untils.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_core/include/se2_grid_core/utils/untils.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_core/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_core/package.xml -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_core/src/SE2Grid.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_core/src/SE2Grid.cpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_msgs/msg/SE2Grid.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_msgs/msg/SE2Grid.msg -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_msgs/msg/SE2GridInfo.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_msgs/msg/SE2GridInfo.msg -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_msgs/package.xml -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_ros/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_ros/CMakeLists.txt -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_ros/include/se2_grid_ros/SE2GridMsgHelpers.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_ros/include/se2_grid_ros/SE2GridMsgHelpers.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_ros/include/se2_grid_ros/SE2GridRosConverter.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_ros/include/se2_grid_ros/SE2GridRosConverter.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_ros/include/se2_grid_ros/message_traits.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_ros/include/se2_grid_ros/message_traits.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_ros/include/se2_grid_ros/se2_grid_ros.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_ros/include/se2_grid_ros/se2_grid_ros.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_ros/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_ros/package.xml -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_ros/src/SE2GridMsgHelpers.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_ros/src/SE2GridMsgHelpers.cpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_ros/src/SE2GridRosConverter.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_ros/src/SE2GridRosConverter.cpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/CMakeLists.txt -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/icons/classes/SE2Grid.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/icons/classes/SE2Grid.png -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/include/se2_grid_rviz_plugin/SE2GridColorMaps.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/include/se2_grid_rviz_plugin/SE2GridColorMaps.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/include/se2_grid_rviz_plugin/SE2GridDisplay.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/include/se2_grid_rviz_plugin/SE2GridDisplay.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/include/se2_grid_rviz_plugin/SE2GridVisual.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/include/se2_grid_rviz_plugin/SE2GridVisual.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/include/se2_grid_rviz_plugin/modified/frame_manager.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/include/se2_grid_rviz_plugin/modified/frame_manager.h -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/include/se2_grid_rviz_plugin/modified/message_filter_display.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/include/se2_grid_rviz_plugin/modified/message_filter_display.h -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/package.xml -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/plugin_description.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/plugin_description.xml -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/src/SE2GridDisplay.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/src/SE2GridDisplay.cpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/src/SE2GridVisual.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_rviz_plugin/src/SE2GridVisual.cpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_tests/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_tests/CMakeLists.txt -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_tests/launch/interpolation_test.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_tests/launch/interpolation_test.launch -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_tests/launch/iterators_test.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_tests/launch/iterators_test.launch -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_tests/launch/move_test.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_tests/launch/move_test.launch -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_tests/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_tests/package.xml -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_tests/rviz/test.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_tests/rviz/test.rviz -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_tests/src/interpolation_test_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_tests/src/interpolation_test_node.cpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_tests/src/iterators_test_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_tests/src/iterators_test_node.cpp -------------------------------------------------------------------------------- /src/uneven_mapping/se2_grid/se2_grid_tests/src/move_test_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/se2_grid/se2_grid_tests/src/move_test_node.cpp -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/CMakeLists.txt -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/TerrainAnalyzer.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/TerrainAnalyzer.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/post_processors/CurvatureComputer.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/post_processors/CurvatureComputer.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/post_processors/InpaintProcessor.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/post_processors/InpaintProcessor.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/post_processors/MathProcessor.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/post_processors/MathProcessor.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/post_processors/MeanInRadiusFilter.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/post_processors/MeanInRadiusFilter.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/post_processors/NormalComputer.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/post_processors/NormalComputer.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/post_processors/PostProcessorBase.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/post_processors/PostProcessorBase.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/post_processors/SignedDistanceField.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/post_processors/SignedDistanceField.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/post_processors/post_processors.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/post_processors/post_processors.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/sensor_processors/OusterLidarProcessor.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/sensor_processors/OusterLidarProcessor.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/sensor_processors/SensorProcessorVirtual.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/sensor_processors/SensorProcessorVirtual.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/sensor_processors/sensor_processors.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/sensor_processors/sensor_processors.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/utils/EigenLab.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/utils/EigenLab.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/utils/WeightedEmpiricalCumulativeDistributionFunction.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/utils/WeightedEmpiricalCumulativeDistributionFunction.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/utils/utils.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/include/terrain_analyzer/utils/utils.hpp -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/launch/terrain_analyzer.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/launch/terrain_analyzer.launch -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/package.xml -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/params/elevation_map.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/params/elevation_map.yaml -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/params/elevation_map_gpu.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/params/elevation_map_gpu.yaml -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/post_processors.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/post_processors.xml -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/src/R2_terrain/TerrainAnalyzerR2.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/src/R2_terrain/TerrainAnalyzerR2.cpp -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/src/R2_terrain/TerrainBankR2.cu: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/src/R2_terrain/TerrainBankR2.cu -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/src/TerrainAnalyzer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/src/TerrainAnalyzer.cpp -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/src/TerrainBank.cu: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/src/TerrainBank.cu -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/src/TerrainBank_huawei.cu: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/src/TerrainBank_huawei.cu -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/src/helper_math.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/src/helper_math.h -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/src/post_processors.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/src/post_processors.cpp -------------------------------------------------------------------------------- /src/uneven_mapping/terrain_analyzer/src/terrain_analyzer_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ZJU-FAST-Lab/seb_naver/HEAD/src/uneven_mapping/terrain_analyzer/src/terrain_analyzer_node.cpp --------------------------------------------------------------------------------