├── README.md ├── gazebo_worlds ├── corridor.world ├── empty.world ├── playground.world └── square_hall.world ├── images ├── 01.png ├── 02.png ├── 03.png ├── 04.png ├── 05.png ├── 06.png ├── 07.png ├── 08.png ├── 09.png ├── 10.png ├── 11.png ├── 12.png └── 13.jpg ├── robot_remould ├── hokuyo.dae ├── kobuki_hexagons_hokuyo.urdf.xacro ├── turtlebot_world.launch └── urdf │ ├── common_properties.urdf.xacro │ ├── sensors │ ├── astra.urdf.xacro │ ├── asus_xtion_pro.urdf.xacro │ ├── asus_xtion_pro_offset.urdf.xacro │ ├── hokuyo.urdf.xacro │ ├── kinect.urdf.xacro │ └── r200.urdf.xacro │ ├── stacks │ ├── circles.urdf.xacro │ └── hexagons.urdf.xacro │ ├── turtlebot_common_library.urdf.xacro │ ├── turtlebot_gazebo.urdf.xacro │ ├── turtlebot_library.urdf.xacro │ └── turtlebot_properties.urdf.xacro ├── ros_maps ├── square_hall.pgm └── square_hall.yaml ├── scripts ├── .vscode │ └── settings.json ├── README.md ├── coffee_bot.py ├── draw_a_square.py ├── follow_the_route.py ├── go_to_specific_point_on_map.py ├── goforward.py ├── goforward_and_avoid_obstacle.py ├── kobuki_battery.py ├── kobuki_buttons.py ├── netbook_battery.py ├── route.yaml └── take_photo.py └── src ├── .rosinstall ├── .rosinstall.bak ├── .vscode ├── c_cpp_properties.json └── settings.json ├── CMakeLists.txt ├── dstar ├── CMakeLists.txt ├── bgp_plugin.xml ├── include │ └── dstar_global_planner │ │ ├── Dstar.h │ │ ├── dstar_global_planner.h │ │ └── pathSplineSmoother │ │ ├── pathSplineSmoother.cpp │ │ ├── pathSplineSmoother.h │ │ └── realPoint.h ├── package.xml └── src │ ├── Dstar.cpp │ ├── Dstar.cpp~ │ └── dstar_global_planner.cpp ├── hector_slam ├── .gitignore ├── README.txt ├── hector_compressed_map_transport │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── package.xml │ └── src │ │ └── map_to_image_node.cpp ├── hector_geotiff │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ │ └── hector_geotiff │ │ │ ├── geotiff_writer.h │ │ │ ├── map_writer_interface.h │ │ │ └── map_writer_plugin_interface.h │ ├── launch │ │ ├── geotiff_mapper.launch │ │ └── geotiff_mapper_only.launch │ ├── package.xml │ └── src │ │ ├── geotiff_node.cpp │ │ ├── geotiff_saver.cpp │ │ └── geotiff_writer │ │ └── geotiff_writer.cpp ├── hector_geotiff_plugins │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── hector_geotiff_plugins.xml │ ├── package.xml │ └── src │ │ └── trajectory_geotiff_plugin.cpp ├── hector_imu_attitude_to_tf │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── launch │ │ └── example.launch │ ├── package.xml │ └── src │ │ └── imu_attitude_to_tf_node.cpp ├── hector_imu_tools │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── launch │ │ ├── bertl_robot.launch │ │ └── jasmine_robot.launch │ ├── package.xml │ └── src │ │ └── pose_and_orientation_to_imu_node.cpp ├── hector_map_server │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── package.xml │ └── src │ │ └── hector_map_server.cpp ├── hector_map_tools │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ │ └── hector_map_tools │ │ │ └── HectorMapTools.h │ └── package.xml ├── hector_mapping │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ │ └── hector_slam_lib │ │ │ ├── map │ │ │ ├── GridMap.h │ │ │ ├── GridMapBase.h │ │ │ ├── GridMapCacheArray.h │ │ │ ├── GridMapLogOdds.h │ │ │ ├── GridMapReflectanceCount.h │ │ │ ├── GridMapSimpleCount.h │ │ │ ├── MapDimensionProperties.h │ │ │ ├── OccGridMapBase.h │ │ │ ├── OccGridMapUtil.h │ │ │ └── OccGridMapUtilConfig.h │ │ │ ├── matcher │ │ │ └── ScanMatcher.h │ │ │ ├── scan │ │ │ └── DataPointContainer.h │ │ │ ├── slam_main │ │ │ ├── HectorSlamProcessor.h │ │ │ ├── MapProcContainer.h │ │ │ ├── MapRepMultiMap.h │ │ │ ├── MapRepSingleMap.h │ │ │ └── MapRepresentationInterface.h │ │ │ └── util │ │ │ ├── DrawInterface.h │ │ │ ├── HectorDebugInfoInterface.h │ │ │ ├── MapLockerInterface.h │ │ │ └── UtilFunctions.h │ ├── launch │ │ └── mapping_default.launch │ ├── msg │ │ ├── HectorDebugInfo.msg │ │ └── HectorIterData.msg │ ├── package.xml │ └── src │ │ ├── HectorDebugInfoProvider.h │ │ ├── HectorDrawings.h │ │ ├── HectorMapMutex.h │ │ ├── HectorMappingRos.cpp │ │ ├── HectorMappingRos.h │ │ ├── PoseInfoContainer.cpp │ │ ├── PoseInfoContainer.h │ │ ├── main.cpp │ │ └── main_mapper.cpp ├── hector_marker_drawing │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ │ └── hector_marker_drawing │ │ │ ├── DrawInterface.h │ │ │ └── HectorDrawings.h │ └── package.xml ├── hector_nav_msgs │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── package.xml │ └── srv │ │ ├── GetDistanceToObstacle.srv │ │ ├── GetNormal.srv │ │ ├── GetRecoveryInfo.srv │ │ ├── GetRobotTrajectory.srv │ │ └── GetSearchPosition.srv ├── hector_slam │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ └── package.xml ├── hector_slam_launch │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── launch │ │ ├── cityflyer_logfile_processing.launch │ │ ├── hector_ugv.launch │ │ ├── height_mapping.launch │ │ ├── mapping_box.launch │ │ ├── mpo700_mapping.launch │ │ ├── postproc_data.launch │ │ ├── postproc_qut_logs.launch │ │ ├── pr2os.launch │ │ └── tutorial.launch │ ├── package.xml │ └── rviz_cfg │ │ └── mapping_demo.rviz └── hector_trajectory_server │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── package.xml │ └── src │ └── hector_trajectory_server.cpp ├── navigation ├── .gitignore ├── README.md ├── amcl │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── cfg │ │ └── AMCL.cfg │ ├── examples │ │ ├── amcl_diff.launch │ │ └── amcl_omni.launch │ ├── include │ │ └── amcl │ │ │ ├── map │ │ │ └── map.h │ │ │ ├── pf │ │ │ ├── eig3.h │ │ │ ├── pf.h │ │ │ ├── pf_kdtree.h │ │ │ ├── pf_pdf.h │ │ │ └── pf_vector.h │ │ │ └── sensors │ │ │ ├── amcl_laser.h │ │ │ ├── amcl_odom.h │ │ │ └── amcl_sensor.h │ ├── package.xml │ ├── src │ │ ├── amcl │ │ │ ├── map │ │ │ │ ├── map.c │ │ │ │ ├── map_cspace.cpp │ │ │ │ ├── map_draw.c │ │ │ │ ├── map_range.c │ │ │ │ └── map_store.c │ │ │ ├── pf │ │ │ │ ├── eig3.c │ │ │ │ ├── pf.c │ │ │ │ ├── pf_draw.c │ │ │ │ ├── pf_kdtree.c │ │ │ │ ├── pf_pdf.c │ │ │ │ └── pf_vector.c │ │ │ └── sensors │ │ │ │ ├── amcl_laser.cpp │ │ │ │ ├── amcl_odom.cpp │ │ │ │ └── amcl_sensor.cpp │ │ └── amcl_node.cpp │ └── test │ │ ├── basic_localization.py │ │ ├── basic_localization_stage.xml │ │ ├── global_localization_stage.xml │ │ ├── rosie_multilaser.xml │ │ ├── set_initial_pose.xml │ │ ├── set_initial_pose_delayed.xml │ │ ├── set_pose.py │ │ ├── small_loop_crazy_driving_prg.xml │ │ ├── small_loop_crazy_driving_prg_corrected.xml │ │ ├── small_loop_prf.xml │ │ ├── texas_greenroom_loop.xml │ │ ├── texas_greenroom_loop_corrected.xml │ │ ├── texas_willow_hallway_loop.xml │ │ └── texas_willow_hallway_loop_corrected.xml ├── base_local_planner │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── blp_plugin.xml │ ├── cfg │ │ ├── BaseLocalPlanner.cfg │ │ └── LocalPlannerLimits.cfg │ ├── include │ │ └── base_local_planner │ │ │ ├── costmap_model.h │ │ │ ├── footprint_helper.h │ │ │ ├── goal_functions.h │ │ │ ├── latched_stop_rotate_controller.h │ │ │ ├── line_iterator.h │ │ │ ├── local_planner_limits.h │ │ │ ├── local_planner_util.h │ │ │ ├── map_cell.h │ │ │ ├── map_grid.h │ │ │ ├── map_grid_cost_function.h │ │ │ ├── map_grid_cost_point.h │ │ │ ├── map_grid_visualizer.h │ │ │ ├── obstacle_cost_function.h │ │ │ ├── odometry_helper_ros.h │ │ │ ├── oscillation_cost_function.h │ │ │ ├── planar_laser_scan.h │ │ │ ├── point_grid.h │ │ │ ├── prefer_forward_cost_function.h │ │ │ ├── simple_scored_sampling_planner.h │ │ │ ├── simple_trajectory_generator.h │ │ │ ├── trajectory.h │ │ │ ├── trajectory_cost_function.h │ │ │ ├── trajectory_inc.h │ │ │ ├── trajectory_planner.h │ │ │ ├── trajectory_planner_ros.h │ │ │ ├── trajectory_sample_generator.h │ │ │ ├── trajectory_search.h │ │ │ ├── twirling_cost_function.h │ │ │ ├── velocity_iterator.h │ │ │ ├── voxel_grid_model.h │ │ │ └── world_model.h │ ├── msg │ │ └── Position2DInt.msg │ ├── package.xml │ ├── setup.py │ ├── src │ │ ├── costmap_model.cpp │ │ ├── footprint_helper.cpp │ │ ├── goal_functions.cpp │ │ ├── latched_stop_rotate_controller.cpp │ │ ├── local_planner_limits │ │ │ ├── .gitignore │ │ │ └── __init__.py │ │ ├── local_planner_util.cpp │ │ ├── map_cell.cpp │ │ ├── map_grid.cpp │ │ ├── map_grid_cost_function.cpp │ │ ├── map_grid_visualizer.cpp │ │ ├── obstacle_cost_function.cpp │ │ ├── odometry_helper_ros.cpp │ │ ├── oscillation_cost_function.cpp │ │ ├── point_grid.cpp │ │ ├── prefer_forward_cost_function.cpp │ │ ├── simple_scored_sampling_planner.cpp │ │ ├── simple_trajectory_generator.cpp │ │ ├── trajectory.cpp │ │ ├── trajectory_planner.cpp │ │ ├── trajectory_planner_ros.cpp │ │ ├── twirling_cost_function.cpp │ │ └── voxel_grid_model.cpp │ └── test │ │ ├── footprint_helper_test.cpp │ │ ├── gtest_main.cpp │ │ ├── line_iterator_test.cpp │ │ ├── map_grid_test.cpp │ │ ├── trajectory_generator_test.cpp │ │ ├── utest.cpp │ │ ├── velocity_iterator_test.cpp │ │ └── wavefront_map_accessor.h ├── carrot_planner │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── bgp_plugin.xml │ ├── include │ │ └── carrot_planner │ │ │ └── carrot_planner.h │ ├── package.xml │ └── src │ │ └── carrot_planner.cpp ├── clear_costmap_recovery │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── ccr_plugin.xml │ ├── include │ │ └── clear_costmap_recovery │ │ │ └── clear_costmap_recovery.h │ ├── package.xml │ ├── src │ │ └── clear_costmap_recovery.cpp │ └── test │ │ ├── clear_tester.cpp │ │ ├── clear_tests.launch │ │ └── params.yaml ├── costmap_2d │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── cfg │ │ ├── Costmap2D.cfg │ │ ├── GenericPlugin.cfg │ │ ├── InflationPlugin.cfg │ │ ├── ObstaclePlugin.cfg │ │ └── VoxelPlugin.cfg │ ├── costmap_plugins.xml │ ├── include │ │ └── costmap_2d │ │ │ ├── array_parser.h │ │ │ ├── cost_values.h │ │ │ ├── costmap_2d.h │ │ │ ├── costmap_2d_publisher.h │ │ │ ├── costmap_2d_ros.h │ │ │ ├── costmap_layer.h │ │ │ ├── costmap_math.h │ │ │ ├── footprint.h │ │ │ ├── inflation_layer.h │ │ │ ├── layer.h │ │ │ ├── layered_costmap.h │ │ │ ├── observation.h │ │ │ ├── observation_buffer.h │ │ │ ├── obstacle_layer.h │ │ │ ├── static_layer.h │ │ │ ├── testing_helper.h │ │ │ └── voxel_layer.h │ ├── launch │ │ ├── example.launch │ │ └── example_params.yaml │ ├── msg │ │ └── VoxelGrid.msg │ ├── package.xml │ ├── plugins │ │ ├── inflation_layer.cpp │ │ ├── obstacle_layer.cpp │ │ ├── static_layer.cpp │ │ └── voxel_layer.cpp │ ├── src │ │ ├── array_parser.cpp │ │ ├── costmap_2d.cpp │ │ ├── costmap_2d_cloud.cpp │ │ ├── costmap_2d_markers.cpp │ │ ├── costmap_2d_node.cpp │ │ ├── costmap_2d_publisher.cpp │ │ ├── costmap_2d_ros.cpp │ │ ├── costmap_layer.cpp │ │ ├── costmap_math.cpp │ │ ├── footprint.cpp │ │ ├── layer.cpp │ │ ├── layered_costmap.cpp │ │ └── observation_buffer.cpp │ └── test │ │ ├── TenByTen.pgm │ │ ├── TenByTen.yaml │ │ ├── array_parser_test.cpp │ │ ├── coordinates_test.cpp │ │ ├── costmap_params.yaml │ │ ├── costmap_tester.cpp │ │ ├── footprint_tests.cpp │ │ ├── footprint_tests.launch │ │ ├── inflation_tests.cpp │ │ ├── inflation_tests.launch │ │ ├── module_tests.cpp │ │ ├── obstacle_tests.cpp │ │ ├── obstacle_tests.launch │ │ ├── simple_driving_test.xml │ │ ├── static_tests.cpp │ │ └── static_tests.launch ├── dwa_local_planner │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── blp_plugin.xml │ ├── cfg │ │ └── DWAPlanner.cfg │ ├── include │ │ └── dwa_local_planner │ │ │ ├── dwa_planner.h │ │ │ └── dwa_planner_ros.h │ ├── package.xml │ └── src │ │ ├── dwa_planner.cpp │ │ └── dwa_planner_ros.cpp ├── fake_localization │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── fake_localization.cpp │ ├── package.xml │ └── static_odom_broadcaster.py ├── global_planner │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── bgp_plugin.xml │ ├── cfg │ │ └── GlobalPlanner.cfg │ ├── include │ │ └── global_planner │ │ │ ├── astar.h │ │ │ ├── dijkstra.h │ │ │ ├── expander.h │ │ │ ├── gradient_path.h │ │ │ ├── grid_path.h │ │ │ ├── orientation_filter.h │ │ │ ├── planner_core.h │ │ │ ├── potential_calculator.h │ │ │ ├── quadratic_calculator.h │ │ │ └── traceback.h │ ├── package.xml │ └── src │ │ ├── astar.cpp │ │ ├── dijkstra.cpp │ │ ├── gradient_path.cpp │ │ ├── grid_path.cpp │ │ ├── orientation_filter.cpp │ │ ├── plan_node.cpp │ │ ├── planner_core.cpp │ │ └── quadratic_calculator.cpp ├── map_server │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ │ └── map_server │ │ │ └── image_loader.h │ ├── package.xml │ ├── scripts │ │ └── crop_map │ ├── src │ │ ├── image_loader.cpp │ │ ├── main.cpp │ │ ├── map_saver.cpp │ │ └── map_server.dox │ └── test │ │ ├── consumer.py │ │ ├── rtest.cpp │ │ ├── rtest.xml │ │ ├── test_constants.cpp │ │ ├── test_constants.h │ │ ├── testmap.bmp │ │ ├── testmap.png │ │ ├── testmap.yaml │ │ └── utest.cpp ├── move_base │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── cfg │ │ └── MoveBase.cfg │ ├── include │ │ └── move_base │ │ │ └── move_base.h │ ├── package.xml │ ├── planner_test.xml │ └── src │ │ ├── move_base.cpp │ │ └── move_base_node.cpp ├── move_slow_and_clear │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ │ └── move_slow_and_clear │ │ │ └── move_slow_and_clear.h │ ├── package.xml │ ├── recovery_plugin.xml │ └── src │ │ └── move_slow_and_clear.cpp ├── nav_core │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ │ └── nav_core │ │ │ ├── base_global_planner.h │ │ │ ├── base_local_planner.h │ │ │ └── recovery_behavior.h │ └── package.xml ├── navfn │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── Makefile.orig │ ├── bgp_plugin.xml │ ├── include │ │ └── navfn │ │ │ ├── navfn.h │ │ │ ├── navfn_ros.h │ │ │ ├── navwin.h │ │ │ ├── potarr_point.h │ │ │ └── read_pgm_costmap.h │ ├── package.xml │ ├── src │ │ ├── navfn.cpp │ │ ├── navfn_node.cpp │ │ ├── navfn_ros.cpp │ │ ├── navtest.cpp │ │ ├── navwin.cpp │ │ └── read_pgm_costmap.cpp │ ├── srv │ │ ├── MakeNavPlan.srv │ │ └── SetCostmap.srv │ └── test │ │ ├── CMakeLists.txt │ │ ├── path_calc_test.cpp │ │ └── willow_costmap.pgm ├── navigation │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── README.rst │ └── package.xml ├── robot_pose_ekf │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── example_with_gps.launch │ ├── include │ │ └── robot_pose_ekf │ │ │ ├── nonlinearanalyticconditionalgaussianodo.h │ │ │ ├── odom_estimation.h │ │ │ └── odom_estimation_node.h │ ├── package.xml │ ├── plotekf.m │ ├── robot_pose_ekf.launch │ ├── scripts │ │ └── wtf.py │ ├── src │ │ ├── nonlinearanalyticconditionalgaussianodo.cpp │ │ ├── odom_estimation.cpp │ │ └── odom_estimation_node.cpp │ ├── srv │ │ └── GetStatus.srv │ └── test │ │ ├── test_robot_pose_ekf.cpp │ │ ├── test_robot_pose_ekf.launch │ │ ├── test_robot_pose_ekf_zero_covariance.cpp │ │ └── test_robot_pose_ekf_zero_covariance.launch ├── rotate_recovery │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ │ └── rotate_recovery │ │ │ └── rotate_recovery.h │ ├── package.xml │ ├── rotate_plugin.xml │ └── src │ │ └── rotate_recovery.cpp └── voxel_grid │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ └── voxel_grid │ │ └── voxel_grid.h │ ├── package.xml │ ├── src │ └── voxel_grid.cpp │ └── test │ └── voxel_grid_tests.cpp ├── relaxed_astar ├── CMakeLists.txt ├── LICENSE ├── README ├── package.xml ├── relaxed_astar_planner_plugin.xml └── src │ ├── RAstar_ros.cpp │ ├── RAstar_ros.cpp~ │ ├── RAstar_ros.h │ └── RAstar_ros.h~ ├── rplidar_ros ├── CHANGELOG.rst ├── CMakeLists.txt ├── LICENSE ├── README.md ├── launch │ ├── hector_mapping_demo.launch │ ├── rplidar.launch │ ├── rplidar_a3.launch │ ├── test_rplidar.launch │ ├── test_rplidar_a3.launch │ ├── view_rplidar.launch │ └── view_rplidar_a3.launch ├── package.xml ├── rplidar_A1.png ├── rplidar_A2.png ├── rviz │ └── rplidar.rviz ├── scripts │ ├── create_udev_rules.sh │ ├── delete_udev_rules.sh │ └── rplidar.rules ├── sdk │ ├── README.txt │ ├── include │ │ ├── rplidar.h │ │ ├── rplidar_cmd.h │ │ ├── rplidar_driver.h │ │ ├── rplidar_protocol.h │ │ └── rptypes.h │ └── src │ │ ├── arch │ │ ├── linux │ │ │ ├── arch_linux.h │ │ │ ├── net_serial.cpp │ │ │ ├── net_serial.h │ │ │ ├── net_socket.cpp │ │ │ ├── thread.hpp │ │ │ ├── timer.cpp │ │ │ └── timer.h │ │ ├── macOS │ │ │ ├── arch_macOS.h │ │ │ ├── net_serial.cpp │ │ │ ├── net_serial.h │ │ │ ├── net_socket.cpp │ │ │ ├── thread.hpp │ │ │ ├── timer.cpp │ │ │ └── timer.h │ │ └── win32 │ │ │ ├── arch_win32.h │ │ │ ├── net_serial.cpp │ │ │ ├── net_serial.h │ │ │ ├── net_socket.cpp │ │ │ ├── timer.cpp │ │ │ ├── timer.h │ │ │ └── winthread.hpp │ │ ├── hal │ │ ├── abs_rxtx.h │ │ ├── assert.h │ │ ├── byteops.h │ │ ├── event.h │ │ ├── locker.h │ │ ├── socket.h │ │ ├── thread.cpp │ │ ├── thread.h │ │ ├── types.h │ │ └── util.h │ │ ├── rplidar_driver.cpp │ │ ├── rplidar_driver_TCP.h │ │ ├── rplidar_driver_impl.h │ │ ├── rplidar_driver_serial.h │ │ └── sdkcommon.h └── src │ ├── client.cpp │ └── node.cpp ├── rrt_exploration ├── CMakeLists.txt ├── LICENSE.md ├── README.md ├── include │ ├── functions.h │ └── mtrand.h ├── launch │ ├── simple.launch │ ├── single.launch │ └── three_robots.launch ├── msg │ └── PointArray.msg ├── package.xml ├── scripts │ ├── assigner.py │ ├── filter.py │ ├── frontier_opencv_detector.py │ ├── functions.py │ ├── functions.pyc │ └── getfrontier.py └── src │ ├── functions.cpp │ ├── global_rrt_detector.cpp │ ├── local_rrt_detector.cpp │ └── mtrand.cpp ├── rrt_exploration_tutorials ├── CMakeLists.txt ├── README.md ├── launch │ ├── includes │ │ ├── initposes.launch │ │ ├── map_merge.launch │ │ ├── meshes │ │ │ ├── MTR_map.dae │ │ │ ├── hokuyo.dae │ │ │ ├── images │ │ │ │ ├── main_body.jpg │ │ │ │ └── wheel.jpg │ │ │ ├── largeMap.dae │ │ │ ├── main_body.dae │ │ │ └── wheel.dae │ │ ├── move_baseSafe.launch │ │ ├── robot.launch.xml │ │ ├── rviz_config │ │ │ ├── simple.rviz │ │ │ ├── single.rviz │ │ │ ├── single2.rviz │ │ │ ├── testing.rviz │ │ │ ├── three.rviz │ │ │ └── two.rviz │ │ ├── urdf │ │ │ ├── common_properties.urdf.xacro │ │ │ ├── kobuki.urdf.xacro │ │ │ ├── kobuki_gazebo.urdf.xacro │ │ │ └── kobuki_standalone.urdf.xacro │ │ └── worlds │ │ │ ├── MTR.world │ │ │ ├── house.world │ │ │ ├── largeMap.world │ │ │ └── square_hall.world │ ├── mutliple_simulated_MTR.launch │ ├── mutliple_simulated_house.launch │ ├── mutliple_simulated_largeMap.launch │ ├── simple.launch │ ├── single_simulated_MTR.launch │ ├── single_simulated_house.launch │ ├── single_simulated_largeMap.launch │ └── single_simulated_square_hall.launch ├── package.xml └── param │ ├── base_local_planner_params.yaml │ ├── costmap_common_params.yaml │ ├── global_costmap_params.yaml │ └── local_costmap_params.yaml └── rrt_planner ├── CMakeLists.txt ├── package.xml ├── rrt_planner_plugin.xml └── src ├── inspire_rrt_planner.h ├── rrt.h └── rrt_planner.cpp /gazebo_worlds/empty.world: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | model://sun 7 | 8 | 9 | 10 | model://ground_plane 11 | 12 | 13 | 14 | 0.01 15 | 1 16 | 100 17 | 0 0 -9.8 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /images/01.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/images/01.png -------------------------------------------------------------------------------- /images/02.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/images/02.png -------------------------------------------------------------------------------- /images/03.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/images/03.png -------------------------------------------------------------------------------- /images/04.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/images/04.png -------------------------------------------------------------------------------- /images/05.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/images/05.png -------------------------------------------------------------------------------- /images/06.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/images/06.png -------------------------------------------------------------------------------- /images/07.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/images/07.png -------------------------------------------------------------------------------- /images/08.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/images/08.png -------------------------------------------------------------------------------- /images/09.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/images/09.png -------------------------------------------------------------------------------- /images/10.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/images/10.png -------------------------------------------------------------------------------- /images/11.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/images/11.png -------------------------------------------------------------------------------- /images/12.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/images/12.png -------------------------------------------------------------------------------- /images/13.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/images/13.jpg -------------------------------------------------------------------------------- /robot_remould/kobuki_hexagons_hokuyo.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /robot_remould/turtlebot_world.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 38 | 39 | -------------------------------------------------------------------------------- /robot_remould/urdf/common_properties.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | -------------------------------------------------------------------------------- /robot_remould/urdf/sensors/hokuyo.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | -------------------------------------------------------------------------------- /robot_remould/urdf/turtlebot_common_library.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | -------------------------------------------------------------------------------- /robot_remould/urdf/turtlebot_library.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /robot_remould/urdf/turtlebot_properties.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 10 | 11 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | -------------------------------------------------------------------------------- /ros_maps/square_hall.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/ros_maps/square_hall.pgm -------------------------------------------------------------------------------- /ros_maps/square_hall.yaml: -------------------------------------------------------------------------------- 1 | image: /home/zhao/ros_maps/square_hall.pgm 2 | resolution: 0.050000 3 | origin: [-15.400000, -13.800000, 0.000000] 4 | negate: 0 5 | occupied_thresh: 0.65 6 | free_thresh: 0.196 7 | 8 | -------------------------------------------------------------------------------- /scripts/.vscode/settings.json: -------------------------------------------------------------------------------- 1 | { 2 | "python.pythonPath": "/usr/bin/python2.7", 3 | "python.linting.flake8Enabled": true, 4 | "python.formatting.provider": "yapf", 5 | "python.linting.flake8Args": ["--max-line-length=248"], 6 | "python.linting.pylintEnabled": false 7 | } -------------------------------------------------------------------------------- /scripts/README.md: -------------------------------------------------------------------------------- 1 | ## A "getting started" guide for developers interested in robotics 2 | 3 | [Learn TurtleBot] (http://learn.turtlebot.com/) is an open source getting started guide for web, mobile and maker developers interested in robotics. 4 | 5 | [Go to the tutorials] (http://learn.turtlebot.com/) 6 | 7 | ### Web App 8 | 9 | This repository includes scripts used in the tutorial series. -------------------------------------------------------------------------------- /scripts/route.yaml: -------------------------------------------------------------------------------- 1 | - {filename: 'dumpster.png', position: { x: 0.355, y: -0.2}, quaternion: {r1: 0, r2: 0, r3: -0.628, r4: 0.778}} 2 | - {filename: 'cube_20k.png', position: { x: 2.843, y: -1.743}, quaternion: {r1: 0, r2: 0, r3: 0.936, r4: 0.353}} 3 | - {filename: 'bookshelf.png', position: { x: 1.401, y: 2.913}, quaternion: {r1: 0, r2: 0, r3: 0.904, r4: -0.427}} 4 | -------------------------------------------------------------------------------- /src/.rosinstall: -------------------------------------------------------------------------------- 1 | # THIS IS AN AUTOGENERATED FILE, LAST GENERATED USING wstool ON 2020-04-12 2 | - git: 3 | local-name: mavlink 4 | uri: https://github.com/mavlink/mavlink-gbp-release.git 5 | version: release/kinetic/mavlink/2020.4.4-1 6 | - git: 7 | local-name: mavros 8 | uri: https://github.com/mavlink/mavros.git 9 | version: 1.1.0 10 | -------------------------------------------------------------------------------- /src/.rosinstall.bak: -------------------------------------------------------------------------------- 1 | # THIS IS AN AUTOGENERATED FILE, LAST GENERATED USING wstool ON 2020-04-12 2 | -------------------------------------------------------------------------------- /src/.vscode/c_cpp_properties.json: -------------------------------------------------------------------------------- 1 | { 2 | "configurations": [ 3 | { 4 | "browse": { 5 | "databaseFilename": "", 6 | "limitSymbolsToIncludedHeaders": true 7 | }, 8 | "includePath": [ 9 | "/home/zhao/px4_catkin_ws/devel/include/**", 10 | "/home/zhao/catkin_ws/devel/include/**", 11 | "/opt/ros/kinetic/include/**", 12 | "/home/zhao/px4_catkin_ws/src/mavros/libmavconn/include/**", 13 | "/home/zhao/px4_catkin_ws/src/mavros/mavros/include/**", 14 | "/home/zhao/px4_catkin_ws/src/mavros/mavros_msgs/include/**", 15 | "/home/zhao/catkin_ws/src/rrt_exploration/include/**", 16 | "/home/zhao/px4_catkin_ws/src/mavros/test_mavros/include/**", 17 | "/usr/include/**" 18 | ], 19 | "name": "ROS" 20 | } 21 | ] 22 | } -------------------------------------------------------------------------------- /src/.vscode/settings.json: -------------------------------------------------------------------------------- 1 | { 2 | "python.autoComplete.extraPaths": [ 3 | "/home/zhao/px4_catkin_ws/devel/lib/python2.7/dist-packages", 4 | "/home/zhao/catkin_ws/devel/lib/python2.7/dist-packages", 5 | "/opt/ros/kinetic/lib/python2.7/dist-packages" 6 | ] 7 | } -------------------------------------------------------------------------------- /src/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | /opt/ros/kinetic/share/catkin/cmake/toplevel.cmake -------------------------------------------------------------------------------- /src/dstar/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(dstar_global_planner) 3 | 4 | ADD_DEFINITIONS(-std=c++0x) # C++ 11 is required 5 | 6 | find_package(catkin REQUIRED COMPONENTS 7 | geometry_msgs 8 | nav_core 9 | nav_msgs 10 | pluginlib 11 | costmap_2d 12 | roscpp 13 | rospy 14 | std_msgs 15 | tf 16 | ) 17 | 18 | find_package(cmake_modules REQUIRED) 19 | 20 | 21 | #FIND_PACKAGE(Eigen REQUIRED) 22 | #FIND_PACKAGE(Boost REQUIRED) 23 | 24 | 25 | 26 | 27 | catkin_package( 28 | 29 | CATKIN_DEPENDS 30 | geometry_msgs 31 | nav_core 32 | nav_msgs 33 | roscpp 34 | rospy 35 | std_msgs 36 | tf 37 | costmap_2d 38 | pluginlib 39 | LIBRARIES 40 | dstar_global_planner 41 | 42 | 43 | ) 44 | 45 | ########### 46 | ## Build ## 47 | ########### 48 | include_directories(${Eigen_INCLUDE_DIRS}) 49 | 50 | include_directories( 51 | ${CMAKE_CURRENT_SOURCE_DIR}/include/ 52 | ${CMAKE_CURRENT_SOURCE_DIR}/src/ 53 | ${CMAKE_CURRENT_SOURCE_DIR} 54 | ${catkin_INCLUDE_DIRS} 55 | ) 56 | 57 | 58 | 59 | set(SOURCES 60 | src/dstar_global_planner.cpp src/Dstar.cpp include/dstar_global_planner/pathSplineSmoother/pathSplineSmoother.cpp 61 | 62 | ) 63 | 64 | 65 | 66 | # Plugin 67 | add_library(dstar_global_planner ${SOURCES_RRT} ${SOURCES}) 68 | 69 | target_link_libraries(dstar_global_planner ${catkin_LIBRARIES} ${BOOST_LIBRARIES} ) 70 | 71 | add_dependencies(dstar_global_planner dstar_global_planner_gencfg ${catkin_EXPORTED_TARGETS}) 72 | 73 | add_dependencies(dstar_global_planner nav_msgs_gencpp) 74 | 75 | 76 | install(TARGETS dstar_global_planner 77 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 78 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 79 | 80 | ) 81 | 82 | install(FILES bgp_plugin.xml 83 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 84 | ) 85 | 86 | 87 | install(DIRECTORY include/${PROJECT_NAME}/ 88 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 89 | PATTERN ".svn" EXCLUDE 90 | ) 91 | -------------------------------------------------------------------------------- /src/dstar/bgp_plugin.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | Global Planner using D* Lite 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /src/dstar/include/dstar_global_planner/pathSplineSmoother/realPoint.h: -------------------------------------------------------------------------------- 1 | struct RealPoint{ 2 | double x; 3 | double y; 4 | double theta; 5 | }; -------------------------------------------------------------------------------- /src/dstar/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | dstar_global_planner 4 | 0.0.1 5 | The dstar_global_planner package 6 | 7 | fuyuan yang 8 | BSD 9 | 10 | 11 | catkin 12 | geometry_msgs 13 | nav_msgs 14 | roscpp 15 | rospy 16 | std_msgs 17 | tf 18 | cmake_modules 19 | pluginlib 20 | costmap_2d 21 | nav_core 22 | 23 | nav_core 24 | costmap_2d 25 | pluginlib 26 | cmake_modules 27 | geometry_msgs 28 | nav_msgs 29 | roscpp 30 | rospy 31 | std_msgs 32 | tf 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | -------------------------------------------------------------------------------- /src/hector_slam/.gitignore: -------------------------------------------------------------------------------- 1 | bin/ 2 | build/ 3 | lib/ 4 | msg_gen/ 5 | srv_gen/ 6 | hector_mapping/src/hector_mapping/ 7 | hector_nav_msgs/src/hector_nav_msgs/ 8 | .idea/ 9 | .vscode/ 10 | cmake-build-*/ 11 | -------------------------------------------------------------------------------- /src/hector_slam/README.txt: -------------------------------------------------------------------------------- 1 | # hector_slam 2 | 3 | See the ROS Wiki for documentation: http://wiki.ros.org/hector_slam 4 | -------------------------------------------------------------------------------- /src/hector_slam/hector_compressed_map_transport/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_compressed_map_transport 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.6 (2019-10-31) 6 | ------------------ 7 | 8 | 0.3.5 (2016-06-24) 9 | ------------------ 10 | * Use the FindEigen3.cmake module provided by Eigen 11 | * Contributors: Johannes Meyer 12 | 13 | 0.3.4 (2015-11-07) 14 | ------------------ 15 | 16 | 0.3.3 (2014-06-15) 17 | ------------------ 18 | * fixed cmake find for eigen in indigo 19 | * fixed libopencv-dev rosdep key 20 | * Contributors: Alexander Stumpf, Johannes Meyer 21 | 22 | 0.3.2 (2014-03-30) 23 | ------------------ 24 | 25 | 0.3.1 (2013-10-09) 26 | ------------------ 27 | * added changelogs 28 | 29 | 0.3.0 (2013-08-08) 30 | ------------------ 31 | * catkinized hector_slam 32 | -------------------------------------------------------------------------------- /src/hector_slam/hector_geotiff/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_geotiff 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.6 (2019-10-31) 6 | ------------------ 7 | * Update geotiff draw interface to support different shapes 8 | * Contributors: Stefan Kohlbrecher 9 | 10 | 0.3.5 (2016-06-24) 11 | ------------------ 12 | * Use the FindEigen3.cmake module provided by Eigen 13 | * hector_geotiff/hector_geotiff_plugins: added possibility to specify Color of robot path in the geotiff file in order to allow multiple color robot paths 14 | * Contributors: Dorothea Koert, Johannes Meyer 15 | 16 | 0.3.4 (2015-11-07) 17 | ------------------ 18 | * Removes trailing spaces and fixes indents 19 | * Contributors: YuK_Ota 20 | 21 | 0.3.3 (2014-06-15) 22 | ------------------ 23 | * fixed cmake find for eigen in indigo 24 | * added launchfile to restart geotiff node 25 | * Contributors: Alexander Stumpf 26 | 27 | 0.3.2 (2014-03-30) 28 | ------------------ 29 | * Add TrajectoryMapWriter to geotiff_mapper.launch per default 30 | * Add arguments to launch files for specifying geotiff file path 31 | * Contributors: Stefan Kohlbrecher 32 | 33 | 0.3.1 (2013-10-09) 34 | ------------------ 35 | * added missing install rule for launch files 36 | * moved header files from include/geotiff_writer to include/hector_geotiff 37 | * fixed warnings for deprecated pluginlib method/macro calls 38 | * added changelogs 39 | 40 | 0.3.0 (2013-08-08) 41 | ------------------ 42 | * catkinized hector_slam 43 | -------------------------------------------------------------------------------- /src/hector_slam/hector_geotiff/launch/geotiff_mapper.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | -------------------------------------------------------------------------------- /src/hector_slam/hector_geotiff/launch/geotiff_mapper_only.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /src/hector_slam/hector_geotiff_plugins/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_geotiff_plugins 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.6 (2019-10-31) 6 | ------------------ 7 | 8 | 0.3.5 (2016-06-24) 9 | ------------------ 10 | * hector_geotiff/hector_geotiff_plugins: added possibility to specify Color of robot path in the geotiff file in order to allow multiple color robot paths 11 | * Contributors: Dorothea Koert 12 | 13 | 0.3.4 (2015-11-07) 14 | ------------------ 15 | 16 | 0.3.3 (2014-06-15) 17 | ------------------ 18 | 19 | 0.3.2 (2014-03-30) 20 | ------------------ 21 | 22 | 0.3.1 (2013-10-09) 23 | ------------------ 24 | * readded PLUGINLIB_DECLARE_CLASS macro for fuerte compatibility 25 | * use hector_geotiff_plugins/TrajectoryMapWriter as legacy lookup name for the trajectory geotiff plugin to not break old launch files 26 | * fixed warnings for deprecated pluginlib method/macro calls 27 | * added changelogs 28 | * added cmake dependencies to catkin exported targets to force message targets to be built before any cpp target using them 29 | 30 | 0.3.0 (2013-08-08) 31 | ------------------ 32 | * catkinized hector_slam 33 | -------------------------------------------------------------------------------- /src/hector_slam/hector_geotiff_plugins/hector_geotiff_plugins.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | This is a MapWriter plugin that draws the robot's trajectory in the map. 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /src/hector_slam/hector_imu_attitude_to_tf/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_imu_attitude_to_tf 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.6 (2019-10-31) 6 | ------------------ 7 | 8 | 0.3.5 (2016-06-24) 9 | ------------------ 10 | 11 | 0.3.4 (2015-11-07) 12 | ------------------ 13 | * hector_imu_attitude_to_tf: fixed default values of the base_frame and base_stabilized_frame parameters (fix #20) 14 | * Contributors: Johannes Meyer 15 | 16 | 0.3.3 (2014-06-15) 17 | ------------------ 18 | 19 | 0.3.2 (2014-03-30) 20 | ------------------ 21 | 22 | 0.3.1 (2013-10-09) 23 | ------------------ 24 | * added missing install rule for launch files 25 | * added changelogs 26 | 27 | 0.3.0 (2013-08-08) 28 | ------------------ 29 | * catkinized hector_slam 30 | -------------------------------------------------------------------------------- /src/hector_slam/hector_imu_attitude_to_tf/launch/example.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /src/hector_slam/hector_imu_tools/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_imu_tools 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.6 (2019-10-31) 6 | ------------------ 7 | 8 | 0.3.5 (2016-06-24) 9 | ------------------ 10 | 11 | 0.3.4 (2015-11-07) 12 | ------------------ 13 | * Fix sim setup 14 | * remap for bertl setup 15 | * Contributors: Florian Kunz, kohlbrecher 16 | 17 | 0.3.3 (2014-06-15) 18 | ------------------ 19 | * hector_imu_tools: Basics of simple height etimation 20 | * hector_imu_tools: Add tf publishers in hector_imu_tools 21 | * hector_imu_tools: Also write out fake odometry 22 | * hector_imu_tools: Fix typo 23 | * hector_imu_tools: Prevent race conditions in slam, formatting 24 | * hector_imu_tools: Small executable for generating a IMU message out of a (2d) pose and roll/pitch imu message 25 | * Contributors: Stefan Kohlbrecher 26 | -------------------------------------------------------------------------------- /src/hector_slam/hector_imu_tools/launch/bertl_robot.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /src/hector_slam/hector_imu_tools/launch/jasmine_robot.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | -------------------------------------------------------------------------------- /src/hector_slam/hector_map_server/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_map_server 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.6 (2019-10-31) 6 | ------------------ 7 | 8 | 0.3.5 (2016-06-24) 9 | ------------------ 10 | 11 | 0.3.4 (2015-11-07) 12 | ------------------ 13 | 14 | 0.3.3 (2014-06-15) 15 | ------------------ 16 | 17 | 0.3.2 (2014-03-30) 18 | ------------------ 19 | 20 | 0.3.1 (2013-10-09) 21 | ------------------ 22 | * added changelogs 23 | * added cmake dependencies to catkin exported targets to force message targets to be built before any cpp target using them 24 | 25 | 0.3.0 (2013-08-08) 26 | ------------------ 27 | * catkinized hector_slam 28 | -------------------------------------------------------------------------------- /src/hector_slam/hector_map_tools/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_map_tools 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.6 (2019-10-31) 6 | ------------------ 7 | * hector_map_tools: Use the FindEigen3.cmake module provided by Eigen 8 | This patch applies the recommendation from http://wiki.ros.org/jade/Migration and removes the 9 | dependency from package cmake_modules (unless your installation of Eigen3 does not provide a 10 | cmake config). 11 | Same as 1251d9dc20854f48da116eed25780c103a5bd003, but package hector_map_tools was not updated 12 | back then. 13 | * Contributors: Johannes Meyer 14 | 15 | 0.3.5 (2016-06-24) 16 | ------------------ 17 | 18 | 0.3.4 (2015-11-07) 19 | ------------------ 20 | * -Fix severe bug when not using square size maps (would results in completely wrong obstacle distances and coordinates) 21 | * Contributors: Stefan Kohlbrecher 22 | 23 | 0.3.3 (2014-06-15) 24 | ------------------ 25 | 26 | 0.3.2 (2014-03-30) 27 | ------------------ 28 | 29 | 0.3.1 (2013-10-09) 30 | ------------------ 31 | * added changelogs 32 | 33 | 0.3.0 (2013-08-08) 34 | ------------------ 35 | * catkinized hector_slam 36 | -------------------------------------------------------------------------------- /src/hector_slam/hector_mapping/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_mapping 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.6 (2019-10-31) 6 | ------------------ 7 | * Merge pull request `#49 `_ from davidbsp/catkin 8 | populate child_frame_id in odometry msg 9 | * Added child_frame_id in hector mapping's odometry msg 10 | * Contributors: David Portugal, Johannes Meyer 11 | 12 | 0.3.5 (2016-06-24) 13 | ------------------ 14 | * Use the FindEigen3.cmake module provided by Eigen 15 | * Contributors: Johannes Meyer 16 | 17 | 0.3.4 (2015-11-07) 18 | ------------------ 19 | 20 | 0.3.3 (2014-06-15) 21 | ------------------ 22 | 23 | 0.3.2 (2014-03-30) 24 | ------------------ 25 | 26 | 0.3.1 (2013-10-09) 27 | ------------------ 28 | * respect ``p_map_frame_`` 29 | * added changelogs 30 | 31 | 0.3.0 (2013-08-08) 32 | ------------------ 33 | * catkinized hector_slam 34 | * hector_mapping: fixed multi-resolution map scan matching index bug in MapRepMultiMap.h 35 | -------------------------------------------------------------------------------- /src/hector_slam/hector_mapping/msg/HectorDebugInfo.msg: -------------------------------------------------------------------------------- 1 | HectorIterData[] iterData -------------------------------------------------------------------------------- /src/hector_slam/hector_mapping/msg/HectorIterData.msg: -------------------------------------------------------------------------------- 1 | float64[9] hessian 2 | float64 conditionNum 3 | float64 determinant 4 | float64 conditionNum2d 5 | float64 determinant2d 6 | -------------------------------------------------------------------------------- /src/hector_slam/hector_mapping/src/HectorMapMutex.h: -------------------------------------------------------------------------------- 1 | #ifndef hectormapmutex_h__ 2 | #define hectormapmutex_h__ 3 | 4 | #include "util/MapLockerInterface.h" 5 | 6 | #include 7 | 8 | class HectorMapMutex : public MapLockerInterface 9 | { 10 | public: 11 | virtual void lockMap() 12 | { 13 | mapModifyMutex_.lock(); 14 | } 15 | 16 | virtual void unlockMap() 17 | { 18 | mapModifyMutex_.unlock(); 19 | } 20 | 21 | boost::mutex mapModifyMutex_; 22 | }; 23 | 24 | #endif 25 | -------------------------------------------------------------------------------- /src/hector_slam/hector_marker_drawing/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_marker_drawing 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.6 (2019-10-31) 6 | ------------------ 7 | 8 | 0.3.5 (2016-06-24) 9 | ------------------ 10 | * Use the FindEigen3.cmake module provided by Eigen 11 | * Contributors: Johannes Meyer 12 | 13 | 0.3.4 (2015-11-07) 14 | ------------------ 15 | 16 | 0.3.3 (2014-06-15) 17 | ------------------ 18 | * fixed cmake find for eigen in indigo 19 | * Contributors: Alexander Stumpf 20 | 21 | 0.3.2 (2014-03-30) 22 | ------------------ 23 | 24 | 0.3.1 (2013-10-09) 25 | ------------------ 26 | * added changelogs 27 | 28 | 0.3.0 (2013-08-08) 29 | ------------------ 30 | * catkinized hector_slam 31 | -------------------------------------------------------------------------------- /src/hector_slam/hector_nav_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_nav_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.6 (2019-10-31) 6 | ------------------ 7 | 8 | 0.3.5 (2016-06-24) 9 | ------------------ 10 | 11 | 0.3.4 (2015-11-07) 12 | ------------------ 13 | * hector_nav_msgs: removed yaw member from GetNormal response 14 | yaw is implicitly given by the normal vector 15 | * Contributors: Dorothea Koert 16 | 17 | 0.3.3 (2014-06-15) 18 | ------------------ 19 | * added GetNormal service, that returns normal and orientation of an occupied cell 20 | * Contributors: Dorothea Koert 21 | 22 | 0.3.2 (2014-03-30) 23 | ------------------ 24 | 25 | 0.3.1 (2013-10-09) 26 | ------------------ 27 | * added changelogs 28 | 29 | 0.3.0 (2013-08-08) 30 | ------------------ 31 | * catkinized hector_slam 32 | -------------------------------------------------------------------------------- /src/hector_slam/hector_nav_msgs/srv/GetDistanceToObstacle.srv: -------------------------------------------------------------------------------- 1 | # Returns the distance to the next obstacle from the origin of frame point.header.frame_id 2 | # in the direction of the point 3 | # 4 | # All units are meters. 5 | 6 | geometry_msgs/PointStamped point 7 | --- 8 | float32 distance 9 | geometry_msgs/PointStamped end_point 10 | 11 | 12 | -------------------------------------------------------------------------------- /src/hector_slam/hector_nav_msgs/srv/GetNormal.srv: -------------------------------------------------------------------------------- 1 | geometry_msgs/PointStamped point 2 | --- 3 | geometry_msgs/Vector3 normal 4 | -------------------------------------------------------------------------------- /src/hector_slam/hector_nav_msgs/srv/GetRecoveryInfo.srv: -------------------------------------------------------------------------------- 1 | # Returns the path travelled to get to req_pose (pose determined by request_time) 2 | # up to request_radius away from req_pose. 3 | # 4 | 5 | time request_time 6 | float64 request_radius 7 | --- 8 | nav_msgs/Path trajectory_radius_entry_pose_to_req_pose 9 | geometry_msgs/PoseStamped radius_entry_pose 10 | geometry_msgs/PoseStamped req_pose 11 | 12 | -------------------------------------------------------------------------------- /src/hector_slam/hector_nav_msgs/srv/GetRobotTrajectory.srv: -------------------------------------------------------------------------------- 1 | # Returns the distance to the next obstacle from the origin of frame point.header.frame_id 2 | # in the direction of the point 3 | # 4 | # All units are meters. 5 | 6 | --- 7 | nav_msgs/Path trajectory 8 | 9 | -------------------------------------------------------------------------------- /src/hector_slam/hector_nav_msgs/srv/GetSearchPosition.srv: -------------------------------------------------------------------------------- 1 | #Returns a suggested search/observation position for an object of interest located at ooi_pose 2 | 3 | geometry_msgs/PoseStamped ooi_pose 4 | float32 distance 5 | --- 6 | geometry_msgs/PoseStamped search_pose 7 | 8 | -------------------------------------------------------------------------------- /src/hector_slam/hector_slam/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_slam 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.6 (2019-10-31) 6 | ------------------ 7 | 8 | 0.3.5 (2016-06-24) 9 | ------------------ 10 | 11 | 0.3.4 (2015-11-07) 12 | ------------------ 13 | 14 | 0.3.3 (2014-06-15) 15 | ------------------ 16 | 17 | 0.3.2 (2014-03-30) 18 | ------------------ 19 | 20 | 0.3.1 (2013-10-09) 21 | ------------------ 22 | * added changelogs 23 | 24 | 0.3.0 (2013-08-08) 25 | ------------------ 26 | * catkinized hector_slam 27 | -------------------------------------------------------------------------------- /src/hector_slam/hector_slam/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(hector_slam) 3 | find_package(catkin REQUIRED) 4 | catkin_metapackage() 5 | -------------------------------------------------------------------------------- /src/hector_slam/hector_slam_launch/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_slam_launch 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.6 (2019-10-31) 6 | ------------------ 7 | 8 | 0.3.5 (2016-06-24) 9 | ------------------ 10 | 11 | 0.3.4 (2015-11-07) 12 | ------------------ 13 | * Removes trailing spaces and fixes indents 14 | * "rviz_cfg" directory in the repository version. 15 | * Contributors: YuK_Ota, dani-carbonell 16 | 17 | 0.3.3 (2014-06-15) 18 | ------------------ 19 | 20 | 0.3.2 (2014-03-30) 21 | ------------------ 22 | * Add arguments to launch files for specifying geotiff file path 23 | * Update rviz config to have proper default displays 24 | * deleted quadrotor_uav.launch (moved to hector_quadrotor) 25 | * Contributors: Johannes Meyer, Stefan Kohlbrecher 26 | 27 | 0.3.1 (2013-10-09) 28 | ------------------ 29 | * updated rviz config to the new .rviz format 30 | * added changelogs 31 | 32 | 0.3.0 (2013-08-08) 33 | ------------------ 34 | * catkinized hector_slam 35 | -------------------------------------------------------------------------------- /src/hector_slam/hector_slam_launch/launch/hector_ugv.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | -------------------------------------------------------------------------------- /src/hector_slam/hector_slam_launch/launch/height_mapping.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | -------------------------------------------------------------------------------- /src/hector_slam/hector_slam_launch/launch/mpo700_mapping.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | -------------------------------------------------------------------------------- /src/hector_slam/hector_slam_launch/launch/postproc_data.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /src/hector_slam/hector_slam_launch/launch/postproc_qut_logs.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /src/hector_slam/hector_slam_launch/launch/tutorial.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /src/hector_slam/hector_trajectory_server/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package hector_trajectory_server 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.6 (2019-10-31) 6 | ------------------ 7 | 8 | 0.3.5 (2016-06-24) 9 | ------------------ 10 | * Changed from ros::WallTime to ros::Time in trajectory server 11 | * hector_trajectory_server: removed bug leading to potential infinite loop 12 | * Contributors: Andreas Lindahl Flåten, Paul Manns 13 | 14 | 0.3.4 (2015-11-07) 15 | ------------------ 16 | 17 | 0.3.3 (2014-06-15) 18 | ------------------ 19 | 20 | 0.3.2 (2014-03-30) 21 | ------------------ 22 | * wait based on WallTime and check ros::ok() in waitForTf() 23 | * Print out tf availability warning only once. 24 | * Wait for tf become available to suppress warnings on startup 25 | * Create a warning instead of an error for TransformExceptions 26 | * Contributors: Johannes Meyer, Stefan Kohlbrecher, wachaja 27 | 28 | 0.3.1 (2013-10-09) 29 | ------------------ 30 | * added changelogs 31 | * added cmake dependencies to catkin exported targets to force message targets to be built before any cpp target using them 32 | 33 | 0.3.0 (2013-08-08) 34 | ------------------ 35 | * catkinized hector_slam 36 | -------------------------------------------------------------------------------- /src/navigation/.gitignore: -------------------------------------------------------------------------------- 1 | *~ 2 | *.project 3 | *.cproject 4 | 5 | -------------------------------------------------------------------------------- /src/navigation/README.md: -------------------------------------------------------------------------------- 1 | ROS Navigation Stack 2 | ==================== 3 | 4 | A 2D navigation stack that takes in information from odometry, sensor 5 | streams, and a goal pose and outputs safe velocity commands that are sent 6 | to a mobile base. 7 | 8 | * AMD64 Debian Job Status: [![Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__navigation__ubuntu_xenial_amd64__binary)](http://build.ros.org/view/Kbin_uX64/job/Kbin_uX64__navigation__ubuntu_xenial_amd64__binary/) 9 | 10 | Related stacks: 11 | 12 | * http://github.com/ros-planning/navigation_msgs (new in Jade+) 13 | * http://github.com/ros-planning/navigation_tutorials 14 | * http://github.com/ros-planning/navigation_experimental 15 | 16 | For discussion, please check out the 17 | https://groups.google.com/group/ros-sig-navigation mailing list. 18 | -------------------------------------------------------------------------------- /src/navigation/amcl/examples/amcl_diff.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | -------------------------------------------------------------------------------- /src/navigation/amcl/examples/amcl_omni.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | -------------------------------------------------------------------------------- /src/navigation/amcl/include/amcl/pf/eig3.h: -------------------------------------------------------------------------------- 1 | 2 | /* Eigen-decomposition for symmetric 3x3 real matrices. 3 | Public domain, copied from the public domain Java library JAMA. */ 4 | 5 | #ifndef _eig_h 6 | 7 | /* Symmetric matrix A => eigenvectors in columns of V, corresponding 8 | eigenvalues in d. */ 9 | void eigen_decomposition(double A[3][3], double V[3][3], double d[3]); 10 | 11 | #endif 12 | -------------------------------------------------------------------------------- /src/navigation/amcl/package.xml: -------------------------------------------------------------------------------- 1 | 2 | amcl 3 | 1.14.7 4 | 5 |

6 | amcl is a probabilistic localization system for a robot moving in 7 | 2D. It implements the adaptive (or KLD-sampling) Monte Carlo 8 | localization approach (as described by Dieter Fox), which uses a 9 | particle filter to track the pose of a robot against a known map. 10 |

11 |

12 | This node is derived, with thanks, from Andrew Howard's excellent 13 | 'amcl' Player driver. 14 |

15 |
16 | http://wiki.ros.org/amcl 17 | Brian P. Gerkey 18 | contradict@gmail.com 19 | David V. Lu!! 20 | Michael Ferguson 21 | Aaron Hoy 22 | LGPL 23 | 24 | catkin 25 | 26 | rosbag 27 | dynamic_reconfigure 28 | message_filters 29 | nav_msgs 30 | roscpp 31 | std_srvs 32 | tf 33 | 34 | rosbag 35 | roscpp 36 | dynamic_reconfigure 37 | tf 38 | nav_msgs 39 | std_srvs 40 | 41 | rostest 42 | map_server 43 |
44 | -------------------------------------------------------------------------------- /src/navigation/amcl/test/set_pose.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | import rospy 4 | 5 | import math 6 | from tf import transformations 7 | from geometry_msgs.msg import PoseWithCovarianceStamped 8 | 9 | 10 | class PoseSetter(rospy.SubscribeListener): 11 | def __init__(self, pose, stamp, publish_time): 12 | self.pose = pose 13 | self.stamp = stamp 14 | self.publish_time = publish_time 15 | 16 | def peer_subscribe(self, topic_name, topic_publish, peer_publish): 17 | p = PoseWithCovarianceStamped() 18 | p.header.frame_id = "map" 19 | p.header.stamp = self.stamp 20 | p.pose.pose.position.x = self.pose[0] 21 | p.pose.pose.position.y = self.pose[1] 22 | (p.pose.pose.orientation.x, 23 | p.pose.pose.orientation.y, 24 | p.pose.pose.orientation.z, 25 | p.pose.pose.orientation.w) = transformations.quaternion_from_euler(0, 0, self.pose[2]) 26 | p.pose.covariance[6*0+0] = 0.5 * 0.5 27 | p.pose.covariance[6*1+1] = 0.5 * 0.5 28 | p.pose.covariance[6*3+3] = math.pi/12.0 * math.pi/12.0 29 | # wait for the desired publish time 30 | while rospy.get_rostime() < self.publish_time: 31 | rospy.sleep(0.01) 32 | peer_publish(p) 33 | 34 | 35 | if __name__ == '__main__': 36 | pose = map(float, rospy.myargv()[1:4]) 37 | t_stamp = rospy.Time() 38 | t_publish = rospy.Time() 39 | if len(rospy.myargv()) > 4: 40 | t_stamp = rospy.Time.from_sec(float(rospy.myargv()[4])) 41 | if len(rospy.myargv()) > 5: 42 | t_publish = rospy.Time.from_sec(float(rospy.myargv()[5])) 43 | rospy.init_node('pose_setter', anonymous=True) 44 | rospy.loginfo("Going to publish pose {} with stamp {} at {}".format(pose, t_stamp.to_sec(), t_publish.to_sec())) 45 | pub = rospy.Publisher("initialpose", PoseWithCovarianceStamped, PoseSetter(pose, stamp=t_stamp, publish_time=t_publish), queue_size=1) 46 | rospy.spin() 47 | -------------------------------------------------------------------------------- /src/navigation/amcl/test/texas_greenroom_loop.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 37 | 38 | -------------------------------------------------------------------------------- /src/navigation/amcl/test/texas_greenroom_loop_corrected.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 37 | 38 | -------------------------------------------------------------------------------- /src/navigation/amcl/test/texas_willow_hallway_loop_corrected.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 37 | 38 | -------------------------------------------------------------------------------- /src/navigation/base_local_planner/blp_plugin.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | A implementation of a local planner using either a DWA or Trajectory Rollout approach based on configuration parameters. 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /src/navigation/base_local_planner/cfg/LocalPlannerLimits.cfg: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | # Generic Local Planner configuration 3 | 4 | # from dynamic_reconfigure.parameter_generator_catkin import * 5 | 6 | 7 | # if __name__ == "__main__": 8 | # gen = ParameterGenerator() 9 | # add_generic_localplanner_params(gen) 10 | # exit(gen.generate(PACKAGE, "base_local_planner", "LocalPlannerLimits")) 11 | -------------------------------------------------------------------------------- /src/navigation/base_local_planner/msg/Position2DInt.msg: -------------------------------------------------------------------------------- 1 | int64 x 2 | int64 y -------------------------------------------------------------------------------- /src/navigation/base_local_planner/setup.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | from distutils.core import setup 3 | from catkin_pkg.python_setup import generate_distutils_setup 4 | 5 | d = generate_distutils_setup( 6 | packages = ['local_planner_limits'], 7 | package_dir = {'': 'src'}, 8 | ) 9 | 10 | setup(**d) 11 | -------------------------------------------------------------------------------- /src/navigation/base_local_planner/src/local_planner_limits/.gitignore: -------------------------------------------------------------------------------- 1 | *.pyc 2 | -------------------------------------------------------------------------------- /src/navigation/base_local_planner/src/prefer_forward_cost_function.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * prefer_forward_cost_function.cpp 3 | * 4 | * Created on: Apr 4, 2012 5 | * Author: tkruse 6 | */ 7 | 8 | #include 9 | 10 | #include 11 | 12 | namespace base_local_planner { 13 | 14 | 15 | double PreferForwardCostFunction::scoreTrajectory(Trajectory &traj) { 16 | // backward motions bad on a robot without backward sensors 17 | if (traj.xv_ < 0.0) { 18 | return penalty_; 19 | } 20 | // strafing motions also bad on such a robot 21 | if (traj.xv_ < 0.1 && fabs(traj.thetav_) < 0.2) { 22 | return penalty_; 23 | } 24 | // the more we rotate, the less we progress forward 25 | return fabs(traj.thetav_) * 10; 26 | } 27 | 28 | } /* namespace base_local_planner */ 29 | -------------------------------------------------------------------------------- /src/navigation/base_local_planner/src/twirling_cost_function.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * twirling_cost_function.cpp 3 | * 4 | * Created on: Apr 20, 2016 5 | * Author: Morgan Quigley 6 | */ 7 | 8 | #include 9 | 10 | #include 11 | 12 | namespace base_local_planner { 13 | 14 | double TwirlingCostFunction::scoreTrajectory(Trajectory &traj) { 15 | return fabs(traj.thetav_); // add cost for making the robot spin 16 | } 17 | 18 | } /* namespace base_local_planner */ 19 | -------------------------------------------------------------------------------- /src/navigation/base_local_planner/test/gtest_main.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * gtest_main.cpp 3 | * 4 | * Created on: Apr 6, 2012 5 | * Author: tkruse 6 | */ 7 | 8 | #include 9 | 10 | #include 11 | 12 | int main(int argc, char **argv) { 13 | std::cout << "Running main() from gtest_main.cc\n"; 14 | 15 | testing::InitGoogleTest(&argc, argv); 16 | return RUN_ALL_TESTS(); 17 | } 18 | 19 | -------------------------------------------------------------------------------- /src/navigation/base_local_planner/test/trajectory_generator_test.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * footprint_helper_test.cpp 3 | * 4 | * Created on: May 2, 2012 5 | * Author: tkruse 6 | */ 7 | 8 | #include 9 | 10 | #include 11 | 12 | #include 13 | 14 | namespace base_local_planner { 15 | 16 | class TrajectoryGeneratorTest : public testing::Test { 17 | public: 18 | SimpleTrajectoryGenerator tg; 19 | 20 | TrajectoryGeneratorTest() { 21 | } 22 | 23 | virtual void TestBody(){} 24 | }; 25 | 26 | } 27 | -------------------------------------------------------------------------------- /src/navigation/base_local_planner/test/wavefront_map_accessor.h: -------------------------------------------------------------------------------- 1 | /* 2 | * wavefront_map_accessor.h 3 | * 4 | * Created on: May 2, 2012 5 | * Author: tkruse 6 | */ 7 | 8 | #ifndef WAVEFRONT_MAP_ACCESSOR_H_ 9 | #define WAVEFRONT_MAP_ACCESSOR_H_ 10 | #include 11 | namespace base_local_planner { 12 | 13 | /** 14 | * Map_grids rely on costmaps to identify obstacles. We need a costmap that we can easily manipulate for unit tests. 15 | * This class has a grid map where we can set grid cell state, and a synchronize method to make the costmap match. 16 | */ 17 | class WavefrontMapAccessor : public costmap_2d::Costmap2D { 18 | public: 19 | WavefrontMapAccessor(MapGrid* map, double outer_radius) 20 | : costmap_2d::Costmap2D(map->size_x_, map->size_y_, 1, 0, 0), 21 | map_(map), outer_radius_(outer_radius) { 22 | synchronize(); 23 | } 24 | 25 | virtual ~WavefrontMapAccessor(){}; 26 | 27 | void synchronize(){ 28 | // Write Cost Data from the map 29 | for(unsigned int x = 0; x < size_x_; x++){ 30 | for (unsigned int y = 0; y < size_y_; y++){ 31 | unsigned int ind = x + (y * size_x_); 32 | if(map_->operator ()(x, y).target_dist == 1) { 33 | costmap_[ind] = costmap_2d::LETHAL_OBSTACLE; 34 | } else { 35 | costmap_[ind] = 0; 36 | } 37 | } 38 | } 39 | } 40 | 41 | private: 42 | MapGrid* map_; 43 | double outer_radius_; 44 | }; 45 | 46 | } 47 | 48 | 49 | 50 | #endif /* WAVEFRONT_MAP_ACCESSOR_H_ */ 51 | -------------------------------------------------------------------------------- /src/navigation/carrot_planner/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package carrot_planner 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.14.7 (2020-03-10) 6 | ------------------- 7 | 8 | 1.14.6 (2020-03-04) 9 | ------------------- 10 | 11 | 1.14.5 (2019-11-15) 12 | ------------------- 13 | 14 | 1.14.4 (2018-06-19) 15 | ------------------- 16 | 17 | 1.14.3 (2018-03-16) 18 | ------------------- 19 | * Merge pull request `#672 `_ from ros-planning/email_update_kinetic 20 | update maintainer email (kinetic) 21 | * Merge pull request `#648 `_ from aaronhoy/kinetic_add_ahoy 22 | Add myself as a maintainer. 23 | * Contributors: Aaron Hoy, Michael Ferguson 24 | 25 | 1.14.2 (2017-08-14) 26 | ------------------- 27 | 28 | 1.14.1 (2017-08-07) 29 | ------------------- 30 | * Fix CMakeLists + package.xmls (`#548 `_) 31 | * Contributors: Martin Günther, Vincent Rabaud 32 | 33 | 1.14.0 (2016-05-20) 34 | ------------------- 35 | 36 | 1.13.1 (2015-10-29) 37 | ------------------- 38 | 39 | 1.13.0 (2015-03-17) 40 | ------------------- 41 | 42 | 1.12.0 (2015-02-04) 43 | ------------------- 44 | * update maintainer email 45 | * Contributors: Michael Ferguson 46 | 47 | 1.11.15 (2015-02-03) 48 | -------------------- 49 | * Add ARCHIVE_DESTINATION for static builds 50 | * Contributors: Gary Servin 51 | 52 | 1.11.14 (2014-12-05) 53 | -------------------- 54 | 55 | 1.11.13 (2014-10-02) 56 | -------------------- 57 | 58 | 1.11.12 (2014-10-01) 59 | -------------------- 60 | 61 | 1.11.11 (2014-07-23) 62 | -------------------- 63 | 64 | 1.11.10 (2014-06-25) 65 | -------------------- 66 | 67 | 1.11.9 (2014-06-10) 68 | ------------------- 69 | 70 | 1.11.8 (2014-05-21) 71 | ------------------- 72 | 73 | 1.11.7 (2014-05-21) 74 | ------------------- 75 | 76 | 1.11.4 (2013-09-27) 77 | ------------------- 78 | * Package URL Updates 79 | -------------------------------------------------------------------------------- /src/navigation/carrot_planner/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(carrot_planner) 3 | 4 | find_package(catkin REQUIRED 5 | COMPONENTS 6 | roscpp 7 | tf 8 | nav_core 9 | costmap_2d 10 | base_local_planner 11 | pluginlib 12 | ) 13 | 14 | include_directories( 15 | include 16 | ${catkin_INCLUDE_DIRS} 17 | ) 18 | add_definitions(${EIGEN3_DEFINITIONS}) 19 | 20 | catkin_package( 21 | INCLUDE_DIRS include 22 | LIBRARIES carrot_planner 23 | CATKIN_DEPENDS 24 | roscpp 25 | pluginlib 26 | costmap_2d 27 | base_local_planner 28 | nav_core 29 | ) 30 | 31 | add_library(carrot_planner src/carrot_planner.cpp) 32 | add_dependencies(carrot_planner ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 33 | target_link_libraries(carrot_planner 34 | ${catkin_LIBRARIES} 35 | ) 36 | 37 | install(TARGETS carrot_planner 38 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 39 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 40 | ) 41 | 42 | install(DIRECTORY include/${PROJECT_NAME}/ 43 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 44 | PATTERN ".svn" EXCLUDE 45 | ) 46 | 47 | install(FILES bgp_plugin.xml 48 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 49 | ) 50 | 51 | 52 | -------------------------------------------------------------------------------- /src/navigation/carrot_planner/bgp_plugin.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | A simple planner that seeks to place a legal carrot in-front of the robot 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /src/navigation/carrot_planner/package.xml: -------------------------------------------------------------------------------- 1 | 2 | carrot_planner 3 | 1.14.7 4 | 5 | 6 | This planner attempts to find a legal place to put a carrot for the robot to follow. It does this by moving back along the vector between the robot and the goal point. 7 | 8 | 9 | Eitan Marder-Eppstein 10 | Sachin Chitta 11 | contradict@gmail.com 12 | David V. Lu!! 13 | Michael Ferguson 14 | Aaron Hoy 15 | BSD 16 | http://wiki.ros.org/carrot_planner 17 | 18 | catkin 19 | 20 | roscpp 21 | costmap_2d 22 | pluginlib 23 | nav_core 24 | base_local_planner 25 | tf 26 | 27 | eigen 28 | 29 | roscpp 30 | costmap_2d 31 | pluginlib 32 | nav_core 33 | base_local_planner 34 | tf 35 | 36 | eigen 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | -------------------------------------------------------------------------------- /src/navigation/clear_costmap_recovery/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(clear_costmap_recovery) 3 | 4 | find_package(catkin REQUIRED 5 | COMPONENTS 6 | cmake_modules 7 | costmap_2d 8 | nav_core 9 | pluginlib 10 | roscpp 11 | tf 12 | ) 13 | 14 | find_package(Eigen3 REQUIRED) 15 | find_package(PCL REQUIRED) 16 | remove_definitions(-DDISABLE_LIBUSB-1.0) 17 | include_directories( 18 | include 19 | ${catkin_INCLUDE_DIRS} 20 | ${EIGEN3_INCLUDE_DIRS} 21 | ${PCL_INCLUDE_DIRS} 22 | ) 23 | add_definitions(${EIGEN3_DEFINITIONS}) 24 | 25 | catkin_package( 26 | INCLUDE_DIRS include 27 | LIBRARIES clear_costmap_recovery 28 | CATKIN_DEPENDS 29 | costmap_2d 30 | nav_core 31 | pluginlib 32 | roscpp 33 | tf 34 | ) 35 | 36 | add_library(clear_costmap_recovery src/clear_costmap_recovery.cpp) 37 | add_dependencies(clear_costmap_recovery ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 38 | target_link_libraries(clear_costmap_recovery ${catkin_LIBRARIES}) 39 | 40 | 41 | ## Configure Tests 42 | if(CATKIN_ENABLE_TESTING) 43 | # Find package test dependencies 44 | find_package(rostest REQUIRED) 45 | 46 | # Add the test folder to the include directories 47 | include_directories(test) 48 | 49 | # Create targets for test executables 50 | add_rostest_gtest(clear_tester test/clear_tests.launch test/clear_tester.cpp) 51 | target_link_libraries(clear_tester clear_costmap_recovery ${GTEST_LIBRARIES}) 52 | endif() 53 | 54 | 55 | install(TARGETS clear_costmap_recovery 56 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 57 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 58 | ) 59 | 60 | install(FILES ccr_plugin.xml 61 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 62 | ) 63 | 64 | install(DIRECTORY include/${PROJECT_NAME}/ 65 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 66 | PATTERN ".svn" EXCLUDE 67 | ) 68 | -------------------------------------------------------------------------------- /src/navigation/clear_costmap_recovery/ccr_plugin.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | A recovery behavior that reverts the costmap to the static map outside of a user specified window. 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /src/navigation/clear_costmap_recovery/package.xml: -------------------------------------------------------------------------------- 1 | 2 | clear_costmap_recovery 3 | 1.14.7 4 | 5 | 6 | This package provides a recovery behavior for the navigation stack that attempts to clear space by reverting the costmaps used by the navigation stack to the static map outside of a given area. 7 | 8 | 9 | Eitan Marder-Eppstein 10 | contradict@gmail.com 11 | David V. Lu!! 12 | Michael Ferguson 13 | Aaron Hoy 14 | BSD 15 | http://wiki.ros.org/clear_costmap_recovery 16 | 17 | catkin 18 | 19 | cmake_modules 20 | roscpp 21 | tf 22 | costmap_2d 23 | nav_core 24 | pluginlib 25 | eigen 26 | 27 | roscpp 28 | tf 29 | costmap_2d 30 | nav_core 31 | pluginlib 32 | eigen 33 | 34 | rostest 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | -------------------------------------------------------------------------------- /src/navigation/clear_costmap_recovery/test/clear_tests.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | -------------------------------------------------------------------------------- /src/navigation/clear_costmap_recovery/test/params.yaml: -------------------------------------------------------------------------------- 1 | base: 2 | global: 3 | plugins: 4 | - {name: static_map, type: "costmap_2d::StaticLayer"} 5 | - {name: obstacles, type: "costmap_2d::ObstacleLayer"} 6 | - {name: inflation, type: "costmap_2d::InflationLayer"} 7 | obstacles: 8 | track_unknown_space: true 9 | local: 10 | plugins: [] 11 | robot_radius: .5 12 | clear: 13 | clearing_distance: 7.0 14 | -------------------------------------------------------------------------------- /src/navigation/costmap_2d/cfg/Costmap2D.cfg: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, double_t, int_t, str_t 4 | 5 | gen = ParameterGenerator() 6 | 7 | gen.add("transform_tolerance", double_t, 0, "Specifies the delay in transform (tf) data that is tolerable in seconds.", 0.3, 0, 10) 8 | gen.add("update_frequency", double_t, 0, "The frequency in Hz for the map to be updated.", 5, 0, 100) 9 | gen.add("publish_frequency", double_t, 0, "The frequency in Hz for the map to be publish display information.", 0, 0, 100) 10 | 11 | #map params 12 | gen.add("width", int_t, 0, "The width of the map in meters.", 10, 0) 13 | gen.add("height", int_t, 0, "The height of the map in meters.", 10, 0) 14 | gen.add("resolution", double_t, 0, "The resolution of the map in meters/cell.", 0.05, 0, 50) 15 | gen.add("origin_x", double_t, 0, "The x origin of the map in the global frame in meters.", 0) 16 | gen.add("origin_y", double_t, 0, "The y origin of the map in the global frame in meters.", 0) 17 | 18 | # robot footprint shape 19 | gen.add("footprint", str_t, 0, "The footprint of the robot specified in the robot_base_frame coordinate frame as a list in the format: [ [x1, y1], [x2, y2], ...., [xn, yn] ].", "[]") 20 | gen.add("robot_radius", double_t, 0, 'The radius of the robot in meters, this parameter should only be set for circular robots, all others should use the footprint parameter described above.', 0.46, 0, 10) 21 | gen.add("footprint_padding", double_t, 0, "How much to pad (increase the size of) the footprint, in meters.", 0.01) 22 | 23 | exit(gen.generate("costmap_2d", "costmap_2d", "Costmap2D")) 24 | -------------------------------------------------------------------------------- /src/navigation/costmap_2d/cfg/GenericPlugin.cfg: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, bool_t 4 | 5 | gen = ParameterGenerator() 6 | gen.add("enabled", bool_t, 0, "Whether to apply this plugin or not", True) 7 | exit(gen.generate("costmap_2d", "costmap_2d", "GenericPlugin")) 8 | -------------------------------------------------------------------------------- /src/navigation/costmap_2d/cfg/InflationPlugin.cfg: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, bool_t, double_t 4 | 5 | gen = ParameterGenerator() 6 | 7 | gen.add("enabled", bool_t, 0, "Whether to apply this plugin or not", True) 8 | gen.add("cost_scaling_factor", double_t, 0, "A scaling factor to apply to cost values during inflation.", 10, 0, 100) 9 | gen.add("inflation_radius", double_t, 0, "The radius in meters to which the map inflates obstacle cost values.", 0.55, 0, 50) 10 | gen.add("inflate_unknown", bool_t, 0, "Whether to inflate unknown cells.", False) 11 | 12 | exit(gen.generate("costmap_2d", "costmap_2d", "InflationPlugin")) 13 | -------------------------------------------------------------------------------- /src/navigation/costmap_2d/cfg/ObstaclePlugin.cfg: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, bool_t, double_t, int_t 4 | 5 | gen = ParameterGenerator() 6 | 7 | gen.add("enabled", bool_t, 0, "Whether to apply this plugin or not", True) 8 | gen.add("footprint_clearing_enabled", bool_t, 0, "Whether to clear the robot's footprint of lethal obstacles", True) 9 | gen.add("max_obstacle_height", double_t, 0, "The maximum height of any obstacle to be inserted into the costmap in meters.", 2, 0, 50) 10 | 11 | combo_enum = gen.enum([ gen.const("Overwrite", int_t, 0, "Overwrite values"), 12 | gen.const("Maximum", int_t, 1, "Take the maximum of the values"), 13 | gen.const("Nothing", int_t, 99, "Do nothing") 14 | ], 15 | "Method for combining layers enum") 16 | 17 | gen.add("combination_method", int_t, 0, "Method for combining two layers", 1, edit_method=combo_enum) 18 | 19 | 20 | #gen.add("max_obstacle_range", double_t, 0, "The default maximum distance from the robot at which an obstacle will be inserted into the cost map in meters.", 2.5, 0, 50) 21 | #gen.add("raytrace_range", double_t, 0, "The default range in meters at which to raytrace out obstacles from the map using sensor data.", 3, 0, 50) 22 | exit(gen.generate("costmap_2d", "costmap_2d", "ObstaclePlugin")) 23 | -------------------------------------------------------------------------------- /src/navigation/costmap_2d/cfg/VoxelPlugin.cfg: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, bool_t, double_t, int_t 4 | 5 | gen = ParameterGenerator() 6 | 7 | gen.add("enabled", bool_t, 0, "Whether to use this plugin or not", True) 8 | gen.add("footprint_clearing_enabled", bool_t, 0, "Whether to clear the robot's footprint of lethal obstacles", True) 9 | gen.add("max_obstacle_height", double_t, 0, "Max Obstacle Height", 2.0, 0, 50) 10 | gen.add("origin_z", double_t, 0, "The z origin of the map in meters.", 0, 0) 11 | gen.add("z_resolution", double_t, 0, "The z resolution of the map in meters/cell.", 0.2, 0, 50) 12 | gen.add("z_voxels", int_t, 0, "The number of voxels to in each vertical column.", 10, 0, 16) 13 | gen.add("unknown_threshold", int_t, 0, 'The number of unknown cells allowed in a column considered to be known', 15, 0, 16) 14 | gen.add("mark_threshold", int_t, 0, 'The maximum number of marked cells allowed in a column considered to be free', 0, 0, 16) 15 | 16 | combo_enum = gen.enum([ gen.const("Overwrite", int_t, 0, "b"), 17 | gen.const("Maximum", int_t, 1, "a") ], 18 | "Method for combining layers enum") 19 | 20 | gen.add("combination_method", int_t, 0, "Method for combining two layers", 1, 0, 2, edit_method=combo_enum) 21 | 22 | exit(gen.generate("costmap_2d", "costmap_2d", "VoxelPlugin")) 23 | -------------------------------------------------------------------------------- /src/navigation/costmap_2d/costmap_plugins.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Inflates obstacles to speed collision checking and to make robot prefer to stay away from obstacles. 5 | 6 | 7 | Listens to laser scan and point cloud messages and marks and clears grid cells. 8 | 9 | 10 | Listens to OccupancyGrid messages and copies them in, like from map_server. 11 | 12 | 13 | Similar to obstacle costmap, but uses 3D voxel grid to store data. 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /src/navigation/costmap_2d/launch/example.launch: -------------------------------------------------------------------------------- 1 | 2 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /src/navigation/costmap_2d/launch/example_params.yaml: -------------------------------------------------------------------------------- 1 | global_frame: /map 2 | robot_base_frame: base_link 3 | update_frequency: 5.0 4 | publish_frequency: 1.0 5 | 6 | #set if you want the voxel map published 7 | publish_voxel_map: true 8 | 9 | #set to true if you want to initialize the costmap from a static map 10 | static_map: false 11 | 12 | #begin - COMMENT these lines if you set static_map to true 13 | rolling_window: true 14 | width: 6.0 15 | height: 6.0 16 | resolution: 0.025 17 | #end - COMMENT these lines if you set static_map to true 18 | 19 | #START VOXEL STUFF 20 | map_type: voxel 21 | origin_z: 0.0 22 | z_resolution: 0.2 23 | z_voxels: 10 24 | unknown_threshold: 10 25 | mark_threshold: 0 26 | #END VOXEL STUFF 27 | 28 | transform_tolerance: 0.3 29 | obstacle_range: 2.5 30 | max_obstacle_height: 2.0 31 | raytrace_range: 3.0 32 | footprint: [[-0.325, -0.325], [-0.325, 0.325], [0.325, 0.325], [0.46, 0.0], [0.325, -0.325]] 33 | #robot_radius: 0.46 34 | footprint_padding: 0.01 35 | inflation_radius: 0.55 36 | cost_scaling_factor: 10.0 37 | lethal_cost_threshold: 100 38 | observation_sources: base_scan 39 | base_scan: {data_type: LaserScan, expected_update_rate: 0.4, 40 | observation_persistence: 0.0, marking: true, clearing: true, max_obstacle_height: 0.4, min_obstacle_height: 0.08} 41 | -------------------------------------------------------------------------------- /src/navigation/costmap_2d/msg/VoxelGrid.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | uint32[] data 3 | geometry_msgs/Point32 origin 4 | geometry_msgs/Vector3 resolutions 5 | uint32 size_x 6 | uint32 size_y 7 | uint32 size_z 8 | 9 | -------------------------------------------------------------------------------- /src/navigation/costmap_2d/test/TenByTen.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/src/navigation/costmap_2d/test/TenByTen.pgm -------------------------------------------------------------------------------- /src/navigation/costmap_2d/test/TenByTen.yaml: -------------------------------------------------------------------------------- 1 | image: TenByTen.pgm 2 | resolution: 1.0 3 | origin: [0,0,0] 4 | negate: 0 5 | occupied_thresh: 0.65 6 | free_thresh: 0.196 7 | 8 | -------------------------------------------------------------------------------- /src/navigation/costmap_2d/test/costmap_params.yaml: -------------------------------------------------------------------------------- 1 | global_frame: /map 2 | robot_base_frame: base_link 3 | update_frequency: 5.0 4 | publish_frequency: 0.0 5 | static_map: true 6 | rolling_window: false 7 | 8 | #START VOXEL STUFF 9 | map_type: voxel 10 | origin_z: 0.0 11 | z_resolution: 0.2 12 | z_voxels: 10 13 | unknown_threshold: 10 14 | mark_threshold: 0 15 | #END VOXEL STUFF 16 | 17 | transform_tolerance: 0.3 18 | obstacle_range: 2.5 19 | max_obstacle_height: 2.0 20 | raytrace_range: 3.0 21 | footprint: [[-0.325, -0.325], [-0.325, 0.325], [0.325, 0.325], [0.46, 0.0], [0.325, -0.325]] 22 | #robot_radius: 0.46 23 | footprint_padding: 0.01 24 | inflation_radius: 0.55 25 | cost_scaling_factor: 10.0 26 | lethal_cost_threshold: 100 27 | observation_sources: base_scan 28 | base_scan: {data_type: LaserScan, expected_update_rate: 0.4, 29 | observation_persistence: 0.0, marking: true, clearing: true, max_obstacle_height: 0.4, min_obstacle_height: 0.08} 30 | -------------------------------------------------------------------------------- /src/navigation/costmap_2d/test/footprint_tests.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | footprint_padding: 0 15 | footprint: [[0.1, 0.1], [-0.1, 0.1], [-0.1, -0.1], [0.1, -0.1]] 16 | 17 | 18 | 19 | footprint_padding: 0 20 | footprint: [[0.1, 0.1], [-0.1, 0.1, 77.0], [-0.1, -0.1], [0.1, -0.1]] 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | -------------------------------------------------------------------------------- /src/navigation/costmap_2d/test/inflation_tests.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | -------------------------------------------------------------------------------- /src/navigation/costmap_2d/test/obstacle_tests.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | -------------------------------------------------------------------------------- /src/navigation/costmap_2d/test/simple_driving_test.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | -------------------------------------------------------------------------------- /src/navigation/costmap_2d/test/static_tests.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | -------------------------------------------------------------------------------- /src/navigation/dwa_local_planner/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(dwa_local_planner) 3 | 4 | find_package(catkin REQUIRED 5 | COMPONENTS 6 | base_local_planner 7 | cmake_modules 8 | costmap_2d 9 | dynamic_reconfigure 10 | nav_core 11 | nav_msgs 12 | pluginlib 13 | pcl_conversions 14 | roscpp 15 | tf 16 | ) 17 | 18 | find_package(Eigen3 REQUIRED) 19 | find_package(PCL REQUIRED) 20 | remove_definitions(-DDISABLE_LIBUSB-1.0) 21 | include_directories( 22 | include 23 | ${catkin_INCLUDE_DIRS} 24 | ${EIGEN3_INCLUDE_DIRS} 25 | ${PCL_INCLUDE_DIRS} 26 | ) 27 | add_definitions(${EIGEN3_DEFINITIONS}) 28 | 29 | # dynamic reconfigure 30 | generate_dynamic_reconfigure_options( 31 | cfg/DWAPlanner.cfg 32 | ) 33 | 34 | catkin_package( 35 | INCLUDE_DIRS include 36 | LIBRARIES dwa_local_planner 37 | CATKIN_DEPENDS 38 | dynamic_reconfigure 39 | nav_msgs 40 | pluginlib 41 | roscpp 42 | ) 43 | 44 | add_library(dwa_local_planner src/dwa_planner.cpp src/dwa_planner_ros.cpp) 45 | add_dependencies(dwa_local_planner ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 46 | target_link_libraries(dwa_local_planner ${catkin_LIBRARIES}) 47 | 48 | install(TARGETS dwa_local_planner 49 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 50 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 51 | ) 52 | 53 | install(FILES blp_plugin.xml 54 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 55 | ) 56 | 57 | install(DIRECTORY include/${PROJECT_NAME}/ 58 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 59 | PATTERN ".svn" EXCLUDE 60 | ) 61 | -------------------------------------------------------------------------------- /src/navigation/dwa_local_planner/blp_plugin.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | A implementation of a local planner using either a DWA approach based on configuration parameters. 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /src/navigation/fake_localization/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(fake_localization) 3 | 4 | find_package(catkin REQUIRED 5 | COMPONENTS 6 | angles 7 | geometry_msgs 8 | message_filters 9 | nav_msgs 10 | rosconsole 11 | roscpp 12 | rospy 13 | tf2_geometry_msgs 14 | ) 15 | 16 | 17 | find_package(Boost REQUIRED COMPONENTS signals) 18 | 19 | catkin_package( 20 | CATKIN_DEPENDS 21 | geometry_msgs 22 | nav_msgs 23 | roscpp 24 | rospy 25 | ) 26 | 27 | include_directories(${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS}) 28 | 29 | add_executable(fake_localization fake_localization.cpp) 30 | target_link_libraries(fake_localization 31 | ${catkin_LIBRARIES} 32 | ${Boost_LIBRARIES} 33 | ) 34 | add_dependencies(fake_localization ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 35 | 36 | install( 37 | PROGRAMS 38 | static_odom_broadcaster.py 39 | DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 40 | ) 41 | 42 | install( 43 | TARGETS 44 | fake_localization 45 | DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 46 | ) 47 | -------------------------------------------------------------------------------- /src/navigation/fake_localization/package.xml: -------------------------------------------------------------------------------- 1 | 2 | fake_localization 3 | 1.14.7 4 | A ROS node that simply forwards odometry information. 5 | Ioan A. Sucan 6 | contradict@gmail.com 7 | David V. Lu!! 8 | Michael Ferguson 9 | Aaron Hoy 10 | BSD 11 | http://wiki.ros.org/fake_localization 12 | 13 | catkin 14 | 15 | angles 16 | roscpp 17 | rosconsole 18 | nav_msgs 19 | geometry_msgs 20 | tf2_geometry_msgs 21 | tf2_ros 22 | message_filters 23 | rospy 24 | 25 | roscpp 26 | rosconsole 27 | nav_msgs 28 | geometry_msgs 29 | tf2_ros 30 | message_filters 31 | rospy 32 | 33 | 34 | -------------------------------------------------------------------------------- /src/navigation/fake_localization/static_odom_broadcaster.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/python 2 | 3 | # 4 | # Similar to static_transform_broadcaster, this node constantly publishes 5 | # static odometry information (Odometry msg and tf). This can be used 6 | # with fake_localization to evaluate planning algorithms without running 7 | # an actual robot with odometry or localization 8 | # 9 | # Author: Armin Hornung 10 | # License: BSD 11 | 12 | import rospy 13 | 14 | import tf 15 | from nav_msgs.msg import Odometry 16 | from geometry_msgs.msg import Pose, Quaternion, Point 17 | 18 | 19 | def publishOdom(): 20 | rospy.init_node('fake_odom') 21 | base_frame_id = rospy.get_param("~base_frame_id", "base_link") 22 | odom_frame_id = rospy.get_param("~odom_frame_id", "odom") 23 | publish_frequency = rospy.get_param("~publish_frequency", 10.0) 24 | pub = rospy.Publisher('odom', Odometry) 25 | tf_pub = tf.TransformBroadcaster() 26 | 27 | #TODO: static pose could be made configurable (cmd.line or parameters) 28 | quat = tf.transformations.quaternion_from_euler(0, 0, 0) 29 | 30 | odom = Odometry() 31 | odom.header.frame_id = odom_frame_id 32 | odom.pose.pose = Pose(Point(0, 0, 0), Quaternion(*quat)) 33 | 34 | rospy.loginfo("Publishing static odometry from \"%s\" to \"%s\"", odom_frame_id, base_frame_id) 35 | r = rospy.Rate(publish_frequency) 36 | while not rospy.is_shutdown(): 37 | odom.header.stamp = rospy.Time.now() 38 | pub.publish(odom) 39 | tf_pub.sendTransform((0, 0, 0), quat, 40 | odom.header.stamp, base_frame_id, odom_frame_id) 41 | r.sleep() 42 | 43 | if __name__ == '__main__': 44 | try: 45 | publishOdom() 46 | except rospy.ROSInterruptException: 47 | pass 48 | -------------------------------------------------------------------------------- /src/navigation/global_planner/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(global_planner) 3 | 4 | find_package(catkin REQUIRED 5 | COMPONENTS 6 | angles 7 | costmap_2d 8 | dynamic_reconfigure 9 | geometry_msgs 10 | nav_core 11 | navfn 12 | nav_msgs 13 | pluginlib 14 | roscpp 15 | tf 16 | ) 17 | 18 | generate_dynamic_reconfigure_options( 19 | cfg/GlobalPlanner.cfg 20 | ) 21 | 22 | catkin_package( 23 | INCLUDE_DIRS include 24 | LIBRARIES ${PROJECT_NAME} 25 | CATKIN_DEPENDS 26 | costmap_2d 27 | dynamic_reconfigure 28 | geometry_msgs 29 | nav_core 30 | navfn 31 | nav_msgs 32 | pluginlib 33 | roscpp 34 | tf 35 | ) 36 | 37 | include_directories( 38 | include 39 | ${catkin_INCLUDE_DIRS} 40 | ) 41 | 42 | add_library(${PROJECT_NAME} 43 | src/quadratic_calculator.cpp 44 | src/dijkstra.cpp 45 | src/astar.cpp 46 | src/grid_path.cpp 47 | src/gradient_path.cpp 48 | src/orientation_filter.cpp 49 | src/planner_core.cpp 50 | ) 51 | add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 52 | target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES}) 53 | 54 | add_executable(planner 55 | src/plan_node.cpp 56 | ) 57 | add_dependencies(planner ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 58 | target_link_libraries(planner 59 | ${PROJECT_NAME} 60 | ${catkin_LIBRARIES} 61 | ) 62 | 63 | install(TARGETS ${PROJECT_NAME} planner 64 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 65 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 66 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) 67 | 68 | install(DIRECTORY include/${PROJECT_NAME}/ 69 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 70 | PATTERN ".svn" EXCLUDE) 71 | 72 | install(FILES bgp_plugin.xml 73 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 74 | -------------------------------------------------------------------------------- /src/navigation/global_planner/bgp_plugin.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | A implementation of a grid based planner using Dijkstras or A* 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /src/navigation/global_planner/cfg/GlobalPlanner.cfg: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | PACKAGE = "global_planner" 3 | 4 | from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, int_t, double_t, bool_t 5 | 6 | gen = ParameterGenerator() 7 | 8 | gen.add("lethal_cost", int_t, 0, "Lethal Cost", 253, 1, 255) 9 | gen.add("neutral_cost", int_t, 0, "Neutral Cost", 50, 1, 255) 10 | gen.add("cost_factor", double_t, 0, "Factor to multiply each cost from costmap by", 3.0, 0.01, 5.0) 11 | gen.add("publish_potential", bool_t, 0, "Publish Potential Costmap", True) 12 | 13 | orientation_enum = gen.enum([ 14 | gen.const("None", int_t, 0, "No orientations added except goal orientation"), 15 | gen.const("Forward", int_t, 1, 16 | "Positive x axis points along path, except for the goal orientation"), 17 | gen.const("Interpolate", int_t, 2, "Orientations are a linear blend of start and goal pose"), 18 | gen.const("ForwardThenInterpolate", 19 | int_t, 3, "Forward orientation until last straightaway, then a linear blend until the goal pose"), 20 | gen.const("Backward", int_t, 4, 21 | "Negative x axis points along the path, except for the goal orientation"), 22 | gen.const("Leftward", int_t, 5, 23 | "Positive y axis points along the path, except for the goal orientation"), 24 | gen.const("Rightward", int_t, 6, 25 | "Negative y axis points along the path, except for the goal orientation"), 26 | ], "How to set the orientation of each point") 27 | 28 | gen.add("orientation_mode", int_t, 0, "How to set the orientation of each point", 1, 0, 6, 29 | edit_method=orientation_enum) 30 | gen.add("orientation_window_size", int_t, 0, "What window to use to determine the orientation based on the " 31 | "position derivative specified by the orientation mode", 1, 1, 255) 32 | 33 | exit(gen.generate(PACKAGE, "global_planner", "GlobalPlanner")) 34 | -------------------------------------------------------------------------------- /src/navigation/global_planner/package.xml: -------------------------------------------------------------------------------- 1 | 2 | global_planner 3 | 1.14.7 4 | 5 | A path planner library and node. 6 | 7 | David V. Lu!! 8 | Michael Ferguson 9 | Aaron Hoy 10 | BSD 11 | 12 | David Lu!! 13 | http://wiki.ros.org/global_planner 14 | 15 | catkin 16 | 17 | angles 18 | costmap_2d 19 | dynamic_reconfigure 20 | geometry_msgs 21 | nav_core 22 | nav_msgs 23 | navfn 24 | pluginlib 25 | roscpp 26 | tf 27 | 28 | costmap_2d 29 | dynamic_reconfigure 30 | geometry_msgs 31 | nav_core 32 | nav_msgs 33 | navfn 34 | pluginlib 35 | roscpp 36 | tf 37 | 38 | 39 | 40 | 41 | 42 | -------------------------------------------------------------------------------- /src/navigation/map_server/package.xml: -------------------------------------------------------------------------------- 1 | 2 | map_server 3 | 1.14.7 4 | 5 | 6 | map_server provides the map_server ROS Node, which offers map data as a ROS Service. It also provides the map_saver command-line utility, which allows dynamically generated maps to be saved to file. 7 | 8 | 9 | Brian Gerkey, Tony Pratkanis 10 | contradict@gmail.com 11 | David V. Lu!! 12 | Michael Ferguson 13 | Aaron Hoy 14 | http://wiki.ros.org/map_server 15 | BSD 16 | 17 | catkin 18 | 19 | bullet 20 | nav_msgs 21 | roscpp 22 | sdl 23 | sdl-image 24 | tf2 25 | yaml-cpp 26 | 27 | bullet 28 | nav_msgs 29 | roscpp 30 | sdl 31 | sdl-image 32 | tf2 33 | yaml-cpp 34 | 35 | rospy 36 | rostest 37 | rosunit 38 | 39 | -------------------------------------------------------------------------------- /src/navigation/map_server/src/map_server.dox: -------------------------------------------------------------------------------- 1 | /** 2 | 3 | @mainpage 4 | 5 | @htmlinclude manifest.html 6 | 7 | Command-line usage is in the wiki. 8 | */ 9 | 10 | -------------------------------------------------------------------------------- /src/navigation/map_server/test/rtest.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /src/navigation/map_server/test/testmap.bmp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/src/navigation/map_server/test/testmap.bmp -------------------------------------------------------------------------------- /src/navigation/map_server/test/testmap.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/src/navigation/map_server/test/testmap.png -------------------------------------------------------------------------------- /src/navigation/map_server/test/testmap.yaml: -------------------------------------------------------------------------------- 1 | image: testmap.png 2 | resolution: 0.1 3 | origin: [2.0, 3.0, 1.0] 4 | negate: 0 5 | occupied_thresh: 0.65 6 | free_thresh: 0.196 7 | -------------------------------------------------------------------------------- /src/navigation/move_base/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(move_base) 3 | 4 | find_package(catkin REQUIRED 5 | COMPONENTS 6 | actionlib 7 | base_local_planner 8 | clear_costmap_recovery 9 | cmake_modules 10 | costmap_2d 11 | dynamic_reconfigure 12 | geometry_msgs 13 | message_generation 14 | move_base_msgs 15 | nav_core 16 | nav_msgs 17 | navfn 18 | pluginlib 19 | roscpp 20 | rospy 21 | rotate_recovery 22 | std_srvs 23 | tf 24 | ) 25 | find_package(Eigen3 REQUIRED) 26 | add_definitions(${EIGEN3_DEFINITIONS}) 27 | 28 | # dynamic reconfigure 29 | generate_dynamic_reconfigure_options( 30 | cfg/MoveBase.cfg 31 | ) 32 | 33 | catkin_package( 34 | CATKIN_DEPENDS 35 | dynamic_reconfigure 36 | geometry_msgs 37 | move_base_msgs 38 | nav_msgs 39 | roscpp 40 | ) 41 | 42 | include_directories( 43 | include 44 | ${catkin_INCLUDE_DIRS} 45 | ${EIGEN3_INCLUDE_DIRS} 46 | ) 47 | 48 | # move_base 49 | add_library(move_base 50 | src/move_base.cpp 51 | ) 52 | target_link_libraries(move_base 53 | ${Boost_LIBRARIES} 54 | ${catkin_LIBRARIES} 55 | ) 56 | add_dependencies(move_base ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 57 | 58 | add_executable(move_base_node 59 | src/move_base_node.cpp 60 | ) 61 | add_dependencies(move_base_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 62 | target_link_libraries(move_base_node move_base) 63 | set_target_properties(move_base_node PROPERTIES OUTPUT_NAME move_base) 64 | 65 | install( 66 | TARGETS 67 | move_base 68 | move_base_node 69 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 70 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 71 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 72 | ) 73 | 74 | ## Mark cpp header files for installation 75 | install(DIRECTORY include/${PROJECT_NAME}/ 76 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 77 | FILES_MATCHING PATTERN "*.h" 78 | ) 79 | -------------------------------------------------------------------------------- /src/navigation/move_base/planner_test.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | -------------------------------------------------------------------------------- /src/navigation/move_base/src/move_base_node.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2013, Willow Garage, Inc. 3 | * All rights reserved. 4 | * 5 | * Redistribution and use in source and binary forms, with or without 6 | * modification, are permitted provided that the following conditions are met: 7 | * 8 | * * Redistributions of source code must retain the above copyright 9 | * notice, this list of conditions and the following disclaimer. 10 | * * Redistributions in binary form must reproduce the above copyright 11 | * notice, this list of conditions and the following disclaimer in the 12 | * documentation and/or other materials provided with the distribution. 13 | * * Neither the name of the Willow Garage, Inc. nor the names of its 14 | * contributors may be used to endorse or promote products derived from 15 | * this software without specific prior written permission. 16 | * 17 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 20 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 21 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | * POSSIBILITY OF SUCH DAMAGE. 28 | */ 29 | 30 | #include 31 | 32 | int main(int argc, char** argv){ 33 | ros::init(argc, argv, "move_base_node"); 34 | tf::TransformListener tf(ros::Duration(10)); 35 | 36 | move_base::MoveBase move_base( tf ); 37 | 38 | //ros::MultiThreadedSpinner s; 39 | ros::spin(); 40 | 41 | return(0); 42 | } 43 | -------------------------------------------------------------------------------- /src/navigation/move_slow_and_clear/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(move_slow_and_clear) 3 | 4 | find_package(catkin REQUIRED 5 | COMPONENTS 6 | cmake_modules 7 | costmap_2d 8 | geometry_msgs 9 | nav_core 10 | pluginlib 11 | roscpp 12 | ) 13 | 14 | 15 | find_package(Eigen3 REQUIRED) 16 | find_package(PCL REQUIRED) 17 | remove_definitions(-DDISABLE_LIBUSB-1.0) 18 | find_package(Boost REQUIRED COMPONENTS thread) 19 | include_directories( 20 | include 21 | ${catkin_INCLUDE_DIRS} 22 | ${EIGEN3_INCLUDE_DIRS} 23 | ${PCL_INCLUDE_DIRS} 24 | ) 25 | add_definitions(${EIGEN3_DEFINITIONS}) 26 | 27 | catkin_package( 28 | INCLUDE_DIRS include 29 | LIBRARIES move_slow_and_clear 30 | CATKIN_DEPENDS 31 | geometry_msgs 32 | nav_core 33 | pluginlib 34 | roscpp 35 | ) 36 | 37 | add_library(${PROJECT_NAME} src/move_slow_and_clear.cpp) 38 | add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 39 | target_link_libraries(${PROJECT_NAME} 40 | ${Boost_LIBRARIES} 41 | ${catkin_LIBRARIES} 42 | ) 43 | 44 | ## Install project namespaced headers 45 | install(DIRECTORY include/${PROJECT_NAME}/ 46 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 47 | FILES_MATCHING PATTERN "*.h" 48 | PATTERN ".svn" EXCLUDE) 49 | 50 | install(TARGETS move_slow_and_clear 51 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 52 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 53 | ) 54 | 55 | install(FILES recovery_plugin.xml 56 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 57 | ) 58 | 59 | 60 | -------------------------------------------------------------------------------- /src/navigation/move_slow_and_clear/package.xml: -------------------------------------------------------------------------------- 1 | 2 | move_slow_and_clear 3 | 1.14.7 4 | 5 | 6 | move_slow_and_clear 7 | 8 | 9 | Eitan Marder-Eppstein 10 | contradict@gmail.com 11 | David V. Lu!! 12 | Michael Ferguson 13 | Aaron Hoy 14 | BSD 15 | http://wiki.ros.org/move_slow_and_clear 16 | 17 | catkin 18 | 19 | cmake_modules 20 | roscpp 21 | nav_core 22 | costmap_2d 23 | geometry_msgs 24 | pluginlib 25 | pluginlib 26 | 27 | roscpp 28 | nav_core 29 | costmap_2d 30 | geometry_msgs 31 | pluginlib 32 | pluginlib 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | -------------------------------------------------------------------------------- /src/navigation/move_slow_and_clear/recovery_plugin.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | A recovery behavior that clears information in the costmap within the circumscribed radius of the robot and then limits the speed of the robot. Note, this recovery behavior is not truly safe, the robot may hit things, it'll just happen at a user-specified speed. Also, this recovery behavior is only compatible with local planners that allow maximum speeds to be set via dynamic reconfigure. 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /src/navigation/nav_core/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package nav_core 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.14.7 (2020-03-10) 6 | ------------------- 7 | 8 | 1.14.6 (2020-03-04) 9 | ------------------- 10 | 11 | 1.14.5 (2019-11-15) 12 | ------------------- 13 | 14 | 1.14.4 (2018-06-19) 15 | ------------------- 16 | 17 | 1.14.3 (2018-03-16) 18 | ------------------- 19 | * Merge pull request `#672 `_ from ros-planning/email_update_kinetic 20 | update maintainer email (kinetic) 21 | * Merge pull request `#648 `_ from aaronhoy/kinetic_add_ahoy 22 | Add myself as a maintainer. 23 | * Contributors: Aaron Hoy, Michael Ferguson 24 | 25 | 1.14.2 (2017-08-14) 26 | ------------------- 27 | 28 | 1.14.1 (2017-08-07) 29 | ------------------- 30 | * makePlan overload must return. 31 | * Contributors: Eric Tappan 32 | 33 | 1.14.0 (2016-05-20) 34 | ------------------- 35 | 36 | 1.13.1 (2015-10-29) 37 | ------------------- 38 | * Merge pull request `#338 `_ from mikeferguson/planner_review 39 | * fix doxygen, couple style fixes 40 | * Contributors: Michael Ferguson 41 | 42 | 1.13.0 (2015-03-17) 43 | ------------------- 44 | * adding makePlan function with returned cost to base_global_planner 45 | * Contributors: phil0stine 46 | 47 | 1.12.0 (2015-02-04) 48 | ------------------- 49 | * update maintainer email 50 | * Contributors: Michael Ferguson 51 | 52 | 1.11.15 (2015-02-03) 53 | -------------------- 54 | 55 | 1.11.14 (2014-12-05) 56 | -------------------- 57 | 58 | 1.11.13 (2014-10-02) 59 | -------------------- 60 | 61 | 1.11.12 (2014-10-01) 62 | -------------------- 63 | 64 | 1.11.11 (2014-07-23) 65 | -------------------- 66 | 67 | 1.11.10 (2014-06-25) 68 | -------------------- 69 | 70 | 1.11.9 (2014-06-10) 71 | ------------------- 72 | 73 | 1.11.8 (2014-05-21) 74 | ------------------- 75 | 76 | 1.11.7 (2014-05-21) 77 | ------------------- 78 | 79 | 1.11.4 (2013-09-27) 80 | ------------------- 81 | * Package URL Updates 82 | -------------------------------------------------------------------------------- /src/navigation/nav_core/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(nav_core) 3 | 4 | find_package(catkin REQUIRED 5 | COMPONENTS 6 | std_msgs 7 | geometry_msgs 8 | tf 9 | costmap_2d 10 | ) 11 | 12 | catkin_package( 13 | INCLUDE_DIRS 14 | include 15 | CATKIN_DEPENDS 16 | std_msgs 17 | geometry_msgs 18 | tf 19 | costmap_2d 20 | ) 21 | 22 | 23 | ## Install project namespaced headers 24 | install(DIRECTORY include/${PROJECT_NAME}/ 25 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 26 | FILES_MATCHING PATTERN "*.h" 27 | PATTERN ".svn" EXCLUDE) 28 | -------------------------------------------------------------------------------- /src/navigation/nav_core/package.xml: -------------------------------------------------------------------------------- 1 | 2 | nav_core 3 | 1.14.7 4 | 5 | 6 | This package provides common interfaces for navigation specific robot actions. Currently, this package provides the BaseGlobalPlanner, BaseLocalPlanner, and RecoveryBehavior interfaces, which can be used to build actions that can easily swap their planner, local controller, or recovery behavior for new versions adhering to the same interface. 7 | 8 | 9 | Eitan Marder-Eppstein 10 | contradict@gmail.com 11 | David V. Lu!! 12 | Michael Ferguson 13 | Aaron Hoy 14 | BSD 15 | http://wiki.ros.org/nav_core 16 | 17 | catkin 18 | 19 | std_msgs 20 | geometry_msgs 21 | costmap_2d 22 | tf 23 | 24 | std_msgs 25 | geometry_msgs 26 | costmap_2d 27 | tf 28 | 29 | 30 | 31 | -------------------------------------------------------------------------------- /src/navigation/navfn/Makefile.orig: -------------------------------------------------------------------------------- 1 | # 2 | # Makefile for navigation function planner 3 | # 4 | 5 | CC = g++ 6 | CXX = g++ 7 | LD = g++ 8 | CPPFLAGS = -Wall -g -O3 -Iinclude -I/usr/local/include -I/usr/local/include/opencv 9 | CFLAGS = -DGCC -msse2 -mpreferred-stack-boundary=4 -O3 -Wall -Iinclude -I/usr/local/include 10 | GCC = g++ 11 | LDFLAGS = -Lbin 12 | SHAREDFLAGS = -shared -Wl,-soname, 13 | LIBS = -lfltk -lnetpbm 14 | 15 | OBJECTS = navfn navwin 16 | 17 | all: bin/navtest 18 | 19 | bin/navtest: obj/navtest.o $(OBJECTS:%=obj/%.o) 20 | $(LD) $(LDFLAGS) -o $@ $(OBJECTS:%=obj/%.o) obj/navtest.o $(LIBS) 21 | 22 | # general cpp command from src->obj 23 | obj/%.o:src/%.cpp 24 | $(GCC) $(CPPFLAGS) -c $< -o $@ 25 | 26 | # general c command from src->obj 27 | obj/%.o:src/%.c 28 | $(GCC) $(CFLAGS) -c $< -o $@ 29 | 30 | obj/navfn.o: include/navfn/navfn.h 31 | 32 | clean: 33 | - rm obj/*.o 34 | - rm bin/navtest 35 | 36 | dist: 37 | 38 | 39 | 40 | -------------------------------------------------------------------------------- /src/navigation/navfn/bgp_plugin.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | A implementation of a grid based planner using Dijkstra 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /src/navigation/navfn/include/navfn/navwin.h: -------------------------------------------------------------------------------- 1 | // 2 | // drawing fns for nav fn 3 | // 4 | 5 | #include 6 | #include 7 | #include 8 | 9 | #include 10 | #include 11 | #include 12 | #include 13 | #include 14 | 15 | #include "navfn.h" 16 | 17 | namespace navfn { 18 | class NavWin 19 | : public Fl_Double_Window 20 | { 21 | public: 22 | NavWin(int w, int h, const char *name); 23 | ~NavWin(); 24 | 25 | int nw,nh; // width and height of image 26 | int pw,ph; // width and height of pot field 27 | int dec, inc; // decimation or expansion for display 28 | 29 | float maxval; // max potential value 30 | void drawPot(NavFn *nav); // draw everything... 31 | 32 | void drawOverlay(); 33 | 34 | uchar *im; // image for drawing 35 | int *pc, *pn, *po; // priority buffers 36 | int pce, pne, poe; // buffer sizes 37 | int goal[2]; 38 | int start[2]; 39 | int *path; // path buffer, cell indices 40 | int pathlen; // how many we have 41 | int pathbuflen; // how big the path buffer is 42 | 43 | void draw(); // draw the image 44 | }; 45 | }; 46 | -------------------------------------------------------------------------------- /src/navigation/navfn/include/navfn/read_pgm_costmap.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2012, Willow Garage, Inc. 3 | * All rights reserved. 4 | * 5 | * Redistribution and use in source and binary forms, with or without 6 | * modification, are permitted provided that the following conditions are met: 7 | * 8 | * * Redistributions of source code must retain the above copyright 9 | * notice, this list of conditions and the following disclaimer. 10 | * * Redistributions in binary form must reproduce the above copyright 11 | * notice, this list of conditions and the following disclaimer in the 12 | * documentation and/or other materials provided with the distribution. 13 | * * Neither the name of the Willow Garage, Inc. nor the names of its 14 | * contributors may be used to endorse or promote products derived from 15 | * this software without specific prior written permission. 16 | * 17 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 20 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 21 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | * POSSIBILITY OF SUCH DAMAGE. 28 | */ 29 | #ifndef READ_PGM_COSTMAP_H 30 | #define READ_PGM_COSTMAP_H 31 | 32 | // is true for ROS-generated raw cost maps 33 | COSTTYPE *readPGM(const char *fname, int *width, int *height, bool raw = false); 34 | 35 | #endif // READ_PGM_COSTMAP_H 36 | -------------------------------------------------------------------------------- /src/navigation/navfn/srv/MakeNavPlan.srv: -------------------------------------------------------------------------------- 1 | geometry_msgs/PoseStamped start 2 | geometry_msgs/PoseStamped goal 3 | --- 4 | 5 | uint8 plan_found 6 | string error_message 7 | 8 | # if plan_found is true, this is an array of waypoints from start to goal, where the first one equals start and the last one equals goal 9 | geometry_msgs/PoseStamped[] path 10 | -------------------------------------------------------------------------------- /src/navigation/navfn/srv/SetCostmap.srv: -------------------------------------------------------------------------------- 1 | uint8[] costs 2 | uint16 height 3 | uint16 width 4 | --- -------------------------------------------------------------------------------- /src/navigation/navfn/test/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | catkin_add_gtest(path_calc_test path_calc_test.cpp ../src/read_pgm_costmap.cpp) 2 | target_link_libraries(path_calc_test navfn netpbm) 3 | -------------------------------------------------------------------------------- /src/navigation/navfn/test/willow_costmap.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/src/navigation/navfn/test/willow_costmap.pgm -------------------------------------------------------------------------------- /src/navigation/navigation/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package navigation 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.14.7 (2020-03-10) 6 | ------------------- 7 | 8 | 1.14.6 (2020-03-04) 9 | ------------------- 10 | 11 | 1.14.5 (2019-11-15) 12 | ------------------- 13 | 14 | 1.14.4 (2018-06-19) 15 | ------------------- 16 | 17 | 1.14.3 (2018-03-16) 18 | ------------------- 19 | * Merge pull request `#672 `_ from ros-planning/email_update_kinetic 20 | update maintainer email (kinetic) 21 | * Merge pull request `#648 `_ from aaronhoy/kinetic_add_ahoy 22 | Add myself as a maintainer. 23 | * Contributors: Aaron Hoy, Michael Ferguson 24 | 25 | 1.14.2 (2017-08-14) 26 | ------------------- 27 | 28 | 1.14.1 (2017-08-07) 29 | ------------------- 30 | 31 | 1.14.0 (2016-05-20) 32 | ------------------- 33 | 34 | 1.13.1 (2015-10-29) 35 | ------------------- 36 | 37 | 1.13.0 (2015-03-17) 38 | ------------------- 39 | 40 | 1.12.0 (2015-02-04) 41 | ------------------- 42 | * update maintainer email 43 | * Contributors: Michael Ferguson 44 | 45 | 1.11.15 (2015-02-03) 46 | -------------------- 47 | 48 | 1.11.14 (2014-12-05) 49 | -------------------- 50 | * add global planner run depend in meta package. 51 | * Contributors: Jihoon Lee 52 | 53 | 1.11.13 (2014-10-02) 54 | -------------------- 55 | 56 | 1.11.12 (2014-10-01) 57 | -------------------- 58 | 59 | 1.11.11 (2014-07-23) 60 | -------------------- 61 | 62 | 1.11.10 (2014-06-25) 63 | -------------------- 64 | 65 | 1.11.9 (2014-06-10) 66 | ------------------- 67 | 68 | 1.11.8 (2014-05-21) 69 | ------------------- 70 | 71 | 1.11.7 (2014-05-21) 72 | ------------------- 73 | 74 | 1.11.4 (2013-09-27) 75 | ------------------- 76 | * Package URL Updates 77 | -------------------------------------------------------------------------------- /src/navigation/navigation/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(navigation) 3 | find_package(catkin REQUIRED) 4 | catkin_metapackage() 5 | -------------------------------------------------------------------------------- /src/navigation/navigation/README.rst: -------------------------------------------------------------------------------- 1 | ROS Navigation Stack 2 | -------------------- 3 | 4 | A 2D navigation stack that takes in information from odometry, sensor 5 | streams, and a goal pose and outputs safe velocity commands that are sent 6 | to a mobile base. 7 | 8 | Related stacks: 9 | 10 | * http://github.com/ros-planning/navigation_tutorials 11 | * http://github.com/ros-planning/navigation_experimental 12 | -------------------------------------------------------------------------------- /src/navigation/navigation/package.xml: -------------------------------------------------------------------------------- 1 | 2 | navigation 3 | 1.14.7 4 | 5 | A 2D navigation stack that takes in information from odometry, sensor 6 | streams, and a goal pose and outputs safe velocity commands that are sent 7 | to a mobile base. 8 | 9 | David V. Lu!! 10 | Michael Ferguson 11 | Aaron Hoy 12 | contradict@gmail.com 13 | Eitan Marder-Eppstein 14 | BSD,LGPL,LGPL (amcl) 15 | http://wiki.ros.org/navigation 16 | 17 | catkin 18 | 19 | amcl 20 | carrot_planner 21 | dwa_local_planner 22 | move_base 23 | nav_core 24 | robot_pose_ekf 25 | base_local_planner 26 | clear_costmap_recovery 27 | fake_localization 28 | global_planner 29 | move_base_msgs 30 | navfn 31 | rotate_recovery 32 | costmap_2d 33 | map_server 34 | move_slow_and_clear 35 | voxel_grid 36 | 37 | 38 | 39 | 40 | 41 | -------------------------------------------------------------------------------- /src/navigation/robot_pose_ekf/example_with_gps.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /src/navigation/robot_pose_ekf/package.xml: -------------------------------------------------------------------------------- 1 | 2 | robot_pose_ekf 3 | 1.14.7 4 | 5 | 6 | The Robot Pose EKF package is used to estimate the 3D pose of a robot, based on (partial) pose measurements coming from different sources. It uses an extended Kalman filter with a 6D model (3D position and 3D orientation) to combine measurements from wheel odometry, IMU sensor and visual odometry. The basic idea is to offer loosely coupled integration with different sensors, where sensor signals are received as ROS messages. 7 | 8 | 9 | Wim Meeussen 10 | contradict@gmail.com 11 | David V. Lu!! 12 | Michael Ferguson 13 | Aaron Hoy 14 | BSD 15 | http://wiki.ros.org/robot_pose_ekf 16 | 17 | catkin 18 | 19 | message_generation 20 | roscpp 21 | bfl 22 | std_msgs 23 | geometry_msgs 24 | sensor_msgs 25 | nav_msgs 26 | tf 27 | message_generation 28 | 29 | message_runtime 30 | roscpp 31 | bfl 32 | std_msgs 33 | geometry_msgs 34 | sensor_msgs 35 | nav_msgs 36 | tf 37 | 38 | rosbag 39 | rostest 40 | 41 | -------------------------------------------------------------------------------- /src/navigation/robot_pose_ekf/robot_pose_ekf.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /src/navigation/robot_pose_ekf/scripts/wtf.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | import rospy 4 | from robot_pose_ekf.srv import GetStatus, GetStatusRequest 5 | 6 | if __name__ == '__main__': 7 | rospy.init_node('spawner', anonymous=True) 8 | print 'looking for node robot_pose_ekf...' 9 | rospy.wait_for_service('robot_pose_ekf/get_status') 10 | 11 | s = rospy.ServiceProxy('robot_pose_ekf/get_status', GetStatus) 12 | resp = s.call(GetStatusRequest()) 13 | print resp.status 14 | -------------------------------------------------------------------------------- /src/navigation/robot_pose_ekf/srv/GetStatus.srv: -------------------------------------------------------------------------------- 1 | 2 | --- 3 | string status -------------------------------------------------------------------------------- /src/navigation/robot_pose_ekf/test/test_robot_pose_ekf.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /src/navigation/robot_pose_ekf/test/test_robot_pose_ekf_zero_covariance.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /src/navigation/rotate_recovery/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(rotate_recovery) 3 | 4 | find_package(catkin REQUIRED 5 | COMPONENTS 6 | cmake_modules 7 | roscpp 8 | tf 9 | costmap_2d 10 | nav_core 11 | pluginlib 12 | base_local_planner 13 | ) 14 | 15 | find_package(Eigen3 REQUIRED) 16 | include_directories( 17 | include 18 | ${catkin_INCLUDE_DIRS} 19 | ${EIGEN3_INCLUDE_DIRS} 20 | ) 21 | add_definitions(${EIGEN3_DEFINITIONS}) 22 | 23 | catkin_package( 24 | INCLUDE_DIRS include 25 | LIBRARIES rotate_recovery 26 | CATKIN_DEPENDS 27 | roscpp 28 | pluginlib 29 | ) 30 | 31 | add_library(rotate_recovery src/rotate_recovery.cpp) 32 | add_dependencies(rotate_recovery ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 33 | target_link_libraries(rotate_recovery ${catkin_LIBRARIES}) 34 | 35 | install(TARGETS rotate_recovery 36 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 37 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 38 | ) 39 | 40 | install(DIRECTORY include/${PROJECT_NAME}/ 41 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 42 | FILES_MATCHING PATTERN "*.h" 43 | ) 44 | 45 | install(FILES rotate_plugin.xml 46 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 47 | ) 48 | 49 | -------------------------------------------------------------------------------- /src/navigation/rotate_recovery/package.xml: -------------------------------------------------------------------------------- 1 | 2 | rotate_recovery 3 | 1.14.7 4 | 5 | 6 | This package provides a recovery behavior for the navigation stack that attempts to clear space by performing a 360 degree rotation of the robot. 7 | 8 | 9 | Eitan Marder-Eppstein 10 | contradict@gmail.com 11 | David V. Lu!! 12 | Michael Ferguson 13 | Aaron Hoy 14 | BSD 15 | http://wiki.ros.org/rotate_recovery 16 | 17 | catkin 18 | 19 | cmake_modules 20 | roscpp 21 | tf 22 | costmap_2d 23 | nav_core 24 | pluginlib 25 | eigen 26 | base_local_planner 27 | 28 | roscpp 29 | tf 30 | costmap_2d 31 | nav_core 32 | pluginlib 33 | eigen 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | -------------------------------------------------------------------------------- /src/navigation/rotate_recovery/rotate_plugin.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | A recovery behavior that performs a 360 degree in-place rotation to attempt to clear out space. 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /src/navigation/voxel_grid/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(voxel_grid) 3 | 4 | find_package(catkin REQUIRED 5 | COMPONENTS 6 | roscpp 7 | ) 8 | 9 | catkin_package( 10 | INCLUDE_DIRS 11 | include 12 | LIBRARIES 13 | voxel_grid 14 | CATKIN_DEPENDS 15 | roscpp 16 | ) 17 | 18 | include_directories(include ${catkin_INCLUDE_DIRS}) 19 | 20 | add_library(voxel_grid src/voxel_grid.cpp) 21 | add_dependencies(voxel_grid ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 22 | target_link_libraries(voxel_grid ${catkin_LIBRARIES}) 23 | 24 | install(TARGETS voxel_grid 25 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 26 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 27 | ) 28 | 29 | install(DIRECTORY include/${PROJECT_NAME}/ 30 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 31 | ) 32 | 33 | if(CATKIN_ENABLE_TESTING) 34 | catkin_add_gtest(voxel_grid_tests test/voxel_grid_tests.cpp) 35 | target_link_libraries(voxel_grid_tests 36 | voxel_grid 37 | ${catkin_LIBRARIES} 38 | ) 39 | endif() 40 | -------------------------------------------------------------------------------- /src/navigation/voxel_grid/package.xml: -------------------------------------------------------------------------------- 1 | 2 | voxel_grid 3 | 1.14.7 4 | 5 | 6 | voxel_grid provides an implementation of an efficient 3D voxel grid. The occupancy grid can support 3 different representations for the state of a cell: marked, free, or unknown. Due to the underlying implementation relying on bitwise and and or integer operations, the voxel grid only supports 16 different levels per voxel column. However, this limitation yields raytracing and cell marking performance in the grid comparable to standard 2D structures making it quite fast compared to most 3D structures. 7 | 8 | 9 | Eitan Marder-Eppstein, Eric Berger 10 | contradict@gmail.com 11 | David V. Lu!! 12 | Michael Ferguson 13 | Aaron Hoy 14 | BSD 15 | http://wiki.ros.org/voxel_grid 16 | 17 | catkin 18 | 19 | roscpp 20 | 21 | roscpp 22 | 23 | rosunit 24 | 25 | -------------------------------------------------------------------------------- /src/relaxed_astar/README: -------------------------------------------------------------------------------- 1 | Website: http://www.iroboapp.org/index.php?title=Adding_Relaxed_Astar_Global_Path_Planner_As_Plugin_in_ROS 2 | 3 | To use the package add following line in your launch file under move_base node package 4 | 5 | 6 | -------------------------------------------------------------------------------- /src/relaxed_astar/relaxed_astar_planner_plugin.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | This is Relaxed Astar global planner plugin by iroboapp project. 4 | 5 | 6 | -------------------------------------------------------------------------------- /src/rplidar_ros/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package rplidar_ros 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.9.0 (2018-08-24) 6 | ------------------ 7 | * Update RPLIDAR SDK to 1.9.0 8 | * [new feature] support baudrate 57600 and 1382400, support HQ scan response 9 | * [bugfix] TCP channel doesn't work 10 | * [improvement] Print warning messages when deprecated APIs are called; imporve angular accuracy for ultra capsuled scan points 11 | * Contributors: tony,kint 12 | 13 | 1.7.0 (2018-07-19) 14 | ------------------ 15 | * Update RPLIDAR SDK to 1.7.0 16 | * support scan points farther than 16.38m 17 | * upport display and set scan mode 18 | * Contributors: kint 19 | 20 | 21 | 1.6.0 (2018-05-21) 22 | ------------------ 23 | * Release 1.6.0. 24 | * Update RPLIDAR SDK to 1.6.0 25 | * Support new product RPLIDAR A3(default 16K model and max_distance 25m) 26 | * Contributors: kint 27 | 28 | 29 | 1.5.7 (2016-12-15) 30 | ------------------ 31 | * Release 1.5.7. 32 | * Update RPLIDAR SDK to 1.5.7 33 | * Fixed the motor default speed at 10 HZ. Extend the measurement of max_distance from 6m to 8m. 34 | * Contributors: kint 35 | 36 | 1.5.5 (2016-08-23) 37 | ------------------ 38 | * Release 1.5.5. 39 | * Update RPLIDAR SDK to 1.5.5 40 | * Add RPLIDAR information print, and fix the standard motor speed of RPLIDAR A2. 41 | * Contributors: kint 42 | 43 | 1.5.4 (2016-06-02) 44 | ------------------ 45 | * Release 1.5.4. 46 | * Update RPLIDAR SDK to 1.5.4 47 | * Support RPLIDAR A2 48 | * Contributors: kint 49 | 50 | 1.5.2 (2016-04-29) 51 | ------------------ 52 | * Release 1.5.2. 53 | * Update RPLIDAR SDK to 1.5.2 54 | * Support RPLIDAR A2 55 | * Contributors: kint 56 | 57 | 1.0.1 (2014-06-03) 58 | ------------------ 59 | * Release 1.0.1. 60 | * Add angle compensate mechanism to compatible with ROS scan message 61 | * Add RPLIDAR sdk to the repo. 62 | * First release of RPLIDAR ROS package (1.0.0) 63 | * Initial commit 64 | * Contributors: Ling, RoboPeak Public Repos 65 | -------------------------------------------------------------------------------- /src/rplidar_ros/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(rplidar_ros) 3 | 4 | set(RPLIDAR_SDK_PATH "./sdk/") 5 | 6 | FILE(GLOB RPLIDAR_SDK_SRC 7 | "${RPLIDAR_SDK_PATH}/src/arch/linux/*.cpp" 8 | "${RPLIDAR_SDK_PATH}/src/hal/*.cpp" 9 | "${RPLIDAR_SDK_PATH}/src/*.cpp" 10 | ) 11 | 12 | find_package(catkin REQUIRED COMPONENTS 13 | roscpp 14 | rosconsole 15 | sensor_msgs 16 | ) 17 | 18 | include_directories( 19 | ${RPLIDAR_SDK_PATH}/include 20 | ${RPLIDAR_SDK_PATH}/src 21 | ${catkin_INCLUDE_DIRS} 22 | ) 23 | 24 | catkin_package() 25 | 26 | add_executable(rplidarNode src/node.cpp ${RPLIDAR_SDK_SRC}) 27 | target_link_libraries(rplidarNode ${catkin_LIBRARIES}) 28 | 29 | add_executable(rplidarNodeClient src/client.cpp) 30 | target_link_libraries(rplidarNodeClient ${catkin_LIBRARIES}) 31 | 32 | install(TARGETS rplidarNode rplidarNodeClient 33 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 34 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 35 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 36 | ) 37 | 38 | install(DIRECTORY launch rviz sdk 39 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 40 | USE_SOURCE_PERMISSIONS 41 | ) 42 | -------------------------------------------------------------------------------- /src/rplidar_ros/LICENSE: -------------------------------------------------------------------------------- 1 | Copyright (c) 2009 - 2014 RoboPeak Team 2 | Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. 3 | All rights reserved. 4 | 5 | Redistribution and use in source and binary forms, with or without 6 | modification, are permitted provided that the following conditions are met: 7 | 8 | * Redistributions of source code must retain the above copyright notice, this 9 | list of conditions and the following disclaimer. 10 | 11 | * Redistributions in binary form must reproduce the above copyright notice, 12 | this list of conditions and the following disclaimer in the documentation 13 | and/or other materials provided with the distribution. 14 | 15 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 18 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 19 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 20 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 21 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 22 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 23 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 24 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 25 | -------------------------------------------------------------------------------- /src/rplidar_ros/README.md: -------------------------------------------------------------------------------- 1 | RPLIDAR ROS package 2 | ===================================================================== 3 | 4 | ROS node and test application for RPLIDAR 5 | 6 | Visit following Website for more details about RPLIDAR: 7 | 8 | rplidar roswiki: http://wiki.ros.org/rplidar 9 | 10 | rplidar HomePage: http://www.slamtec.com/en/Lidar 11 | 12 | rplidar SDK: https://github.com/Slamtec/rplidar_sdk 13 | 14 | rplidar Tutorial: https://github.com/robopeak/rplidar_ros/wiki 15 | 16 | How to build rplidar ros package 17 | ===================================================================== 18 | 1) Clone this project to your catkin's workspace src folder 19 | 2) Running catkin_make to build rplidarNode and rplidarNodeClient 20 | 21 | How to run rplidar ros package 22 | ===================================================================== 23 | There're two ways to run rplidar ros package 24 | 25 | I. Run rplidar node and view in the rviz 26 | ------------------------------------------------------------ 27 | roslaunch rplidar_ros view_rplidar.launch (for RPLIDAR A1/A2) 28 | or 29 | roslaunch rplidar_ros view_rplidar_a3.launch (for RPLIDAR A3) 30 | 31 | You should see rplidar's scan result in the rviz. 32 | 33 | II. Run rplidar node and view using test application 34 | ------------------------------------------------------------ 35 | roslaunch rplidar_ros rplidar.launch (for RPLIDAR A1/A2) 36 | or 37 | roslaunch rplidar_ros rplidar_a3.launch (for RPLIDAR A3) 38 | 39 | rosrun rplidar_ros rplidarNodeClient 40 | 41 | You should see rplidar's scan result in the console 42 | 43 | Notice: the different is serial_baudrate between A1/A2 and A3 44 | 45 | RPLidar frame 46 | ===================================================================== 47 | RPLidar frame must be broadcasted according to picture shown in rplidar-frame.png 48 | -------------------------------------------------------------------------------- /src/rplidar_ros/launch/hector_mapping_demo.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 46 | 47 | -------------------------------------------------------------------------------- /src/rplidar_ros/launch/rplidar.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /src/rplidar_ros/launch/rplidar_a3.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /src/rplidar_ros/launch/test_rplidar.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | -------------------------------------------------------------------------------- /src/rplidar_ros/launch/test_rplidar_a3.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | -------------------------------------------------------------------------------- /src/rplidar_ros/launch/view_rplidar.launch: -------------------------------------------------------------------------------- 1 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /src/rplidar_ros/launch/view_rplidar_a3.launch: -------------------------------------------------------------------------------- 1 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /src/rplidar_ros/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | rplidar_ros 4 | 1.9.0 5 | The rplidar ros package, support rplidar A2/A1 and A3 6 | 7 | Slamtec ROS Maintainer 8 | BSD 9 | 10 | catkin 11 | roscpp 12 | rosconsole 13 | sensor_msgs 14 | std_srvs 15 | roscpp 16 | rosconsole 17 | sensor_msgs 18 | std_srvs 19 | 20 | 21 | -------------------------------------------------------------------------------- /src/rplidar_ros/rplidar_A1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/src/rplidar_ros/rplidar_A1.png -------------------------------------------------------------------------------- /src/rplidar_ros/rplidar_A2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/src/rplidar_ros/rplidar_A2.png -------------------------------------------------------------------------------- /src/rplidar_ros/scripts/create_udev_rules.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | echo "remap the device serial port(ttyUSBX) to rplidar" 4 | echo "rplidar usb connection as /dev/rplidar , check it using the command : ls -l /dev|grep ttyUSB" 5 | echo "start copy rplidar.rules to /etc/udev/rules.d/" 6 | echo "`rospack find rplidar_ros`/scripts/rplidar.rules" 7 | sudo cp `rospack find rplidar_ros`/scripts/rplidar.rules /etc/udev/rules.d 8 | echo " " 9 | echo "Restarting udev" 10 | echo "" 11 | sudo service udev reload 12 | sudo service udev restart 13 | echo "finish " 14 | -------------------------------------------------------------------------------- /src/rplidar_ros/scripts/delete_udev_rules.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | echo "delete remap the device serial port(ttyUSBX) to rplidar" 4 | echo "sudo rm /etc/udev/rules.d/rplidar.rules" 5 | sudo rm /etc/udev/rules.d/rplidar.rules 6 | echo " " 7 | echo "Restarting udev" 8 | echo "" 9 | sudo service udev reload 10 | sudo service udev restart 11 | echo "finish delete" 12 | -------------------------------------------------------------------------------- /src/rplidar_ros/scripts/rplidar.rules: -------------------------------------------------------------------------------- 1 | # set the udev rule , make the device_port be fixed by rplidar 2 | # 3 | KERNEL=="ttyUSB*", ATTRS{idVendor}=="10c4", ATTRS{idProduct}=="ea60", MODE:="0777", SYMLINK+="rplidar" 4 | 5 | -------------------------------------------------------------------------------- /src/rplidar_ros/sdk/README.txt: -------------------------------------------------------------------------------- 1 | Copyright (c) 2009 - 2014 RoboPeak Team 2 | Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. 3 | All rights reserved. 4 | 5 | Redistribution and use in source and binary forms, with or without 6 | modification, are permitted provided that the following conditions are met: 7 | 8 | * Redistributions of source code must retain the above copyright notice, this 9 | list of conditions and the following disclaimer. 10 | 11 | * Redistributions in binary form must reproduce the above copyright notice, 12 | this list of conditions and the following disclaimer in the documentation 13 | and/or other materials provided with the distribution. 14 | 15 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 18 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 19 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 20 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 21 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 22 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 23 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 24 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 25 | 26 | 27 | 28 | This folder contains RPLIDAR SDK source code which is provided by RoboPeak. 29 | 30 | RoboPeak Website: http://www.robopeak.com 31 | SlamTec HomePage: http://www.slamtec.com 32 | RPLIDAR_SDK_VERSION: 1.9.0 33 | Note: The SDK version may not up-to-date. 34 | rplidar product: http://www.slamtec.com/en/Lidar 35 | -------------------------------------------------------------------------------- /src/rplidar_ros/sdk/include/rplidar.h: -------------------------------------------------------------------------------- 1 | /* 2 | * RPLIDAR SDK 3 | * 4 | * Copyright (c) 2009 - 2014 RoboPeak Team 5 | * http://www.robopeak.com 6 | * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. 7 | * http://www.slamtec.com 8 | * 9 | */ 10 | /* 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted provided that the following conditions are met: 13 | * 14 | * 1. Redistributions of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 17 | * 2. Redistributions in binary form must reproduce the above copyright notice, 18 | * this list of conditions and the following disclaimer in the documentation 19 | * and/or other materials provided with the distribution. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 22 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, 23 | * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 24 | * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR 25 | * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, 26 | * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, 27 | * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; 28 | * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, 29 | * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR 30 | * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 31 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 32 | * 33 | */ 34 | 35 | #pragma once 36 | 37 | #include 38 | #include "hal/types.h" 39 | #include "rplidar_protocol.h" 40 | #include "rplidar_cmd.h" 41 | 42 | #include "rplidar_driver.h" 43 | 44 | #define RPLIDAR_SDK_VERSION "1.9.0" 45 | -------------------------------------------------------------------------------- /src/rplidar_ros/sdk/src/arch/linux/timer.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * RPLIDAR SDK 3 | * 4 | * Copyright (c) 2009 - 2014 RoboPeak Team 5 | * http://www.robopeak.com 6 | * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. 7 | * http://www.slamtec.com 8 | * 9 | */ 10 | /* 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted provided that the following conditions are met: 13 | * 14 | * 1. Redistributions of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 17 | * 2. Redistributions in binary form must reproduce the above copyright notice, 18 | * this list of conditions and the following disclaimer in the documentation 19 | * and/or other materials provided with the distribution. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 22 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, 23 | * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 24 | * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR 25 | * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, 26 | * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, 27 | * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; 28 | * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, 29 | * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR 30 | * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 31 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 32 | * 33 | */ 34 | 35 | #include "arch/linux/arch_linux.h" 36 | 37 | namespace rp{ namespace arch{ 38 | _u64 rp_getus() 39 | { 40 | struct timespec t; 41 | t.tv_sec = t.tv_nsec = 0; 42 | clock_gettime(CLOCK_MONOTONIC, &t); 43 | return t.tv_sec*1000000LL + t.tv_nsec/1000; 44 | } 45 | _u32 rp_getms() 46 | { 47 | struct timespec t; 48 | t.tv_sec = t.tv_nsec = 0; 49 | clock_gettime(CLOCK_MONOTONIC, &t); 50 | return t.tv_sec*1000L + t.tv_nsec/1000000L; 51 | } 52 | }} 53 | -------------------------------------------------------------------------------- /src/rplidar_ros/sdk/src/arch/linux/timer.h: -------------------------------------------------------------------------------- 1 | /* 2 | * RPLIDAR SDK 3 | * 4 | * Copyright (c) 2009 - 2014 RoboPeak Team 5 | * http://www.robopeak.com 6 | * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. 7 | * http://www.slamtec.com 8 | * 9 | */ 10 | /* 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted provided that the following conditions are met: 13 | * 14 | * 1. Redistributions of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 17 | * 2. Redistributions in binary form must reproduce the above copyright notice, 18 | * this list of conditions and the following disclaimer in the documentation 19 | * and/or other materials provided with the distribution. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 22 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, 23 | * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 24 | * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR 25 | * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, 26 | * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, 27 | * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; 28 | * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, 29 | * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR 30 | * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 31 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 32 | * 33 | */ 34 | 35 | #pragma once 36 | 37 | #include "hal/types.h" 38 | 39 | #include 40 | static inline void delay(_word_size_t ms){ 41 | while (ms>=1000){ 42 | usleep(1000*1000); 43 | ms-=1000; 44 | }; 45 | if (ms!=0) 46 | usleep(ms*1000); 47 | } 48 | 49 | // TODO: the highest timer interface should be clock_gettime 50 | namespace rp{ namespace arch{ 51 | 52 | _u64 rp_getus(); 53 | _u32 rp_getms(); 54 | 55 | }} 56 | 57 | #define getms() rp::arch::rp_getms() 58 | -------------------------------------------------------------------------------- /src/rplidar_ros/sdk/src/arch/macOS/timer.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * RPLIDAR SDK 3 | * 4 | * Copyright (c) 2009 - 2014 RoboPeak Team 5 | * http://www.robopeak.com 6 | * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. 7 | * http://www.slamtec.com 8 | * 9 | */ 10 | /* 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted provided that the following conditions are met: 13 | * 14 | * 1. Redistributions of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 17 | * 2. Redistributions in binary form must reproduce the above copyright notice, 18 | * this list of conditions and the following disclaimer in the documentation 19 | * and/or other materials provided with the distribution. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 22 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, 23 | * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 24 | * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR 25 | * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, 26 | * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, 27 | * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; 28 | * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, 29 | * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR 30 | * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 31 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 32 | * 33 | */ 34 | 35 | #include "arch/macOS/arch_macOS.h" 36 | 37 | 38 | namespace rp{ namespace arch{ 39 | _u64 getus() 40 | { 41 | timeval now; 42 | gettimeofday(&now,NULL); 43 | return now.tv_sec*1000000 + now.tv_usec; 44 | } 45 | 46 | _u32 rp_getms() 47 | { 48 | timeval now; 49 | gettimeofday(&now,NULL); 50 | return now.tv_sec*1000L + now.tv_usec/1000L; 51 | } 52 | 53 | }} 54 | -------------------------------------------------------------------------------- /src/rplidar_ros/sdk/src/arch/macOS/timer.h: -------------------------------------------------------------------------------- 1 | /* 2 | * RPLIDAR SDK 3 | * 4 | * Copyright (c) 2009 - 2014 RoboPeak Team 5 | * http://www.robopeak.com 6 | * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. 7 | * http://www.slamtec.com 8 | * 9 | */ 10 | /* 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted provided that the following conditions are met: 13 | * 14 | * 1. Redistributions of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 17 | * 2. Redistributions in binary form must reproduce the above copyright notice, 18 | * this list of conditions and the following disclaimer in the documentation 19 | * and/or other materials provided with the distribution. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 22 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, 23 | * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 24 | * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR 25 | * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, 26 | * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, 27 | * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; 28 | * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, 29 | * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR 30 | * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 31 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 32 | * 33 | */ 34 | 35 | #pragma once 36 | 37 | #include "rptypes.h" 38 | 39 | #include 40 | static inline void delay(_word_size_t ms){ 41 | while (ms>=1000){ 42 | usleep(1000*1000); 43 | ms-=1000; 44 | }; 45 | if (ms!=0) 46 | usleep(ms*1000); 47 | } 48 | 49 | // TODO: the highest timer interface should be clock_gettime 50 | namespace rp{ namespace arch{ 51 | 52 | _u64 rp_getus(); 53 | _u32 rp_getms(); 54 | 55 | }} 56 | 57 | #define getms() rp::arch::rp_getms() 58 | -------------------------------------------------------------------------------- /src/rplidar_ros/sdk/src/arch/win32/timer.h: -------------------------------------------------------------------------------- 1 | /* 2 | * RPLIDAR SDK 3 | * 4 | * Copyright (c) 2009 - 2014 RoboPeak Team 5 | * http://www.robopeak.com 6 | * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. 7 | * http://www.slamtec.com 8 | * 9 | */ 10 | /* 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted provided that the following conditions are met: 13 | * 14 | * 1. Redistributions of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 17 | * 2. Redistributions in binary form must reproduce the above copyright notice, 18 | * this list of conditions and the following disclaimer in the documentation 19 | * and/or other materials provided with the distribution. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 22 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, 23 | * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 24 | * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR 25 | * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, 26 | * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, 27 | * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; 28 | * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, 29 | * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR 30 | * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 31 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 32 | * 33 | */ 34 | 35 | #pragma once 36 | 37 | #include "hal/types.h" 38 | 39 | #define delay(x) ::Sleep(x) 40 | 41 | namespace rp{ namespace arch{ 42 | void HPtimer_reset(); 43 | _u32 getHDTimer(); 44 | }} 45 | 46 | #define getms() rp::arch::getHDTimer() 47 | 48 | -------------------------------------------------------------------------------- /src/rplidar_ros/sdk/src/hal/assert.h: -------------------------------------------------------------------------------- 1 | #ifndef _INFRA_HAL_ASSERT_H 2 | #define _INFRA_HAL_ASSERT_H 3 | 4 | #ifdef WIN32 5 | #include 6 | #ifndef assert 7 | #define assert(x) _ASSERT(x) 8 | #endif 9 | #elif defined(_AVR_) 10 | #define assert(x) 11 | #elif defined(__GNUC__) 12 | #ifndef assert 13 | #define assert(x) 14 | #endif 15 | #else 16 | #error assert.h cannot identify your platform 17 | #endif 18 | #endif 19 | -------------------------------------------------------------------------------- /src/rplidar_ros/sdk/src/hal/thread.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * RPLIDAR SDK 3 | * 4 | * Copyright (c) 2009 - 2014 RoboPeak Team 5 | * http://www.robopeak.com 6 | * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. 7 | * http://www.slamtec.com 8 | * 9 | */ 10 | /* 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted provided that the following conditions are met: 13 | * 14 | * 1. Redistributions of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 17 | * 2. Redistributions in binary form must reproduce the above copyright notice, 18 | * this list of conditions and the following disclaimer in the documentation 19 | * and/or other materials provided with the distribution. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 22 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, 23 | * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 24 | * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR 25 | * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, 26 | * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, 27 | * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; 28 | * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, 29 | * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR 30 | * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 31 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 32 | * 33 | */ 34 | 35 | #include "sdkcommon.h" 36 | #include "hal/thread.h" 37 | 38 | #if defined(_WIN32) 39 | #include "arch/win32/winthread.hpp" 40 | #elif defined(_MACOS) 41 | #include "arch/macOS/thread.hpp" 42 | #elif defined(__GNUC__) 43 | #include "arch/linux/thread.hpp" 44 | #else 45 | #error no threading implemention found for this platform. 46 | #endif 47 | 48 | 49 | -------------------------------------------------------------------------------- /src/rplidar_ros/sdk/src/sdkcommon.h: -------------------------------------------------------------------------------- 1 | /* 2 | * RPLIDAR SDK 3 | * 4 | * Copyright (c) 2009 - 2014 RoboPeak Team 5 | * http://www.robopeak.com 6 | * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd. 7 | * http://www.slamtec.com 8 | * 9 | */ 10 | /* 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted provided that the following conditions are met: 13 | * 14 | * 1. Redistributions of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 17 | * 2. Redistributions in binary form must reproduce the above copyright notice, 18 | * this list of conditions and the following disclaimer in the documentation 19 | * and/or other materials provided with the distribution. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 22 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, 23 | * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 24 | * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR 25 | * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, 26 | * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, 27 | * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; 28 | * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, 29 | * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR 30 | * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 31 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 32 | * 33 | */ 34 | 35 | #if defined(_WIN32) 36 | #include "arch\win32\arch_win32.h" 37 | #elif defined(_MACOS) 38 | #include "arch/macOS/arch_macOS.h" 39 | #elif defined(__GNUC__) 40 | #include "arch/linux/arch_linux.h" 41 | #else 42 | #error "unsupported target" 43 | #endif 44 | 45 | #include "hal/types.h" 46 | #include "hal/assert.h" 47 | 48 | #include "rplidar.h" 49 | 50 | #include "hal/util.h" -------------------------------------------------------------------------------- /src/rrt_exploration/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(rrt_exploration) 3 | 4 | ## Find catkin macros and libraries 5 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) 6 | ## is used, also find other catkin packages 7 | find_package(catkin REQUIRED COMPONENTS 8 | geometry_msgs 9 | nav_msgs 10 | roscpp 11 | rospy 12 | std_msgs 13 | tf 14 | visualization_msgs 15 | message_generation 16 | ) 17 | 18 | 19 | add_message_files( 20 | FILES 21 | PointArray.msg 22 | ) 23 | 24 | generate_messages( 25 | DEPENDENCIES 26 | std_msgs 27 | geometry_msgs 28 | ) 29 | 30 | 31 | catkin_package( 32 | 33 | CATKIN_DEPENDS message_runtime 34 | ) 35 | 36 | 37 | 38 | 39 | 40 | include_directories(include ${catkin_INCLUDE_DIRS}) 41 | 42 | add_executable(global_rrt_detector src/global_rrt_detector.cpp src/functions.cpp src/mtrand.cpp) 43 | target_link_libraries(global_rrt_detector ${catkin_LIBRARIES}) 44 | 45 | add_executable(local_rrt_detector src/local_rrt_detector.cpp src/functions.cpp src/mtrand.cpp) 46 | target_link_libraries(local_rrt_detector ${catkin_LIBRARIES}) 47 | -------------------------------------------------------------------------------- /src/rrt_exploration/LICENSE.md: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2016 Hassan Umari 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /src/rrt_exploration/include/functions.h: -------------------------------------------------------------------------------- 1 | #ifndef functions_H 2 | #define functions_H 3 | #include "ros/ros.h" 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include "nav_msgs/OccupancyGrid.h" 9 | #include "geometry_msgs/Point.h" 10 | #include "visualization_msgs/Marker.h" 11 | 12 | // rdm class, for gentaring random flot numbers 13 | class rdm{ 14 | int i; 15 | public: 16 | rdm(); 17 | float randomize(); 18 | }; 19 | 20 | 21 | //Norm function prototype 22 | float Norm( std::vector , std::vector ); 23 | 24 | //sign function prototype 25 | float sign(float ); 26 | 27 | //Nearest function prototype 28 | std::vector Nearest( std::vector< std::vector > , std::vector ); 29 | 30 | //Steer function prototype 31 | std::vector Steer( std::vector, std::vector, float ); 32 | 33 | //gridValue function prototype 34 | int gridValue(nav_msgs::OccupancyGrid &,std::vector); 35 | 36 | //ObstacleFree function prototype 37 | char ObstacleFree(std::vector , std::vector & , nav_msgs::OccupancyGrid); 38 | #endif 39 | -------------------------------------------------------------------------------- /src/rrt_exploration/launch/simple.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | -------------------------------------------------------------------------------- /src/rrt_exploration/launch/single.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | -------------------------------------------------------------------------------- /src/rrt_exploration/msg/PointArray.msg: -------------------------------------------------------------------------------- 1 | # An array of points 2 | 3 | geometry_msgs/Point[] points 4 | -------------------------------------------------------------------------------- /src/rrt_exploration/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | rrt_exploration 4 | 1.0.0 5 | A ROS package that implements a multi-robot RRT-based map exploration algorithm. It also has the image-based frontier detection that uses image processing to extract frontier points 6 | 7 | Hassan Umari 8 | Hassan Umari 9 | 10 | MIT 11 | http://wiki.ros.org/rrt_exploration 12 | 13 | 14 | catkin 15 | geometry_msgs 16 | nav_msgs 17 | roscpp 18 | rospy 19 | std_msgs 20 | tf 21 | visualization_msgs 22 | message_generation 23 | geometry_msgs 24 | nav_msgs 25 | roscpp 26 | rospy 27 | std_msgs 28 | tf 29 | visualization_msgs 30 | message_runtime 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | -------------------------------------------------------------------------------- /src/rrt_exploration/scripts/functions.pyc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/src/rrt_exploration/scripts/functions.pyc -------------------------------------------------------------------------------- /src/rrt_exploration/scripts/getfrontier.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | 4 | #--------Include modules--------------- 5 | from copy import copy 6 | import rospy 7 | from nav_msgs.msg import OccupancyGrid 8 | 9 | import numpy as np 10 | import cv2 11 | 12 | #----------------------------------------------------- 13 | 14 | def getfrontier(mapData): 15 | data=mapData.data 16 | w=mapData.info.width 17 | h=mapData.info.height 18 | resolution=mapData.info.resolution 19 | Xstartx=mapData.info.origin.position.x 20 | Xstarty=mapData.info.origin.position.y 21 | 22 | img = np.zeros((h, w, 1), np.uint8) 23 | 24 | for i in range(0,h): 25 | for j in range(0,w): 26 | if data[i*w+j]==100: 27 | img[i,j]=0 28 | elif data[i*w+j]==0: 29 | img[i,j]=255 30 | elif data[i*w+j]==-1: 31 | img[i,j]=205 32 | 33 | 34 | o=cv2.inRange(img,0,1) 35 | edges = cv2.Canny(img,0,255) 36 | im2, contours, hierarchy = cv2.findContours(o,cv2.RETR_TREE,cv2.CHAIN_APPROX_SIMPLE) 37 | cv2.drawContours(o, contours, -1, (255,255,255), 5) 38 | o=cv2.bitwise_not(o) 39 | res = cv2.bitwise_and(o,edges) 40 | #------------------------------ 41 | 42 | frontier=copy(res) 43 | im2, contours, hierarchy = cv2.findContours(frontier,cv2.RETR_TREE,cv2.CHAIN_APPROX_SIMPLE) 44 | cv2.drawContours(frontier, contours, -1, (255,255,255), 2) 45 | 46 | im2, contours, hierarchy = cv2.findContours(frontier,cv2.RETR_TREE,cv2.CHAIN_APPROX_SIMPLE) 47 | all_pts=[] 48 | if len(contours)>0: 49 | upto=len(contours)-1 50 | i=0 51 | maxx=0 52 | maxind=0 53 | 54 | for i in range(0,len(contours)): 55 | cnt = contours[i] 56 | M = cv2.moments(cnt) 57 | cx = int(M['m10']/M['m00']) 58 | cy = int(M['m01']/M['m00']) 59 | xr=cx*resolution+Xstartx 60 | yr=cy*resolution+Xstarty 61 | pt=[np.array([xr,yr])] 62 | if len(all_pts)>0: 63 | all_pts=np.vstack([all_pts,pt]) 64 | else: 65 | 66 | all_pts=pt 67 | 68 | return all_pts 69 | 70 | 71 | -------------------------------------------------------------------------------- /src/rrt_exploration_tutorials/README.md: -------------------------------------------------------------------------------- 1 | # rrt_exploration_tutorials 2 | This package is a complementary package for the [rrt_exploration](https://github.com/hasauino/rrt_exploration) ROS package. It provides all the needed Gazebo simulation files to bring up Kobuki robots equipped with laser scanners and ready for the [rrt_exploration](https://github.com/hasauino/rrt_exploration) package. 3 | 4 | ## 1. Requirements 5 | The package has been tested on both ROS Kinetic and ROS Indigo, it should work on other distributions like Jade. The following requirements are needed before installing the package: 6 | 7 | 1- You should have installed a ROS distribution (indigo or later. Recommended is either indigo or kinetic). 8 | 9 | 2- Created a workspace. 10 | 11 | 3- Installed the "gmapping" ROS package: on Ubuntu, and if you are running ROS Kinectic, you can do that by typing the following command in the terminal: 12 | 13 | ```sh 14 | $ sudo apt-get install ros-kinetic-gmapping 15 | ``` 16 | 4- Install ROS navigation stack. You can do that with the following command (assuming Ubuntu, ROS Kinetic): 17 | ```sh 18 | $ sudo apt-get install ros-kinetic-navigation 19 | ``` 20 | 5- Install Kobuki robot packages: 21 | ```sh 22 | sudo apt-get install ros-kinetic-kobuki ros-kinetic-kobuki-core 23 | sudo apt-get install ros-kinetic-kobuki-gazebo 24 | ``` 25 | ## 2. Installation 26 | Download the package and place it inside the ```/src``` folder in your workspace. And then compile using ```catkin_make```. 27 | 28 | ## 3. Example 29 | ```sh 30 | roslaunch rrt_exploration_tutorials single_simulated_house.launch 31 | ``` -------------------------------------------------------------------------------- /src/rrt_exploration_tutorials/launch/includes/initposes.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | -------------------------------------------------------------------------------- /src/rrt_exploration_tutorials/launch/includes/map_merge.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /src/rrt_exploration_tutorials/launch/includes/meshes/images/main_body.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/src/rrt_exploration_tutorials/launch/includes/meshes/images/main_body.jpg -------------------------------------------------------------------------------- /src/rrt_exploration_tutorials/launch/includes/meshes/images/wheel.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JeremyZhao1998/IndoorRobotSimulation/245f2a622e9078099b01770d7c221d04b5307e3b/src/rrt_exploration_tutorials/launch/includes/meshes/images/wheel.jpg -------------------------------------------------------------------------------- /src/rrt_exploration_tutorials/launch/includes/robot.launch.xml: -------------------------------------------------------------------------------- 1 | 4 | 5 | 6 | 7 | 8 | 10 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /src/rrt_exploration_tutorials/launch/includes/urdf/common_properties.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | -------------------------------------------------------------------------------- /src/rrt_exploration_tutorials/launch/includes/urdf/kobuki_standalone.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 7 | 8 | 9 | 10 | 11 | 12 | -------------------------------------------------------------------------------- /src/rrt_exploration_tutorials/launch/includes/worlds/MTR.world: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | model://ground_plane 6 | 7 | 8 | model://sun 9 | 10 | 11 | 12 | 13 | 0 0 -0.110060 0 0 0 14 | false 15 | 16 | 17 | 18 | file://MTR_map.dae 19 | 20 | 21 | 22 | 23 | 24 | 25 | file://MTR_map.dae 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | -------------------------------------------------------------------------------- /src/rrt_exploration_tutorials/launch/includes/worlds/largeMap.world: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | model://ground_plane 6 | 7 | 8 | model://sun 9 | 10 | 11 | 12 | 13 | 0 0 -0.110060 0 0 0 14 | false 15 | 16 | 17 | 18 | file://largeMap.dae 19 | 20 | 21 | 22 | 23 | 24 | 25 | file://largeMap.dae 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | -------------------------------------------------------------------------------- /src/rrt_exploration_tutorials/launch/simple.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | -------------------------------------------------------------------------------- /src/rrt_exploration_tutorials/launch/single_simulated_MTR.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | -------------------------------------------------------------------------------- /src/rrt_exploration_tutorials/launch/single_simulated_house.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | -------------------------------------------------------------------------------- /src/rrt_exploration_tutorials/launch/single_simulated_largeMap.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | -------------------------------------------------------------------------------- /src/rrt_exploration_tutorials/launch/single_simulated_square_hall.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | -------------------------------------------------------------------------------- /src/rrt_exploration_tutorials/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | rrt_exploration_tutorials 4 | 1.0.0 5 | This package provides launch files for Gazebo simulation needed to test the rrt_exploration package 6 | 7 | 8 | Hassan Umari 9 | 10 | 11 | MIT 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | Hassan Umari 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | catkin 38 | roscpp 39 | rospy 40 | std_msgs 41 | roscpp 42 | rospy 43 | std_msgs 44 | 45 | 46 | 47 | 48 | 49 | 50 | -------------------------------------------------------------------------------- /src/rrt_exploration_tutorials/param/base_local_planner_params.yaml: -------------------------------------------------------------------------------- 1 | TrajectoryPlannerROS: 2 | max_vel_x: 0.3 3 | min_vel_x: 0.05 4 | max_vel_theta: 0.9 5 | min_in_place_vel_theta: 0.7 6 | acc_lim_theta: 2.0 7 | acc_lim_x: 0.05 8 | acc_lim_y: 0.2 9 | holonomic_robot: false 10 | yaw_goal_tolerance: 2.0 11 | xy_goal_tolerance: 0.3 12 | meter_scoring: true 13 | recovery_behavior_enabled: false 14 | clearing_rotation_allowed: false 15 | 16 | 17 | -------------------------------------------------------------------------------- /src/rrt_exploration_tutorials/param/costmap_common_params.yaml: -------------------------------------------------------------------------------- 1 | #This file contains common configuration options for the two costmaps used in the navigation stack for more details on the parameters in this file, and a full list of the parameters used by the costmaps, please see http://www.ros.org/wiki/costmap_2d 2 | 3 | #For this example we'll configure the costmap in voxel-grid mode 4 | map_type: costmap 5 | 6 | 7 | 8 | #Set the tolerance we're willing to have for tf transforms 9 | transform_tolerance: 2.0 10 | obstacle_range: 3.5 11 | raytrace_range: 4.0 12 | 13 | footprint: [[-0.127, -0.127], [-0.18, 0.0], [-0.127, 0.127], [0.0, 0.18], [0.127, 0.127], [0.18, 0.0], [0.127, -0.127], [0.0, -0.18]] 14 | #robot_radius: 0.18 15 | 16 | 17 | footprint_padding: 0.03 18 | 19 | #Cost function parameters 20 | inflation_radius: 0.55 21 | cost_scaling_factor: 10.0 22 | 23 | #The cost at which a cell is considered an obstacle when a map is read from the map_server 24 | lethal_cost_threshold: 100 25 | 26 | 27 | #Configuration for the sensors that the costmap will use to update a map 28 | observation_sources: laser_scan_sensor 29 | laser_scan_sensor: {sensor_frame: base_laser_link, data_type: LaserScan, topic: /base_scan, marking: true, clearing: true, max_obstacle_height: 20.0, min_obstacle_height: 0.0} 30 | 31 | 32 | -------------------------------------------------------------------------------- /src/rrt_exploration_tutorials/param/global_costmap_params.yaml: -------------------------------------------------------------------------------- 1 | global_costmap: 2 | 3 | global_frame: map 4 | robot_base_frame: base_link 5 | update_frequency: 2.0 6 | publish_frequency: 2.0 7 | static_map: true 8 | rolling_window: true 9 | 10 | width: 100.0 11 | height: 100.0 12 | resolution: 0.05 13 | -------------------------------------------------------------------------------- /src/rrt_exploration_tutorials/param/local_costmap_params.yaml: -------------------------------------------------------------------------------- 1 | local_costmap: 2 | 3 | global_frame: odom 4 | robot_base_frame: base_link 5 | update_frequency: 5.0 6 | publish_frequency: 5.0 7 | static_map: false 8 | rolling_window: true 9 | width: 1.5 10 | height: 1.5 11 | resolution: 0.01 12 | -------------------------------------------------------------------------------- /src/rrt_planner/rrt_planner_plugin.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | This is RRT global planner plugin by changxuefeng. 4 | 5 | 6 | --------------------------------------------------------------------------------