├── 2021_IROS_Placed_FastAutonomousRoboticExplorationUsingTheUnderlyingGraphStructure.pdf ├── README.md ├── results ├── Dopt_graph.png ├── Dopt_naive.png ├── RRT_exploration.png ├── SHR_entropy.png ├── closest.png └── random.png └── src ├── 3dParty ├── kobuki_plugins │ ├── CMakeLists.txt │ ├── include │ │ └── kobuki_gazebo_plugins │ │ │ └── gazebo_ros_kobuki.h │ ├── package.xml │ └── src │ │ ├── gazebo_ros_kobuki.cpp │ │ ├── gazebo_ros_kobuki_loads.cpp │ │ └── gazebo_ros_kobuki_updates.cpp ├── navigation │ ├── README.md │ ├── 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_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 │ │ │ ├── point_grid_node.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 │ ├── 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 │ ├── 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 │ │ │ ├── spectrum.png │ │ │ ├── test_constants.cpp │ │ │ ├── test_constants.h │ │ │ ├── testmap.bmp │ │ │ ├── testmap.png │ │ │ ├── testmap.yaml │ │ │ ├── testmap2.png │ │ │ ├── testmap2.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 │ │ │ │ ├── parameter_magic.h │ │ │ │ └── recovery_behavior.h │ │ └── package.xml │ ├── navfn │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── Makefile.orig │ │ ├── bgp_plugin.xml │ │ ├── include │ │ │ └── navfn │ │ │ │ ├── navfn.h │ │ │ │ ├── navfn_ros.h │ │ │ │ ├── potarr_point.h │ │ │ │ └── read_pgm_costmap.h │ │ ├── package.xml │ │ ├── src │ │ │ ├── navfn.cpp │ │ │ ├── navfn_node.cpp │ │ │ ├── navfn_ros.cpp │ │ │ ├── navtest │ │ │ │ ├── navtest.cpp │ │ │ │ ├── navwin.cpp │ │ │ │ └── navwin.h │ │ │ └── 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 │ ├── 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 └── open_karto │ ├── Authors │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── LICENSE │ ├── README.md │ ├── include │ └── open_karto │ │ ├── Karto.h │ │ ├── Macros.h │ │ ├── Mapper.h │ │ ├── Math.h │ │ └── Types.h │ ├── package.xml │ ├── samples │ ├── CMakeLists.txt │ ├── README.txt │ ├── SpaSolver.cpp │ ├── SpaSolver.h │ ├── tutorial1.cpp │ └── tutorial2.cpp │ └── src │ ├── Karto.cpp │ └── Mapper.cpp ├── graph_d_exploration ├── CMakeLists.txt ├── cfg │ └── informationGain.cfg ├── include │ ├── functions.h │ └── mtrand.h ├── launch │ ├── graph_dopt.launch │ ├── include │ │ ├── meshes │ │ │ ├── hokuyo.dae │ │ │ ├── images │ │ │ │ ├── main_body.jpg │ │ │ │ └── wheel.jpg │ │ │ ├── main_body.dae │ │ │ └── wheel.dae │ │ ├── move_baseSafe.launch │ │ ├── robot.launch.xml │ │ ├── rviz_config │ │ │ └── single.rviz │ │ ├── urdf │ │ │ ├── common_properties.urdf.xacro │ │ │ ├── kobuki.urdf.xacro │ │ │ ├── kobuki_gazebo.urdf.xacro │ │ │ └── kobuki_standalone.urdf.xacro │ │ └── worlds │ │ │ └── willowgarage_modified.world │ └── single_willowGarage.launch ├── msg │ └── PointArray.msg ├── package.xml ├── param │ ├── base_global_planner_params.yaml │ ├── base_local_planner_params.yaml │ ├── costmap_common_params.yaml │ ├── global_costmap_params.yaml │ ├── local_costmap_params.yaml │ ├── mapping_karto_g2o.yaml │ └── recovery_behaviors.yaml ├── scripts │ ├── constants.py │ ├── controller_graphD.py │ ├── filter.py │ ├── functions.py │ ├── initializer.py │ ├── opencv_detector.py │ └── weighted_pose_graph_class.py └── src │ ├── functions.cpp │ ├── global_rrt_detector.cpp │ ├── local_rrt_detector.cpp │ └── mtrand.cpp ├── slam_karto_g2o ├── CMakeLists.txt ├── CMakeModules │ ├── FindCSparse.cmake │ ├── FindCholmod.cmake │ ├── FindG2O.cmake │ └── FindSuiteSparse.cmake ├── LICENSE ├── README.md ├── config │ ├── base_local_planner_params.yaml │ ├── costmap_common_params.yaml │ ├── explore_costmap_params.yaml │ ├── global_costmap_params.yaml │ ├── local_costmap_params.yaml │ ├── mapper_params.yaml │ ├── mapping_karto_g2o.yaml │ ├── move_base.xml │ └── recovery_behaviors.yaml ├── include │ └── slam_karto_g2o │ │ └── G2OSolver.h ├── launch │ ├── build_map_w_params.launch │ └── karto_slam.launch ├── package.xml └── src │ ├── G2OSolver.cpp │ └── slam_karto_g2o.cpp └── validation ├── FRH_P_toro_edges.txt ├── FRH_P_toro_nodes.txt ├── FRH_P_toro_opt_edges.txt ├── FRH_P_toro_opt_nodes.txt ├── analyze_graph_var_FIM.py ├── constants.py ├── utils.py └── weighted_pose_graph_class.py /2021_IROS_Placed_FastAutonomousRoboticExplorationUsingTheUnderlyingGraphStructure.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/2021_IROS_Placed_FastAutonomousRoboticExplorationUsingTheUnderlyingGraphStructure.pdf -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/README.md -------------------------------------------------------------------------------- /results/Dopt_graph.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/results/Dopt_graph.png -------------------------------------------------------------------------------- /results/Dopt_naive.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/results/Dopt_naive.png -------------------------------------------------------------------------------- /results/RRT_exploration.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/results/RRT_exploration.png -------------------------------------------------------------------------------- /results/SHR_entropy.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/results/SHR_entropy.png -------------------------------------------------------------------------------- /results/closest.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/results/closest.png -------------------------------------------------------------------------------- /results/random.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/results/random.png -------------------------------------------------------------------------------- /src/3dParty/kobuki_plugins/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/kobuki_plugins/CMakeLists.txt -------------------------------------------------------------------------------- /src/3dParty/kobuki_plugins/include/kobuki_gazebo_plugins/gazebo_ros_kobuki.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/kobuki_plugins/include/kobuki_gazebo_plugins/gazebo_ros_kobuki.h -------------------------------------------------------------------------------- /src/3dParty/kobuki_plugins/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/kobuki_plugins/package.xml -------------------------------------------------------------------------------- /src/3dParty/kobuki_plugins/src/gazebo_ros_kobuki.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/kobuki_plugins/src/gazebo_ros_kobuki.cpp -------------------------------------------------------------------------------- /src/3dParty/kobuki_plugins/src/gazebo_ros_kobuki_loads.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/kobuki_plugins/src/gazebo_ros_kobuki_loads.cpp -------------------------------------------------------------------------------- /src/3dParty/kobuki_plugins/src/gazebo_ros_kobuki_updates.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/kobuki_plugins/src/gazebo_ros_kobuki_updates.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/README.md -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/CHANGELOG.rst -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/CMakeLists.txt -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/blp_plugin.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/blp_plugin.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/cfg/BaseLocalPlanner.cfg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/cfg/BaseLocalPlanner.cfg -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/cfg/LocalPlannerLimits.cfg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/cfg/LocalPlannerLimits.cfg -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/costmap_model.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/costmap_model.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/footprint_helper.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/footprint_helper.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/goal_functions.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/goal_functions.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/latched_stop_rotate_controller.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/latched_stop_rotate_controller.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/line_iterator.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/line_iterator.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/local_planner_limits.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/local_planner_limits.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/local_planner_util.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/local_planner_util.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/map_cell.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/map_cell.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/map_grid.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/map_grid.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/map_grid_cost_function.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/map_grid_cost_function.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/map_grid_visualizer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/map_grid_visualizer.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/obstacle_cost_function.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/obstacle_cost_function.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/odometry_helper_ros.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/odometry_helper_ros.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/oscillation_cost_function.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/oscillation_cost_function.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/planar_laser_scan.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/planar_laser_scan.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/point_grid.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/point_grid.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/prefer_forward_cost_function.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/prefer_forward_cost_function.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/simple_scored_sampling_planner.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/simple_scored_sampling_planner.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/simple_trajectory_generator.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/simple_trajectory_generator.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/trajectory.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/trajectory.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/trajectory_cost_function.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/trajectory_cost_function.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/trajectory_inc.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/trajectory_inc.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/trajectory_planner.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/trajectory_planner.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/trajectory_planner_ros.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/trajectory_planner_ros.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/trajectory_sample_generator.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/trajectory_sample_generator.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/trajectory_search.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/trajectory_search.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/twirling_cost_function.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/twirling_cost_function.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/velocity_iterator.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/velocity_iterator.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/voxel_grid_model.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/voxel_grid_model.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/include/base_local_planner/world_model.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/include/base_local_planner/world_model.h -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/msg/Position2DInt.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/msg/Position2DInt.msg -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/package.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/setup.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/setup.py -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/costmap_model.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/costmap_model.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/footprint_helper.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/footprint_helper.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/goal_functions.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/goal_functions.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/latched_stop_rotate_controller.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/latched_stop_rotate_controller.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/local_planner_limits/.gitignore: -------------------------------------------------------------------------------- 1 | *.pyc 2 | -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/local_planner_limits/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/local_planner_limits/__init__.py -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/local_planner_util.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/local_planner_util.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/map_cell.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/map_cell.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/map_grid.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/map_grid.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/map_grid_cost_function.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/map_grid_cost_function.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/map_grid_visualizer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/map_grid_visualizer.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/obstacle_cost_function.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/obstacle_cost_function.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/odometry_helper_ros.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/odometry_helper_ros.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/oscillation_cost_function.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/oscillation_cost_function.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/point_grid.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/point_grid.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/point_grid_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/point_grid_node.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/prefer_forward_cost_function.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/prefer_forward_cost_function.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/simple_scored_sampling_planner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/simple_scored_sampling_planner.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/simple_trajectory_generator.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/simple_trajectory_generator.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/trajectory.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/trajectory.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/trajectory_planner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/trajectory_planner.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/trajectory_planner_ros.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/trajectory_planner_ros.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/twirling_cost_function.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/twirling_cost_function.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/src/voxel_grid_model.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/src/voxel_grid_model.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/test/footprint_helper_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/test/footprint_helper_test.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/test/gtest_main.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/test/gtest_main.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/test/line_iterator_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/test/line_iterator_test.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/test/map_grid_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/test/map_grid_test.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/test/trajectory_generator_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/test/trajectory_generator_test.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/test/utest.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/test/utest.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/test/velocity_iterator_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/test/velocity_iterator_test.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/base_local_planner/test/wavefront_map_accessor.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/base_local_planner/test/wavefront_map_accessor.h -------------------------------------------------------------------------------- /src/3dParty/navigation/clear_costmap_recovery/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/clear_costmap_recovery/CHANGELOG.rst -------------------------------------------------------------------------------- /src/3dParty/navigation/clear_costmap_recovery/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/clear_costmap_recovery/CMakeLists.txt -------------------------------------------------------------------------------- /src/3dParty/navigation/clear_costmap_recovery/ccr_plugin.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/clear_costmap_recovery/ccr_plugin.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/clear_costmap_recovery/include/clear_costmap_recovery/clear_costmap_recovery.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/clear_costmap_recovery/include/clear_costmap_recovery/clear_costmap_recovery.h -------------------------------------------------------------------------------- /src/3dParty/navigation/clear_costmap_recovery/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/clear_costmap_recovery/package.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/clear_costmap_recovery/src/clear_costmap_recovery.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/clear_costmap_recovery/src/clear_costmap_recovery.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/clear_costmap_recovery/test/clear_tester.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/clear_costmap_recovery/test/clear_tester.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/clear_costmap_recovery/test/clear_tests.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/clear_costmap_recovery/test/clear_tests.launch -------------------------------------------------------------------------------- /src/3dParty/navigation/clear_costmap_recovery/test/params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/clear_costmap_recovery/test/params.yaml -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/CHANGELOG.rst -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/CMakeLists.txt -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/cfg/Costmap2D.cfg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/cfg/Costmap2D.cfg -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/cfg/GenericPlugin.cfg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/cfg/GenericPlugin.cfg -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/cfg/InflationPlugin.cfg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/cfg/InflationPlugin.cfg -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/cfg/ObstaclePlugin.cfg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/cfg/ObstaclePlugin.cfg -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/cfg/VoxelPlugin.cfg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/cfg/VoxelPlugin.cfg -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/costmap_plugins.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/costmap_plugins.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/include/costmap_2d/array_parser.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/include/costmap_2d/array_parser.h -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/include/costmap_2d/cost_values.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/include/costmap_2d/cost_values.h -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/include/costmap_2d/costmap_2d.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/include/costmap_2d/costmap_2d.h -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/include/costmap_2d/costmap_2d_publisher.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/include/costmap_2d/costmap_2d_publisher.h -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/include/costmap_2d/costmap_2d_ros.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/include/costmap_2d/costmap_2d_ros.h -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/include/costmap_2d/costmap_layer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/include/costmap_2d/costmap_layer.h -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/include/costmap_2d/costmap_math.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/include/costmap_2d/costmap_math.h -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/include/costmap_2d/footprint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/include/costmap_2d/footprint.h -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/include/costmap_2d/inflation_layer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/include/costmap_2d/inflation_layer.h -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/include/costmap_2d/layer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/include/costmap_2d/layer.h -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/include/costmap_2d/layered_costmap.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/include/costmap_2d/layered_costmap.h -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/include/costmap_2d/observation.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/include/costmap_2d/observation.h -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/include/costmap_2d/observation_buffer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/include/costmap_2d/observation_buffer.h -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/include/costmap_2d/obstacle_layer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/include/costmap_2d/obstacle_layer.h -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/include/costmap_2d/static_layer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/include/costmap_2d/static_layer.h -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/include/costmap_2d/testing_helper.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/include/costmap_2d/testing_helper.h -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/include/costmap_2d/voxel_layer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/include/costmap_2d/voxel_layer.h -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/launch/example.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/launch/example.launch -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/launch/example_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/launch/example_params.yaml -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/msg/VoxelGrid.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/msg/VoxelGrid.msg -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/package.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/plugins/inflation_layer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/plugins/inflation_layer.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/plugins/obstacle_layer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/plugins/obstacle_layer.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/plugins/static_layer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/plugins/static_layer.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/plugins/voxel_layer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/plugins/voxel_layer.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/src/array_parser.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/src/array_parser.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/src/costmap_2d.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/src/costmap_2d.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/src/costmap_2d_cloud.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/src/costmap_2d_cloud.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/src/costmap_2d_markers.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/src/costmap_2d_markers.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/src/costmap_2d_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/src/costmap_2d_node.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/src/costmap_2d_publisher.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/src/costmap_2d_publisher.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/src/costmap_2d_ros.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/src/costmap_2d_ros.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/src/costmap_layer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/src/costmap_layer.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/src/costmap_math.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/src/costmap_math.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/src/footprint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/src/footprint.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/src/layer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/src/layer.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/src/layered_costmap.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/src/layered_costmap.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/src/observation_buffer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/src/observation_buffer.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/test/TenByTen.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/test/TenByTen.pgm -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/test/TenByTen.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/test/TenByTen.yaml -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/test/array_parser_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/test/array_parser_test.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/test/coordinates_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/test/coordinates_test.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/test/costmap_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/test/costmap_params.yaml -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/test/costmap_tester.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/test/costmap_tester.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/test/footprint_tests.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/test/footprint_tests.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/test/footprint_tests.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/test/footprint_tests.launch -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/test/inflation_tests.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/test/inflation_tests.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/test/inflation_tests.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/test/inflation_tests.launch -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/test/module_tests.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/test/module_tests.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/test/obstacle_tests.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/test/obstacle_tests.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/test/obstacle_tests.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/test/obstacle_tests.launch -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/test/simple_driving_test.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/test/simple_driving_test.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/test/static_tests.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/test/static_tests.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/costmap_2d/test/static_tests.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/costmap_2d/test/static_tests.launch -------------------------------------------------------------------------------- /src/3dParty/navigation/dwa_local_planner/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/dwa_local_planner/CHANGELOG.rst -------------------------------------------------------------------------------- /src/3dParty/navigation/dwa_local_planner/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/dwa_local_planner/CMakeLists.txt -------------------------------------------------------------------------------- /src/3dParty/navigation/dwa_local_planner/blp_plugin.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/dwa_local_planner/blp_plugin.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/dwa_local_planner/cfg/DWAPlanner.cfg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/dwa_local_planner/cfg/DWAPlanner.cfg -------------------------------------------------------------------------------- /src/3dParty/navigation/dwa_local_planner/include/dwa_local_planner/dwa_planner.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/dwa_local_planner/include/dwa_local_planner/dwa_planner.h -------------------------------------------------------------------------------- /src/3dParty/navigation/dwa_local_planner/include/dwa_local_planner/dwa_planner_ros.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/dwa_local_planner/include/dwa_local_planner/dwa_planner_ros.h -------------------------------------------------------------------------------- /src/3dParty/navigation/dwa_local_planner/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/dwa_local_planner/package.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/dwa_local_planner/src/dwa_planner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/dwa_local_planner/src/dwa_planner.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/dwa_local_planner/src/dwa_planner_ros.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/dwa_local_planner/src/dwa_planner_ros.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/CHANGELOG.rst -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/CMakeLists.txt -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/bgp_plugin.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/bgp_plugin.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/cfg/GlobalPlanner.cfg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/cfg/GlobalPlanner.cfg -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/include/global_planner/astar.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/include/global_planner/astar.h -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/include/global_planner/dijkstra.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/include/global_planner/dijkstra.h -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/include/global_planner/expander.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/include/global_planner/expander.h -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/include/global_planner/gradient_path.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/include/global_planner/gradient_path.h -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/include/global_planner/grid_path.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/include/global_planner/grid_path.h -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/include/global_planner/orientation_filter.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/include/global_planner/orientation_filter.h -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/include/global_planner/planner_core.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/include/global_planner/planner_core.h -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/include/global_planner/potential_calculator.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/include/global_planner/potential_calculator.h -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/include/global_planner/quadratic_calculator.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/include/global_planner/quadratic_calculator.h -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/include/global_planner/traceback.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/include/global_planner/traceback.h -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/package.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/src/astar.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/src/astar.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/src/dijkstra.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/src/dijkstra.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/src/gradient_path.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/src/gradient_path.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/src/grid_path.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/src/grid_path.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/src/orientation_filter.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/src/orientation_filter.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/src/plan_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/src/plan_node.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/src/planner_core.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/src/planner_core.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/global_planner/src/quadratic_calculator.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/global_planner/src/quadratic_calculator.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/map_server/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/map_server/CHANGELOG.rst -------------------------------------------------------------------------------- /src/3dParty/navigation/map_server/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/map_server/CMakeLists.txt -------------------------------------------------------------------------------- /src/3dParty/navigation/map_server/include/map_server/image_loader.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/map_server/include/map_server/image_loader.h -------------------------------------------------------------------------------- /src/3dParty/navigation/map_server/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/map_server/package.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/map_server/scripts/crop_map: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/map_server/scripts/crop_map -------------------------------------------------------------------------------- /src/3dParty/navigation/map_server/src/image_loader.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/map_server/src/image_loader.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/map_server/src/main.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/map_server/src/main.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/map_server/src/map_saver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/map_server/src/map_saver.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/map_server/src/map_server.dox: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/map_server/src/map_server.dox -------------------------------------------------------------------------------- /src/3dParty/navigation/map_server/test/consumer.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/map_server/test/consumer.py -------------------------------------------------------------------------------- /src/3dParty/navigation/map_server/test/rtest.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/map_server/test/rtest.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/map_server/test/rtest.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/map_server/test/rtest.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/map_server/test/spectrum.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/map_server/test/spectrum.png -------------------------------------------------------------------------------- /src/3dParty/navigation/map_server/test/test_constants.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/map_server/test/test_constants.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/map_server/test/test_constants.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/map_server/test/test_constants.h -------------------------------------------------------------------------------- /src/3dParty/navigation/map_server/test/testmap.bmp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/map_server/test/testmap.bmp -------------------------------------------------------------------------------- /src/3dParty/navigation/map_server/test/testmap.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/map_server/test/testmap.png -------------------------------------------------------------------------------- /src/3dParty/navigation/map_server/test/testmap.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/map_server/test/testmap.yaml -------------------------------------------------------------------------------- /src/3dParty/navigation/map_server/test/testmap2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/map_server/test/testmap2.png -------------------------------------------------------------------------------- /src/3dParty/navigation/map_server/test/testmap2.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/map_server/test/testmap2.yaml -------------------------------------------------------------------------------- /src/3dParty/navigation/map_server/test/utest.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/map_server/test/utest.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/move_base/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/move_base/CHANGELOG.rst -------------------------------------------------------------------------------- /src/3dParty/navigation/move_base/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/move_base/CMakeLists.txt -------------------------------------------------------------------------------- /src/3dParty/navigation/move_base/cfg/MoveBase.cfg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/move_base/cfg/MoveBase.cfg -------------------------------------------------------------------------------- /src/3dParty/navigation/move_base/include/move_base/move_base.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/move_base/include/move_base/move_base.h -------------------------------------------------------------------------------- /src/3dParty/navigation/move_base/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/move_base/package.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/move_base/planner_test.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/move_base/planner_test.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/move_base/src/move_base.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/move_base/src/move_base.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/move_base/src/move_base_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/move_base/src/move_base_node.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/move_slow_and_clear/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/move_slow_and_clear/CHANGELOG.rst -------------------------------------------------------------------------------- /src/3dParty/navigation/move_slow_and_clear/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/move_slow_and_clear/CMakeLists.txt -------------------------------------------------------------------------------- /src/3dParty/navigation/move_slow_and_clear/include/move_slow_and_clear/move_slow_and_clear.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/move_slow_and_clear/include/move_slow_and_clear/move_slow_and_clear.h -------------------------------------------------------------------------------- /src/3dParty/navigation/move_slow_and_clear/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/move_slow_and_clear/package.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/move_slow_and_clear/recovery_plugin.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/move_slow_and_clear/recovery_plugin.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/move_slow_and_clear/src/move_slow_and_clear.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/move_slow_and_clear/src/move_slow_and_clear.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/nav_core/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/nav_core/CHANGELOG.rst -------------------------------------------------------------------------------- /src/3dParty/navigation/nav_core/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/nav_core/CMakeLists.txt -------------------------------------------------------------------------------- /src/3dParty/navigation/nav_core/include/nav_core/base_global_planner.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/nav_core/include/nav_core/base_global_planner.h -------------------------------------------------------------------------------- /src/3dParty/navigation/nav_core/include/nav_core/base_local_planner.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/nav_core/include/nav_core/base_local_planner.h -------------------------------------------------------------------------------- /src/3dParty/navigation/nav_core/include/nav_core/parameter_magic.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/nav_core/include/nav_core/parameter_magic.h -------------------------------------------------------------------------------- /src/3dParty/navigation/nav_core/include/nav_core/recovery_behavior.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/nav_core/include/nav_core/recovery_behavior.h -------------------------------------------------------------------------------- /src/3dParty/navigation/nav_core/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/nav_core/package.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/navfn/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navfn/CHANGELOG.rst -------------------------------------------------------------------------------- /src/3dParty/navigation/navfn/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navfn/CMakeLists.txt -------------------------------------------------------------------------------- /src/3dParty/navigation/navfn/Makefile.orig: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navfn/Makefile.orig -------------------------------------------------------------------------------- /src/3dParty/navigation/navfn/bgp_plugin.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navfn/bgp_plugin.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/navfn/include/navfn/navfn.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navfn/include/navfn/navfn.h -------------------------------------------------------------------------------- /src/3dParty/navigation/navfn/include/navfn/navfn_ros.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navfn/include/navfn/navfn_ros.h -------------------------------------------------------------------------------- /src/3dParty/navigation/navfn/include/navfn/potarr_point.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navfn/include/navfn/potarr_point.h -------------------------------------------------------------------------------- /src/3dParty/navigation/navfn/include/navfn/read_pgm_costmap.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navfn/include/navfn/read_pgm_costmap.h -------------------------------------------------------------------------------- /src/3dParty/navigation/navfn/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navfn/package.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/navfn/src/navfn.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navfn/src/navfn.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/navfn/src/navfn_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navfn/src/navfn_node.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/navfn/src/navfn_ros.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navfn/src/navfn_ros.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/navfn/src/navtest/navtest.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navfn/src/navtest/navtest.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/navfn/src/navtest/navwin.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navfn/src/navtest/navwin.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/navfn/src/navtest/navwin.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navfn/src/navtest/navwin.h -------------------------------------------------------------------------------- /src/3dParty/navigation/navfn/src/read_pgm_costmap.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navfn/src/read_pgm_costmap.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/navfn/srv/MakeNavPlan.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navfn/srv/MakeNavPlan.srv -------------------------------------------------------------------------------- /src/3dParty/navigation/navfn/srv/SetCostmap.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navfn/srv/SetCostmap.srv -------------------------------------------------------------------------------- /src/3dParty/navigation/navfn/test/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navfn/test/CMakeLists.txt -------------------------------------------------------------------------------- /src/3dParty/navigation/navfn/test/path_calc_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navfn/test/path_calc_test.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/navfn/test/willow_costmap.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navfn/test/willow_costmap.pgm -------------------------------------------------------------------------------- /src/3dParty/navigation/navigation/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navigation/CHANGELOG.rst -------------------------------------------------------------------------------- /src/3dParty/navigation/navigation/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navigation/CMakeLists.txt -------------------------------------------------------------------------------- /src/3dParty/navigation/navigation/README.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navigation/README.rst -------------------------------------------------------------------------------- /src/3dParty/navigation/navigation/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/navigation/package.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/rotate_recovery/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/rotate_recovery/CHANGELOG.rst -------------------------------------------------------------------------------- /src/3dParty/navigation/rotate_recovery/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/rotate_recovery/CMakeLists.txt -------------------------------------------------------------------------------- /src/3dParty/navigation/rotate_recovery/include/rotate_recovery/rotate_recovery.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/rotate_recovery/include/rotate_recovery/rotate_recovery.h -------------------------------------------------------------------------------- /src/3dParty/navigation/rotate_recovery/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/rotate_recovery/package.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/rotate_recovery/rotate_plugin.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/rotate_recovery/rotate_plugin.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/rotate_recovery/src/rotate_recovery.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/rotate_recovery/src/rotate_recovery.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/voxel_grid/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/voxel_grid/CHANGELOG.rst -------------------------------------------------------------------------------- /src/3dParty/navigation/voxel_grid/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/voxel_grid/CMakeLists.txt -------------------------------------------------------------------------------- /src/3dParty/navigation/voxel_grid/include/voxel_grid/voxel_grid.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/voxel_grid/include/voxel_grid/voxel_grid.h -------------------------------------------------------------------------------- /src/3dParty/navigation/voxel_grid/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/voxel_grid/package.xml -------------------------------------------------------------------------------- /src/3dParty/navigation/voxel_grid/src/voxel_grid.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/voxel_grid/src/voxel_grid.cpp -------------------------------------------------------------------------------- /src/3dParty/navigation/voxel_grid/test/voxel_grid_tests.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/navigation/voxel_grid/test/voxel_grid_tests.cpp -------------------------------------------------------------------------------- /src/3dParty/open_karto/Authors: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/open_karto/Authors -------------------------------------------------------------------------------- /src/3dParty/open_karto/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/open_karto/CHANGELOG.rst -------------------------------------------------------------------------------- /src/3dParty/open_karto/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/open_karto/CMakeLists.txt -------------------------------------------------------------------------------- /src/3dParty/open_karto/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/open_karto/LICENSE -------------------------------------------------------------------------------- /src/3dParty/open_karto/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/open_karto/README.md -------------------------------------------------------------------------------- /src/3dParty/open_karto/include/open_karto/Karto.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/open_karto/include/open_karto/Karto.h -------------------------------------------------------------------------------- /src/3dParty/open_karto/include/open_karto/Macros.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/open_karto/include/open_karto/Macros.h -------------------------------------------------------------------------------- /src/3dParty/open_karto/include/open_karto/Mapper.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/open_karto/include/open_karto/Mapper.h -------------------------------------------------------------------------------- /src/3dParty/open_karto/include/open_karto/Math.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/open_karto/include/open_karto/Math.h -------------------------------------------------------------------------------- /src/3dParty/open_karto/include/open_karto/Types.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/open_karto/include/open_karto/Types.h -------------------------------------------------------------------------------- /src/3dParty/open_karto/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/open_karto/package.xml -------------------------------------------------------------------------------- /src/3dParty/open_karto/samples/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/open_karto/samples/CMakeLists.txt -------------------------------------------------------------------------------- /src/3dParty/open_karto/samples/README.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/open_karto/samples/README.txt -------------------------------------------------------------------------------- /src/3dParty/open_karto/samples/SpaSolver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/open_karto/samples/SpaSolver.cpp -------------------------------------------------------------------------------- /src/3dParty/open_karto/samples/SpaSolver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/open_karto/samples/SpaSolver.h -------------------------------------------------------------------------------- /src/3dParty/open_karto/samples/tutorial1.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/open_karto/samples/tutorial1.cpp -------------------------------------------------------------------------------- /src/3dParty/open_karto/samples/tutorial2.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/open_karto/samples/tutorial2.cpp -------------------------------------------------------------------------------- /src/3dParty/open_karto/src/Karto.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/open_karto/src/Karto.cpp -------------------------------------------------------------------------------- /src/3dParty/open_karto/src/Mapper.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/3dParty/open_karto/src/Mapper.cpp -------------------------------------------------------------------------------- /src/graph_d_exploration/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/CMakeLists.txt -------------------------------------------------------------------------------- /src/graph_d_exploration/cfg/informationGain.cfg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/cfg/informationGain.cfg -------------------------------------------------------------------------------- /src/graph_d_exploration/include/functions.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/include/functions.h -------------------------------------------------------------------------------- /src/graph_d_exploration/include/mtrand.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/include/mtrand.h -------------------------------------------------------------------------------- /src/graph_d_exploration/launch/graph_dopt.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/launch/graph_dopt.launch -------------------------------------------------------------------------------- /src/graph_d_exploration/launch/include/meshes/hokuyo.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/launch/include/meshes/hokuyo.dae -------------------------------------------------------------------------------- /src/graph_d_exploration/launch/include/meshes/images/main_body.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/launch/include/meshes/images/main_body.jpg -------------------------------------------------------------------------------- /src/graph_d_exploration/launch/include/meshes/images/wheel.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/launch/include/meshes/images/wheel.jpg -------------------------------------------------------------------------------- /src/graph_d_exploration/launch/include/meshes/main_body.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/launch/include/meshes/main_body.dae -------------------------------------------------------------------------------- /src/graph_d_exploration/launch/include/meshes/wheel.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/launch/include/meshes/wheel.dae -------------------------------------------------------------------------------- /src/graph_d_exploration/launch/include/move_baseSafe.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/launch/include/move_baseSafe.launch -------------------------------------------------------------------------------- /src/graph_d_exploration/launch/include/robot.launch.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/launch/include/robot.launch.xml -------------------------------------------------------------------------------- /src/graph_d_exploration/launch/include/rviz_config/single.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/launch/include/rviz_config/single.rviz -------------------------------------------------------------------------------- /src/graph_d_exploration/launch/include/urdf/common_properties.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/launch/include/urdf/common_properties.urdf.xacro -------------------------------------------------------------------------------- /src/graph_d_exploration/launch/include/urdf/kobuki.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/launch/include/urdf/kobuki.urdf.xacro -------------------------------------------------------------------------------- /src/graph_d_exploration/launch/include/urdf/kobuki_gazebo.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/launch/include/urdf/kobuki_gazebo.urdf.xacro -------------------------------------------------------------------------------- /src/graph_d_exploration/launch/include/urdf/kobuki_standalone.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/launch/include/urdf/kobuki_standalone.urdf.xacro -------------------------------------------------------------------------------- /src/graph_d_exploration/launch/include/worlds/willowgarage_modified.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/launch/include/worlds/willowgarage_modified.world -------------------------------------------------------------------------------- /src/graph_d_exploration/launch/single_willowGarage.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/launch/single_willowGarage.launch -------------------------------------------------------------------------------- /src/graph_d_exploration/msg/PointArray.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/msg/PointArray.msg -------------------------------------------------------------------------------- /src/graph_d_exploration/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/package.xml -------------------------------------------------------------------------------- /src/graph_d_exploration/param/base_global_planner_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/param/base_global_planner_params.yaml -------------------------------------------------------------------------------- /src/graph_d_exploration/param/base_local_planner_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/param/base_local_planner_params.yaml -------------------------------------------------------------------------------- /src/graph_d_exploration/param/costmap_common_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/param/costmap_common_params.yaml -------------------------------------------------------------------------------- /src/graph_d_exploration/param/global_costmap_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/param/global_costmap_params.yaml -------------------------------------------------------------------------------- /src/graph_d_exploration/param/local_costmap_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/param/local_costmap_params.yaml -------------------------------------------------------------------------------- /src/graph_d_exploration/param/mapping_karto_g2o.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/param/mapping_karto_g2o.yaml -------------------------------------------------------------------------------- /src/graph_d_exploration/param/recovery_behaviors.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/param/recovery_behaviors.yaml -------------------------------------------------------------------------------- /src/graph_d_exploration/scripts/constants.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/scripts/constants.py -------------------------------------------------------------------------------- /src/graph_d_exploration/scripts/controller_graphD.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/scripts/controller_graphD.py -------------------------------------------------------------------------------- /src/graph_d_exploration/scripts/filter.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/scripts/filter.py -------------------------------------------------------------------------------- /src/graph_d_exploration/scripts/functions.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/scripts/functions.py -------------------------------------------------------------------------------- /src/graph_d_exploration/scripts/initializer.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/scripts/initializer.py -------------------------------------------------------------------------------- /src/graph_d_exploration/scripts/opencv_detector.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/scripts/opencv_detector.py -------------------------------------------------------------------------------- /src/graph_d_exploration/scripts/weighted_pose_graph_class.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/scripts/weighted_pose_graph_class.py -------------------------------------------------------------------------------- /src/graph_d_exploration/src/functions.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/src/functions.cpp -------------------------------------------------------------------------------- /src/graph_d_exploration/src/global_rrt_detector.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/src/global_rrt_detector.cpp -------------------------------------------------------------------------------- /src/graph_d_exploration/src/local_rrt_detector.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/src/local_rrt_detector.cpp -------------------------------------------------------------------------------- /src/graph_d_exploration/src/mtrand.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/graph_d_exploration/src/mtrand.cpp -------------------------------------------------------------------------------- /src/slam_karto_g2o/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/CMakeLists.txt -------------------------------------------------------------------------------- /src/slam_karto_g2o/CMakeModules/FindCSparse.cmake: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/CMakeModules/FindCSparse.cmake -------------------------------------------------------------------------------- /src/slam_karto_g2o/CMakeModules/FindCholmod.cmake: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/CMakeModules/FindCholmod.cmake -------------------------------------------------------------------------------- /src/slam_karto_g2o/CMakeModules/FindG2O.cmake: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/CMakeModules/FindG2O.cmake -------------------------------------------------------------------------------- /src/slam_karto_g2o/CMakeModules/FindSuiteSparse.cmake: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/CMakeModules/FindSuiteSparse.cmake -------------------------------------------------------------------------------- /src/slam_karto_g2o/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/LICENSE -------------------------------------------------------------------------------- /src/slam_karto_g2o/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/README.md -------------------------------------------------------------------------------- /src/slam_karto_g2o/config/base_local_planner_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/config/base_local_planner_params.yaml -------------------------------------------------------------------------------- /src/slam_karto_g2o/config/costmap_common_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/config/costmap_common_params.yaml -------------------------------------------------------------------------------- /src/slam_karto_g2o/config/explore_costmap_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/config/explore_costmap_params.yaml -------------------------------------------------------------------------------- /src/slam_karto_g2o/config/global_costmap_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/config/global_costmap_params.yaml -------------------------------------------------------------------------------- /src/slam_karto_g2o/config/local_costmap_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/config/local_costmap_params.yaml -------------------------------------------------------------------------------- /src/slam_karto_g2o/config/mapper_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/config/mapper_params.yaml -------------------------------------------------------------------------------- /src/slam_karto_g2o/config/mapping_karto_g2o.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/config/mapping_karto_g2o.yaml -------------------------------------------------------------------------------- /src/slam_karto_g2o/config/move_base.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/config/move_base.xml -------------------------------------------------------------------------------- /src/slam_karto_g2o/config/recovery_behaviors.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/config/recovery_behaviors.yaml -------------------------------------------------------------------------------- /src/slam_karto_g2o/include/slam_karto_g2o/G2OSolver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/include/slam_karto_g2o/G2OSolver.h -------------------------------------------------------------------------------- /src/slam_karto_g2o/launch/build_map_w_params.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/launch/build_map_w_params.launch -------------------------------------------------------------------------------- /src/slam_karto_g2o/launch/karto_slam.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/launch/karto_slam.launch -------------------------------------------------------------------------------- /src/slam_karto_g2o/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/package.xml -------------------------------------------------------------------------------- /src/slam_karto_g2o/src/G2OSolver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/src/G2OSolver.cpp -------------------------------------------------------------------------------- /src/slam_karto_g2o/src/slam_karto_g2o.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/slam_karto_g2o/src/slam_karto_g2o.cpp -------------------------------------------------------------------------------- /src/validation/FRH_P_toro_edges.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/validation/FRH_P_toro_edges.txt -------------------------------------------------------------------------------- /src/validation/FRH_P_toro_nodes.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/validation/FRH_P_toro_nodes.txt -------------------------------------------------------------------------------- /src/validation/FRH_P_toro_opt_edges.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/validation/FRH_P_toro_opt_edges.txt -------------------------------------------------------------------------------- /src/validation/FRH_P_toro_opt_nodes.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/validation/FRH_P_toro_opt_nodes.txt -------------------------------------------------------------------------------- /src/validation/analyze_graph_var_FIM.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/validation/analyze_graph_var_FIM.py -------------------------------------------------------------------------------- /src/validation/constants.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/validation/constants.py -------------------------------------------------------------------------------- /src/validation/utils.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/validation/utils.py -------------------------------------------------------------------------------- /src/validation/weighted_pose_graph_class.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JulioPlaced/active_graph_slam/HEAD/src/validation/weighted_pose_graph_class.py --------------------------------------------------------------------------------