├── .gitignore ├── CMakeLists.txt ├── LeGO-LOAM ├── .vscode │ └── settings.json ├── LICENSE ├── LeGO-LOAM │ ├── CMakeLists.txt │ ├── include │ │ ├── fftm │ │ │ ├── fftm.cpp │ │ │ └── fftm.hpp │ │ ├── tic_toc.h │ │ └── utility.h │ ├── launch │ │ ├── block.png │ │ ├── dataset-demo.gif │ │ ├── demo-map.rviz │ │ ├── demo.gif │ │ ├── faster.launch │ │ ├── google-earth.png │ │ ├── jackal-label.jpg │ │ ├── odometry.jpg │ │ ├── run.launch │ │ ├── seg-total.jpg │ │ ├── test.launch │ │ ├── test.rviz │ │ ├── xxx.txt │ │ ├── xxx00.txt │ │ ├── xxx09.txt │ │ ├── 启动文件说明.md │ │ └── 启动文件说明.pdf │ ├── package.xml │ ├── src1 │ │ ├── LidarIris.cpp │ │ ├── LidarIris.h │ │ ├── featureAssociation.cpp │ │ ├── imageProjection.cpp │ │ ├── main.cpp │ │ ├── mapOptmization_loop_iris.cpp │ │ ├── mapOptmization_loop_iris_cleaned.cpp │ │ ├── mapOptmization_loop_iris_submap.cpp │ │ └── transformFusion.cpp │ └── urdf │ │ └── car.urdf ├── README.md └── cloud_msgs │ ├── CMakeLists.txt │ ├── msg │ └── cloud_info.msg │ └── package.xml ├── LidarAtlas ├── CMakeLists.txt ├── launch │ └── run.launch ├── package.xml └── src │ ├── LidarAtlas_node.cpp │ ├── LidarAtlas_noloop_node.cpp.bak │ ├── gd │ ├── commonRansac.h │ ├── config.h │ ├── globalmap_builder.cpp │ ├── globalmap_builder.h │ ├── ground_detect.cpp │ ├── ground_detect.h │ ├── legoFeature.cpp │ ├── legoFeature.h │ ├── lidarRoadDetect.cpp │ ├── lidarRoadDetect.h │ ├── map_builder.cpp │ ├── map_builder.h │ ├── map_builder_noloop.cpp.bak │ ├── map_builder_noloop.h │ ├── mutli_execute.h │ ├── probability_values.cpp │ ├── probability_values.h │ └── simple_probability_values.h.bak │ └── lidar_atlas_node.cpp ├── README.md ├── autonomous_exploration_development_environment ├── .gitignore ├── README.md ├── img │ └── header.jpg └── src │ ├── joystick_drivers │ ├── README.md │ ├── joy │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── README.md │ │ ├── config │ │ │ └── ps4joy.yaml │ │ ├── launch │ │ │ └── ps4joy.launch │ │ ├── mainpage.dox │ │ ├── migration_rules │ │ │ └── Joy.bmr │ │ ├── package.xml │ │ ├── scripts │ │ │ └── joy_remap.py │ │ ├── src │ │ │ └── joy_node.cpp │ │ └── test │ │ │ ├── saved │ │ │ └── Joy.saved │ │ │ └── test_joy_msg_migration.py │ ├── joystick_drivers │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ └── package.xml │ └── ps3joy │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── README.md │ │ ├── diagnostics.yaml │ │ ├── doc │ │ ├── bluetooth_devices.md │ │ ├── testing.md │ │ └── troubleshooting.md │ │ ├── launch │ │ └── ps3.launch │ │ ├── package.xml │ │ ├── scripts │ │ ├── ps3joy.py │ │ ├── ps3joy_node.py │ │ └── ps3joysim.py │ │ └── src │ │ └── sixpair.c │ ├── loam_interface │ ├── CMakeLists.txt │ ├── launch │ │ └── loam_interface.launch │ ├── package.xml │ └── src │ │ └── loamInterface.cpp │ ├── local_planner │ ├── CMakeLists.txt │ ├── launch │ │ └── local_planner.launch │ ├── package.xml │ ├── paths │ │ ├── correspondences.txt │ │ ├── pathList.ply │ │ ├── path_generator.m │ │ ├── paths.ply │ │ └── startPaths.ply │ └── src │ │ ├── localPlanner.cpp │ │ └── pathFollower.cpp │ ├── sensor_scan_generation │ ├── CMakeLists.txt │ ├── launch │ │ └── sensor_scan_generation.launch │ ├── package.xml │ └── src │ │ └── sensorScanGeneration.cpp │ ├── terrain_analysis │ ├── CMakeLists.txt │ ├── launch │ │ └── terrain_analysis.launch │ ├── package.xml │ └── src │ │ └── terrainAnalysis.cpp │ ├── terrain_analysis_ext │ ├── CMakeLists.txt │ ├── launch │ │ └── terrain_analysis_ext.launch │ ├── package.xml │ └── src │ │ └── terrainAnalysisExt.cpp │ ├── vehicle_simulator │ ├── CMakeLists.txt │ ├── launch │ │ ├── rviz.launch │ │ ├── system_campus.launch │ │ ├── system_forest.launch │ │ ├── system_garage.launch │ │ ├── system_indoor.launch │ │ ├── system_real_robot.launch │ │ ├── system_tunnel.launch │ │ └── vehicle_simulator.launch │ ├── log │ │ └── readme.txt │ ├── mesh │ │ └── download_environments.sh │ ├── package.xml │ ├── rviz │ │ └── vehicle_simulator.rviz │ ├── src │ │ └── vehicleSimulator.cpp │ ├── urdf │ │ ├── camera.urdf.xacro │ │ ├── lidar.urdf.xacro │ │ └── robot.urdf.xacro │ └── world │ │ ├── campus.world │ │ ├── forest.world │ │ ├── garage.world │ │ ├── indoor.world │ │ └── tunnel.world │ ├── velodyne_simulator │ ├── LICENSE │ ├── README.md │ ├── velodyne_description │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── launch │ │ │ └── example.launch │ │ ├── meshes │ │ │ ├── HDL32E_base.dae │ │ │ ├── HDL32E_base.stl │ │ │ ├── HDL32E_scan.dae │ │ │ ├── HDL32E_scan.stl │ │ │ ├── VLP16_base_1.dae │ │ │ ├── VLP16_base_1.stl │ │ │ ├── VLP16_base_2.dae │ │ │ ├── VLP16_base_2.stl │ │ │ ├── VLP16_scan.dae │ │ │ └── VLP16_scan.stl │ │ ├── package.xml │ │ ├── rviz │ │ │ └── example.rviz │ │ ├── urdf │ │ │ ├── HDL-32E.urdf.xacro │ │ │ ├── VLP-16.urdf.xacro │ │ │ └── example.urdf.xacro │ │ └── world │ │ │ └── example.world │ ├── velodyne_gazebo_plugins │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── include │ │ │ └── velodyne_gazebo_plugins │ │ │ │ └── GazeboRosVelodyneLaser.h │ │ ├── package.xml │ │ └── src │ │ │ └── GazeboRosVelodyneLaser.cpp │ └── velodyne_simulator │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ └── package.xml │ ├── visualization_tools │ ├── CMakeLists.txt │ ├── launch │ │ └── visualization_tools.launch │ ├── package.xml │ ├── scripts │ │ └── realTimePlot.py │ └── src │ │ └── visualizationTools.cpp │ ├── waypoint_example │ ├── CMakeLists.txt │ ├── data │ │ ├── boundary_garage.ply │ │ └── waypoints_garage.ply │ ├── launch │ │ └── waypoint_example_garage.launch │ ├── package.xml │ └── src │ │ └── waypointExample.cpp │ └── waypoint_rviz_plugin │ ├── CMakeLists.txt │ ├── include │ └── waypoint_tool.h │ ├── package.xml │ ├── plugin_description.xml │ └── src │ └── waypoint_tool.cpp ├── chunkmap ├── CMakeLists.txt ├── include │ ├── chunkmap │ │ ├── LidarIris │ │ │ ├── LidarIris.h │ │ │ └── fftm │ │ │ │ └── fftm.hpp │ │ ├── aztools │ │ │ ├── bitset.hpp │ │ │ └── mat.hpp │ │ ├── chunk_map.h │ │ ├── simple_probability_values.h │ │ └── simple_probability_values.h.bak │ └── chunkmap_ros │ │ ├── chunk_map_client.h │ │ └── chunk_map_service.h ├── package.xml └── src │ ├── chunkmap │ ├── LidarIris │ │ ├── LidarIris.cpp │ │ └── fftm │ │ │ └── fftm.cpp │ ├── chunk_map.cpp │ ├── chunk_map_msgpack_serialise.cpp │ └── chunk_map_msgpack_serialise_minimal.cpp │ └── chunkmap_ros │ ├── chunk_map_client.cpp │ └── chunk_map_service.cpp ├── chunkmap_msgs ├── CMakeLists.txt ├── msg │ ├── ChunkData.msg │ ├── ChunkIndex.msg │ ├── ChunkLayer.msg │ ├── ChunkMapInfo.msg │ ├── ChunkVizData.msg │ ├── ChunkVizLayer.msg │ ├── KeyFrameData.msg │ ├── KeyFrameInfo.msg │ └── UpdateList.msg ├── package.xml └── srv │ ├── GetChunkData.srv │ ├── GetChunkMapInfo.srv │ ├── GetChunkVizData.srv │ ├── GetKeyFrameData.srv │ └── GetKeyFrameInfo.srv ├── chunkmap_rviz ├── CMakeLists.txt ├── ogre_media │ └── materials │ │ ├── glsl120 │ │ ├── chunk_cell.frag │ │ ├── chunk_cell.program │ │ └── chunk_cell.vert │ │ └── scripts │ │ └── chunk_cell.material ├── package.xml ├── plugin_description.xml └── src │ └── chunkmap_rviz │ ├── chunk_visual.cpp │ ├── chunk_visual.h │ ├── chunkmap_display.cpp │ └── chunkmap_display.h ├── chunkmap_terrain ├── CMakeLists.txt ├── launch │ └── run.launch ├── package.xml └── src │ └── chunkmap_terrain_node.cpp ├── graph_gain_exploration └── src │ ├── catkin_simple │ ├── CMakeLists.txt │ ├── README.md │ ├── cmake │ │ └── catkin_simple-extras.cmake.em │ ├── package.xml │ └── test │ │ └── scenarios │ │ └── hello_world │ │ ├── .gitignore │ │ ├── bar │ │ ├── include │ │ │ └── bar │ │ │ │ └── hello.h │ │ ├── msg │ │ │ └── HeaderString.msg │ │ ├── package.xml │ │ └── src │ │ │ └── hello.cpp │ │ ├── baz │ │ ├── include │ │ │ └── baz │ │ │ │ └── world.h │ │ └── package.xml │ │ └── foo │ │ ├── package.xml │ │ └── src │ │ └── main.cpp │ ├── dsvplanner │ ├── dsvp_launch │ │ ├── CMakeLists.txt │ │ ├── config │ │ │ ├── exploration.yaml │ │ │ ├── exploration_campus.yaml │ │ │ ├── exploration_forest.yaml │ │ │ ├── exploration_garage.yaml │ │ │ ├── exploration_indoor.yaml │ │ │ ├── exploration_matterport.yaml │ │ │ ├── exploration_tunnel.yaml │ │ │ ├── octomap.yaml │ │ │ ├── octomap_campus.yaml │ │ │ ├── octomap_forest.yaml │ │ │ ├── octomap_garage.yaml │ │ │ ├── octomap_indoor.yaml │ │ │ ├── octomap_matterport.yaml │ │ │ └── octomap_tunnel.yaml │ │ ├── data │ │ │ └── boundary.ply │ │ ├── default.rviz │ │ ├── dsvp.rviz │ │ ├── launch │ │ │ ├── dog.launch │ │ │ ├── dsvp.launch │ │ │ ├── explore_campus.launch │ │ │ ├── explore_forest.launch │ │ │ ├── explore_garage.launch │ │ │ ├── explore_indoor.launch │ │ │ ├── explore_matterport.launch │ │ │ ├── explore_tunnel.launch │ │ │ └── rosbag_record.launch │ │ ├── package.xml │ │ └── src │ │ │ ├── exploration.cpp │ │ │ └── navigationBoundary.cpp │ ├── dsvplanner │ │ ├── CMakeLists.txt │ │ ├── include │ │ │ ├── concave2d │ │ │ │ ├── az_concave2d.hpp │ │ │ │ └── delaunator.hpp │ │ │ └── dsvplanner │ │ │ │ ├── chunkmap_helper.h │ │ │ │ ├── drrt.h │ │ │ │ ├── drrt_base.h │ │ │ │ ├── drrtp.h │ │ │ │ ├── dual_state_frontier.h │ │ │ │ ├── dual_state_graph.h │ │ │ │ └── grid.h │ │ ├── package.xml │ │ ├── src │ │ │ ├── chunkmap_helper.cpp │ │ │ ├── drrt.cpp │ │ │ ├── drrtp.cpp │ │ │ ├── drrtp_node.cpp │ │ │ ├── dual_state_frontier.cpp │ │ │ ├── dual_state_graph.cpp │ │ │ └── grid.cpp │ │ └── srv │ │ │ ├── clean_frontier_srv.srv │ │ │ └── dsvplanner_srv.srv │ ├── graph_planner │ │ ├── CMakeLists.txt │ │ ├── config │ │ │ ├── default.yaml │ │ │ └── matterport.yaml │ │ ├── include │ │ │ └── graph_planner.h │ │ ├── launch │ │ │ ├── graph_planner.launch │ │ │ └── graph_planner_matterport.launch │ │ ├── msg │ │ │ ├── GraphPlannerCommand.msg │ │ │ └── GraphPlannerStatus.msg │ │ ├── package.xml │ │ └── src │ │ │ ├── graph_planner.cpp │ │ │ └── graph_planner_node.cpp │ ├── graph_utils │ │ ├── CMakeLists.txt │ │ ├── config │ │ │ └── default.yaml │ │ ├── include │ │ │ ├── graph_utils.h │ │ │ └── graph_visualization.h │ │ ├── launch │ │ │ └── graph_visualization.launch │ │ ├── msg │ │ │ ├── Edge.msg │ │ │ ├── TopologicalGraph.msg │ │ │ └── Vertex.msg │ │ ├── package.xml │ │ └── src │ │ │ ├── graph_utils.cpp │ │ │ ├── graph_visualization.cpp │ │ │ └── graph_visualization_node.cpp │ └── misc_utils │ │ ├── CMakeLists.txt │ │ ├── include │ │ └── misc_utils │ │ │ └── misc_utils.h │ │ ├── package.xml │ │ └── src │ │ └── misc_utils.cpp │ ├── kdtree │ ├── CMakeLists.txt │ ├── include │ │ └── kdtree │ │ │ └── kdtree.h │ ├── package.xml │ └── src │ │ └── kdtree.c │ ├── minkindr │ ├── README.md │ └── minkindr │ │ ├── CMakeLists.txt │ │ ├── include │ │ └── kindr │ │ │ └── minimal │ │ │ ├── angle-axis.h │ │ │ ├── common.h │ │ │ ├── implementation │ │ │ ├── angle-axis-inl.h │ │ │ ├── quat-sim-transform-inl.h │ │ │ ├── quat-transformation-inl.h │ │ │ └── rotation-quaternion-inl.h │ │ │ ├── position.h │ │ │ ├── quat-sim-transform.h │ │ │ ├── quat-transformation.h │ │ │ └── rotation-quaternion.h │ │ ├── package.xml │ │ └── test │ │ ├── test-main.cc │ │ ├── test-rotation.cc │ │ ├── test-sim3.cc │ │ └── test-transformation.cc │ ├── minkindr_ros │ ├── README.md │ └── minkindr_conversions │ │ ├── CMakeLists.txt │ │ ├── include │ │ └── minkindr_conversions │ │ │ ├── kindr_msg.h │ │ │ ├── kindr_tf.h │ │ │ └── kindr_xml.h │ │ ├── package.xml │ │ ├── src │ │ ├── kindr_msg.cc │ │ ├── kindr_tf.cc │ │ └── kindr_xml.cc │ │ └── test │ │ ├── kindr_msg_test.cc │ │ ├── kindr_tf_test.cc │ │ └── testing_predicates.h │ └── volumetric_mapping │ ├── README.md │ ├── octomap_world │ ├── CMakeLists.txt │ ├── include │ │ └── octomap_world │ │ │ ├── octomap_manager.h │ │ │ └── octomap_world.h │ ├── package.xml │ └── src │ │ ├── octomap_manager.cc │ │ ├── octomap_manager_node.cc │ │ └── octomap_world.cc │ ├── volumetric_map_base │ ├── CMakeLists.txt │ ├── include │ │ └── volumetric_map_base │ │ │ ├── point_weighing.h │ │ │ └── world_base.h │ ├── package.xml │ └── src │ │ └── world_base.cc │ └── volumetric_msgs │ ├── CMakeLists.txt │ ├── package.xml │ └── srv │ ├── LoadMap.srv │ ├── SaveMap.srv │ ├── SetBoxOccupancy.srv │ └── SetDisplayBounds.srv ├── lkh_tsp_solver ├── CMakeLists.txt ├── include │ ├── Delaunay.h │ ├── GainType.h │ ├── Genetic.h │ ├── GeoConversion.h │ ├── Hashing.h │ ├── Heap.h │ ├── LKH.h │ ├── Segment.h │ ├── Sequence.h │ ├── gpx.h │ └── lkh_tsp_solver │ │ └── lkh_interface.h ├── package.xml ├── resource │ ├── single.par │ ├── single.tsp │ ├── single.txt │ ├── test.par │ ├── test.tsp │ └── test.txt └── src │ ├── Activate.c │ ├── AddCandidate.c │ ├── AddExtraCandidates.c │ ├── AddTourCandidates.c │ ├── AdjustCandidateSet.c │ ├── AdjustClusters.c │ ├── AllocateStructures.c │ ├── Ascent.c │ ├── Best2OptMove.c │ ├── Best3OptMove.c │ ├── Best4OptMove.c │ ├── Best5OptMove.c │ ├── BestKOptMove.c │ ├── Between.c │ ├── Between_SL.c │ ├── Between_SSL.c │ ├── BridgeGain.c │ ├── BuildKDTree.c │ ├── C.c │ ├── CandidateReport.c │ ├── ChooseInitialTour.c │ ├── Connect.c │ ├── CreateCandidateSet.c │ ├── CreateDelaunayCandidateSet.c │ ├── CreateNNCandidateSet.c │ ├── CreateQuadrantCandidateSet.c │ ├── Create_POPMUSIC_CandidateSet.c │ ├── Delaunay.c │ ├── Distance.c │ ├── Distance_SPECIAL.c │ ├── ERXT.c │ ├── Excludable.c │ ├── Exclude.c │ ├── FindTour.c │ ├── FixedOrCommonCandidates.c │ ├── Flip.c │ ├── Flip_SL.c │ ├── Flip_SSL.c │ ├── Forbidden.c │ ├── FreeStructures.c │ ├── Gain23.c │ ├── GenerateCandidates.c │ ├── Genetic.c │ ├── GeoConversion.c │ ├── GetTime.c │ ├── GreedyTour.c │ ├── Hashing.c │ ├── Heap.c │ ├── IsBackboneCandidate.c │ ├── IsCandidate.c │ ├── IsCommonEdge.c │ ├── IsPossibleCandidate.c │ ├── KSwapKick.c │ ├── LKHmain.c │ ├── LinKernighan.c │ ├── Make2OptMove.c │ ├── Make3OptMove.c │ ├── Make4OptMove.c │ ├── Make5OptMove.c │ ├── MakeKOptMove.c │ ├── MergeTourWithBestTour.c │ ├── MergeWithTourGPX2.c │ ├── MergeWithTourIPT.c │ ├── Minimum1TreeCost.c │ ├── MinimumSpanningTree.c │ ├── NormalizeNodeList.c │ ├── NormalizeSegmentList.c │ ├── OrderCandidateSet.c │ ├── PatchCycles.c │ ├── PrintParameters.c │ ├── Random.c │ ├── ReadCandidates.c │ ├── ReadEdges.c │ ├── ReadLine.c │ ├── ReadParameters.c │ ├── ReadPenalties.c │ ├── ReadProblem.c │ ├── RecordBestTour.c │ ├── RecordBetterTour.c │ ├── RemoveFirstActive.c │ ├── ResetCandidateSet.c │ ├── RestoreTour.c │ ├── SFCTour.c │ ├── SegmentSize.c │ ├── Sequence.c │ ├── SolveCompressedSubproblem.c │ ├── SolveDelaunaySubproblems.c │ ├── SolveKCenterSubproblems.c │ ├── SolveKMeansSubproblems.c │ ├── SolveKarpSubproblems.c │ ├── SolveRoheSubproblems.c │ ├── SolveSFCSubproblems.c │ ├── SolveSubproblem.c │ ├── SolveSubproblemBorderProblems.c │ ├── SolveTourSegmentSubproblems.c │ ├── Statistics.c │ ├── StoreTour.c │ ├── SymmetrizeCandidateSet.c │ ├── TrimCandidateSet.c │ ├── WriteCandidates.c │ ├── WritePenalties.c │ ├── WriteTour.c │ ├── eprintf.c │ ├── fscanint.c │ ├── gpx.c │ ├── lkh_interface.cpp │ └── printff.c ├── localization ├── .vscode │ ├── c_cpp_properties.json │ └── settings.json ├── CMakeLists.txt ├── launch │ ├── locate.rviz │ ├── params.yaml │ └── run.launch ├── package.xml └── src │ ├── gd │ ├── commonRansac.h │ ├── config.h │ ├── ground_detect.cpp │ ├── ground_detect.h │ ├── legoFeature.cpp │ ├── legoFeature.h │ ├── lidarRoadDetect.cpp │ ├── lidarRoadDetect.h │ ├── map_builder.cpp │ ├── map_builder.h │ ├── map_builder_noloop.cpp.bak │ ├── map_builder_noloop.h │ ├── mutli_execute.h │ ├── probability_values.cpp │ ├── probability_values.h │ └── simple_probability_values.h.bak │ └── localization_node.cpp ├── ogm_sender ├── .vscode │ └── settings.json ├── CMakeLists.txt ├── package.xml ├── run.launch └── src │ └── ogm_sender_node.cpp ├── static_map_server ├── CMakeLists.txt ├── launch │ └── run.launch ├── package.xml └── src │ └── static_map_server_node.cpp └── way_point_sender ├── CMakeLists.txt ├── package.xml ├── src └── way_point_sender_node.cpp └── wpt.rviz /.gitignore: -------------------------------------------------------------------------------- 1 | .DS_Store 2 | .catkin_workspace 3 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | /opt/ros/noetic/share/catkin/cmake/toplevel.cmake -------------------------------------------------------------------------------- /LeGO-LOAM/.vscode/settings.json: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/.vscode/settings.json -------------------------------------------------------------------------------- /LeGO-LOAM/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LICENSE -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/CMakeLists.txt -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/include/fftm/fftm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/include/fftm/fftm.cpp -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/include/fftm/fftm.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/include/fftm/fftm.hpp -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/include/tic_toc.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/include/tic_toc.h -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/include/utility.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/include/utility.h -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/launch/block.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/launch/block.png -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/launch/dataset-demo.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/launch/dataset-demo.gif -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/launch/demo-map.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/launch/demo-map.rviz -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/launch/demo.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/launch/demo.gif -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/launch/faster.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/launch/faster.launch -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/launch/google-earth.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/launch/google-earth.png -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/launch/jackal-label.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/launch/jackal-label.jpg -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/launch/odometry.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/launch/odometry.jpg -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/launch/run.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/launch/run.launch -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/launch/seg-total.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/launch/seg-total.jpg -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/launch/test.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/launch/test.launch -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/launch/test.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/launch/test.rviz -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/launch/xxx.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/launch/xxx.txt -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/launch/xxx00.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/launch/xxx00.txt -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/launch/xxx09.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/launch/xxx09.txt -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/launch/启动文件说明.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/launch/启动文件说明.md -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/launch/启动文件说明.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/launch/启动文件说明.pdf -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/package.xml -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/src1/LidarIris.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/src1/LidarIris.cpp -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/src1/LidarIris.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/src1/LidarIris.h -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/src1/featureAssociation.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/src1/featureAssociation.cpp -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/src1/imageProjection.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/src1/imageProjection.cpp -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/src1/main.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/src1/main.cpp -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/src1/mapOptmization_loop_iris.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/src1/mapOptmization_loop_iris.cpp -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/src1/mapOptmization_loop_iris_cleaned.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/src1/mapOptmization_loop_iris_cleaned.cpp -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/src1/mapOptmization_loop_iris_submap.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/src1/mapOptmization_loop_iris_submap.cpp -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/src1/transformFusion.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/src1/transformFusion.cpp -------------------------------------------------------------------------------- /LeGO-LOAM/LeGO-LOAM/urdf/car.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/LeGO-LOAM/urdf/car.urdf -------------------------------------------------------------------------------- /LeGO-LOAM/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/README.md -------------------------------------------------------------------------------- /LeGO-LOAM/cloud_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/cloud_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /LeGO-LOAM/cloud_msgs/msg/cloud_info.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/cloud_msgs/msg/cloud_info.msg -------------------------------------------------------------------------------- /LeGO-LOAM/cloud_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LeGO-LOAM/cloud_msgs/package.xml -------------------------------------------------------------------------------- /LidarAtlas/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/CMakeLists.txt -------------------------------------------------------------------------------- /LidarAtlas/launch/run.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/launch/run.launch -------------------------------------------------------------------------------- /LidarAtlas/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/package.xml -------------------------------------------------------------------------------- /LidarAtlas/src/LidarAtlas_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/src/LidarAtlas_node.cpp -------------------------------------------------------------------------------- /LidarAtlas/src/LidarAtlas_noloop_node.cpp.bak: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /LidarAtlas/src/gd/commonRansac.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/src/gd/commonRansac.h -------------------------------------------------------------------------------- /LidarAtlas/src/gd/config.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/src/gd/config.h -------------------------------------------------------------------------------- /LidarAtlas/src/gd/globalmap_builder.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/src/gd/globalmap_builder.cpp -------------------------------------------------------------------------------- /LidarAtlas/src/gd/globalmap_builder.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/src/gd/globalmap_builder.h -------------------------------------------------------------------------------- /LidarAtlas/src/gd/ground_detect.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/src/gd/ground_detect.cpp -------------------------------------------------------------------------------- /LidarAtlas/src/gd/ground_detect.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/src/gd/ground_detect.h -------------------------------------------------------------------------------- /LidarAtlas/src/gd/legoFeature.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/src/gd/legoFeature.cpp -------------------------------------------------------------------------------- /LidarAtlas/src/gd/legoFeature.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/src/gd/legoFeature.h -------------------------------------------------------------------------------- /LidarAtlas/src/gd/lidarRoadDetect.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/src/gd/lidarRoadDetect.cpp -------------------------------------------------------------------------------- /LidarAtlas/src/gd/lidarRoadDetect.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/src/gd/lidarRoadDetect.h -------------------------------------------------------------------------------- /LidarAtlas/src/gd/map_builder.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/src/gd/map_builder.cpp -------------------------------------------------------------------------------- /LidarAtlas/src/gd/map_builder.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/src/gd/map_builder.h -------------------------------------------------------------------------------- /LidarAtlas/src/gd/map_builder_noloop.cpp.bak: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/src/gd/map_builder_noloop.cpp.bak -------------------------------------------------------------------------------- /LidarAtlas/src/gd/map_builder_noloop.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/src/gd/map_builder_noloop.h -------------------------------------------------------------------------------- /LidarAtlas/src/gd/mutli_execute.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/src/gd/mutli_execute.h -------------------------------------------------------------------------------- /LidarAtlas/src/gd/probability_values.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/src/gd/probability_values.cpp -------------------------------------------------------------------------------- /LidarAtlas/src/gd/probability_values.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/src/gd/probability_values.h -------------------------------------------------------------------------------- /LidarAtlas/src/gd/simple_probability_values.h.bak: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/src/gd/simple_probability_values.h.bak -------------------------------------------------------------------------------- /LidarAtlas/src/lidar_atlas_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/LidarAtlas/src/lidar_atlas_node.cpp -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/README.md -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/.gitignore: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/.gitignore -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/README.md -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/img/header.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/img/header.jpg -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/README.md -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/joy/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/joy/CHANGELOG.rst -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/joy/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/joy/CMakeLists.txt -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/joy/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/joy/README.md -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/joy/config/ps4joy.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/joy/config/ps4joy.yaml -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/joy/launch/ps4joy.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/joy/launch/ps4joy.launch -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/joy/mainpage.dox: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/joy/mainpage.dox -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/joy/migration_rules/Joy.bmr: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/joy/migration_rules/Joy.bmr -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/joy/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/joy/package.xml -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/joy/scripts/joy_remap.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/joy/scripts/joy_remap.py -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/joy/src/joy_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/joy/src/joy_node.cpp -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/joy/test/saved/Joy.saved: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/joy/test/saved/Joy.saved -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/joy/test/test_joy_msg_migration.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/joy/test/test_joy_msg_migration.py -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/joystick_drivers/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/joystick_drivers/CHANGELOG.rst -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/joystick_drivers/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/joystick_drivers/CMakeLists.txt -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/joystick_drivers/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/joystick_drivers/package.xml -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/CHANGELOG.rst -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/CMakeLists.txt -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/README.md -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/diagnostics.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/diagnostics.yaml -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/doc/bluetooth_devices.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/doc/bluetooth_devices.md -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/doc/testing.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/doc/testing.md -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/doc/troubleshooting.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/doc/troubleshooting.md -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/launch/ps3.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/launch/ps3.launch -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/package.xml -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/scripts/ps3joy.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/scripts/ps3joy.py -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/scripts/ps3joy_node.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/scripts/ps3joy_node.py -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/scripts/ps3joysim.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/scripts/ps3joysim.py -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/src/sixpair.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/joystick_drivers/ps3joy/src/sixpair.c -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/loam_interface/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/loam_interface/CMakeLists.txt -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/loam_interface/launch/loam_interface.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/loam_interface/launch/loam_interface.launch -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/loam_interface/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/loam_interface/package.xml -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/loam_interface/src/loamInterface.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/loam_interface/src/loamInterface.cpp -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/local_planner/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/local_planner/CMakeLists.txt -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/local_planner/launch/local_planner.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/local_planner/launch/local_planner.launch -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/local_planner/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/local_planner/package.xml -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/local_planner/paths/correspondences.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/local_planner/paths/correspondences.txt -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/local_planner/paths/pathList.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/local_planner/paths/pathList.ply -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/local_planner/paths/path_generator.m: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/local_planner/paths/path_generator.m -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/local_planner/paths/paths.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/local_planner/paths/paths.ply -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/local_planner/paths/startPaths.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/local_planner/paths/startPaths.ply -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/local_planner/src/localPlanner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/local_planner/src/localPlanner.cpp -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/local_planner/src/pathFollower.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/local_planner/src/pathFollower.cpp -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/sensor_scan_generation/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/sensor_scan_generation/CMakeLists.txt -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/sensor_scan_generation/launch/sensor_scan_generation.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/sensor_scan_generation/launch/sensor_scan_generation.launch -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/sensor_scan_generation/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/sensor_scan_generation/package.xml -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/sensor_scan_generation/src/sensorScanGeneration.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/sensor_scan_generation/src/sensorScanGeneration.cpp -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/terrain_analysis/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/terrain_analysis/CMakeLists.txt -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/terrain_analysis/launch/terrain_analysis.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/terrain_analysis/launch/terrain_analysis.launch -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/terrain_analysis/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/terrain_analysis/package.xml -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/terrain_analysis/src/terrainAnalysis.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/terrain_analysis/src/terrainAnalysis.cpp -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/terrain_analysis_ext/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/terrain_analysis_ext/CMakeLists.txt -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/terrain_analysis_ext/launch/terrain_analysis_ext.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/terrain_analysis_ext/launch/terrain_analysis_ext.launch -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/terrain_analysis_ext/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/terrain_analysis_ext/package.xml -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/terrain_analysis_ext/src/terrainAnalysisExt.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/terrain_analysis_ext/src/terrainAnalysisExt.cpp -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/CMakeLists.txt -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/launch/rviz.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/launch/rviz.launch -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/launch/system_campus.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/launch/system_campus.launch -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/launch/system_forest.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/launch/system_forest.launch -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/launch/system_garage.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/launch/system_garage.launch -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/launch/system_indoor.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/launch/system_indoor.launch -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/launch/system_real_robot.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/launch/system_real_robot.launch -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/launch/system_tunnel.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/launch/system_tunnel.launch -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/launch/vehicle_simulator.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/launch/vehicle_simulator.launch -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/log/readme.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/log/readme.txt -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/mesh/download_environments.sh: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/mesh/download_environments.sh -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/package.xml -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/rviz/vehicle_simulator.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/rviz/vehicle_simulator.rviz -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/src/vehicleSimulator.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/src/vehicleSimulator.cpp -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/urdf/camera.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/urdf/camera.urdf.xacro -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/urdf/lidar.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/urdf/lidar.urdf.xacro -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/urdf/robot.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/urdf/robot.urdf.xacro -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/world/campus.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/world/campus.world -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/world/forest.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/world/forest.world -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/world/garage.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/world/garage.world -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/world/indoor.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/world/indoor.world -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/vehicle_simulator/world/tunnel.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/vehicle_simulator/world/tunnel.world -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/LICENSE -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/README.md -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/CHANGELOG.rst -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/CMakeLists.txt -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/launch/example.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/launch/example.launch -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/meshes/HDL32E_base.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/meshes/HDL32E_base.dae -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/meshes/HDL32E_base.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/meshes/HDL32E_base.stl -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/meshes/HDL32E_scan.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/meshes/HDL32E_scan.dae -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/meshes/HDL32E_scan.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/meshes/HDL32E_scan.stl -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/meshes/VLP16_base_1.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/meshes/VLP16_base_1.dae -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/meshes/VLP16_base_1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/meshes/VLP16_base_1.stl -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/meshes/VLP16_base_2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/meshes/VLP16_base_2.dae -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/meshes/VLP16_base_2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/meshes/VLP16_base_2.stl -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/meshes/VLP16_scan.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/meshes/VLP16_scan.dae -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/meshes/VLP16_scan.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/meshes/VLP16_scan.stl -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/package.xml -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/rviz/example.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/rviz/example.rviz -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/urdf/HDL-32E.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/urdf/HDL-32E.urdf.xacro -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/urdf/VLP-16.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/urdf/VLP-16.urdf.xacro -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/urdf/example.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/urdf/example.urdf.xacro -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/world/example.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_description/world/example.world -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_gazebo_plugins/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_gazebo_plugins/CHANGELOG.rst -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_gazebo_plugins/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_gazebo_plugins/CMakeLists.txt -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_gazebo_plugins/include/velodyne_gazebo_plugins/GazeboRosVelodyneLaser.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_gazebo_plugins/include/velodyne_gazebo_plugins/GazeboRosVelodyneLaser.h -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_gazebo_plugins/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_gazebo_plugins/package.xml -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_gazebo_plugins/src/GazeboRosVelodyneLaser.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_gazebo_plugins/src/GazeboRosVelodyneLaser.cpp -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_simulator/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_simulator/CHANGELOG.rst -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_simulator/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_simulator/CMakeLists.txt -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_simulator/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/velodyne_simulator/velodyne_simulator/package.xml -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/visualization_tools/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/visualization_tools/CMakeLists.txt -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/visualization_tools/launch/visualization_tools.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/visualization_tools/launch/visualization_tools.launch -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/visualization_tools/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/visualization_tools/package.xml -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/visualization_tools/scripts/realTimePlot.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/visualization_tools/scripts/realTimePlot.py -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/visualization_tools/src/visualizationTools.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/visualization_tools/src/visualizationTools.cpp -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/waypoint_example/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/waypoint_example/CMakeLists.txt -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/waypoint_example/data/boundary_garage.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/waypoint_example/data/boundary_garage.ply -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/waypoint_example/data/waypoints_garage.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/waypoint_example/data/waypoints_garage.ply -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/waypoint_example/launch/waypoint_example_garage.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/waypoint_example/launch/waypoint_example_garage.launch -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/waypoint_example/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/waypoint_example/package.xml -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/waypoint_example/src/waypointExample.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/waypoint_example/src/waypointExample.cpp -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/waypoint_rviz_plugin/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/waypoint_rviz_plugin/CMakeLists.txt -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/waypoint_rviz_plugin/include/waypoint_tool.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/waypoint_rviz_plugin/include/waypoint_tool.h -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/waypoint_rviz_plugin/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/waypoint_rviz_plugin/package.xml -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/waypoint_rviz_plugin/plugin_description.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/waypoint_rviz_plugin/plugin_description.xml -------------------------------------------------------------------------------- /autonomous_exploration_development_environment/src/waypoint_rviz_plugin/src/waypoint_tool.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/autonomous_exploration_development_environment/src/waypoint_rviz_plugin/src/waypoint_tool.cpp -------------------------------------------------------------------------------- /chunkmap/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap/CMakeLists.txt -------------------------------------------------------------------------------- /chunkmap/include/chunkmap/LidarIris/LidarIris.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap/include/chunkmap/LidarIris/LidarIris.h -------------------------------------------------------------------------------- /chunkmap/include/chunkmap/LidarIris/fftm/fftm.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap/include/chunkmap/LidarIris/fftm/fftm.hpp -------------------------------------------------------------------------------- /chunkmap/include/chunkmap/aztools/bitset.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap/include/chunkmap/aztools/bitset.hpp -------------------------------------------------------------------------------- /chunkmap/include/chunkmap/aztools/mat.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap/include/chunkmap/aztools/mat.hpp -------------------------------------------------------------------------------- /chunkmap/include/chunkmap/chunk_map.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap/include/chunkmap/chunk_map.h -------------------------------------------------------------------------------- /chunkmap/include/chunkmap/simple_probability_values.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap/include/chunkmap/simple_probability_values.h -------------------------------------------------------------------------------- /chunkmap/include/chunkmap/simple_probability_values.h.bak: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap/include/chunkmap/simple_probability_values.h.bak -------------------------------------------------------------------------------- /chunkmap/include/chunkmap_ros/chunk_map_client.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap/include/chunkmap_ros/chunk_map_client.h -------------------------------------------------------------------------------- /chunkmap/include/chunkmap_ros/chunk_map_service.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap/include/chunkmap_ros/chunk_map_service.h -------------------------------------------------------------------------------- /chunkmap/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap/package.xml -------------------------------------------------------------------------------- /chunkmap/src/chunkmap/LidarIris/LidarIris.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap/src/chunkmap/LidarIris/LidarIris.cpp -------------------------------------------------------------------------------- /chunkmap/src/chunkmap/LidarIris/fftm/fftm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap/src/chunkmap/LidarIris/fftm/fftm.cpp -------------------------------------------------------------------------------- /chunkmap/src/chunkmap/chunk_map.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap/src/chunkmap/chunk_map.cpp -------------------------------------------------------------------------------- /chunkmap/src/chunkmap/chunk_map_msgpack_serialise.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap/src/chunkmap/chunk_map_msgpack_serialise.cpp -------------------------------------------------------------------------------- /chunkmap/src/chunkmap/chunk_map_msgpack_serialise_minimal.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap/src/chunkmap/chunk_map_msgpack_serialise_minimal.cpp -------------------------------------------------------------------------------- /chunkmap/src/chunkmap_ros/chunk_map_client.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap/src/chunkmap_ros/chunk_map_client.cpp -------------------------------------------------------------------------------- /chunkmap/src/chunkmap_ros/chunk_map_service.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap/src/chunkmap_ros/chunk_map_service.cpp -------------------------------------------------------------------------------- /chunkmap_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /chunkmap_msgs/msg/ChunkData.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_msgs/msg/ChunkData.msg -------------------------------------------------------------------------------- /chunkmap_msgs/msg/ChunkIndex.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_msgs/msg/ChunkIndex.msg -------------------------------------------------------------------------------- /chunkmap_msgs/msg/ChunkLayer.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_msgs/msg/ChunkLayer.msg -------------------------------------------------------------------------------- /chunkmap_msgs/msg/ChunkMapInfo.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_msgs/msg/ChunkMapInfo.msg -------------------------------------------------------------------------------- /chunkmap_msgs/msg/ChunkVizData.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_msgs/msg/ChunkVizData.msg -------------------------------------------------------------------------------- /chunkmap_msgs/msg/ChunkVizLayer.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_msgs/msg/ChunkVizLayer.msg -------------------------------------------------------------------------------- /chunkmap_msgs/msg/KeyFrameData.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_msgs/msg/KeyFrameData.msg -------------------------------------------------------------------------------- /chunkmap_msgs/msg/KeyFrameInfo.msg: -------------------------------------------------------------------------------- 1 | int64 index 2 | float32[] pose 3 | -------------------------------------------------------------------------------- /chunkmap_msgs/msg/UpdateList.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_msgs/msg/UpdateList.msg -------------------------------------------------------------------------------- /chunkmap_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_msgs/package.xml -------------------------------------------------------------------------------- /chunkmap_msgs/srv/GetChunkData.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_msgs/srv/GetChunkData.srv -------------------------------------------------------------------------------- /chunkmap_msgs/srv/GetChunkMapInfo.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_msgs/srv/GetChunkMapInfo.srv -------------------------------------------------------------------------------- /chunkmap_msgs/srv/GetChunkVizData.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_msgs/srv/GetChunkVizData.srv -------------------------------------------------------------------------------- /chunkmap_msgs/srv/GetKeyFrameData.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_msgs/srv/GetKeyFrameData.srv -------------------------------------------------------------------------------- /chunkmap_msgs/srv/GetKeyFrameInfo.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_msgs/srv/GetKeyFrameInfo.srv -------------------------------------------------------------------------------- /chunkmap_rviz/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_rviz/CMakeLists.txt -------------------------------------------------------------------------------- /chunkmap_rviz/ogre_media/materials/glsl120/chunk_cell.frag: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_rviz/ogre_media/materials/glsl120/chunk_cell.frag -------------------------------------------------------------------------------- /chunkmap_rviz/ogre_media/materials/glsl120/chunk_cell.program: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_rviz/ogre_media/materials/glsl120/chunk_cell.program -------------------------------------------------------------------------------- /chunkmap_rviz/ogre_media/materials/glsl120/chunk_cell.vert: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_rviz/ogre_media/materials/glsl120/chunk_cell.vert -------------------------------------------------------------------------------- /chunkmap_rviz/ogre_media/materials/scripts/chunk_cell.material: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_rviz/ogre_media/materials/scripts/chunk_cell.material -------------------------------------------------------------------------------- /chunkmap_rviz/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_rviz/package.xml -------------------------------------------------------------------------------- /chunkmap_rviz/plugin_description.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_rviz/plugin_description.xml -------------------------------------------------------------------------------- /chunkmap_rviz/src/chunkmap_rviz/chunk_visual.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_rviz/src/chunkmap_rviz/chunk_visual.cpp -------------------------------------------------------------------------------- /chunkmap_rviz/src/chunkmap_rviz/chunk_visual.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_rviz/src/chunkmap_rviz/chunk_visual.h -------------------------------------------------------------------------------- /chunkmap_rviz/src/chunkmap_rviz/chunkmap_display.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_rviz/src/chunkmap_rviz/chunkmap_display.cpp -------------------------------------------------------------------------------- /chunkmap_rviz/src/chunkmap_rviz/chunkmap_display.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_rviz/src/chunkmap_rviz/chunkmap_display.h -------------------------------------------------------------------------------- /chunkmap_terrain/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_terrain/CMakeLists.txt -------------------------------------------------------------------------------- /chunkmap_terrain/launch/run.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_terrain/launch/run.launch -------------------------------------------------------------------------------- /chunkmap_terrain/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_terrain/package.xml -------------------------------------------------------------------------------- /chunkmap_terrain/src/chunkmap_terrain_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/chunkmap_terrain/src/chunkmap_terrain_node.cpp -------------------------------------------------------------------------------- /graph_gain_exploration/src/catkin_simple/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/catkin_simple/CMakeLists.txt -------------------------------------------------------------------------------- /graph_gain_exploration/src/catkin_simple/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/catkin_simple/README.md -------------------------------------------------------------------------------- /graph_gain_exploration/src/catkin_simple/cmake/catkin_simple-extras.cmake.em: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/catkin_simple/cmake/catkin_simple-extras.cmake.em -------------------------------------------------------------------------------- /graph_gain_exploration/src/catkin_simple/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/catkin_simple/package.xml -------------------------------------------------------------------------------- /graph_gain_exploration/src/catkin_simple/test/scenarios/hello_world/.gitignore: -------------------------------------------------------------------------------- 1 | CMakeLists.txt 2 | -------------------------------------------------------------------------------- /graph_gain_exploration/src/catkin_simple/test/scenarios/hello_world/bar/include/bar/hello.h: -------------------------------------------------------------------------------- 1 | void hello(); 2 | -------------------------------------------------------------------------------- /graph_gain_exploration/src/catkin_simple/test/scenarios/hello_world/bar/msg/HeaderString.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/catkin_simple/test/scenarios/hello_world/bar/msg/HeaderString.msg -------------------------------------------------------------------------------- /graph_gain_exploration/src/catkin_simple/test/scenarios/hello_world/bar/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/catkin_simple/test/scenarios/hello_world/bar/package.xml -------------------------------------------------------------------------------- /graph_gain_exploration/src/catkin_simple/test/scenarios/hello_world/bar/src/hello.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/catkin_simple/test/scenarios/hello_world/bar/src/hello.cpp -------------------------------------------------------------------------------- /graph_gain_exploration/src/catkin_simple/test/scenarios/hello_world/baz/include/baz/world.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/catkin_simple/test/scenarios/hello_world/baz/include/baz/world.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/catkin_simple/test/scenarios/hello_world/baz/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/catkin_simple/test/scenarios/hello_world/baz/package.xml -------------------------------------------------------------------------------- /graph_gain_exploration/src/catkin_simple/test/scenarios/hello_world/foo/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/catkin_simple/test/scenarios/hello_world/foo/package.xml -------------------------------------------------------------------------------- /graph_gain_exploration/src/catkin_simple/test/scenarios/hello_world/foo/src/main.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/catkin_simple/test/scenarios/hello_world/foo/src/main.cpp -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/CMakeLists.txt -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/config/exploration.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/config/exploration.yaml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/config/exploration_campus.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/config/exploration_campus.yaml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/config/exploration_forest.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/config/exploration_forest.yaml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/config/exploration_garage.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/config/exploration_garage.yaml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/config/exploration_indoor.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/config/exploration_indoor.yaml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/config/exploration_matterport.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/config/exploration_matterport.yaml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/config/exploration_tunnel.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/config/exploration_tunnel.yaml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/config/octomap.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/config/octomap.yaml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/config/octomap_campus.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/config/octomap_campus.yaml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/config/octomap_forest.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/config/octomap_forest.yaml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/config/octomap_garage.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/config/octomap_garage.yaml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/config/octomap_indoor.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/config/octomap_indoor.yaml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/config/octomap_matterport.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/config/octomap_matterport.yaml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/config/octomap_tunnel.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/config/octomap_tunnel.yaml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/data/boundary.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/data/boundary.ply -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/default.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/default.rviz -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/dsvp.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/dsvp.rviz -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/launch/dog.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/launch/dog.launch -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/launch/dsvp.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/launch/dsvp.launch -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/launch/explore_campus.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/launch/explore_campus.launch -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/launch/explore_forest.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/launch/explore_forest.launch -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/launch/explore_garage.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/launch/explore_garage.launch -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/launch/explore_indoor.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/launch/explore_indoor.launch -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/launch/explore_matterport.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/launch/explore_matterport.launch -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/launch/explore_tunnel.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/launch/explore_tunnel.launch -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/launch/rosbag_record.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/launch/rosbag_record.launch -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/package.xml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/src/exploration.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/src/exploration.cpp -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvp_launch/src/navigationBoundary.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvp_launch/src/navigationBoundary.cpp -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvplanner/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvplanner/CMakeLists.txt -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvplanner/include/concave2d/az_concave2d.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvplanner/include/concave2d/az_concave2d.hpp -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvplanner/include/concave2d/delaunator.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvplanner/include/concave2d/delaunator.hpp -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvplanner/include/dsvplanner/chunkmap_helper.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvplanner/include/dsvplanner/chunkmap_helper.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvplanner/include/dsvplanner/drrt.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvplanner/include/dsvplanner/drrt.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvplanner/include/dsvplanner/drrt_base.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvplanner/include/dsvplanner/drrt_base.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvplanner/include/dsvplanner/drrtp.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvplanner/include/dsvplanner/drrtp.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvplanner/include/dsvplanner/dual_state_frontier.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvplanner/include/dsvplanner/dual_state_frontier.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvplanner/include/dsvplanner/dual_state_graph.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvplanner/include/dsvplanner/dual_state_graph.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvplanner/include/dsvplanner/grid.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvplanner/include/dsvplanner/grid.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvplanner/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvplanner/package.xml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvplanner/src/chunkmap_helper.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvplanner/src/chunkmap_helper.cpp -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvplanner/src/drrt.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvplanner/src/drrt.cpp -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvplanner/src/drrtp.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvplanner/src/drrtp.cpp -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvplanner/src/drrtp_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvplanner/src/drrtp_node.cpp -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvplanner/src/dual_state_frontier.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvplanner/src/dual_state_frontier.cpp -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvplanner/src/dual_state_graph.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvplanner/src/dual_state_graph.cpp -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvplanner/src/grid.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvplanner/src/grid.cpp -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvplanner/srv/clean_frontier_srv.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvplanner/srv/clean_frontier_srv.srv -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/dsvplanner/srv/dsvplanner_srv.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/dsvplanner/srv/dsvplanner_srv.srv -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_planner/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_planner/CMakeLists.txt -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_planner/config/default.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_planner/config/default.yaml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_planner/config/matterport.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_planner/config/matterport.yaml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_planner/include/graph_planner.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_planner/include/graph_planner.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_planner/launch/graph_planner.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_planner/launch/graph_planner.launch -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_planner/launch/graph_planner_matterport.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_planner/launch/graph_planner_matterport.launch -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_planner/msg/GraphPlannerCommand.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_planner/msg/GraphPlannerCommand.msg -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_planner/msg/GraphPlannerStatus.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_planner/msg/GraphPlannerStatus.msg -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_planner/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_planner/package.xml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_planner/src/graph_planner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_planner/src/graph_planner.cpp -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_planner/src/graph_planner_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_planner/src/graph_planner_node.cpp -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_utils/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_utils/CMakeLists.txt -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_utils/config/default.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_utils/config/default.yaml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_utils/include/graph_utils.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_utils/include/graph_utils.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_utils/include/graph_visualization.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_utils/include/graph_visualization.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_utils/launch/graph_visualization.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_utils/launch/graph_visualization.launch -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_utils/msg/Edge.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_utils/msg/Edge.msg -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_utils/msg/TopologicalGraph.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_utils/msg/TopologicalGraph.msg -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_utils/msg/Vertex.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_utils/msg/Vertex.msg -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_utils/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_utils/package.xml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_utils/src/graph_utils.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_utils/src/graph_utils.cpp -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_utils/src/graph_visualization.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_utils/src/graph_visualization.cpp -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/graph_utils/src/graph_visualization_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/graph_utils/src/graph_visualization_node.cpp -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/misc_utils/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/misc_utils/CMakeLists.txt -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/misc_utils/include/misc_utils/misc_utils.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/misc_utils/include/misc_utils/misc_utils.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/misc_utils/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/misc_utils/package.xml -------------------------------------------------------------------------------- /graph_gain_exploration/src/dsvplanner/misc_utils/src/misc_utils.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/dsvplanner/misc_utils/src/misc_utils.cpp -------------------------------------------------------------------------------- /graph_gain_exploration/src/kdtree/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/kdtree/CMakeLists.txt -------------------------------------------------------------------------------- /graph_gain_exploration/src/kdtree/include/kdtree/kdtree.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/kdtree/include/kdtree/kdtree.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/kdtree/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/kdtree/package.xml -------------------------------------------------------------------------------- /graph_gain_exploration/src/kdtree/src/kdtree.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/kdtree/src/kdtree.c -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr/README.md -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr/minkindr/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr/minkindr/CMakeLists.txt -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr/minkindr/include/kindr/minimal/angle-axis.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr/minkindr/include/kindr/minimal/angle-axis.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr/minkindr/include/kindr/minimal/common.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr/minkindr/include/kindr/minimal/common.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr/minkindr/include/kindr/minimal/implementation/angle-axis-inl.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr/minkindr/include/kindr/minimal/implementation/angle-axis-inl.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr/minkindr/include/kindr/minimal/implementation/quat-sim-transform-inl.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr/minkindr/include/kindr/minimal/implementation/quat-sim-transform-inl.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr/minkindr/include/kindr/minimal/implementation/quat-transformation-inl.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr/minkindr/include/kindr/minimal/implementation/quat-transformation-inl.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr/minkindr/include/kindr/minimal/implementation/rotation-quaternion-inl.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr/minkindr/include/kindr/minimal/implementation/rotation-quaternion-inl.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr/minkindr/include/kindr/minimal/position.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr/minkindr/include/kindr/minimal/position.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr/minkindr/include/kindr/minimal/quat-sim-transform.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr/minkindr/include/kindr/minimal/quat-sim-transform.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr/minkindr/include/kindr/minimal/quat-transformation.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr/minkindr/include/kindr/minimal/quat-transformation.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr/minkindr/include/kindr/minimal/rotation-quaternion.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr/minkindr/include/kindr/minimal/rotation-quaternion.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr/minkindr/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr/minkindr/package.xml -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr/minkindr/test/test-main.cc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr/minkindr/test/test-main.cc -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr/minkindr/test/test-rotation.cc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr/minkindr/test/test-rotation.cc -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr/minkindr/test/test-sim3.cc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr/minkindr/test/test-sim3.cc -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr/minkindr/test/test-transformation.cc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr/minkindr/test/test-transformation.cc -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr_ros/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr_ros/README.md -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr_ros/minkindr_conversions/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr_ros/minkindr_conversions/CMakeLists.txt -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr_ros/minkindr_conversions/include/minkindr_conversions/kindr_msg.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr_ros/minkindr_conversions/include/minkindr_conversions/kindr_msg.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr_ros/minkindr_conversions/include/minkindr_conversions/kindr_tf.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr_ros/minkindr_conversions/include/minkindr_conversions/kindr_tf.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr_ros/minkindr_conversions/include/minkindr_conversions/kindr_xml.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr_ros/minkindr_conversions/include/minkindr_conversions/kindr_xml.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr_ros/minkindr_conversions/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr_ros/minkindr_conversions/package.xml -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr_ros/minkindr_conversions/src/kindr_msg.cc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr_ros/minkindr_conversions/src/kindr_msg.cc -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr_ros/minkindr_conversions/src/kindr_tf.cc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr_ros/minkindr_conversions/src/kindr_tf.cc -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr_ros/minkindr_conversions/src/kindr_xml.cc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr_ros/minkindr_conversions/src/kindr_xml.cc -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr_ros/minkindr_conversions/test/kindr_msg_test.cc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr_ros/minkindr_conversions/test/kindr_msg_test.cc -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr_ros/minkindr_conversions/test/kindr_tf_test.cc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr_ros/minkindr_conversions/test/kindr_tf_test.cc -------------------------------------------------------------------------------- /graph_gain_exploration/src/minkindr_ros/minkindr_conversions/test/testing_predicates.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/minkindr_ros/minkindr_conversions/test/testing_predicates.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/volumetric_mapping/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/volumetric_mapping/README.md -------------------------------------------------------------------------------- /graph_gain_exploration/src/volumetric_mapping/octomap_world/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/volumetric_mapping/octomap_world/CMakeLists.txt -------------------------------------------------------------------------------- /graph_gain_exploration/src/volumetric_mapping/octomap_world/include/octomap_world/octomap_manager.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/volumetric_mapping/octomap_world/include/octomap_world/octomap_manager.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/volumetric_mapping/octomap_world/include/octomap_world/octomap_world.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/volumetric_mapping/octomap_world/include/octomap_world/octomap_world.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/volumetric_mapping/octomap_world/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/volumetric_mapping/octomap_world/package.xml -------------------------------------------------------------------------------- /graph_gain_exploration/src/volumetric_mapping/octomap_world/src/octomap_manager.cc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/volumetric_mapping/octomap_world/src/octomap_manager.cc -------------------------------------------------------------------------------- /graph_gain_exploration/src/volumetric_mapping/octomap_world/src/octomap_manager_node.cc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/volumetric_mapping/octomap_world/src/octomap_manager_node.cc -------------------------------------------------------------------------------- /graph_gain_exploration/src/volumetric_mapping/octomap_world/src/octomap_world.cc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/volumetric_mapping/octomap_world/src/octomap_world.cc -------------------------------------------------------------------------------- /graph_gain_exploration/src/volumetric_mapping/volumetric_map_base/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/volumetric_mapping/volumetric_map_base/CMakeLists.txt -------------------------------------------------------------------------------- /graph_gain_exploration/src/volumetric_mapping/volumetric_map_base/include/volumetric_map_base/point_weighing.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/volumetric_mapping/volumetric_map_base/include/volumetric_map_base/point_weighing.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/volumetric_mapping/volumetric_map_base/include/volumetric_map_base/world_base.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/volumetric_mapping/volumetric_map_base/include/volumetric_map_base/world_base.h -------------------------------------------------------------------------------- /graph_gain_exploration/src/volumetric_mapping/volumetric_map_base/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/volumetric_mapping/volumetric_map_base/package.xml -------------------------------------------------------------------------------- /graph_gain_exploration/src/volumetric_mapping/volumetric_map_base/src/world_base.cc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/volumetric_mapping/volumetric_map_base/src/world_base.cc -------------------------------------------------------------------------------- /graph_gain_exploration/src/volumetric_mapping/volumetric_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/volumetric_mapping/volumetric_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /graph_gain_exploration/src/volumetric_mapping/volumetric_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/volumetric_mapping/volumetric_msgs/package.xml -------------------------------------------------------------------------------- /graph_gain_exploration/src/volumetric_mapping/volumetric_msgs/srv/LoadMap.srv: -------------------------------------------------------------------------------- 1 | string file_path 2 | --- 3 | -------------------------------------------------------------------------------- /graph_gain_exploration/src/volumetric_mapping/volumetric_msgs/srv/SaveMap.srv: -------------------------------------------------------------------------------- 1 | string file_path 2 | --- 3 | -------------------------------------------------------------------------------- /graph_gain_exploration/src/volumetric_mapping/volumetric_msgs/srv/SetBoxOccupancy.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/volumetric_mapping/volumetric_msgs/srv/SetBoxOccupancy.srv -------------------------------------------------------------------------------- /graph_gain_exploration/src/volumetric_mapping/volumetric_msgs/srv/SetDisplayBounds.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/graph_gain_exploration/src/volumetric_mapping/volumetric_msgs/srv/SetDisplayBounds.srv -------------------------------------------------------------------------------- /lkh_tsp_solver/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/CMakeLists.txt -------------------------------------------------------------------------------- /lkh_tsp_solver/include/Delaunay.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/include/Delaunay.h -------------------------------------------------------------------------------- /lkh_tsp_solver/include/GainType.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/include/GainType.h -------------------------------------------------------------------------------- /lkh_tsp_solver/include/Genetic.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/include/Genetic.h -------------------------------------------------------------------------------- /lkh_tsp_solver/include/GeoConversion.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/include/GeoConversion.h -------------------------------------------------------------------------------- /lkh_tsp_solver/include/Hashing.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/include/Hashing.h -------------------------------------------------------------------------------- /lkh_tsp_solver/include/Heap.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/include/Heap.h -------------------------------------------------------------------------------- /lkh_tsp_solver/include/LKH.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/include/LKH.h -------------------------------------------------------------------------------- /lkh_tsp_solver/include/Segment.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/include/Segment.h -------------------------------------------------------------------------------- /lkh_tsp_solver/include/Sequence.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/include/Sequence.h -------------------------------------------------------------------------------- /lkh_tsp_solver/include/gpx.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/include/gpx.h -------------------------------------------------------------------------------- /lkh_tsp_solver/include/lkh_tsp_solver/lkh_interface.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/include/lkh_tsp_solver/lkh_interface.h -------------------------------------------------------------------------------- /lkh_tsp_solver/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/package.xml -------------------------------------------------------------------------------- /lkh_tsp_solver/resource/single.par: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/resource/single.par -------------------------------------------------------------------------------- /lkh_tsp_solver/resource/single.tsp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/resource/single.tsp -------------------------------------------------------------------------------- /lkh_tsp_solver/resource/single.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/resource/single.txt -------------------------------------------------------------------------------- /lkh_tsp_solver/resource/test.par: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/resource/test.par -------------------------------------------------------------------------------- /lkh_tsp_solver/resource/test.tsp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/resource/test.tsp -------------------------------------------------------------------------------- /lkh_tsp_solver/resource/test.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/resource/test.txt -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Activate.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Activate.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/AddCandidate.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/AddCandidate.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/AddExtraCandidates.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/AddExtraCandidates.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/AddTourCandidates.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/AddTourCandidates.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/AdjustCandidateSet.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/AdjustCandidateSet.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/AdjustClusters.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/AdjustClusters.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/AllocateStructures.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/AllocateStructures.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Ascent.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Ascent.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Best2OptMove.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Best2OptMove.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Best3OptMove.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Best3OptMove.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Best4OptMove.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Best4OptMove.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Best5OptMove.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Best5OptMove.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/BestKOptMove.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/BestKOptMove.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Between.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Between.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Between_SL.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Between_SL.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Between_SSL.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Between_SSL.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/BridgeGain.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/BridgeGain.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/BuildKDTree.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/BuildKDTree.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/C.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/C.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/CandidateReport.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/CandidateReport.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/ChooseInitialTour.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/ChooseInitialTour.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Connect.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Connect.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/CreateCandidateSet.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/CreateCandidateSet.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/CreateDelaunayCandidateSet.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/CreateDelaunayCandidateSet.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/CreateNNCandidateSet.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/CreateNNCandidateSet.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/CreateQuadrantCandidateSet.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/CreateQuadrantCandidateSet.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Create_POPMUSIC_CandidateSet.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Create_POPMUSIC_CandidateSet.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Delaunay.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Delaunay.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Distance.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Distance.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Distance_SPECIAL.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Distance_SPECIAL.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/ERXT.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/ERXT.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Excludable.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Excludable.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Exclude.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Exclude.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/FindTour.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/FindTour.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/FixedOrCommonCandidates.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/FixedOrCommonCandidates.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Flip.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Flip.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Flip_SL.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Flip_SL.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Flip_SSL.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Flip_SSL.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Forbidden.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Forbidden.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/FreeStructures.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/FreeStructures.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Gain23.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Gain23.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/GenerateCandidates.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/GenerateCandidates.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Genetic.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Genetic.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/GeoConversion.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/GeoConversion.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/GetTime.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/GetTime.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/GreedyTour.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/GreedyTour.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Hashing.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Hashing.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Heap.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Heap.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/IsBackboneCandidate.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/IsBackboneCandidate.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/IsCandidate.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/IsCandidate.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/IsCommonEdge.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/IsCommonEdge.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/IsPossibleCandidate.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/IsPossibleCandidate.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/KSwapKick.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/KSwapKick.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/LKHmain.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/LKHmain.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/LinKernighan.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/LinKernighan.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Make2OptMove.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Make2OptMove.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Make3OptMove.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Make3OptMove.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Make4OptMove.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Make4OptMove.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Make5OptMove.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Make5OptMove.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/MakeKOptMove.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/MakeKOptMove.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/MergeTourWithBestTour.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/MergeTourWithBestTour.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/MergeWithTourGPX2.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/MergeWithTourGPX2.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/MergeWithTourIPT.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/MergeWithTourIPT.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Minimum1TreeCost.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Minimum1TreeCost.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/MinimumSpanningTree.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/MinimumSpanningTree.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/NormalizeNodeList.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/NormalizeNodeList.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/NormalizeSegmentList.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/NormalizeSegmentList.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/OrderCandidateSet.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/OrderCandidateSet.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/PatchCycles.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/PatchCycles.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/PrintParameters.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/PrintParameters.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Random.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Random.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/ReadCandidates.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/ReadCandidates.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/ReadEdges.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/ReadEdges.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/ReadLine.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/ReadLine.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/ReadParameters.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/ReadParameters.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/ReadPenalties.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/ReadPenalties.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/ReadProblem.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/ReadProblem.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/RecordBestTour.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/RecordBestTour.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/RecordBetterTour.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/RecordBetterTour.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/RemoveFirstActive.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/RemoveFirstActive.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/ResetCandidateSet.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/ResetCandidateSet.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/RestoreTour.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/RestoreTour.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/SFCTour.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/SFCTour.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/SegmentSize.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/SegmentSize.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Sequence.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Sequence.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/SolveCompressedSubproblem.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/SolveCompressedSubproblem.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/SolveDelaunaySubproblems.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/SolveDelaunaySubproblems.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/SolveKCenterSubproblems.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/SolveKCenterSubproblems.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/SolveKMeansSubproblems.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/SolveKMeansSubproblems.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/SolveKarpSubproblems.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/SolveKarpSubproblems.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/SolveRoheSubproblems.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/SolveRoheSubproblems.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/SolveSFCSubproblems.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/SolveSFCSubproblems.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/SolveSubproblem.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/SolveSubproblem.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/SolveSubproblemBorderProblems.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/SolveSubproblemBorderProblems.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/SolveTourSegmentSubproblems.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/SolveTourSegmentSubproblems.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/Statistics.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/Statistics.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/StoreTour.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/StoreTour.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/SymmetrizeCandidateSet.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/SymmetrizeCandidateSet.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/TrimCandidateSet.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/TrimCandidateSet.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/WriteCandidates.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/WriteCandidates.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/WritePenalties.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/WritePenalties.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/WriteTour.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/WriteTour.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/eprintf.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/eprintf.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/fscanint.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/fscanint.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/gpx.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/gpx.c -------------------------------------------------------------------------------- /lkh_tsp_solver/src/lkh_interface.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/lkh_interface.cpp -------------------------------------------------------------------------------- /lkh_tsp_solver/src/printff.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/lkh_tsp_solver/src/printff.c -------------------------------------------------------------------------------- /localization/.vscode/c_cpp_properties.json: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/.vscode/c_cpp_properties.json -------------------------------------------------------------------------------- /localization/.vscode/settings.json: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/.vscode/settings.json -------------------------------------------------------------------------------- /localization/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/CMakeLists.txt -------------------------------------------------------------------------------- /localization/launch/locate.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/launch/locate.rviz -------------------------------------------------------------------------------- /localization/launch/params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/launch/params.yaml -------------------------------------------------------------------------------- /localization/launch/run.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/launch/run.launch -------------------------------------------------------------------------------- /localization/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/package.xml -------------------------------------------------------------------------------- /localization/src/gd/commonRansac.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/src/gd/commonRansac.h -------------------------------------------------------------------------------- /localization/src/gd/config.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/src/gd/config.h -------------------------------------------------------------------------------- /localization/src/gd/ground_detect.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/src/gd/ground_detect.cpp -------------------------------------------------------------------------------- /localization/src/gd/ground_detect.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/src/gd/ground_detect.h -------------------------------------------------------------------------------- /localization/src/gd/legoFeature.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/src/gd/legoFeature.cpp -------------------------------------------------------------------------------- /localization/src/gd/legoFeature.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/src/gd/legoFeature.h -------------------------------------------------------------------------------- /localization/src/gd/lidarRoadDetect.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/src/gd/lidarRoadDetect.cpp -------------------------------------------------------------------------------- /localization/src/gd/lidarRoadDetect.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/src/gd/lidarRoadDetect.h -------------------------------------------------------------------------------- /localization/src/gd/map_builder.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/src/gd/map_builder.cpp -------------------------------------------------------------------------------- /localization/src/gd/map_builder.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/src/gd/map_builder.h -------------------------------------------------------------------------------- /localization/src/gd/map_builder_noloop.cpp.bak: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/src/gd/map_builder_noloop.cpp.bak -------------------------------------------------------------------------------- /localization/src/gd/map_builder_noloop.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/src/gd/map_builder_noloop.h -------------------------------------------------------------------------------- /localization/src/gd/mutli_execute.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/src/gd/mutli_execute.h -------------------------------------------------------------------------------- /localization/src/gd/probability_values.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/src/gd/probability_values.cpp -------------------------------------------------------------------------------- /localization/src/gd/probability_values.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/src/gd/probability_values.h -------------------------------------------------------------------------------- /localization/src/gd/simple_probability_values.h.bak: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/src/gd/simple_probability_values.h.bak -------------------------------------------------------------------------------- /localization/src/localization_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/localization/src/localization_node.cpp -------------------------------------------------------------------------------- /ogm_sender/.vscode/settings.json: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/ogm_sender/.vscode/settings.json -------------------------------------------------------------------------------- /ogm_sender/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/ogm_sender/CMakeLists.txt -------------------------------------------------------------------------------- /ogm_sender/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/ogm_sender/package.xml -------------------------------------------------------------------------------- /ogm_sender/run.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/ogm_sender/run.launch -------------------------------------------------------------------------------- /ogm_sender/src/ogm_sender_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/ogm_sender/src/ogm_sender_node.cpp -------------------------------------------------------------------------------- /static_map_server/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/static_map_server/CMakeLists.txt -------------------------------------------------------------------------------- /static_map_server/launch/run.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/static_map_server/launch/run.launch -------------------------------------------------------------------------------- /static_map_server/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/static_map_server/package.xml -------------------------------------------------------------------------------- /static_map_server/src/static_map_server_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/static_map_server/src/static_map_server_node.cpp -------------------------------------------------------------------------------- /way_point_sender/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/way_point_sender/CMakeLists.txt -------------------------------------------------------------------------------- /way_point_sender/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/way_point_sender/package.xml -------------------------------------------------------------------------------- /way_point_sender/src/way_point_sender_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/way_point_sender/src/way_point_sender_node.cpp -------------------------------------------------------------------------------- /way_point_sender/wpt.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/IMRL/Graph_Gain_Exploration/HEAD/way_point_sender/wpt.rviz --------------------------------------------------------------------------------