├── .gitignore ├── CMakeLists.txt ├── LICENSE ├── README.md ├── _docker └── Dockerfile ├── _docker_grvc └── Dockerfile ├── _generate_plots ├── .ipynb_checkpoints │ ├── Experimental 3d - Subplot time vs path lenght-checkpoint.ipynb │ ├── Exploration - Take 2-checkpoint.ipynb │ ├── Lazy Theta *-checkpoint.ipynb │ ├── Lazy Theta Real-Time Tor del Águila-checkpoint.ipynb │ ├── Obstacle detection-checkpoint.ipynb │ ├── Paper - Exploration real world-checkpoint.ipynb │ ├── Paper - Lazy Theta Star Online-checkpoint.ipynb │ ├── Paper A - Communications relay-checkpoint.ipynb │ ├── Paper C - Large structures test-checkpoint.ipynb │ ├── Sparse - 3d Puzzle - Subplot time vs path lenght-checkpoint.ipynb │ ├── Subplot Obstacle Avoidance-checkpoint.ipynb │ ├── Subplot v2-checkpoint.ipynb │ ├── Success rate-Copy1-checkpoint.ipynb │ ├── Success rate-checkpoint.ipynb │ ├── Time vs Path Length - new heuristic-checkpoint.ipynb │ ├── Time vs Path Length-checkpoint.ipynb │ └── Trajectory Following-checkpoint.ipynb ├── Architecture.svg ├── Experimental 3d - Subplot time vs path lenght.ipynb ├── Exploration - Take 2.ipynb ├── Exploration │ ├── .ipynb_checkpoints │ │ ├── Execution Time - Goal Manager-checkpoint.ipynb │ │ ├── Execution Time-checkpoint.ipynb │ │ ├── Exploration-checkpoint.ipynb │ │ └── Local geofence-checkpoint.ipynb │ ├── Execution Time - Goal Manager.ipynb │ ├── Execution Time.ipynb │ ├── Exploration.ipynb │ ├── Local geofence.ipynb │ ├── Volume.ipynb │ └── execution_time.py ├── Lazy Theta *.ipynb ├── Lazy Theta Real-Time Tor del Águila.ipynb ├── New Heuristic │ ├── .ipynb_checkpoints │ │ ├── Success rate - new heuristic-checkpoint.ipynb │ │ └── Time vs Path Length - new heuristic-checkpoint.ipynb │ ├── Success rate - new heuristic.ipynb │ ├── Time vs Path Length - new heuristic.ipynb │ ├── success_rate.py │ └── time_vs_pathLegth_lazyThetaStar.py ├── Obstacle detection.ipynb ├── Paper - Exploration real world.ipynb ├── Paper - Lazy Theta Star Online.ipynb ├── Paper A - Communications relay.ipynb ├── Paper C - Large structures test.ipynb ├── Sparse - 3d Puzzle - Subplot time vs path lenght.ipynb ├── State Machine.png ├── Subplot Obstacle Avoidance.ipynb ├── Success rate.ipynb ├── Time vs Path Length.ipynb ├── Trajectory Following.ipynb ├── analyzed_voxels.html ├── csv_sripts │ ├── compare_box_graphs.py │ ├── iterations_vs_voxelSize.py │ └── plots.py ├── deterministic.py ├── example_eachRunMeasurementPerRow.csv ├── example_vertical_timestamped.csv ├── plots │ ├── countVStime_Filtered getNeighbor execution time by call count.html │ ├── path_waypoints_closed.html │ ├── stackedTime_byVolume_Run 1 overall time vs neighbor time byt call count of getNeighbor.html │ ├── voxelSizeDistribution_Predicted.html │ └── voxelSizeDistribution_Stright line, 1m, no obstacles.html ├── subPlot_obstacleAvoidance.png ├── subPlot_obstacleAvoidance_scale.png ├── success_rate.py └── time_vs_pathLegth_lazyThetaStar.py ├── architecture ├── CMakeLists.txt ├── Tools │ ├── Firmware_changes_instructions.txt │ ├── iris.xacro │ ├── iris_base.urdf │ ├── iris_base.xacro │ ├── iris_base_notShowingVelodyne.urdf │ ├── iris_collectDataHokuyo.xacro │ ├── save_free_mem.bash │ └── set_ip.sh ├── cfg │ ├── bag_generateOctomap_params.yaml │ ├── bag_hitl_params.yaml │ ├── debug_oppairs.yaml │ ├── exploration_params.yaml │ ├── exploration_params_actinia.yaml │ ├── powerPlant_params.yaml │ ├── realUav_hitl_params.yaml │ ├── realUav_params.yaml │ ├── sim_hitl_params.yaml │ ├── sim_hitl_params_vanillaGeofence.yaml │ └── sim_sitl_collectData.yaml ├── include │ ├── architecture_math.h │ ├── exploration_state_machine.h │ ├── goal_state_machine.h │ └── ual_flightPlan_comms.h ├── install │ ├── ubuntu_sim_common_deps.sh │ └── ubuntu_sim_ros_gazebo.sh ├── launch │ ├── hitl_laptop_powerPlant.launch │ ├── hitl_laptop_px4_simulation.launch │ ├── hitl_laptop_saveOctomap.launch │ ├── hitl_upboard_highComputation.launch │ ├── hitl_upboard_path_command.launch │ ├── hitl_upboard_powerPlant.launch │ ├── laptop_octomapFromFile.launch │ ├── mision_ual.launch │ ├── px4_ual_powerPlant.launch │ ├── realUav_laptop_monitor.launch │ ├── realUav_upboard_exploration.launch │ ├── realUav_upboard_octomap.launch │ ├── realUav_upboard_path_command.launch │ ├── realUav_upboard_px4_old.launch │ ├── realUav_upboard_px4comms.launch │ ├── realUav_upboard_ualServer.launch │ ├── sitl_laptop_collectData.launch │ ├── sitl_laptop_debugGoalNode.launch │ ├── sitl_laptop_path_command.launch │ ├── sitl_powerPlant.launch │ ├── sitl_powerPlant_goal.launch │ └── test_server.launch ├── maneuvers │ ├── corridor_path.csv │ └── test_flight_path.csv ├── meshes │ └── hokuyo.dae ├── models │ ├── puzzle │ │ ├── meshes │ │ │ └── PUZZLE.stl │ │ ├── model.config │ │ └── model.sdf │ └── puzzle_3 │ │ ├── meshes │ │ └── PUZZLE2.stl │ │ ├── model.config │ │ └── model.sdf ├── package.xml ├── rviz_configurations │ ├── bag_filterPointCloud.rviz │ ├── debug_pose.rviz │ ├── exploration_ltstarPaths.rviz │ ├── hitl.rviz │ ├── hitl_lazyThetaStar_debug.rviz │ ├── measure.rviz │ ├── model_octomap.rviz │ ├── realUAV.rviz │ ├── rviz_velodyne_model.rviz │ ├── sim_filterPointCloud.rviz │ └── video_architecture.rviz ├── src │ ├── current_position_provider_node.cpp │ ├── exploration_state_machine.cpp │ ├── fake_position_provider_node.cpp │ ├── goal_sm_node.cpp │ ├── goal_state_machine.cpp │ ├── gps_utm_tf_broadcaster_node.cpp │ ├── mav_comms_node.cpp │ ├── state_manager_node.cpp │ ├── ual_communication_node.cpp │ ├── ual_flightPlan_comms.cpp │ └── ual_server.cpp ├── test │ ├── architecture_tests.cpp │ └── work_in_progress_architecture_tests.cpp └── worlds │ ├── 3D_puzzle_model.world │ ├── actinia.world │ ├── actinia_detail_3.world │ ├── actinia_extra_beams.world │ ├── box.world │ ├── crane_5 │ ├── model.config │ └── model.sdf │ ├── force_waypoint_sequence.world │ ├── force_waypoint_sequence_more_space.world │ ├── huge_block.world │ ├── power_plant │ └── power_plant.world │ └── water_deposit │ ├── model.config │ └── model.sdf ├── architecture_msgs ├── CMakeLists.txt ├── package.xml └── srv │ ├── DeclareUnobservable.srv │ ├── EnableHandbrakeTrigger.srv │ ├── FindNextGoal.srv │ ├── PositionMiddleMan.srv │ ├── PositionRequest.srv │ └── YawSpin.srv ├── catkin_simple ├── CMakeLists.txt ├── README.md ├── cmake │ └── catkin_simple-extras.cmake.em └── package.xml ├── dependencies └── odometry_plugin_dependencies │ ├── mav_msgs │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── cmake │ │ └── export_flags.cmake │ ├── include │ │ └── mav_msgs │ │ │ ├── common.h │ │ │ ├── conversions.h │ │ │ ├── default_topics.h │ │ │ ├── default_values.h │ │ │ └── eigen_mav_msgs.h │ ├── msg │ │ ├── Actuators.msg │ │ ├── AttitudeThrust.msg │ │ ├── RateThrust.msg │ │ ├── RollPitchYawrateThrust.msg │ │ ├── Status.msg │ │ └── TorqueThrust.msg │ └── package.xml │ ├── rotors_comm │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── msg │ │ └── WindSpeed.msg │ ├── package.xml │ └── srv │ │ └── Octomap.srv │ ├── rotors_control │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ │ └── rotors_control │ │ │ ├── attitude_controller.h │ │ │ ├── attitude_controller_samy.h │ │ │ ├── common.h │ │ │ ├── lee_position_controller.h │ │ │ ├── motor_controller.h │ │ │ ├── parameters.h │ │ │ ├── parameters_ros.h │ │ │ ├── rate_controller.h │ │ │ └── roll_pitch_yawrate_thrust_controller.h │ ├── package.xml │ └── src │ │ ├── attitude_controller.cpp │ │ ├── attitude_controller_samy.cpp │ │ ├── library │ │ ├── lee_position_controller.cpp │ │ └── roll_pitch_yawrate_thrust_controller.cpp │ │ ├── motor_controller.cpp │ │ ├── nodes │ │ ├── lee_position_controller_node.cpp │ │ ├── lee_position_controller_node.h │ │ ├── roll_pitch_yawrate_thrust_controller_node.cpp │ │ └── roll_pitch_yawrate_thrust_controller_node.h │ │ └── rate_controller.cpp │ └── rotors_gazebo_plugins │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ └── rotors_gazebo_plugins │ │ ├── common.h │ │ ├── gazebo_bag_plugin.h │ │ ├── gazebo_controller_interface.h │ │ ├── gazebo_imu_plugin.h │ │ ├── gazebo_mavlink_interface.h │ │ ├── gazebo_motor_model.h │ │ ├── gazebo_multirotor_base_plugin.h │ │ ├── gazebo_octomap_plugin.h │ │ ├── gazebo_odometry_plugin.h │ │ ├── gazebo_wind_plugin.h │ │ ├── motor_controller.hpp │ │ ├── motor_model.hpp │ │ └── multi_copter.hpp │ ├── package.xml │ └── src │ ├── gazebo_bag_plugin.cpp │ ├── gazebo_controller_interface.cpp │ ├── gazebo_imu_plugin.cpp │ ├── gazebo_mavlink_interface.cpp │ ├── gazebo_motor_model.cpp │ ├── gazebo_multirotor_base_plugin.cpp │ ├── gazebo_octomap_plugin.cpp │ ├── gazebo_odometry_plugin.cpp │ └── gazebo_wind_plugin.cpp ├── frontiers ├── CMakeLists.txt ├── include │ ├── frontiers.h │ ├── frontiers_common.h │ ├── neighbors.h │ ├── ordered_neighbors.h │ └── volume.h ├── launch │ ├── debug_frontiers.rviz │ ├── debug_neighbors.launch │ └── wip_node.launch ├── package.xml ├── src │ ├── frontiers.cpp │ ├── frontiers_async_node.cpp │ ├── frontiers_debug_node.cpp │ └── neighbors.cpp └── test │ ├── frontier_lib_tests.cpp │ ├── neighbor_tests.cpp │ ├── volume_tests.cpp │ └── work_in_progress_frontiers_tests.cpp ├── frontiers_msgs ├── CMakeLists.txt ├── msg │ ├── FrontierReply.msg │ ├── FrontierRequest.msg │ ├── LocalGeofenceRequest.msg │ └── VoxelMsg.msg ├── package.xml └── srv │ ├── CheckIsExplored.srv │ ├── CheckIsFrontier.srv │ ├── FindFrontiers.srv │ └── FrontierNodeStatus.srv ├── launch_options ├── 20161114_reviewMeeting.rviz ├── CMakeLists.txt ├── custom_rosconsole.conf ├── include │ └── argument_parser.h ├── launch │ ├── 20161114_rm_demo.launch │ ├── 20170222_generateOctree.launch │ ├── 20170829_showLazyThetaStarPaths.launch │ ├── 20180219_freiburg_showLazyThetaStarPaths.launch │ ├── building_octree_and_gazebo_grvc_velodyne.launch │ ├── octree_and_gazebo_grvc_velodyne.launch │ ├── test_grvc_velodyne.launch │ ├── test_lazyThetaLocal_mavlink_hal_velodyne.launch │ ├── test_lazyTheta_mavlink_hal_velodyne.launch │ ├── test_mavlink_hal_grvc.launch │ ├── test_mavlink_hal_grvc_velodyne.launch │ ├── test_multidofService_mavlink_hal_grvc_velodyne.launch │ └── test_server.launch ├── lazyThetaConfig.rviz ├── package.xml ├── showPath.rviz ├── showPath_px4.rviz ├── src │ └── teleop_pandora.cpp ├── urdf │ ├── actinia_scaled_px4.world │ ├── box.urdf.xacro │ ├── circle.world │ ├── circle_1m.world │ ├── circle_buildingEditor.sdf │ ├── circle_fix.world │ ├── double_circle_1m.world │ ├── double_circle_v4.world │ ├── offShoreOil.world │ ├── offShoreOil_1m.world │ ├── s_1m.world │ ├── s_v3.world │ ├── tunnel.world │ └── worldMaybe.world └── world │ └── disaster.world ├── lazy_theta_star ├── CMakeLists.txt ├── Doxyfile ├── include │ ├── ltStarOctree_common.h │ ├── ltStar_dispatcher.h │ ├── ltStar_lib_ortho.h │ ├── open.h │ ├── orthogonal_planes.h │ ├── resultSet.h │ └── voxel.h ├── launch │ ├── debug_experimental_tests.rviz │ ├── debug_path_generation_field.launch │ └── testing.launch ├── package.xml ├── src │ ├── ltStar_async_node.cpp │ ├── ltStar_async_node_sparse.cpp │ ├── ltStar_command_path_node.cpp │ ├── ltStar_dispatcher_node.cpp │ ├── ltStar_lib_ortho.cpp │ └── save_octomap_node.cpp └── test │ ├── analyze_point_cloud.cpp │ ├── collect_results.cpp │ ├── collect_results_3d_puzzle_ortho.cpp │ ├── collect_results_3d_puzzle_sparse.cpp │ ├── collect_results_experimental_ortho.cpp │ ├── collect_results_experimental_sparse.cpp │ ├── collect_results_obstacleAvoidance.cpp │ ├── collect_results_obstacleAvoidance_ortho.cpp │ ├── collect_results_ortho_deterministic.cpp │ ├── depth_voxelSide_tests.cpp │ ├── lazyTheta_tests_ortho.cpp │ ├── open_tests.cpp │ ├── orthogonal_planes_tests.cpp │ ├── visibility_test.cpp │ └── work_in_progress_test.cpp ├── lazy_theta_star_msgs ├── CMakeLists.txt ├── msg │ ├── LTStarReply.msg │ └── LTStarRequest.msg ├── package.xml └── srv │ ├── CheckFlightCorridor.srv │ ├── CheckVisibility.srv │ └── LTStarNodeStatus.srv ├── observation_maneuver ├── CMakeLists.txt ├── include │ └── observation_maneuver.h ├── launch │ └── visualize_oppairs.launch ├── package.xml ├── rviz_config │ └── visualize_oppairs.rviz ├── src │ ├── observation_maneuver.cpp │ └── observation_maneuver_node.cpp └── test │ ├── observationPoints_tests.cpp │ └── work_in_progress_observationPoints_tests.cpp ├── observation_maneuver_msgs ├── CMakeLists.txt ├── msg │ ├── OPPairsReply.msg │ └── OPPairsRequest.msg └── package.xml └── rviz_interface ├── CMakeLists.txt ├── include └── marker_publishing_utils.h ├── package.xml └── src └── marker_publishing_utils.cpp /.gitignore: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/.gitignore -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/CMakeLists.txt -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/LICENSE -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/README.md -------------------------------------------------------------------------------- /_docker/Dockerfile: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_docker/Dockerfile -------------------------------------------------------------------------------- /_docker_grvc/Dockerfile: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_docker_grvc/Dockerfile -------------------------------------------------------------------------------- /_generate_plots/.ipynb_checkpoints/Experimental 3d - Subplot time vs path lenght-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/.ipynb_checkpoints/Experimental 3d - Subplot time vs path lenght-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/.ipynb_checkpoints/Exploration - Take 2-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/.ipynb_checkpoints/Exploration - Take 2-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/.ipynb_checkpoints/Lazy Theta *-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/.ipynb_checkpoints/Lazy Theta *-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/.ipynb_checkpoints/Lazy Theta Real-Time Tor del Águila-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/.ipynb_checkpoints/Lazy Theta Real-Time Tor del Águila-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/.ipynb_checkpoints/Obstacle detection-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/.ipynb_checkpoints/Obstacle detection-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/.ipynb_checkpoints/Paper - Exploration real world-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/.ipynb_checkpoints/Paper - Exploration real world-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/.ipynb_checkpoints/Paper - Lazy Theta Star Online-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/.ipynb_checkpoints/Paper - Lazy Theta Star Online-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/.ipynb_checkpoints/Paper A - Communications relay-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/.ipynb_checkpoints/Paper A - Communications relay-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/.ipynb_checkpoints/Paper C - Large structures test-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/.ipynb_checkpoints/Paper C - Large structures test-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/.ipynb_checkpoints/Sparse - 3d Puzzle - Subplot time vs path lenght-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/.ipynb_checkpoints/Sparse - 3d Puzzle - Subplot time vs path lenght-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/.ipynb_checkpoints/Subplot Obstacle Avoidance-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/.ipynb_checkpoints/Subplot Obstacle Avoidance-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/.ipynb_checkpoints/Subplot v2-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/.ipynb_checkpoints/Subplot v2-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/.ipynb_checkpoints/Success rate-Copy1-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/.ipynb_checkpoints/Success rate-Copy1-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/.ipynb_checkpoints/Success rate-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/.ipynb_checkpoints/Success rate-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/.ipynb_checkpoints/Time vs Path Length - new heuristic-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/.ipynb_checkpoints/Time vs Path Length - new heuristic-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/.ipynb_checkpoints/Time vs Path Length-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/.ipynb_checkpoints/Time vs Path Length-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/.ipynb_checkpoints/Trajectory Following-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/.ipynb_checkpoints/Trajectory Following-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/Architecture.svg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Architecture.svg -------------------------------------------------------------------------------- /_generate_plots/Experimental 3d - Subplot time vs path lenght.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Experimental 3d - Subplot time vs path lenght.ipynb -------------------------------------------------------------------------------- /_generate_plots/Exploration - Take 2.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Exploration - Take 2.ipynb -------------------------------------------------------------------------------- /_generate_plots/Exploration/.ipynb_checkpoints/Execution Time - Goal Manager-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Exploration/.ipynb_checkpoints/Execution Time - Goal Manager-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/Exploration/.ipynb_checkpoints/Execution Time-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Exploration/.ipynb_checkpoints/Execution Time-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/Exploration/.ipynb_checkpoints/Exploration-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Exploration/.ipynb_checkpoints/Exploration-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/Exploration/.ipynb_checkpoints/Local geofence-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Exploration/.ipynb_checkpoints/Local geofence-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/Exploration/Execution Time - Goal Manager.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Exploration/Execution Time - Goal Manager.ipynb -------------------------------------------------------------------------------- /_generate_plots/Exploration/Execution Time.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Exploration/Execution Time.ipynb -------------------------------------------------------------------------------- /_generate_plots/Exploration/Exploration.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Exploration/Exploration.ipynb -------------------------------------------------------------------------------- /_generate_plots/Exploration/Local geofence.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Exploration/Local geofence.ipynb -------------------------------------------------------------------------------- /_generate_plots/Exploration/Volume.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Exploration/Volume.ipynb -------------------------------------------------------------------------------- /_generate_plots/Exploration/execution_time.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Exploration/execution_time.py -------------------------------------------------------------------------------- /_generate_plots/Lazy Theta *.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Lazy Theta *.ipynb -------------------------------------------------------------------------------- /_generate_plots/Lazy Theta Real-Time Tor del Águila.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Lazy Theta Real-Time Tor del Águila.ipynb -------------------------------------------------------------------------------- /_generate_plots/New Heuristic/.ipynb_checkpoints/Success rate - new heuristic-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/New Heuristic/.ipynb_checkpoints/Success rate - new heuristic-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/New Heuristic/.ipynb_checkpoints/Time vs Path Length - new heuristic-checkpoint.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/New Heuristic/.ipynb_checkpoints/Time vs Path Length - new heuristic-checkpoint.ipynb -------------------------------------------------------------------------------- /_generate_plots/New Heuristic/Success rate - new heuristic.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/New Heuristic/Success rate - new heuristic.ipynb -------------------------------------------------------------------------------- /_generate_plots/New Heuristic/Time vs Path Length - new heuristic.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/New Heuristic/Time vs Path Length - new heuristic.ipynb -------------------------------------------------------------------------------- /_generate_plots/New Heuristic/success_rate.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/New Heuristic/success_rate.py -------------------------------------------------------------------------------- /_generate_plots/New Heuristic/time_vs_pathLegth_lazyThetaStar.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/New Heuristic/time_vs_pathLegth_lazyThetaStar.py -------------------------------------------------------------------------------- /_generate_plots/Obstacle detection.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Obstacle detection.ipynb -------------------------------------------------------------------------------- /_generate_plots/Paper - Exploration real world.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Paper - Exploration real world.ipynb -------------------------------------------------------------------------------- /_generate_plots/Paper - Lazy Theta Star Online.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Paper - Lazy Theta Star Online.ipynb -------------------------------------------------------------------------------- /_generate_plots/Paper A - Communications relay.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Paper A - Communications relay.ipynb -------------------------------------------------------------------------------- /_generate_plots/Paper C - Large structures test.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Paper C - Large structures test.ipynb -------------------------------------------------------------------------------- /_generate_plots/Sparse - 3d Puzzle - Subplot time vs path lenght.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Sparse - 3d Puzzle - Subplot time vs path lenght.ipynb -------------------------------------------------------------------------------- /_generate_plots/State Machine.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/State Machine.png -------------------------------------------------------------------------------- /_generate_plots/Subplot Obstacle Avoidance.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Subplot Obstacle Avoidance.ipynb -------------------------------------------------------------------------------- /_generate_plots/Success rate.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Success rate.ipynb -------------------------------------------------------------------------------- /_generate_plots/Time vs Path Length.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Time vs Path Length.ipynb -------------------------------------------------------------------------------- /_generate_plots/Trajectory Following.ipynb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/Trajectory Following.ipynb -------------------------------------------------------------------------------- /_generate_plots/analyzed_voxels.html: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/analyzed_voxels.html -------------------------------------------------------------------------------- /_generate_plots/csv_sripts/compare_box_graphs.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/csv_sripts/compare_box_graphs.py -------------------------------------------------------------------------------- /_generate_plots/csv_sripts/iterations_vs_voxelSize.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/csv_sripts/iterations_vs_voxelSize.py -------------------------------------------------------------------------------- /_generate_plots/csv_sripts/plots.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/csv_sripts/plots.py -------------------------------------------------------------------------------- /_generate_plots/deterministic.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/deterministic.py -------------------------------------------------------------------------------- /_generate_plots/example_eachRunMeasurementPerRow.csv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/example_eachRunMeasurementPerRow.csv -------------------------------------------------------------------------------- /_generate_plots/example_vertical_timestamped.csv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/example_vertical_timestamped.csv -------------------------------------------------------------------------------- /_generate_plots/plots/countVStime_Filtered getNeighbor execution time by call count.html: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/plots/countVStime_Filtered getNeighbor execution time by call count.html -------------------------------------------------------------------------------- /_generate_plots/plots/path_waypoints_closed.html: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/plots/path_waypoints_closed.html -------------------------------------------------------------------------------- /_generate_plots/plots/stackedTime_byVolume_Run 1 overall time vs neighbor time byt call count of getNeighbor.html: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/plots/stackedTime_byVolume_Run 1 overall time vs neighbor time byt call count of getNeighbor.html -------------------------------------------------------------------------------- /_generate_plots/plots/voxelSizeDistribution_Predicted.html: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/plots/voxelSizeDistribution_Predicted.html -------------------------------------------------------------------------------- /_generate_plots/plots/voxelSizeDistribution_Stright line, 1m, no obstacles.html: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/plots/voxelSizeDistribution_Stright line, 1m, no obstacles.html -------------------------------------------------------------------------------- /_generate_plots/subPlot_obstacleAvoidance.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/subPlot_obstacleAvoidance.png -------------------------------------------------------------------------------- /_generate_plots/subPlot_obstacleAvoidance_scale.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/subPlot_obstacleAvoidance_scale.png -------------------------------------------------------------------------------- /_generate_plots/success_rate.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/success_rate.py -------------------------------------------------------------------------------- /_generate_plots/time_vs_pathLegth_lazyThetaStar.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/_generate_plots/time_vs_pathLegth_lazyThetaStar.py -------------------------------------------------------------------------------- /architecture/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/CMakeLists.txt -------------------------------------------------------------------------------- /architecture/Tools/Firmware_changes_instructions.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/Tools/Firmware_changes_instructions.txt -------------------------------------------------------------------------------- /architecture/Tools/iris.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/Tools/iris.xacro -------------------------------------------------------------------------------- /architecture/Tools/iris_base.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/Tools/iris_base.urdf -------------------------------------------------------------------------------- /architecture/Tools/iris_base.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/Tools/iris_base.xacro -------------------------------------------------------------------------------- /architecture/Tools/iris_base_notShowingVelodyne.urdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/Tools/iris_base_notShowingVelodyne.urdf -------------------------------------------------------------------------------- /architecture/Tools/iris_collectDataHokuyo.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/Tools/iris_collectDataHokuyo.xacro -------------------------------------------------------------------------------- /architecture/Tools/save_free_mem.bash: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/Tools/save_free_mem.bash -------------------------------------------------------------------------------- /architecture/Tools/set_ip.sh: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/Tools/set_ip.sh -------------------------------------------------------------------------------- /architecture/cfg/bag_generateOctomap_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/cfg/bag_generateOctomap_params.yaml -------------------------------------------------------------------------------- /architecture/cfg/bag_hitl_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/cfg/bag_hitl_params.yaml -------------------------------------------------------------------------------- /architecture/cfg/debug_oppairs.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/cfg/debug_oppairs.yaml -------------------------------------------------------------------------------- /architecture/cfg/exploration_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/cfg/exploration_params.yaml -------------------------------------------------------------------------------- /architecture/cfg/exploration_params_actinia.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/cfg/exploration_params_actinia.yaml -------------------------------------------------------------------------------- /architecture/cfg/powerPlant_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/cfg/powerPlant_params.yaml -------------------------------------------------------------------------------- /architecture/cfg/realUav_hitl_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/cfg/realUav_hitl_params.yaml -------------------------------------------------------------------------------- /architecture/cfg/realUav_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/cfg/realUav_params.yaml -------------------------------------------------------------------------------- /architecture/cfg/sim_hitl_params.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/cfg/sim_hitl_params.yaml -------------------------------------------------------------------------------- /architecture/cfg/sim_hitl_params_vanillaGeofence.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/cfg/sim_hitl_params_vanillaGeofence.yaml -------------------------------------------------------------------------------- /architecture/cfg/sim_sitl_collectData.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/cfg/sim_sitl_collectData.yaml -------------------------------------------------------------------------------- /architecture/include/architecture_math.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/include/architecture_math.h -------------------------------------------------------------------------------- /architecture/include/exploration_state_machine.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/include/exploration_state_machine.h -------------------------------------------------------------------------------- /architecture/include/goal_state_machine.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/include/goal_state_machine.h -------------------------------------------------------------------------------- /architecture/include/ual_flightPlan_comms.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/include/ual_flightPlan_comms.h -------------------------------------------------------------------------------- /architecture/install/ubuntu_sim_common_deps.sh: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/install/ubuntu_sim_common_deps.sh -------------------------------------------------------------------------------- /architecture/install/ubuntu_sim_ros_gazebo.sh: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/install/ubuntu_sim_ros_gazebo.sh -------------------------------------------------------------------------------- /architecture/launch/hitl_laptop_powerPlant.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/hitl_laptop_powerPlant.launch -------------------------------------------------------------------------------- /architecture/launch/hitl_laptop_px4_simulation.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/hitl_laptop_px4_simulation.launch -------------------------------------------------------------------------------- /architecture/launch/hitl_laptop_saveOctomap.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/hitl_laptop_saveOctomap.launch -------------------------------------------------------------------------------- /architecture/launch/hitl_upboard_highComputation.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/hitl_upboard_highComputation.launch -------------------------------------------------------------------------------- /architecture/launch/hitl_upboard_path_command.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/hitl_upboard_path_command.launch -------------------------------------------------------------------------------- /architecture/launch/hitl_upboard_powerPlant.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/hitl_upboard_powerPlant.launch -------------------------------------------------------------------------------- /architecture/launch/laptop_octomapFromFile.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/laptop_octomapFromFile.launch -------------------------------------------------------------------------------- /architecture/launch/mision_ual.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/mision_ual.launch -------------------------------------------------------------------------------- /architecture/launch/px4_ual_powerPlant.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/px4_ual_powerPlant.launch -------------------------------------------------------------------------------- /architecture/launch/realUav_laptop_monitor.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/realUav_laptop_monitor.launch -------------------------------------------------------------------------------- /architecture/launch/realUav_upboard_exploration.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/realUav_upboard_exploration.launch -------------------------------------------------------------------------------- /architecture/launch/realUav_upboard_octomap.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/realUav_upboard_octomap.launch -------------------------------------------------------------------------------- /architecture/launch/realUav_upboard_path_command.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/realUav_upboard_path_command.launch -------------------------------------------------------------------------------- /architecture/launch/realUav_upboard_px4_old.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/realUav_upboard_px4_old.launch -------------------------------------------------------------------------------- /architecture/launch/realUav_upboard_px4comms.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/realUav_upboard_px4comms.launch -------------------------------------------------------------------------------- /architecture/launch/realUav_upboard_ualServer.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/realUav_upboard_ualServer.launch -------------------------------------------------------------------------------- /architecture/launch/sitl_laptop_collectData.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/sitl_laptop_collectData.launch -------------------------------------------------------------------------------- /architecture/launch/sitl_laptop_debugGoalNode.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/sitl_laptop_debugGoalNode.launch -------------------------------------------------------------------------------- /architecture/launch/sitl_laptop_path_command.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/sitl_laptop_path_command.launch -------------------------------------------------------------------------------- /architecture/launch/sitl_powerPlant.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/sitl_powerPlant.launch -------------------------------------------------------------------------------- /architecture/launch/sitl_powerPlant_goal.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/sitl_powerPlant_goal.launch -------------------------------------------------------------------------------- /architecture/launch/test_server.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/launch/test_server.launch -------------------------------------------------------------------------------- /architecture/maneuvers/corridor_path.csv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/maneuvers/corridor_path.csv -------------------------------------------------------------------------------- /architecture/maneuvers/test_flight_path.csv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/maneuvers/test_flight_path.csv -------------------------------------------------------------------------------- /architecture/meshes/hokuyo.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/meshes/hokuyo.dae -------------------------------------------------------------------------------- /architecture/models/puzzle/meshes/PUZZLE.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/models/puzzle/meshes/PUZZLE.stl -------------------------------------------------------------------------------- /architecture/models/puzzle/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/models/puzzle/model.config -------------------------------------------------------------------------------- /architecture/models/puzzle/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/models/puzzle/model.sdf -------------------------------------------------------------------------------- /architecture/models/puzzle_3/meshes/PUZZLE2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/models/puzzle_3/meshes/PUZZLE2.stl -------------------------------------------------------------------------------- /architecture/models/puzzle_3/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/models/puzzle_3/model.config -------------------------------------------------------------------------------- /architecture/models/puzzle_3/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/models/puzzle_3/model.sdf -------------------------------------------------------------------------------- /architecture/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/package.xml -------------------------------------------------------------------------------- /architecture/rviz_configurations/bag_filterPointCloud.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/rviz_configurations/bag_filterPointCloud.rviz -------------------------------------------------------------------------------- /architecture/rviz_configurations/debug_pose.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/rviz_configurations/debug_pose.rviz -------------------------------------------------------------------------------- /architecture/rviz_configurations/exploration_ltstarPaths.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/rviz_configurations/exploration_ltstarPaths.rviz -------------------------------------------------------------------------------- /architecture/rviz_configurations/hitl.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/rviz_configurations/hitl.rviz -------------------------------------------------------------------------------- /architecture/rviz_configurations/hitl_lazyThetaStar_debug.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/rviz_configurations/hitl_lazyThetaStar_debug.rviz -------------------------------------------------------------------------------- /architecture/rviz_configurations/measure.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/rviz_configurations/measure.rviz -------------------------------------------------------------------------------- /architecture/rviz_configurations/model_octomap.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/rviz_configurations/model_octomap.rviz -------------------------------------------------------------------------------- /architecture/rviz_configurations/realUAV.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/rviz_configurations/realUAV.rviz -------------------------------------------------------------------------------- /architecture/rviz_configurations/rviz_velodyne_model.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/rviz_configurations/rviz_velodyne_model.rviz -------------------------------------------------------------------------------- /architecture/rviz_configurations/sim_filterPointCloud.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/rviz_configurations/sim_filterPointCloud.rviz -------------------------------------------------------------------------------- /architecture/rviz_configurations/video_architecture.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/rviz_configurations/video_architecture.rviz -------------------------------------------------------------------------------- /architecture/src/current_position_provider_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/src/current_position_provider_node.cpp -------------------------------------------------------------------------------- /architecture/src/exploration_state_machine.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/src/exploration_state_machine.cpp -------------------------------------------------------------------------------- /architecture/src/fake_position_provider_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/src/fake_position_provider_node.cpp -------------------------------------------------------------------------------- /architecture/src/goal_sm_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/src/goal_sm_node.cpp -------------------------------------------------------------------------------- /architecture/src/goal_state_machine.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/src/goal_state_machine.cpp -------------------------------------------------------------------------------- /architecture/src/gps_utm_tf_broadcaster_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/src/gps_utm_tf_broadcaster_node.cpp -------------------------------------------------------------------------------- /architecture/src/mav_comms_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/src/mav_comms_node.cpp -------------------------------------------------------------------------------- /architecture/src/state_manager_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/src/state_manager_node.cpp -------------------------------------------------------------------------------- /architecture/src/ual_communication_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/src/ual_communication_node.cpp -------------------------------------------------------------------------------- /architecture/src/ual_flightPlan_comms.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/src/ual_flightPlan_comms.cpp -------------------------------------------------------------------------------- /architecture/src/ual_server.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/src/ual_server.cpp -------------------------------------------------------------------------------- /architecture/test/architecture_tests.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/test/architecture_tests.cpp -------------------------------------------------------------------------------- /architecture/test/work_in_progress_architecture_tests.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/test/work_in_progress_architecture_tests.cpp -------------------------------------------------------------------------------- /architecture/worlds/3D_puzzle_model.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/worlds/3D_puzzle_model.world -------------------------------------------------------------------------------- /architecture/worlds/actinia.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/worlds/actinia.world -------------------------------------------------------------------------------- /architecture/worlds/actinia_detail_3.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/worlds/actinia_detail_3.world -------------------------------------------------------------------------------- /architecture/worlds/actinia_extra_beams.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/worlds/actinia_extra_beams.world -------------------------------------------------------------------------------- /architecture/worlds/box.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/worlds/box.world -------------------------------------------------------------------------------- /architecture/worlds/crane_5/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/worlds/crane_5/model.config -------------------------------------------------------------------------------- /architecture/worlds/crane_5/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/worlds/crane_5/model.sdf -------------------------------------------------------------------------------- /architecture/worlds/force_waypoint_sequence.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/worlds/force_waypoint_sequence.world -------------------------------------------------------------------------------- /architecture/worlds/force_waypoint_sequence_more_space.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/worlds/force_waypoint_sequence_more_space.world -------------------------------------------------------------------------------- /architecture/worlds/huge_block.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/worlds/huge_block.world -------------------------------------------------------------------------------- /architecture/worlds/power_plant/power_plant.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/worlds/power_plant/power_plant.world -------------------------------------------------------------------------------- /architecture/worlds/water_deposit/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/worlds/water_deposit/model.config -------------------------------------------------------------------------------- /architecture/worlds/water_deposit/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture/worlds/water_deposit/model.sdf -------------------------------------------------------------------------------- /architecture_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /architecture_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture_msgs/package.xml -------------------------------------------------------------------------------- /architecture_msgs/srv/DeclareUnobservable.srv: -------------------------------------------------------------------------------- 1 | --- 2 | -------------------------------------------------------------------------------- /architecture_msgs/srv/EnableHandbrakeTrigger.srv: -------------------------------------------------------------------------------- 1 | --- -------------------------------------------------------------------------------- /architecture_msgs/srv/FindNextGoal.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture_msgs/srv/FindNextGoal.srv -------------------------------------------------------------------------------- /architecture_msgs/srv/PositionMiddleMan.srv: -------------------------------------------------------------------------------- 1 | --- 2 | geometry_msgs/Point current_position -------------------------------------------------------------------------------- /architecture_msgs/srv/PositionRequest.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/architecture_msgs/srv/PositionRequest.srv -------------------------------------------------------------------------------- /architecture_msgs/srv/YawSpin.srv: -------------------------------------------------------------------------------- 1 | geometry_msgs/Point position 2 | --- -------------------------------------------------------------------------------- /catkin_simple/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/catkin_simple/CMakeLists.txt -------------------------------------------------------------------------------- /catkin_simple/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/catkin_simple/README.md -------------------------------------------------------------------------------- /catkin_simple/cmake/catkin_simple-extras.cmake.em: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/catkin_simple/cmake/catkin_simple-extras.cmake.em -------------------------------------------------------------------------------- /catkin_simple/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/catkin_simple/package.xml -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/mav_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/mav_msgs/CHANGELOG.rst -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/mav_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/mav_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/mav_msgs/cmake/export_flags.cmake: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/mav_msgs/cmake/export_flags.cmake -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/mav_msgs/include/mav_msgs/common.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/mav_msgs/include/mav_msgs/common.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/mav_msgs/include/mav_msgs/conversions.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/mav_msgs/include/mav_msgs/conversions.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/mav_msgs/include/mav_msgs/default_topics.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/mav_msgs/include/mav_msgs/default_topics.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/mav_msgs/include/mav_msgs/default_values.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/mav_msgs/include/mav_msgs/default_values.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/mav_msgs/include/mav_msgs/eigen_mav_msgs.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/mav_msgs/include/mav_msgs/eigen_mav_msgs.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/mav_msgs/msg/Actuators.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/mav_msgs/msg/Actuators.msg -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/mav_msgs/msg/AttitudeThrust.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/mav_msgs/msg/AttitudeThrust.msg -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/mav_msgs/msg/RateThrust.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/mav_msgs/msg/RateThrust.msg -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/mav_msgs/msg/RollPitchYawrateThrust.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/mav_msgs/msg/RollPitchYawrateThrust.msg -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/mav_msgs/msg/Status.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/mav_msgs/msg/Status.msg -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/mav_msgs/msg/TorqueThrust.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/mav_msgs/msg/TorqueThrust.msg -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/mav_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/mav_msgs/package.xml -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_comm/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_comm/CHANGELOG.rst -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_comm/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_comm/CMakeLists.txt -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_comm/msg/WindSpeed.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_comm/msg/WindSpeed.msg -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_comm/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_comm/package.xml -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_comm/srv/Octomap.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_comm/srv/Octomap.srv -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/CHANGELOG.rst -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/CMakeLists.txt -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/include/rotors_control/attitude_controller.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/include/rotors_control/attitude_controller.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/include/rotors_control/attitude_controller_samy.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/include/rotors_control/attitude_controller_samy.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/include/rotors_control/common.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/include/rotors_control/common.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/include/rotors_control/lee_position_controller.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/include/rotors_control/lee_position_controller.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/include/rotors_control/motor_controller.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/include/rotors_control/motor_controller.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/include/rotors_control/parameters.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/include/rotors_control/parameters.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/include/rotors_control/parameters_ros.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/include/rotors_control/parameters_ros.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/include/rotors_control/rate_controller.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/include/rotors_control/rate_controller.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/include/rotors_control/roll_pitch_yawrate_thrust_controller.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/include/rotors_control/roll_pitch_yawrate_thrust_controller.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/package.xml -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/src/attitude_controller.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/src/attitude_controller.cpp -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/src/attitude_controller_samy.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/src/attitude_controller_samy.cpp -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/src/library/lee_position_controller.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/src/library/lee_position_controller.cpp -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/src/library/roll_pitch_yawrate_thrust_controller.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/src/library/roll_pitch_yawrate_thrust_controller.cpp -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/src/motor_controller.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/src/motor_controller.cpp -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/src/nodes/lee_position_controller_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/src/nodes/lee_position_controller_node.cpp -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/src/nodes/lee_position_controller_node.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/src/nodes/lee_position_controller_node.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/src/nodes/roll_pitch_yawrate_thrust_controller_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/src/nodes/roll_pitch_yawrate_thrust_controller_node.cpp -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/src/nodes/roll_pitch_yawrate_thrust_controller_node.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/src/nodes/roll_pitch_yawrate_thrust_controller_node.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_control/src/rate_controller.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_control/src/rate_controller.cpp -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/CHANGELOG.rst -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/CMakeLists.txt -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/common.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/common.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/gazebo_bag_plugin.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/gazebo_bag_plugin.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/gazebo_controller_interface.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/gazebo_controller_interface.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/gazebo_imu_plugin.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/gazebo_imu_plugin.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/gazebo_mavlink_interface.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/gazebo_mavlink_interface.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/gazebo_motor_model.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/gazebo_motor_model.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/gazebo_multirotor_base_plugin.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/gazebo_multirotor_base_plugin.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/gazebo_octomap_plugin.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/gazebo_octomap_plugin.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/gazebo_odometry_plugin.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/gazebo_odometry_plugin.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/gazebo_wind_plugin.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/gazebo_wind_plugin.h -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/motor_controller.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/motor_controller.hpp -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/motor_model.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/motor_model.hpp -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/multi_copter.hpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/include/rotors_gazebo_plugins/multi_copter.hpp -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/package.xml -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/src/gazebo_bag_plugin.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/src/gazebo_bag_plugin.cpp -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/src/gazebo_controller_interface.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/src/gazebo_controller_interface.cpp -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/src/gazebo_imu_plugin.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/src/gazebo_imu_plugin.cpp -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/src/gazebo_mavlink_interface.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/src/gazebo_mavlink_interface.cpp -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/src/gazebo_motor_model.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/src/gazebo_motor_model.cpp -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/src/gazebo_multirotor_base_plugin.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/src/gazebo_multirotor_base_plugin.cpp -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/src/gazebo_octomap_plugin.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/src/gazebo_octomap_plugin.cpp -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/src/gazebo_odometry_plugin.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/src/gazebo_odometry_plugin.cpp -------------------------------------------------------------------------------- /dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/src/gazebo_wind_plugin.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/dependencies/odometry_plugin_dependencies/rotors_gazebo_plugins/src/gazebo_wind_plugin.cpp -------------------------------------------------------------------------------- /frontiers/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers/CMakeLists.txt -------------------------------------------------------------------------------- /frontiers/include/frontiers.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers/include/frontiers.h -------------------------------------------------------------------------------- /frontiers/include/frontiers_common.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers/include/frontiers_common.h -------------------------------------------------------------------------------- /frontiers/include/neighbors.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers/include/neighbors.h -------------------------------------------------------------------------------- /frontiers/include/ordered_neighbors.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers/include/ordered_neighbors.h -------------------------------------------------------------------------------- /frontiers/include/volume.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers/include/volume.h -------------------------------------------------------------------------------- /frontiers/launch/debug_frontiers.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers/launch/debug_frontiers.rviz -------------------------------------------------------------------------------- /frontiers/launch/debug_neighbors.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers/launch/debug_neighbors.launch -------------------------------------------------------------------------------- /frontiers/launch/wip_node.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers/launch/wip_node.launch -------------------------------------------------------------------------------- /frontiers/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers/package.xml -------------------------------------------------------------------------------- /frontiers/src/frontiers.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers/src/frontiers.cpp -------------------------------------------------------------------------------- /frontiers/src/frontiers_async_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers/src/frontiers_async_node.cpp -------------------------------------------------------------------------------- /frontiers/src/frontiers_debug_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers/src/frontiers_debug_node.cpp -------------------------------------------------------------------------------- /frontiers/src/neighbors.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers/src/neighbors.cpp -------------------------------------------------------------------------------- /frontiers/test/frontier_lib_tests.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers/test/frontier_lib_tests.cpp -------------------------------------------------------------------------------- /frontiers/test/neighbor_tests.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers/test/neighbor_tests.cpp -------------------------------------------------------------------------------- /frontiers/test/volume_tests.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers/test/volume_tests.cpp -------------------------------------------------------------------------------- /frontiers/test/work_in_progress_frontiers_tests.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers/test/work_in_progress_frontiers_tests.cpp -------------------------------------------------------------------------------- /frontiers_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /frontiers_msgs/msg/FrontierReply.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers_msgs/msg/FrontierReply.msg -------------------------------------------------------------------------------- /frontiers_msgs/msg/FrontierRequest.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers_msgs/msg/FrontierRequest.msg -------------------------------------------------------------------------------- /frontiers_msgs/msg/LocalGeofenceRequest.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers_msgs/msg/LocalGeofenceRequest.msg -------------------------------------------------------------------------------- /frontiers_msgs/msg/VoxelMsg.msg: -------------------------------------------------------------------------------- 1 | geometry_msgs/Point xyz_m 2 | float64 size -------------------------------------------------------------------------------- /frontiers_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers_msgs/package.xml -------------------------------------------------------------------------------- /frontiers_msgs/srv/CheckIsExplored.srv: -------------------------------------------------------------------------------- 1 | geometry_msgs/Point candidate 2 | --- 3 | bool is_explored -------------------------------------------------------------------------------- /frontiers_msgs/srv/CheckIsFrontier.srv: -------------------------------------------------------------------------------- 1 | geometry_msgs/Point candidate 2 | --- 3 | bool is_frontier -------------------------------------------------------------------------------- /frontiers_msgs/srv/FindFrontiers.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/frontiers_msgs/srv/FindFrontiers.srv -------------------------------------------------------------------------------- /frontiers_msgs/srv/FrontierNodeStatus.srv: -------------------------------------------------------------------------------- 1 | --- 2 | bool is_accepting_requests -------------------------------------------------------------------------------- /launch_options/20161114_reviewMeeting.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/20161114_reviewMeeting.rviz -------------------------------------------------------------------------------- /launch_options/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/CMakeLists.txt -------------------------------------------------------------------------------- /launch_options/custom_rosconsole.conf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/custom_rosconsole.conf -------------------------------------------------------------------------------- /launch_options/include/argument_parser.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/include/argument_parser.h -------------------------------------------------------------------------------- /launch_options/launch/20161114_rm_demo.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/launch/20161114_rm_demo.launch -------------------------------------------------------------------------------- /launch_options/launch/20170222_generateOctree.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/launch/20170222_generateOctree.launch -------------------------------------------------------------------------------- /launch_options/launch/20170829_showLazyThetaStarPaths.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/launch/20170829_showLazyThetaStarPaths.launch -------------------------------------------------------------------------------- /launch_options/launch/20180219_freiburg_showLazyThetaStarPaths.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/launch/20180219_freiburg_showLazyThetaStarPaths.launch -------------------------------------------------------------------------------- /launch_options/launch/building_octree_and_gazebo_grvc_velodyne.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/launch/building_octree_and_gazebo_grvc_velodyne.launch -------------------------------------------------------------------------------- /launch_options/launch/octree_and_gazebo_grvc_velodyne.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/launch/octree_and_gazebo_grvc_velodyne.launch -------------------------------------------------------------------------------- /launch_options/launch/test_grvc_velodyne.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/launch/test_grvc_velodyne.launch -------------------------------------------------------------------------------- /launch_options/launch/test_lazyThetaLocal_mavlink_hal_velodyne.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/launch/test_lazyThetaLocal_mavlink_hal_velodyne.launch -------------------------------------------------------------------------------- /launch_options/launch/test_lazyTheta_mavlink_hal_velodyne.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/launch/test_lazyTheta_mavlink_hal_velodyne.launch -------------------------------------------------------------------------------- /launch_options/launch/test_mavlink_hal_grvc.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/launch/test_mavlink_hal_grvc.launch -------------------------------------------------------------------------------- /launch_options/launch/test_mavlink_hal_grvc_velodyne.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/launch/test_mavlink_hal_grvc_velodyne.launch -------------------------------------------------------------------------------- /launch_options/launch/test_multidofService_mavlink_hal_grvc_velodyne.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/launch/test_multidofService_mavlink_hal_grvc_velodyne.launch -------------------------------------------------------------------------------- /launch_options/launch/test_server.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/launch/test_server.launch -------------------------------------------------------------------------------- /launch_options/lazyThetaConfig.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/lazyThetaConfig.rviz -------------------------------------------------------------------------------- /launch_options/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/package.xml -------------------------------------------------------------------------------- /launch_options/showPath.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/showPath.rviz -------------------------------------------------------------------------------- /launch_options/showPath_px4.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/showPath_px4.rviz -------------------------------------------------------------------------------- /launch_options/src/teleop_pandora.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/src/teleop_pandora.cpp -------------------------------------------------------------------------------- /launch_options/urdf/actinia_scaled_px4.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/urdf/actinia_scaled_px4.world -------------------------------------------------------------------------------- /launch_options/urdf/box.urdf.xacro: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/urdf/box.urdf.xacro -------------------------------------------------------------------------------- /launch_options/urdf/circle.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/urdf/circle.world -------------------------------------------------------------------------------- /launch_options/urdf/circle_1m.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/urdf/circle_1m.world -------------------------------------------------------------------------------- /launch_options/urdf/circle_buildingEditor.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/urdf/circle_buildingEditor.sdf -------------------------------------------------------------------------------- /launch_options/urdf/circle_fix.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/urdf/circle_fix.world -------------------------------------------------------------------------------- /launch_options/urdf/double_circle_1m.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/urdf/double_circle_1m.world -------------------------------------------------------------------------------- /launch_options/urdf/double_circle_v4.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/urdf/double_circle_v4.world -------------------------------------------------------------------------------- /launch_options/urdf/offShoreOil.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/urdf/offShoreOil.world -------------------------------------------------------------------------------- /launch_options/urdf/offShoreOil_1m.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/urdf/offShoreOil_1m.world -------------------------------------------------------------------------------- /launch_options/urdf/s_1m.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/urdf/s_1m.world -------------------------------------------------------------------------------- /launch_options/urdf/s_v3.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/urdf/s_v3.world -------------------------------------------------------------------------------- /launch_options/urdf/tunnel.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/urdf/tunnel.world -------------------------------------------------------------------------------- /launch_options/urdf/worldMaybe.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/urdf/worldMaybe.world -------------------------------------------------------------------------------- /launch_options/world/disaster.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/launch_options/world/disaster.world -------------------------------------------------------------------------------- /lazy_theta_star/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/CMakeLists.txt -------------------------------------------------------------------------------- /lazy_theta_star/Doxyfile: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/Doxyfile -------------------------------------------------------------------------------- /lazy_theta_star/include/ltStarOctree_common.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/include/ltStarOctree_common.h -------------------------------------------------------------------------------- /lazy_theta_star/include/ltStar_dispatcher.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/include/ltStar_dispatcher.h -------------------------------------------------------------------------------- /lazy_theta_star/include/ltStar_lib_ortho.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/include/ltStar_lib_ortho.h -------------------------------------------------------------------------------- /lazy_theta_star/include/open.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/include/open.h -------------------------------------------------------------------------------- /lazy_theta_star/include/orthogonal_planes.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/include/orthogonal_planes.h -------------------------------------------------------------------------------- /lazy_theta_star/include/resultSet.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/include/resultSet.h -------------------------------------------------------------------------------- /lazy_theta_star/include/voxel.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/include/voxel.h -------------------------------------------------------------------------------- /lazy_theta_star/launch/debug_experimental_tests.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/launch/debug_experimental_tests.rviz -------------------------------------------------------------------------------- /lazy_theta_star/launch/debug_path_generation_field.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/launch/debug_path_generation_field.launch -------------------------------------------------------------------------------- /lazy_theta_star/launch/testing.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/launch/testing.launch -------------------------------------------------------------------------------- /lazy_theta_star/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/package.xml -------------------------------------------------------------------------------- /lazy_theta_star/src/ltStar_async_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/src/ltStar_async_node.cpp -------------------------------------------------------------------------------- /lazy_theta_star/src/ltStar_async_node_sparse.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/src/ltStar_async_node_sparse.cpp -------------------------------------------------------------------------------- /lazy_theta_star/src/ltStar_command_path_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/src/ltStar_command_path_node.cpp -------------------------------------------------------------------------------- /lazy_theta_star/src/ltStar_dispatcher_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/src/ltStar_dispatcher_node.cpp -------------------------------------------------------------------------------- /lazy_theta_star/src/ltStar_lib_ortho.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/src/ltStar_lib_ortho.cpp -------------------------------------------------------------------------------- /lazy_theta_star/src/save_octomap_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/src/save_octomap_node.cpp -------------------------------------------------------------------------------- /lazy_theta_star/test/analyze_point_cloud.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/test/analyze_point_cloud.cpp -------------------------------------------------------------------------------- /lazy_theta_star/test/collect_results.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/test/collect_results.cpp -------------------------------------------------------------------------------- /lazy_theta_star/test/collect_results_3d_puzzle_ortho.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/test/collect_results_3d_puzzle_ortho.cpp -------------------------------------------------------------------------------- /lazy_theta_star/test/collect_results_3d_puzzle_sparse.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/test/collect_results_3d_puzzle_sparse.cpp -------------------------------------------------------------------------------- /lazy_theta_star/test/collect_results_experimental_ortho.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/test/collect_results_experimental_ortho.cpp -------------------------------------------------------------------------------- /lazy_theta_star/test/collect_results_experimental_sparse.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/test/collect_results_experimental_sparse.cpp -------------------------------------------------------------------------------- /lazy_theta_star/test/collect_results_obstacleAvoidance.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/test/collect_results_obstacleAvoidance.cpp -------------------------------------------------------------------------------- /lazy_theta_star/test/collect_results_obstacleAvoidance_ortho.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/test/collect_results_obstacleAvoidance_ortho.cpp -------------------------------------------------------------------------------- /lazy_theta_star/test/collect_results_ortho_deterministic.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/test/collect_results_ortho_deterministic.cpp -------------------------------------------------------------------------------- /lazy_theta_star/test/depth_voxelSide_tests.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/test/depth_voxelSide_tests.cpp -------------------------------------------------------------------------------- /lazy_theta_star/test/lazyTheta_tests_ortho.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/test/lazyTheta_tests_ortho.cpp -------------------------------------------------------------------------------- /lazy_theta_star/test/open_tests.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/test/open_tests.cpp -------------------------------------------------------------------------------- /lazy_theta_star/test/orthogonal_planes_tests.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/test/orthogonal_planes_tests.cpp -------------------------------------------------------------------------------- /lazy_theta_star/test/visibility_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/test/visibility_test.cpp -------------------------------------------------------------------------------- /lazy_theta_star/test/work_in_progress_test.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star/test/work_in_progress_test.cpp -------------------------------------------------------------------------------- /lazy_theta_star_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /lazy_theta_star_msgs/msg/LTStarReply.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star_msgs/msg/LTStarReply.msg -------------------------------------------------------------------------------- /lazy_theta_star_msgs/msg/LTStarRequest.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star_msgs/msg/LTStarRequest.msg -------------------------------------------------------------------------------- /lazy_theta_star_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star_msgs/package.xml -------------------------------------------------------------------------------- /lazy_theta_star_msgs/srv/CheckFlightCorridor.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star_msgs/srv/CheckFlightCorridor.srv -------------------------------------------------------------------------------- /lazy_theta_star_msgs/srv/CheckVisibility.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/lazy_theta_star_msgs/srv/CheckVisibility.srv -------------------------------------------------------------------------------- /lazy_theta_star_msgs/srv/LTStarNodeStatus.srv: -------------------------------------------------------------------------------- 1 | --- 2 | bool is_accepting_requests -------------------------------------------------------------------------------- /observation_maneuver/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/observation_maneuver/CMakeLists.txt -------------------------------------------------------------------------------- /observation_maneuver/include/observation_maneuver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/observation_maneuver/include/observation_maneuver.h -------------------------------------------------------------------------------- /observation_maneuver/launch/visualize_oppairs.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/observation_maneuver/launch/visualize_oppairs.launch -------------------------------------------------------------------------------- /observation_maneuver/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/observation_maneuver/package.xml -------------------------------------------------------------------------------- /observation_maneuver/rviz_config/visualize_oppairs.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/observation_maneuver/rviz_config/visualize_oppairs.rviz -------------------------------------------------------------------------------- /observation_maneuver/src/observation_maneuver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/observation_maneuver/src/observation_maneuver.cpp -------------------------------------------------------------------------------- /observation_maneuver/src/observation_maneuver_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/observation_maneuver/src/observation_maneuver_node.cpp -------------------------------------------------------------------------------- /observation_maneuver/test/observationPoints_tests.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/observation_maneuver/test/observationPoints_tests.cpp -------------------------------------------------------------------------------- /observation_maneuver/test/work_in_progress_observationPoints_tests.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/observation_maneuver/test/work_in_progress_observationPoints_tests.cpp -------------------------------------------------------------------------------- /observation_maneuver_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/observation_maneuver_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /observation_maneuver_msgs/msg/OPPairsReply.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/observation_maneuver_msgs/msg/OPPairsReply.msg -------------------------------------------------------------------------------- /observation_maneuver_msgs/msg/OPPairsRequest.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/observation_maneuver_msgs/msg/OPPairsRequest.msg -------------------------------------------------------------------------------- /observation_maneuver_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/observation_maneuver_msgs/package.xml -------------------------------------------------------------------------------- /rviz_interface/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/rviz_interface/CMakeLists.txt -------------------------------------------------------------------------------- /rviz_interface/include/marker_publishing_utils.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/rviz_interface/include/marker_publishing_utils.h -------------------------------------------------------------------------------- /rviz_interface/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/rviz_interface/package.xml -------------------------------------------------------------------------------- /rviz_interface/src/marker_publishing_utils.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/margaridaCF/FlyingOctomap_code/HEAD/rviz_interface/src/marker_publishing_utils.cpp --------------------------------------------------------------------------------