├── .gitmodules ├── LICENSE ├── README.md ├── config ├── drone1 │ ├── ardrone_bottom.yaml │ ├── ardrone_front.yaml │ ├── base_local_planner_params.yaml │ ├── configFile.xml │ ├── costmap_common_params.yaml │ ├── driver_pelican.xml │ ├── droneConfiguration.xml │ ├── ekf_state_estimator_config.xml │ ├── global_costmap_params.yaml │ ├── local_costmap_params.yaml │ ├── midlevel_autopilot.xml │ ├── obstacle_config.xml │ ├── params_localization_obs.xml │ ├── path_tracker.yaml │ └── quadrotor_pid_controller_config.yaml └── mission │ ├── behavior_catalog.yaml │ └── setup.sh ├── doc └── wiki │ ├── CoverPageAuster.png │ ├── PhotoMBZIRC2020_1.png │ ├── wiki_aerostack_gregale │ ├── wiki_aerostack_gregale.pdf │ └── wiki_aerostack_gregale │ │ ├── .DS_Store │ │ ├── AR-Drone-and-Visual-Markers.md │ │ ├── Add-a-GPS-Sensor.md │ │ ├── Add-a-New-Camera.md │ │ ├── Aerostack-Architecture.md │ │ ├── Aerostack-Virtual-Machine.md │ │ ├── Calibrate-Controllers.md │ │ ├── Catalog-of-Available-Processes.md │ │ ├── Configure-Launcher.md │ │ ├── Configure-Map.md │ │ ├── Getting-Started.md │ │ ├── Home.md │ │ ├── Human-Machine-Interface.md │ │ ├── Launch-Real-Flight.md │ │ ├── Launch-Simulated-Flight.md │ │ ├── License.md │ │ ├── List-of-Actions-for-TML.md │ │ ├── List-of-Parameters-for-TML.md │ │ ├── List-of-Skills-for-TML.md │ │ ├── List-of-distributions.md │ │ ├── Practical-Tips-for-Real-Flights.md │ │ ├── Publications.md │ │ ├── Setup-the-Communication-Network.md │ │ ├── Simulated-Quadrotor.md │ │ ├── Specify-Mission-Tasks.md │ │ ├── TML-Language.md │ │ ├── Use-Aerostack-for-a-New-Physical-Platform.md │ │ ├── What-is-Aerostack?.md │ │ ├── Wi-Fi-Communication-with-Multiple-Drones.md │ │ ├── _Footer.md │ │ ├── _Sidebar.md │ │ └── images │ │ ├── .DS_Store │ │ ├── ARDrone.png │ │ ├── Architecture.png │ │ ├── BlocksDiagram.png │ │ ├── CameraManager.png │ │ ├── CoverPage.png │ │ ├── ExecutiveSystem.png │ │ ├── HMIAbout.png │ │ ├── HMICameraViewer.png │ │ ├── HMIControlPanelAbortMission.png │ │ ├── HMIControlPanelKeyboard.png │ │ ├── HMIControlPanelStartMission.png │ │ ├── HMIGeneral.png │ │ ├── HMIKeyboardGuide.png │ │ ├── HMIMissionReporter.png │ │ ├── HMIParameterView.png │ │ ├── HMIProcessMonitor.png │ │ ├── HMIRequestedSkills.png │ │ ├── HMIVehicleDynamics.png │ │ ├── Logo Aerostack.png │ │ ├── LogoAerostack (bitbucket).png │ │ ├── LogoGPLv3.png │ │ ├── MapComplete.png │ │ ├── MapDimensions.png │ │ ├── MapObstacles.png │ │ ├── PlanningSystem.png │ │ ├── ProcessMonitor.png │ │ ├── Processes.png │ │ ├── ROSNetworkConfig.png │ │ ├── RobotEnvironment.png │ │ ├── SensorGPS.png │ │ ├── SituationAwarenessSystem.png │ │ ├── StateTransitionDiagram.png │ │ └── SupervisionSystem.png │ ├── wiki_aerostack_levant_2.0 │ ├── wiki_aerostack_levant │ │ ├── .DS_Store │ │ ├── AR-Drone-and-Visual-Markers.md │ │ ├── Add-a-GPS-Sensor.md │ │ ├── Add-a-New-Camera.md │ │ ├── Aerostack-Architecture.md │ │ ├── Aerostack-Virtual-Machine.md │ │ ├── Behavior-Tree.md │ │ ├── Calibrate-Controllers.md │ │ ├── Catalog-of-Behaviors.md │ │ ├── Catalog-of-Processes.md │ │ ├── Configure-Launcher.md │ │ ├── Configure-Map.md │ │ ├── Configure-the-Environment-Map-Using-XML-Files.md │ │ ├── Files │ │ │ ├── .DS_Store │ │ │ ├── ARDrone.png │ │ │ ├── ATENCION FALTA ESTA FIGURA HMIAbout.png │ │ │ ├── Architecture.png │ │ │ ├── BlocksDiagram.png │ │ │ ├── CameraManager.png │ │ │ ├── CoverPage.png │ │ │ ├── GUIBTGuideStep1.png │ │ │ ├── GUIBTGuideStep2.png │ │ │ ├── GUIBTGuideStep3.png │ │ │ ├── GUIBTGuideStep4_1.png │ │ │ ├── GUIBTGuideStep4_2.png │ │ │ ├── GUIBTGuideStep5.png │ │ │ ├── GUIBehaviorViewer.png │ │ │ ├── GUIBeliefViewer.png │ │ │ ├── GUICameraViewer.png │ │ │ ├── GUIComplexBTExample.png │ │ │ ├── GUIControlPanelBTExecuting.png │ │ │ ├── GUIControlPanelBTStart.png │ │ │ ├── GUIControlPanelKeyboardFirst.png │ │ │ ├── GUIControlPanelKeyboardSecond.png │ │ │ ├── GUIControlPanelTMLAbort.png │ │ │ ├── GUIControlPanelTMLStart.png │ │ │ ├── GUIEnvironmentViewer.png │ │ │ ├── GUIKeyboardTeleoperationGuide.png │ │ │ ├── GUIMapEditionMode1.png │ │ │ ├── GUIMapEditionMode2.png │ │ │ ├── GUIMapEditionMode3.png │ │ │ ├── GUIMapEditionModeFinal.png │ │ │ ├── GUIMapEditionModeFinal2.png │ │ │ ├── GUIMapEditionTools.png │ │ │ ├── GUIParameterView.png │ │ │ ├── GUIWindowsLayout.png │ │ │ ├── HMIBehaviorTree.png │ │ │ ├── HMIControlPanelAbortMission.png │ │ │ ├── HMIControlPanelStartMission.png │ │ │ ├── HMINewMap.png │ │ │ ├── LogoGPLv3.png │ │ │ ├── MapComplete.png │ │ │ ├── MapDimensions.png │ │ │ ├── MapObstacles.png │ │ │ ├── ProcessMonitor.png │ │ │ ├── Processes.png │ │ │ ├── ROSNetworkConfig.png │ │ │ ├── RobotEnvironment.png │ │ │ ├── SensorGPS.png │ │ │ ├── StateTransitionDiagram.png │ │ │ ├── VideoMapConfiguration.mp4 │ │ │ └── wiki_aerostack_gregale.pdf │ │ ├── Getting-Started.md │ │ ├── Graphical-User-Interface.md │ │ ├── Home.md │ │ ├── How-to-Create-an-Environment-Map.md │ │ ├── How-to-Program-a-New-Behavior.md │ │ ├── How-to-Program-a-New-Process.md │ │ ├── Launch-Real-Flight.md │ │ ├── License.md │ │ ├── List-of-distributions.md │ │ ├── Memory-of-Beliefs.md │ │ ├── Practical-Tips-for-Real-Flights.md │ │ ├── Publications.md │ │ ├── Python-Language.md │ │ ├── Setup-the-Communication-Network.md │ │ ├── Simulated-Quadrotor.md │ │ ├── Specify-Mission-Tasks.md │ │ ├── TML-Language.md │ │ ├── The-Class-RobotProcess.md │ │ ├── Use-Aerostack-for-a-New-Physical-Platform.md │ │ ├── What-is-Aerostack.md │ │ ├── Wi-Fi-Communication-with-Multiple-Drones.md │ │ ├── _Footer.md │ │ └── _Sidebar.md │ └── wiki_aerostack_levant_2.0.pdf │ ├── wiki_aerostack_levant_2.1 │ ├── wiki_aerostack_levant_2.1.pdf │ └── wiki_aerostack_levant_2.1 │ │ ├── .DS_Store │ │ ├── 4th-place-at-IMAV-2016.md │ │ ├── Add-a-GPS-Sensor.md │ │ ├── Add-a-New-Camera.md │ │ ├── Add-new-hardware.md │ │ ├── Aerostack-Architecture.md │ │ ├── Aerostack-Virtual-Machine.md │ │ ├── Alphanumeric-User-Interface.md │ │ ├── Behavior-Tree.md │ │ ├── Belief-management-processes.md │ │ ├── Build-flight-environment-with-visual-markers.md │ │ ├── Calibrate-Controllers.md │ │ ├── Catalog-of-Behaviors.md │ │ ├── Catalog-of-Processes.md │ │ ├── Communication-processes.md │ │ ├── Configure-the-Environment-Map-Using-XML-Files.md │ │ ├── Configure-the-Environment-Map.md │ │ ├── Execute-Missions.md │ │ ├── Execute-a-simulated-mission-using-Python.md │ │ ├── Execute-a-simulated-mission-using-TML.md │ │ ├── Execute-a-simulated-mission-using-a-behavior-tree.md │ │ ├── Execute-missions-that-follow-object-images.md │ │ ├── Execution-processes.md │ │ ├── Feature-extraction-processes.md │ │ ├── Files │ │ ├── .DS_Store │ │ ├── ARDrone.png │ │ ├── ATENCION FALTA ESTA FIGURA HMIAbout.png │ │ ├── AddChild.png │ │ ├── AerostackMainView.png │ │ ├── Architecture.png │ │ ├── BlocksDiagram.png │ │ ├── CameraManager.png │ │ ├── CoverPageLevant.png │ │ ├── CreateNewBehaviorTree.png │ │ ├── ExecuteTmlMission.png │ │ ├── GUIBTGuideStep1.png │ │ ├── GUIBTGuideStep2.png │ │ ├── GUIBTGuideStep3.png │ │ ├── GUIBTGuideStep4_1.png │ │ ├── GUIBTGuideStep4_2.png │ │ ├── GUIBTGuideStep5.png │ │ ├── GUIBehaviorTree.png │ │ ├── GUIBehaviorViewer.png │ │ ├── GUIBeliefViewer.png │ │ ├── GUICameraViewer.png │ │ ├── GUIComplexBTExample.png │ │ ├── GUIControlPanelAbortMission.png │ │ ├── GUIControlPanelKeyboardFirst.png │ │ ├── GUIControlPanelKeyboardSecond.png │ │ ├── GUIControlPanelStartMission.png │ │ ├── GUIEnvironmentViewer.png │ │ ├── GUIFirstPersonViewBig.png │ │ ├── GUIFirstPersonViewSmall.png │ │ ├── GUIKeyboardTeleoperationGuide.png │ │ ├── GUIMapEditionMode1.png │ │ ├── GUIMapEditionMode2.png │ │ ├── GUIMapEditionMode3.png │ │ ├── GUIMapEditionModeFinal.png │ │ ├── GUIMapEditionModeFinal2.png │ │ ├── GUIMapEditionTools.png │ │ ├── GUINewMap.png │ │ ├── GUIParameterView.png │ │ ├── GUIWindowsLayout.png │ │ ├── GuidedByBehaviorTress.png │ │ ├── LogoGPLv3.png │ │ ├── MapComplete.png │ │ ├── MapDimensions.png │ │ ├── MapObstacles.png │ │ ├── PressEditMission.png │ │ ├── ProcessMonitor.png │ │ ├── Processes.png │ │ ├── ROSNetworkConfig.png │ │ ├── RobotEnvironment.png │ │ ├── RvizMainView.png │ │ ├── SaveBehaviorTree.png │ │ ├── SensorGPS.png │ │ ├── ShellUserInterface.png │ │ ├── StateTransitionDiagram.png │ │ ├── TerminalsView.png │ │ ├── TmlOperationMode.png │ │ ├── VideoMapConfiguration.mp4 │ │ ├── wiki_aerostack_gregale.pdf │ │ └── wiki_aerostack_levant_2.0.pdf │ │ ├── Graphical-User-Interface.md │ │ ├── Home.md │ │ ├── How-to-Program-a-New-Process.md │ │ ├── How-to-create-a-launcher.md │ │ ├── Install-Aerostack.md │ │ ├── Launch-Aerostack-for-AR-Drone-2.0.md │ │ ├── Launch-Aerostack-with-Drone-Simulator.md │ │ ├── Launch-Real-Flight.md │ │ ├── License.md │ │ ├── List-of-distributions.md │ │ ├── Memory-of-Beliefs.md │ │ ├── Mission-Plan-Languages.md │ │ ├── Motion-control-processes.md │ │ ├── Motion-planning-processes.md │ │ ├── Physical-layer-processes.md │ │ ├── Practical-Tips-for-Real-Flights.md │ │ ├── Prepare-the-Mission.md │ │ ├── Program-New-Behaviors.md │ │ ├── Publications.md │ │ ├── Python-Language.md │ │ ├── Select-Launcher.md │ │ ├── Self-localization-and-mapping-processes.md │ │ ├── Setup-Communications.md │ │ ├── Setup-the-Communication-Network.md │ │ ├── TML-Language.md │ │ ├── Teleoperate-a-simulated-drone.md │ │ ├── The-Class-RobotProcess.md │ │ ├── Use-Aerostack-for-a-New-Physical-Platform.md │ │ ├── What-is-Aerostack.md │ │ ├── Wi-Fi-Communication-with-Multiple-Drones.md │ │ ├── _Footer.md │ │ └── _Sidebar.md │ └── wiki_aerostack_sirocco_3.0 │ ├── wiki_aerostack_sirocco_3.0.pdf │ └── wiki_aerostack_sirocco_3.0 │ ├── 3rd-place-at-MBZIRC-2020.md │ ├── 4th-place-at-IMAV-2016.md │ ├── Add-a-GPS-Sensor.md │ ├── Add-a-New-Camera.md │ ├── Add-new-hardware.md │ ├── Aerostack-Architecture.md │ ├── Alphanumeric-User-Interface.md │ ├── Basic-mission-with-"Drone-simulator".md │ ├── Basic-mission-with-Rotors-simulator.md │ ├── Basic-use-of-lidar-with-Rotors-simulator.md │ ├── Behavior-Tree.md │ ├── Behavior-tree-mission-with-"Drone-simulator".md │ ├── Bridge-inspection-with-Rotors-simulator.md │ ├── Calibrate-Controllers.md │ ├── Catalog-of-Behaviors.md │ ├── Configure-the-Environment-Map-Using-XML-Files.md │ ├── Configure-the-Environment-Map.md │ ├── Example-projects.md │ ├── Files │ ├── Architecture.png │ ├── BehaviorTreeEditor.png │ ├── BehaviorTreeNodeOptions.png │ ├── BehaviorTreeVariables.png │ ├── BlocksDiagram.png │ ├── CameraManager.png │ ├── CoverPageSirocco.png │ ├── CreatingNewMap.png │ ├── CreatingNewObject.png │ ├── EditEnvironment.png │ ├── EnvironmentMapEditor.png │ ├── ExampleProjects.png │ ├── GUIBehaviorTree.png │ ├── GUIBehaviorTreeControlWindow.png │ ├── GUIBehaviorTreeEditor.png │ ├── GUICameraViewer.png │ ├── GUIComplexBTExample.png │ ├── GUIDynamicsViewer.png │ ├── GUIEnvironmentEditor.png │ ├── GUIEnvironmentViewer.png │ ├── GUIExecutionViewer.png │ ├── GUIFirstPersonViewer.png │ ├── GUIGraphicalTeleoperationWindow.png │ ├── GUILayoutAlphanumericInterface.png │ ├── GUILayoutBehaviorTreeControl.png │ ├── GUILayoutGraphicalTeleoperation.png │ ├── GUILayoutPythonMissionControl.png │ ├── GUIMenuBarAerostack.png │ ├── GUIParametersViewer.png │ ├── LogoBSD.png │ ├── MapComplete.png │ ├── MapDimensions.png │ ├── MapObstacles.png │ ├── MessageToOperator.png │ ├── OperatorAssistanceRequest.png │ ├── PhotoMBZIRC2020_1.png │ ├── PhotoMBZIRC2020_2.png │ ├── ProcessMonitor.png │ ├── ProjectBIRSBehaviorTree.png │ ├── ProjectBIRSCamera.png │ ├── ProjectBIRSGazebo.png │ ├── ProjectBLRSExecutionViewer.png │ ├── ProjectBLRSGazebo.png │ ├── ProjectBLRSOccupancyGrid.png │ ├── ProjectBMDSArVizDroneSimulator.png │ ├── ProjectBMDSExecutionViewer.png │ ├── ProjectBMRSExecutionViewer.png │ ├── ProjectBMRSGazebo.png │ ├── ProjectBTDSArVizDroneSimulator.png │ ├── ProjectBTDSBehaviorTree.png │ ├── ProjectBTDSExecutionViewer.png │ ├── ProjectTDSArVizDroneSimulator.png │ ├── ProjectTDSDroneAlphanumericInterface.png │ ├── ProjectTRSAlphanumericInterface.png │ ├── ProjectTRSGazebo.png │ ├── ProjectWRSCameraView.png │ ├── ProjectWRSGazebo1.png │ ├── ProjectWRSGazebo2.png │ ├── ProjectWRSGazebo3.png │ ├── ProjectWRSOccupancyGrid.png │ ├── ROSNetworkConfig.png │ ├── RobotEnvironment.png │ ├── RvizMainView.png │ ├── SensorGPS.png │ ├── ShellUserInterface.png │ ├── StateTransitionDiagram.png │ ├── TerminalsView.png │ ├── wiki_aerostack_gregale.pdf │ ├── wiki_aerostack_levant_2.0.pdf │ └── wiki_aerostack_levant_2.1.pdf │ ├── Graphical-User-Interface.md │ ├── Home.md │ ├── How-to-Program-a-New-Process.md │ ├── Install-Aerostack.md │ ├── License.md │ ├── List-of-distributions.md │ ├── Memory-of-Beliefs.md │ ├── Mission-Plan-Languages.md │ ├── Program-New-Behaviors.md │ ├── Publications.md │ ├── Python-Language.md │ ├── Setup-Communications.md │ ├── Setup-the-Communication-Network.md │ ├── Teleoperation-with-"Drone-simulator".md │ ├── Teleoperation-with-Rotors-simulator.md │ ├── The-Class-RobotProcess.md │ ├── Use-Aerostack-for-a-New-Physical-Platform.md │ ├── Warehouse-inventory-with-Rotors-simulator.md │ ├── What-is-Aerostack.md │ ├── Wi-Fi-Communication-with-Multiple-Drones.md │ ├── _Footer.md │ └── _Sidebar.md ├── installation ├── aerostack_project_selector.py ├── install_dependencies.sh ├── installation_dep_script.sh ├── installers │ ├── installStack.sh │ ├── installWS.sh │ └── linux 18 │ │ ├── README.md │ │ └── linux18_update.sh └── project_customizer.py ├── launchers ├── ardrone_launch │ ├── ardrone_indoors.launch │ ├── ardrone_indoors_hriday.launch │ ├── ardrone_indoors_ip_w_maclock_ROS_10.launch │ ├── ardrone_launch.sh │ ├── ardrone_realflight_instructions.md │ ├── launch_files │ │ ├── EKF.launch │ │ ├── opentld_for_IBVSController.launch │ │ └── opentld_gui_for_IBVSController.launch │ ├── sh_files │ │ ├── run_IBVS_controller.sh │ │ ├── run_ardrone_autonomy.sh │ │ ├── run_driver_parrot.sh │ │ ├── run_ekf_odometry.sh │ │ ├── run_interface_node.sh │ │ ├── run_opentld_node.sh │ │ ├── run_supervisor_node.sh │ │ └── run_trajectory_controller.sh │ └── stop.sh ├── bebop_launchers │ ├── bebop.sh │ ├── bebop_IMAV2017.sh │ ├── bebop_IMAV2017_sim.sh │ ├── bebop_adr.sh │ ├── bebop_face_tracking.sh │ ├── bebop_realflight_instructions.md │ ├── bebop_robot_localization.sh │ ├── bebop_semantic.sh │ ├── defaults.yaml │ ├── launch_files │ │ ├── EKF.launch │ │ ├── EKF_no_slamdunk.launch │ │ ├── EKF_semantic.launch │ │ ├── bebop_node.launch │ │ ├── opentld_for_IBVSController.launch │ │ └── opentld_gui_for_IBVSController.launch │ ├── sh_files │ │ ├── run_IBVS_controller.sh │ │ ├── run_bebop_autonomy.sh │ │ ├── run_driver_bebop.sh │ │ ├── run_ekf_odometry.sh │ │ ├── run_interface_node.sh │ │ ├── run_opentld_node.sh │ │ ├── run_supervisor_node.sh │ │ └── run_trajectory_controller.sh │ └── stop.sh ├── dji_launchers │ ├── matrice_100 │ │ ├── dji_launch.sh │ │ ├── dji_launch_mbzirc.sh │ │ ├── dji_launch_mbzirc_mpc_real.sh │ │ ├── dji_launch_mbzirc_mpc_sim.sh │ │ ├── dji_launch_mbzirc_wo_tmux.sh │ │ ├── dji_ouster_launch.sh │ │ ├── dji_simulation_launch.sh │ │ ├── launch_files │ │ │ ├── EKF.launch │ │ │ ├── EKF_LSM_+_HS.launch │ │ │ ├── EKF_only_HS.launch │ │ │ ├── EKF_ouster.launch │ │ │ ├── EKF_rl.launch │ │ │ ├── EKF_sim.launch │ │ │ ├── demo.launch │ │ │ ├── dji_sdk_client.launch │ │ │ ├── geotiff_mapper.launch │ │ │ ├── guidance_node.launch │ │ │ ├── hector_imu.launch │ │ │ ├── hector_mapping.launch │ │ │ ├── hector_slam.launch │ │ │ ├── hokuyo_node.launch │ │ │ ├── lightware_altitude_node.launch │ │ │ ├── mapping_default.launch │ │ │ ├── sdk.launch │ │ │ ├── sdk_manifold.launch │ │ │ └── usb_cam-test.launch │ │ ├── sdk_manifold.launch │ │ └── stop.sh │ └── matrice_210 │ │ ├── dji_launch_mbzirc_lmpc_REAL_msf_geodesic_outdoors.launch │ │ ├── dji_launch_mbzirc_lmpc_REAL_msf_indoors.launch │ │ ├── dji_launch_mbzirc_lmpc_REAL_msf_outdoors.launch │ │ ├── dji_launch_mbzirc_lmpc_REAL_msf_outdoors_FSM.launch │ │ ├── dji_launch_mbzirc_lmpc_REAL_msf_outdoors_balloon.launch │ │ ├── dji_launch_mbzirc_lmpc_REAL_msf_outdoors_balloon_geodesic.launch │ │ ├── dji_launch_mbzirc_lmpc_sim_msf.sh │ │ ├── dji_launch_mbzirc_lmpc_sim_msf_state_machine.sh │ │ ├── launch_files │ │ ├── EKF_RTK.launch │ │ ├── EKF_optitrack.launch │ │ ├── EKF_ouster.launch │ │ ├── sdk.launch │ │ ├── sdk_mbzirc.launch │ │ └── usb_cam.launch │ │ ├── old_launchers │ │ ├── dji_launch.sh │ │ ├── dji_launch_mbzirc.sh │ │ ├── dji_launch_mbzirc_lmpc_REAL.sh │ │ ├── dji_launch_mbzirc_lmpc_REAL_RTK.sh │ │ ├── dji_launch_mbzirc_lmpc_sim.sh │ │ ├── dji_launch_mbzirc_mpc.sh │ │ ├── dji_launch_mbzirc_nlmpc_REAL.sh │ │ ├── dji_launch_mbzirc_nlmpc_REAL_optitrack.sh │ │ └── dji_launch_mbzirc_nlmpc_sim.sh │ │ └── stop.sh ├── hector_slam_launchers │ ├── geotiff_mapper.launch │ ├── hector_imu.launch │ ├── hector_mapping_NOT_USED.launch │ ├── hector_slam.launch │ └── mapping_default.launch ├── mikrokopter_launchers │ ├── launch_files │ │ ├── EKFSimulatorRvizROSModule.launch │ │ ├── SimulatorRvizROSModule.launch │ │ ├── driver_px4flow_interface_ROSModule.launch │ │ ├── driver_px4flow_interface_ROSModule_lidar.launch │ │ ├── droneLoggerROSModule.launch │ │ ├── joy.launch │ │ ├── joyConverterToDrvOktoCmdNode.launch │ │ ├── laser_altimeter.launch │ │ └── mikrocopter_driver_ros_module.launch │ ├── mikrokopter_current_key_bindings.md │ ├── mikrokopter_realflight_instructions.md │ └── sh_files │ │ ├── okto_EKF_simulator.sh │ │ ├── run_droneLogger_node.sh │ │ ├── run_ekf_odometry.sh │ │ ├── run_interface_node.sh │ │ ├── run_joy_converter_okto_command_node_js0.sh │ │ ├── run_joy_converter_okto_command_node_js0_odroid.sh │ │ ├── run_laser_altimeter.sh │ │ ├── run_midlevelautopilot_node.sh │ │ ├── run_mikrokopter_driver.sh │ │ ├── run_mikrokopter_driver_ros_module.sh │ │ ├── run_mikrokopter_sub.sh │ │ ├── run_px4flow_interface.sh │ │ ├── run_px4flow_interface_lidar.sh │ │ ├── run_px4flow_node.sh │ │ └── run_trajectory_controller.sh ├── move_base_launcher │ └── move_base.launch ├── msf_localization │ ├── msf_localization_interface.launch │ ├── msf_localization_ros.launch │ ├── parrot_msf_localization_test.sh │ ├── parrot_msf_localization_test0.sh │ ├── parrot_msf_localization_test1.sh │ ├── parrot_msf_localization_test_flight.sh │ └── stop.sh ├── okto_launchers │ ├── launch_files │ │ ├── driverOktoROSModule.launch │ │ ├── driver_px4flow_interface_ROSModule.launch │ │ ├── px4flow.launch │ │ └── rviz_visualizations_jp.launch │ ├── okto_date_update.sh │ ├── okto_realflight_instructions.md │ ├── okto_simulation_instructions.md │ ├── sh_files │ │ ├── run_driverOktoROSModule.sh │ │ ├── run_ekf_odometry.sh │ │ ├── run_interface_node.sh │ │ ├── run_joy_converter_driver_okto_command_node_js0.sh │ │ ├── run_joy_converter_driver_okto_command_node_js1.sh │ │ ├── run_joy_converter_midlevelautopilot_test_js0.sh │ │ ├── run_joy_converter_midlevelautopilot_test_js1.sh │ │ ├── run_joy_converter_okto_command_node_js0.sh │ │ ├── run_joy_converter_okto_command_node_js1.sh │ │ ├── run_midlevelautopilot_node.sh │ │ ├── run_okto_driver.sh │ │ ├── run_okto_simulator.sh │ │ ├── run_px4flow_interface.sh │ │ ├── run_px4flow_node.sh │ │ ├── run_rviz_interface_for_okto_simulator.sh │ │ └── run_trajectory_controller.sh │ └── time_update.sh ├── pelican_launchers │ ├── launch_files │ │ ├── asctec_driver_node.launch │ │ ├── driverPelicanROSModule.launch │ │ ├── driver_px4flow_interface_ROSModule.launch │ │ ├── driver_px4flow_interface_ROSModule_lidar.launch │ │ ├── droneInterface_jp_ROSModule.launch │ │ ├── laser_altimeter.launch │ │ ├── opentld_for_IBVSController.launch │ │ ├── opentld_gui_for_IBVSController.launch │ │ ├── px4flow.launch │ │ └── ueye_cvg_cam.launch │ ├── pelican_real_flight_instructions.md │ ├── pelican_real_flight_instructions_3cams.md │ └── sh_files │ │ ├── run_IBVS_controller.sh │ │ ├── run_arucoeye_front.sh │ │ ├── run_arucoeye_left.sh │ │ ├── run_arucoeye_right.sh │ │ ├── run_communication_manager.sh │ │ ├── run_cvg_ueye_02_front.sh │ │ ├── run_cvg_ueye_02_left.sh │ │ ├── run_cvg_ueye_04_front_IBVS.sh │ │ ├── run_cvg_ueye_04_right.sh │ │ ├── run_driverPelicanROSModule.sh │ │ ├── run_ekf_odometry.sh │ │ ├── run_interface_node.sh │ │ ├── run_laser_altimeter.sh │ │ ├── run_localizer.sh │ │ ├── run_logger.sh │ │ ├── run_manager.sh │ │ ├── run_midlevelautopilot_node.sh │ │ ├── run_mission_scheduler.sh │ │ ├── run_obstacle_distance_calculator.sh │ │ ├── run_obstacle_processor.sh │ │ ├── run_opentld_node.sh │ │ ├── run_pelican_node.sh │ │ ├── run_px4flow_interface_lidar.sh │ │ ├── run_px4flow_node.sh │ │ ├── run_supervisor_node.sh │ │ ├── run_trajectory_controller.sh │ │ ├── run_trajectory_planner.sh │ │ ├── run_yaw_commander.sh │ │ └── start_roscore.sh ├── pixhawk_launchers │ ├── launch_files │ │ ├── Ekf.launch │ │ ├── Ekf_new.launch │ │ ├── apm.launch │ │ ├── bottom_cam.launch │ │ ├── driver_px4flow_interface_ROSModule.launch │ │ ├── driver_px4flow_interface_ROSModule_wo_altitude.launch │ │ ├── geotiff_mapper.launch │ │ ├── hector_imu.launch │ │ ├── hector_slam.launch │ │ ├── hector_slam_new.launch │ │ ├── hokuyo_node.launch │ │ ├── lightware_altitude_node.launch │ │ ├── mapping_default.launch │ │ ├── mapping_new.launch │ │ ├── move_base.launch │ │ ├── px4.launch │ │ ├── px4_HILT.launch │ │ ├── px4_SITL.launch │ │ ├── px4_config.yaml │ │ ├── px4_pluginlists.yaml │ │ ├── px4flow.launch │ │ ├── realsense_r200_manual.launch │ │ ├── ros_tld_gui.launch │ │ ├── ros_tld_tracker.launch │ │ ├── rosserial.launch │ │ ├── teleop.launch │ │ ├── ueye_cvg_front.launch │ │ ├── ueye_front.launch │ │ └── usb_cam.launch │ ├── pixhawk_GMP_altitude_filter.sh │ ├── pixhawk_ground_station.sh │ ├── pixhawk_navigation_stack.sh │ ├── pixhawk_navigation_stack_GMP.sh │ ├── pixhawk_navigation_stack_GMP_VS.sh │ ├── pixhawk_navigation_stack_altitude_filtering.sh │ ├── pixhawk_navigation_stack_laser_scan_pose.sh │ ├── pixhawk_real_flight.sh │ ├── pixhawk_realflight_instructions.md │ ├── pixhawk_simflight_instructions.md │ ├── pixhawk_visual_servoing.sh │ ├── sh_files │ │ ├── run_driver_pixhawk.sh │ │ ├── run_ekf_odometry.sh │ │ ├── run_interface_node.sh │ │ ├── run_joy_node.sh │ │ ├── run_mavros_node.sh │ │ ├── run_mavros_node_simulator.sh │ │ ├── run_midlevelautopilot_node.sh │ │ ├── run_px4flow_interface.sh │ │ ├── run_px4flow_node.sh │ │ ├── run_supervisor_node.sh │ │ └── run_trajectory_controller.sh │ └── stop.sh └── pixhawk_simulation_launchers │ ├── launch_files │ ├── Ekf.launch │ ├── geotiff_mapper.launch │ ├── hector_imu.launch │ ├── hector_slam.launch │ ├── mapping_default.launch │ ├── move_base.launch │ ├── px4.launch │ ├── px4_HILT.launch │ ├── px4_SITL.launch │ ├── px4flow.launch │ └── tutorial.launch │ ├── pixhawk_IMAV_RL_IBVS.sh │ ├── pixhawk_IMAV_RL_IBVS_test.sh │ ├── pixhawk_laser_estimation.sh │ ├── pixhawk_mission_simulation.sh │ ├── pixhawk_mission_simulation_mavros.sh │ ├── pixhawk_navigation_stack.sh │ ├── pixhawk_navigation_stack_IMAV.sh │ ├── pixhawk_navigation_stack_IMAV_VS.sh │ ├── pixhawk_navigation_stack_altitude_filtering.sh │ ├── pixhawk_navigation_stack_boiler.sh │ ├── pixhawk_robotlocalization.sh │ ├── pixhawk_simflight_instructions.md │ ├── pixhawk_simulation.sh │ ├── pre_takeoff.sh │ ├── sh_files │ ├── run_driver_pixhawk.sh │ ├── run_ekf_odometry.sh │ ├── run_interface_node.sh │ ├── run_mavros_node_simulator.sh │ ├── run_midlevelautopilot_node.sh │ ├── run_supervisor_node.sh │ └── run_trajectory_controller.sh │ └── stop.sh └── stack_deprecated └── utils └── CATKIN_IGNORE /README.md: -------------------------------------------------------------------------------- 1 | ## Aerostack 2 | 3 | Please visit the [Aerostack Wiki](https://github.com/cvar-upm/aerostack/wiki) for a complete project documentation. 4 | 5 | -------------------------------------------------------------------------------- /config/drone1/ardrone_bottom.yaml: -------------------------------------------------------------------------------- 1 | %YAML:1.0 2 | image_width: 640 3 | image_height: 360 4 | camera_name: ardrone_bottom 5 | camera_matrix: !!opencv-matrix 6 | rows: 3 7 | cols: 3 8 | dt: d 9 | data: [667.35847908272, 0, 330.449976314247, 0, 668.587872507243, 179.014729860623, 0, 0, 1] 10 | distortion_model: plumb_bob 11 | distortion_coefficients: !!opencv-matrix 12 | rows: 1 13 | cols: 5 14 | dt: d 15 | data: [-0.00951101387422823, 0.0172421866821302, 0.00677571945374994, 0.00135614726225701, 0] 16 | rectification_matrix: !!opencv-matrix 17 | rows: 3 18 | cols: 3 19 | data: [1, 0, 0, 0, 1, 0, 0, 0, 1] 20 | projection_matrix: !!opencv-matrix 21 | rows: 3 22 | cols: 4 23 | data: [667.782287597656, 0, 330.612895204358, 0, 0, 668.265930175781, 180.031499195671, 0, 0, 0, 1, 0] 24 | -------------------------------------------------------------------------------- /config/drone1/ardrone_front.yaml: -------------------------------------------------------------------------------- 1 | %YAML:1.0 2 | image_width: 640 3 | image_height: 360 4 | camera_name: ardrone_front 5 | camera_matrix: !!opencv-matrix 6 | rows: 3 7 | cols: 3 8 | dt: d 9 | data: [564.445569348335, 0, 324.238794500839, 0, 562.403768220257, 194.367064448638, 0, 0, 1] 10 | distortion_model: plumb_bob 11 | distortion_coefficients: !!opencv-matrix 12 | rows: 1 13 | cols: 5 14 | dt: d 15 | data: [-0.514375572455534, 0.27666934140516, 0.00472389076018357, 0.000222577065168822, 0] 16 | rectification_matrix: !!opencv-matrix 17 | rows: 3 18 | cols: 3 19 | data: [1, 0, 0, 0, 1, 0, 0, 0, 1] 20 | projection_matrix: !!opencv-matrix 21 | rows: 3 22 | cols: 4 23 | data: [459.826202392578, 0, 325.709532364381, 0, 0, 528.362854003906, 196.604602978983, 0, 0, 0, 1, 0] 24 | -------------------------------------------------------------------------------- /config/drone1/configFile.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 1.0 1.0 5 | 6 | 7 | 8 | 9 | 10 | 9.0 14.0 11 | 0.0 -1.0 12 | 13 | 14 | 15 | 16 | 17 | 1 18 | 0 19 | 20 | 21 | 5000 22 | 5 23 | 24 | 25 | 1500 26 | 2 3 27 | 5 5 28 | 29 | 30 | 31 | 32 | 33 | 34 | -------------------------------------------------------------------------------- /config/drone1/costmap_common_params.yaml: -------------------------------------------------------------------------------- 1 | obstacle_range: 2.5 2 | raytrace_range: 3.0 3 | footprint: [[-0.35, 0.35], [0.35, 0.35], [0.35, -0.35], [-0.35, -0.35]] 4 | robot_radius: 0.4 5 | inflation_radius: 0.5 6 | 7 | #observation_sources: laser_scan_sensor point_cloud_sensor 8 | observation_sources: laser_scan_sensor 9 | 10 | # Simulation 11 | laser_scan_sensor: {sensor_frame: "hokuyo::sensors_link", data_type: LaserScan, topic: scan, marking: true, clearing: true} 12 | 13 | #point_cloud_sensor: {sensor_frame: frame_name, data_type: PointCloud, topic: topic_name, marking: true, clearing: true} 14 | -------------------------------------------------------------------------------- /config/drone1/droneConfiguration.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 0 4 | 5 | 0.2 6 | 0.0 7 | 0.035 8 | -90 9 | 0.0 10 | -84.5 11 | 12 | 13 | 14 | 15 | 1 16 | 17 | -0.05 18 | 0.0 19 | -0.05 20 | -90 21 | 0.0 22 | -84.5 23 | 24 | 25 | 26 | 27 | -------------------------------------------------------------------------------- /config/drone1/global_costmap_params.yaml: -------------------------------------------------------------------------------- 1 | global_costmap: 2 | global_frame: /map 3 | robot_base_frame: base_link 4 | update_frequency: 1.0 5 | static_map: true 6 | width: 5.0 7 | height: 5.0 8 | resolution: 0.05 9 | origin_x: -7.0 10 | origin_y: -7.0 11 | -------------------------------------------------------------------------------- /config/drone1/local_costmap_params.yaml: -------------------------------------------------------------------------------- 1 | local_costmap: 2 | global_frame: /map 3 | robot_base_frame: base_link 4 | update_frequency: 50.0 5 | publish_frequency: 30.0 6 | static_map: true 7 | rolling_window: true 8 | width: 5.0 9 | height: 5.0 10 | resolution: 0.05 11 | origin_x: -7.0 12 | origin_y: -7.0 13 | -------------------------------------------------------------------------------- /config/drone1/path_tracker.yaml: -------------------------------------------------------------------------------- 1 | vxy_max: 0.30 2 | vz_max: 0.15 3 | precision: 0.25 4 | path_facing: false 5 | -------------------------------------------------------------------------------- /config/mission/setup.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | NETWORK_ROSCORE=$1 4 | 5 | shell=${SHELL:-"/bin/bash"} 6 | shell=`basename $shell` 7 | 8 | #echo "Running setup.sh .." 9 | echo "-Setting ROS workspace" 10 | #http://stackoverflow.com/questions/16011245/source-files-in-a-bash-script 11 | . ${AEROSTACK_WORKSPACE}/devel/setup.$shell 12 | 13 | 14 | # http://stackoverflow.com/questions/6482377/bash-shell-script-check-input-argument 15 | if [ -z $NETWORK_ROSCORE ] # Check if NETWORK_ROSCORE is NULL 16 | then 17 | echo "-Setting roscore in localhost" 18 | host_name=`cat /etc/hostname` 19 | export ROS_MASTER_URI=http://$host_name:11311 20 | export ROS_IP=$host_name 21 | export ROS_HOSTNAME=$host_name 22 | else 23 | echo "-Setting roscore in $NETWORK_ROSCORE" 24 | export ROS_MASTER_URI=http://$NETWORK_ROSCORE:11311 25 | OWN_IP=$(ifconfig | grep -Eo "[0-9]{3}\.[0-9]{2,3}\.[0-9]{1,3}\.[0-9]{1,3}" | head -n1) 26 | echo "-My IP in network (please check!)="$OWN_IP 27 | export ROS_IP=$OWN_IP 28 | export ROS_HOSTNAME=$OWN_IP 29 | fi 30 | -------------------------------------------------------------------------------- /doc/wiki/CoverPageAuster.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/CoverPageAuster.png -------------------------------------------------------------------------------- /doc/wiki/PhotoMBZIRC2020_1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/PhotoMBZIRC2020_1.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale.pdf -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/.DS_Store: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/.DS_Store -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/AR-Drone-and-Visual-Markers.md: -------------------------------------------------------------------------------- 1 | Here you can find an example that describes how to perform a complete mission with a real flight. This example assumes that the self-localization uses Aruco visual markers. 2 | 3 | This example uses the following configuration files: 4 | 5 | ./config/drone02/* 6 | 7 | Execute the following launcher: 8 | 9 | ./launchers/ardrone_basic.sh 10 | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/Aerostack-Virtual-Machine.md: -------------------------------------------------------------------------------- 1 | In the following link you can download a Virtual Machine (Virtual Box VM) with Aerostack installed: https://drive.google.com/open?id=0BziAte9fn_WzQk41cTJaYk85dlE 2 | 3 | Features: 4 | - Architecture: x64 5 | - OS: Ubuntu 14.04 6 | - ROS: Jade 7 | - Aerostack 8 | 9 | Host: 10 | - Architecture: x64 11 | - OS: Linux Ubuntu 14.04 12 | 13 | User and password: 14 | - User: aerostack 15 | - Pass: paerostack -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/Home.md: -------------------------------------------------------------------------------- 1 | ## **IMPORTANT ANNOUNCEMENT:** 2 | ### We plan to release in a few weeks the new version Aerostack 2.0, Levant Distribution 3 | ### For more information, please consult [[List of distributions]] 4 | 5 | ---- 6 | 7 |

[[images/CoverPage.png]]

-------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/Launch-Real-Flight.md: -------------------------------------------------------------------------------- 1 | To launch a real flight using an AR Drone perform the following steps: 2 | 3 | - First, connect the AR Drone to the computer using wifi. 4 | 5 | - Launch the roscore 6 | 7 | ``` 8 | $ roscore 9 | ``` 10 | - Go to the folder that contains launchers. It includes different pre-configured .sh files that launch the set of processes for different mission types: 11 | 12 | ``` 13 | $ cd ${AEROSTACK_STACK}/launchers 14 | ``` 15 | - In this example we select the file *ardrone_basic.sh*. Write the following to launch the mission: 16 | 17 | ``` 18 | $ ./ardrone_basic.sh 19 | ``` 20 | 21 | Then you can use the human machine interface to start the mission (see [[Human Machine Interface]]). The AR Drone will execute the mission defined in the config files. 22 | 23 | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/Launch-Simulated-Flight.md: -------------------------------------------------------------------------------- 1 | Before real flights, a mission can be simulated with the Rviz simulator. 2 | 3 | First, start a roscore in the host system: 4 | 5 | $ roscore 6 | 7 | Next, to launch the simulation go to the launchers/Noche_de_los_investigadores folder and run: 8 | 9 | $ ./quadrotor_laNocheInvestigadores_simulator.sh {droneId} localhost 10 | 11 | The {droneId} argument is the Id for the drone config files that were created and the localhost parameter is used to specify you are running the roscore on your host computer. This will open up several terminals with the modules running. To visualize the mission in Rviz, in another terminal run the following command: 12 | 13 | $ ./rvizInterface_Test.sh {droneId} localhost 14 | 15 | This will bring up the Rviz simulator but will not start the simulation. Finally, launch the mission by typing the following command in a sourced terminal. 16 | 17 | $ rosservice call /drone{Id}/droneMissionScheduleProcessor/start 18 | 19 | Sample screenshot of drone simulator in RVIZ with example mission: 20 | 21 | [[images/MapComplete.png]] 22 | 23 | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/List-of-Parameters-for-TML.md: -------------------------------------------------------------------------------- 1 | 2 | | Parameter | Values | Description | Comments | 3 | | :-----------|:---------------|:------------|:------------| 4 | | BATTERY_CHARGE_PERCENTAGE | Number | Percentage of battery charge (100% means full battery) | 5 | | ACTION_FAILURE | {timeout, general} | The action has failed because of a time out (value: timeout) or another unclassified failure (value: general) | Not implemented yet | 6 | | RECOGNIZED_ARUCO_MARKERS | Set of numbers | Recognized Aruco visual markers | 7 | | CURRENT_TASK | String | Absolute name of a task within the task tree of the mission | 8 | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/List-of-Skills-for-TML.md: -------------------------------------------------------------------------------- 1 | | Skill | Description | Comments | 2 | | :-------|:-------------|:-------------| 3 | | AVOID_OBSTACLES | The vehicle is able to avoid obstacles|| 4 | | RECOGNIZE_ARUCO_MARKERS| The vehicle is able to recognize the ID number of an Aruco marker|| 5 | | DETECT_OBSTACLES_BY_ARUCO_MARKERS | The vehicle is able to detect obstacles identified by Aruco markers| Not implemented yet| 6 | | SELF_LOCALIZE_BY_ARUCO_MARKERS | The vehicle is able to self localize by Aruco markers| Not implemented yet| 7 | | SAY_OUT_LOUD_CURRENT_TASK | The vehicle says out loud the current task|Not implemented yet| 8 | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/List-of-distributions.md: -------------------------------------------------------------------------------- 1 | | Distribution | Release date | Main features | Tested platforms | Requirements | 2 | | :-----------| :---------| :--------|:-----|:------| 3 | | Version 1.0 Gregale Distribution| June, 2016 |Aerial robot library of software components (perception, control, planning, etc.), TML language for mission plan specification, human machine interface (HMI) for user-robot interaction. | Parrot AR Drone 1.0 and 2.0, Asctec Pelican, Mikrokopter Oktokopter, Pixhawk. | Ubuntu 14.04, ROS Jade| 4 | | Version 2.0 Levant Distribution| Planned to be released in September or October 2017| Behavior-based execution system, graphical user interface (GUI) for environment maps and mission plans, Python API for mission plans. | Parrot AR Drone 2.0, Pixhawk, Parrot Bebop 2 (with SLAM-dunk).| Ubuntu 16.04, ROS Kinetic| 5 | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/Simulated-Quadrotor.md: -------------------------------------------------------------------------------- 1 | Here you can find an example that describes how to perform a simulated mission. This example assumes that the vehicle is simulated. 2 | 3 | This example uses the following configuration files: 4 | 5 | ./config/drone01/* 6 | 7 | Execute the following launcher: 8 | 9 | ./launchers/simulated_quadrotor.sh 10 | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/Specify-Mission-Tasks.md: -------------------------------------------------------------------------------- 1 | Follow these steps to specify the tasks of a mission: 2 | 3 | ### 1. Edit the Mission Specification File 4 | 5 | The task-based mission of the robot is specified in a XML file called `mission_specification_file.xml` (this is the default name, as it is established in the .launch file located within the `launch` directory in the repository `task_based_mission_planner_process`). This file must be located in `$AEROSTACK_STACK/configs/` within a folder selected by the operator called `drone{Id}` (`{Id}` = 00, 01, 02, ...). 6 | 7 | Write your own mission specification file according to [[TML language]]. 8 | 9 | ### 2. Check Syntax Errors 10 | 11 | To check if the file has syntax errors, launch the mission planner executing the following command: 12 | 13 | $ roslaunch task_based_mission_planner_process task_based_mission_planner_process.launch 14 | 15 | If the xml file does not have any errors, the following message is presented: 16 | 17 | File loaded without errors! Waiting to start ... 18 | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/_Footer.md: -------------------------------------------------------------------------------- 1 | **Contact** 2 | 3 | We thank and welcome any suggestion or comment about Aerostack. For any question or bug report you can read and/or write at the [issues page](https://github.com/Vision4UAV/Aerostack/issues). 4 | 5 | You can also contact the team support at the following address: aerostack.vision4uav@gmail.com -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/.DS_Store: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/.DS_Store -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/ARDrone.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/ARDrone.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/Architecture.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/Architecture.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/BlocksDiagram.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/BlocksDiagram.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/CameraManager.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/CameraManager.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/CoverPage.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/CoverPage.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/ExecutiveSystem.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/ExecutiveSystem.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIAbout.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIAbout.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMICameraViewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMICameraViewer.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIControlPanelAbortMission.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIControlPanelAbortMission.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIControlPanelKeyboard.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIControlPanelKeyboard.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIControlPanelStartMission.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIControlPanelStartMission.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIGeneral.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIGeneral.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIKeyboardGuide.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIKeyboardGuide.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIMissionReporter.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIMissionReporter.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIParameterView.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIParameterView.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIProcessMonitor.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIProcessMonitor.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIRequestedSkills.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIRequestedSkills.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIVehicleDynamics.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/HMIVehicleDynamics.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/Logo Aerostack.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/Logo Aerostack.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/LogoAerostack (bitbucket).png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/LogoAerostack (bitbucket).png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/LogoGPLv3.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/LogoGPLv3.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/MapComplete.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/MapComplete.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/MapDimensions.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/MapDimensions.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/MapObstacles.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/MapObstacles.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/PlanningSystem.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/PlanningSystem.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/ProcessMonitor.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/ProcessMonitor.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/Processes.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/Processes.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/ROSNetworkConfig.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/ROSNetworkConfig.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/RobotEnvironment.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/RobotEnvironment.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/SensorGPS.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/SensorGPS.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/SituationAwarenessSystem.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/SituationAwarenessSystem.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/StateTransitionDiagram.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/StateTransitionDiagram.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/SupervisionSystem.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_gregale/wiki_aerostack_gregale/images/SupervisionSystem.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/.DS_Store: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/.DS_Store -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/AR-Drone-and-Visual-Markers.md: -------------------------------------------------------------------------------- 1 | Here you can find an example that describes how to perform a complete mission with a real flight. This example assumes that the self-localization uses Aruco visual markers. 2 | 3 | This example uses the following configuration files: 4 | 5 | ./config/drone02/* 6 | 7 | Execute the following launcher: 8 | 9 | ./launchers/ardrone_basic.sh 10 | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Aerostack-Virtual-Machine.md: -------------------------------------------------------------------------------- 1 | In the following link you can download a Virtual Machine (Virtual Box VM) with Aerostack 1.0 (Gregale) installed: https://drive.google.com/open?id=0BziAte9fn_WzQk41cTJaYk85dlE 2 | 3 | Features: 4 | - Architecture: x64 5 | - OS: Ubuntu 14.04 6 | - ROS: Jade 7 | - Aerostack 8 | 9 | Host: 10 | - Architecture: x64 11 | - OS: Linux Ubuntu 14.04 12 | 13 | User and password: 14 | - User: aerostack 15 | - Pass: paerostack -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Configure-Map.md: -------------------------------------------------------------------------------- 1 | The operator can configure the environment map using the graphical user interface (GUI). Please, consult the following link to know how to use the GUI to configure the environment map: 2 | 3 | - [[How to create an environment map]] 4 | 5 | Alternatively, the operator can also configure the environment map using a set of XML files. Please, consult the following link to know how to write these files: 6 | 7 | - [[Configure the Environment Map Using XML Files]] -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/.DS_Store: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/.DS_Store -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/ARDrone.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/ARDrone.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/ATENCION FALTA ESTA FIGURA HMIAbout.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/ATENCION FALTA ESTA FIGURA HMIAbout.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/Architecture.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/Architecture.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/BlocksDiagram.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/BlocksDiagram.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/CameraManager.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/CameraManager.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/CoverPage.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/CoverPage.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIBTGuideStep1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIBTGuideStep1.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIBTGuideStep2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIBTGuideStep2.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIBTGuideStep3.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIBTGuideStep3.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIBTGuideStep4_1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIBTGuideStep4_1.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIBTGuideStep4_2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIBTGuideStep4_2.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIBTGuideStep5.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIBTGuideStep5.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIBehaviorViewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIBehaviorViewer.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIBeliefViewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIBeliefViewer.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUICameraViewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUICameraViewer.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIComplexBTExample.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIComplexBTExample.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIControlPanelBTExecuting.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIControlPanelBTExecuting.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIControlPanelBTStart.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIControlPanelBTStart.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIControlPanelKeyboardFirst.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIControlPanelKeyboardFirst.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIControlPanelKeyboardSecond.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIControlPanelKeyboardSecond.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIControlPanelTMLAbort.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIControlPanelTMLAbort.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIControlPanelTMLStart.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIControlPanelTMLStart.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIEnvironmentViewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIEnvironmentViewer.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIKeyboardTeleoperationGuide.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIKeyboardTeleoperationGuide.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIMapEditionMode1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIMapEditionMode1.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIMapEditionMode2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIMapEditionMode2.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIMapEditionMode3.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIMapEditionMode3.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIMapEditionModeFinal.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIMapEditionModeFinal.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIMapEditionModeFinal2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIMapEditionModeFinal2.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIMapEditionTools.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIMapEditionTools.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIParameterView.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIParameterView.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIWindowsLayout.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/GUIWindowsLayout.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/HMIBehaviorTree.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/HMIBehaviorTree.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/HMIControlPanelAbortMission.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/HMIControlPanelAbortMission.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/HMIControlPanelStartMission.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/HMIControlPanelStartMission.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/HMINewMap.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/HMINewMap.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/LogoGPLv3.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/LogoGPLv3.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/MapComplete.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/MapComplete.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/MapDimensions.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/MapDimensions.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/MapObstacles.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/MapObstacles.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/ProcessMonitor.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/ProcessMonitor.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/Processes.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/Processes.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/ROSNetworkConfig.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/ROSNetworkConfig.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/RobotEnvironment.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/RobotEnvironment.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/SensorGPS.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/SensorGPS.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/StateTransitionDiagram.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/StateTransitionDiagram.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/VideoMapConfiguration.mp4: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/VideoMapConfiguration.mp4 -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/wiki_aerostack_gregale.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Files/wiki_aerostack_gregale.pdf -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Home.md: -------------------------------------------------------------------------------- 1 | 2 | 3 |

[[Files/CoverPage.png]]

4 | 5 |

Example of search and rescue mission using Aerostack:

6 | 7 |

8 | IMAGE ALT TEXT HERE 11 |

12 | 13 |

Example of object delivery mission using Aerostack:

14 | 15 |

16 | IMAGE ALT TEXT HERE 19 |

20 | 21 | 22 | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Launch-Real-Flight.md: -------------------------------------------------------------------------------- 1 | To launch a real flight using an AR Drone perform the following steps: 2 | 3 | - First, connect the AR Drone to the computer using wifi. 4 | 5 | - Launch the roscore 6 | 7 | ``` 8 | $ roscore 9 | ``` 10 | - Go to the folder that contains launchers. It includes different pre-configured .sh files that launch the set of processes for different mission types: 11 | 12 | ``` 13 | $ cd ${AEROSTACK_STACK}/launchers 14 | ``` 15 | - In this example we select the file *ardrone_basic.sh*. Write the following to launch the mission: 16 | 17 | ``` 18 | $ ./ardrone_basic.sh 19 | ``` 20 | 21 | Then you can use the human machine interface to start the mission (see [[Graphical User Interface]]). The AR Drone will execute the mission defined in the config files. 22 | 23 | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/List-of-distributions.md: -------------------------------------------------------------------------------- 1 | | Distribution | Release date | Main features | Tested platforms | Requirements | 2 | | :-----------| :---------| :--------|:-----|:------| 3 | | Version 1.0 Gregale Distribution| June 2016 [PDF wiki](https://raw.githubusercontent.com/wiki/Vision4UAV/Aerostack/Files/wiki_aerostack_gregale.pdf)|Aerial robot library of software components (perception, control, planning, etc.), TML language for mission plan specification, human machine interface (HMI) for user-robot interaction. | Parrot AR Drone 1.0 and 2.0, Asctec Pelican, Mikrokopter Oktokopter, Pixhawk. | Ubuntu 14.04, ROS Jade| 4 | | Version 2.0 Levant Distribution| October 2017| Behavior-based execution system, graphical user interface (GUI) for environment maps and mission plans, Python API for mission plans, Memory of beliefs | Parrot AR Drone 2.0, Pixhawk, Parrot Bebop 2 (with SLAM-dunk).| Ubuntu 16.04, ROS Kinetic| 5 | 6 | 7 | You can download a Virtual Machine (Virtual Box VM) with Aerostack 1.0 (Gregale) in the following link: 8 | - [[Aerostack Virtual Machine]] 9 | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/Simulated-Quadrotor.md: -------------------------------------------------------------------------------- 1 | Here you can find an example that describes how to perform a simulated mission. This example assumes that the vehicle is simulated. 2 | 3 | This example uses the following configuration files: 4 | 5 | ./config/drone01/* 6 | 7 | Execute the following launcher: 8 | 9 | ./launchers/simulated_quadrotor.sh 10 | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant/_Footer.md: -------------------------------------------------------------------------------- 1 | **Contact** 2 | 3 | We thank and welcome any suggestion or comment about Aerostack. For any question or bug report you can read and/or write at the [issues page](https://github.com/Vision4UAV/Aerostack/issues). 4 | 5 | You can also contact the team support at the following address: aerostack.vision4uav@gmail.com -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant_2.0.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.0/wiki_aerostack_levant_2.0.pdf -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1.pdf -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/.DS_Store: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/.DS_Store -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/4th-place-at-IMAV-2016.md: -------------------------------------------------------------------------------- 1 | This page shows some videos corresponding to the International Competition at IMAV 2016, where our group achieved the 4th place. 2 | 3 | Entering the house: 4 | 5 | [![](https://img.youtube.com/vi/9_06GtO4-70/0.jpg)](https://www.youtube.com/watch?v=9_06GtO4-70) 6 | 7 | Autonomous landing: 8 | 9 | [![](https://img.youtube.com/vi/qon8UK0fvwk/0.jpg)](https://www.youtube.com/watch?v=qon8UK0fvwk) 10 | 11 | In the house: 12 | 13 | [![](https://img.youtube.com/vi/XhwO3w2bxFA/0.jpg)](https://www.youtube.com/watch?v=XhwO3w2bxFA) 14 | 15 | Experimental flights: 16 | 17 | [![](https://img.youtube.com/vi/y9Bj3deT-Kw/0.jpg)](https://www.youtube.com/watch?v=y9Bj3deT-Kw) -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Add-new-hardware.md: -------------------------------------------------------------------------------- 1 | Here you can find how to do the following tasks: 2 | 3 | * [[Calibrate Controllers]] 4 | * [[Add a New Camera]] 5 | * [[Add a GPS Sensor]] 6 | * [[Use Aerostack for a New Physical Platform]] -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Aerostack-Virtual-Machine.md: -------------------------------------------------------------------------------- 1 | In the following link you can download a Virtual Machine (Virtual Box VM) with Aerostack 1.0 (Gregale) installed: https://drive.google.com/open?id=0BziAte9fn_WzQk41cTJaYk85dlE 2 | 3 | Features: 4 | - Architecture: x64 5 | - OS: Ubuntu 14.04 6 | - ROS: Jade 7 | - Aerostack 8 | 9 | Host: 10 | - Architecture: x64 11 | - OS: Linux Ubuntu 14.04 12 | 13 | User and password: 14 | - User: aerostack 15 | - Pass: paerostack -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Belief-management-processes.md: -------------------------------------------------------------------------------- 1 | ## Capability: Belief management 2 | 3 | | Process | System | Launcher | 4 | | :-------| :------- | :-------- | 5 | | Belief Manager | Situation awareness |belief_manager_process.launch | 6 | | Belief Updater| Situation awareness |belief_updater_process.launch | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Catalog-of-Processes.md: -------------------------------------------------------------------------------- 1 | This page shows the catalog of available processes in Aerostack. Processes are organized according to the general architecture: 2 | 3 | [[Files/Architecture.png]] 4 | 5 | For each process, the catalog shows the launcher to be used and the system to which it belongs. 6 | 7 | | PROCESSES | 8 | | :-----------| 9 | | [[Physical layer processes]] | 10 | | [[Feature extraction processes]] | 11 | | [[Self localization and mapping processes]] | 12 | | [[Motion control processes]] | 13 | | [[Belief management processes]] | 14 | | [[Execution processes]] | 15 | | [[Motion planning processes]] | 16 | | [[Communication processes]] | 17 | 18 | To ensure the correct supervised execution of the processes it is also necessary to run the next launcher: 19 | 20 | | Process | System | Launcher | 21 | | :-------| :------- | :-------- | 22 | | Process monitor | Supervision system | process_monitor_process.launch | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Communication-processes.md: -------------------------------------------------------------------------------- 1 | | Process | System | Launcher | Comment | 2 | | :-------| :----- | :--------- |:------- | 3 | | Shell User Interface | Ground control system | droneInterface_jp_ROSModule.launch |Shell user interface| 4 | | Graphical User Interface |Ground control system | graphical_user_interface gui.launch |Graphical User Interface| 5 | | HUD |Ground control system | first_view.launch |Graphical User Interface| 6 | | Speech module |Ground control station | droneSpeechROSModule.launch |Speech-based communication| 7 | | Sound module| Ground control station | droneSoundROSModule.launch |Speech-based communication. NOTE (1)| 8 | |Leap motion|Ground control station | droneLeapMotionDrone ControlUserInterface ROSModule.launch|Communication with leap motion| 9 | | Communication manager | Communication system | droneCommunication Manager ROSModule.launch |Swarm Coordination| 10 | 11 | NOTE (1): Required launcher: `${AEROSTACK_STACK}/launchers/sound_play.launch` 12 | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Execute-Missions.md: -------------------------------------------------------------------------------- 1 | Here you can find a list of tutorials describing how to use Aerostack for different types of missions. It is recommended to complete the list of tutorials to learn the available features. 2 | 3 | ## Preparing the mission 4 | 5 | 1. [[Select launcher]] 6 | 1. [[Configure the environment map]] 7 | 8 | ## Executing missions using Drone Simulator 9 | 10 | 1. [[Launch Aerostack with Drone Simulator]] 11 | 1. [[Teleoperate a simulated drone]] 12 | 1. [[Execute a simulated mission using a behavior tree]] 13 | 1. [[Execute a simulated mission using TML]] 14 | 1. [[Execute a simulated mission using Python]] 15 | 16 | ## Executing real flight missions using AR Drone 2.0 17 | 18 | 1. [[Launch Aerostack for AR Drone 2.0]] 19 | 1. [[Build flight environment with visual markers]] 20 | 1. [[Execute missions that follow object images]] 21 | 1. [[Practical tips for real flights]] -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Execute-missions-that-follow-object-images.md: -------------------------------------------------------------------------------- 1 | If your robotic system follows object images (with visual servoing), take into account the following considerations. 2 | 3 | ### OpenTLD GUI for Visual Servoing 4 | When you are using the OpenTLD GUI you have to press the F5 button to refresh the image on the screen, select the area you want the drone to follow and then press and hold (just for few seconds) the ENTER key. Then the drone will start following the selected area. 5 | 6 | ### Visual servoing processes 7 | If visual servoing produces unxpected behavior, double check that the following processes have been started (with ``` rosnode list ```): 8 | * /droneN/droneIBVSController 9 | * /droneN/open\_tld\_translator 10 | * /droneN/ros\_tld\_tracker\_node 11 | * /droneN/ros\_tld\_gui\_node 12 | * /droneN/trackerEye -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Execution-processes.md: -------------------------------------------------------------------------------- 1 | | Process | System | Launcher | Comment | 2 | | :-------| :------- | :-------- |:-------- | 3 | |Manager of actions |Executive system | droneManagerOfActionsROSModule.launch |Execution of simple actions | 4 | | Behavior coordinator | Executive system |behavior_coordinator_process.launch |Execution of behaviors | 5 | | Behavior specialist | Executive system |behavior_specialist_process.launch |Execution of behaviors | 6 | | Resource manager | Executive system |resource_manager_process.launch |Execution of behaviors| 7 | | Mission plan interpreter (schedule processor)| Planning system | droneMissionSheduleProcessorROSModule.launch |Mission schedule processor| 8 | | Mission plan interpreter (TML)| Planning system | task_based_mission_planner_process.launch |Task-based mission plan interpreter| 9 | | Mission plan interpreter (Python)| Planning system | python_based_mission_interpreter_process.launch |Python-based mission plan interpreter| 10 | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Feature-extraction-processes.md: -------------------------------------------------------------------------------- 1 | | Process | System | Launcher | 2 | | :-------| :------- | :-------- | 3 | | Aruco eye | Feature extraction | droneArucoEyeROSModule.launch | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/.DS_Store: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/.DS_Store -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/ARDrone.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/ARDrone.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/ATENCION FALTA ESTA FIGURA HMIAbout.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/ATENCION FALTA ESTA FIGURA HMIAbout.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/AddChild.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/AddChild.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/AerostackMainView.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/AerostackMainView.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/Architecture.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/Architecture.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/BlocksDiagram.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/BlocksDiagram.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/CameraManager.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/CameraManager.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/CoverPageLevant.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/CoverPageLevant.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/CreateNewBehaviorTree.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/CreateNewBehaviorTree.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/ExecuteTmlMission.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/ExecuteTmlMission.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIBTGuideStep1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIBTGuideStep1.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIBTGuideStep2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIBTGuideStep2.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIBTGuideStep3.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIBTGuideStep3.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIBTGuideStep4_1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIBTGuideStep4_1.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIBTGuideStep4_2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIBTGuideStep4_2.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIBTGuideStep5.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIBTGuideStep5.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIBehaviorTree.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIBehaviorTree.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIBehaviorViewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIBehaviorViewer.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIBeliefViewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIBeliefViewer.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUICameraViewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUICameraViewer.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIComplexBTExample.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIComplexBTExample.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIControlPanelAbortMission.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIControlPanelAbortMission.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIControlPanelKeyboardFirst.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIControlPanelKeyboardFirst.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIControlPanelKeyboardSecond.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIControlPanelKeyboardSecond.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIControlPanelStartMission.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIControlPanelStartMission.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIEnvironmentViewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIEnvironmentViewer.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIFirstPersonViewBig.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIFirstPersonViewBig.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIFirstPersonViewSmall.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIFirstPersonViewSmall.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIKeyboardTeleoperationGuide.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIKeyboardTeleoperationGuide.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIMapEditionMode1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIMapEditionMode1.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIMapEditionMode2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIMapEditionMode2.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIMapEditionMode3.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIMapEditionMode3.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIMapEditionModeFinal.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIMapEditionModeFinal.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIMapEditionModeFinal2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIMapEditionModeFinal2.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIMapEditionTools.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIMapEditionTools.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUINewMap.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUINewMap.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIParameterView.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIParameterView.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIWindowsLayout.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GUIWindowsLayout.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GuidedByBehaviorTress.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/GuidedByBehaviorTress.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/LogoGPLv3.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/LogoGPLv3.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/MapComplete.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/MapComplete.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/MapDimensions.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/MapDimensions.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/MapObstacles.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/MapObstacles.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/PressEditMission.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/PressEditMission.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/ProcessMonitor.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/ProcessMonitor.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/Processes.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/Processes.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/ROSNetworkConfig.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/ROSNetworkConfig.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/RobotEnvironment.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/RobotEnvironment.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/RvizMainView.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/RvizMainView.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/SaveBehaviorTree.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/SaveBehaviorTree.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/SensorGPS.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/SensorGPS.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/ShellUserInterface.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/ShellUserInterface.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/StateTransitionDiagram.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/StateTransitionDiagram.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/TerminalsView.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/TerminalsView.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/TmlOperationMode.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/TmlOperationMode.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/VideoMapConfiguration.mp4: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/VideoMapConfiguration.mp4 -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/wiki_aerostack_gregale.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/wiki_aerostack_gregale.pdf -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/wiki_aerostack_levant_2.0.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Files/wiki_aerostack_levant_2.0.pdf -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Home.md: -------------------------------------------------------------------------------- 1 | 2 | 3 |

[[Files/CoverPageLevant.png]]

4 | 5 |

Example of search and rescue mission using Aerostack (click to see video):

6 | 7 |

8 | IMAGE ALT TEXT HERE 11 |

12 | 13 | 14 | 15 | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Launch-Aerostack-with-Drone-Simulator.md: -------------------------------------------------------------------------------- 1 | Drone Simulator is a process that simulates the dynamics of a quadrotor. To launch Aerostack with Drone Simulator, perform the following steps: 2 | 3 | 1. Open a terminal window and execute the ROS Master Node: 4 | 5 | $ roscore 6 | 7 | 1. Open another terminal and change your current directory to the folder that contains the launchers: 8 | 9 | $ cd $AEROSTACK_STACK/launchers 10 | 11 | 1. Execute the launcher script: 12 | 13 | $ ./simulated_quadrotor_basic.sh 14 | 15 | 4. Three new terminal windows pop up. Wait until they finish executing. 16 | 17 | ![View of init terminals](Files/TerminalsView.png) 18 | 19 | 6. Finally, Aerostack GUI and Rviz will open ready to be used. 20 | 21 | ![View of Aerostack GUI](Files/AerostackMainView.png) 22 | 23 | ![View of Rviz](Files/RvizMainView.png) 24 | 25 | See here a video that presents this process: 26 | 27 | [![Launch tutorial](https://img.youtube.com/vi/zre0XzRC9Xs/0.jpg)](https://www.youtube.com/watch?v=zre0XzRC9Xs) -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Mission-Plan-Languages.md: -------------------------------------------------------------------------------- 1 | The operator can specify a mission plan using three alternative options: 2 | 3 | - [[TML language]]. This is a special-purpose language using a hierarchical task-based approach and XML syntax. 4 | 5 | - [[Behavior tree]]. In this case, a graphical editor can be used to specify missions using a visual modeling language. 6 | 7 | - [[Python language]]. Python language can be used (with a library of functions) to specify a mission plan. 8 | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Motion-planning-processes.md: -------------------------------------------------------------------------------- 1 | | Process | System | Launcher | 2 | | :-------| :------- | :-------- | 3 | | Trajectory planner | Planning system | droneTrajectoryPlanner2dROSModule.launch | 4 | | Yaw commander | Planning system | droneYawCommanderROSModule.launch | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Physical-layer-processes.md: -------------------------------------------------------------------------------- 1 | | Process | System | Launcher | Comments | 2 | | :-------| :------- | :------- |:------- | 3 | | Drivers AR Drone | Hardware interface | driverParrotARDroneROSModule.launch | Operation with AR Drone 2.0. NOTE (1) | 4 | | Drone Simulator | Simulation system | droneSimulatorROSModule.launch | Operation with "Drone Simulator" | 5 | 6 | NOTE (1) This option also requires the launcher related to "ARDrone Autonomy": `${AEROSTACK_STACK}/launchers/ardrone_launch/ardrone_indoors.launch` 7 | 8 | NOTE (2): Other aerial platforms not described here can also be used with Aerostack (e.g., Asctec Pelican, Bebop, etc.). -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Prepare-the-Mission.md: -------------------------------------------------------------------------------- 1 | 2 | * [[Configure Launcher]] 3 | * [[Configure Map]] 4 | * [[Specify a Mission Plan]] 5 | * [[Practical Tips for Real Flights]] 6 | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Select-Launcher.md: -------------------------------------------------------------------------------- 1 | 2 | The launcher is a file that specifies the architecture of processes that will be executed for a particular aerial robot system. The available launchers in Aerostack are in the folder `${AEROSTACK_STACK}/launchers`. Next table shows examples of launchers (.sh files) that you can find in this folder and are ready to be used. 3 | 4 | | Launcher | Description | 5 | | :-----------| :--------- | 6 | | simulated_quadrotor_basic.sh |Architecture of processes for Drone Simulator| 7 | | ardrone_basic.sh |Architecture of processes for AR Drone 2.0| 8 | | ardrone_visual_marker_localization.sh |Architecture of processes for AR Drone 2.0 using visual markers for self-localization| 9 | 10 | 11 | To create a new launcher for a particular robotic system you can consult the following link: 12 | 13 | - [[How to create a launcher]] 14 | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Self-localization-and-mapping-processes.md: -------------------------------------------------------------------------------- 1 | | Process | System | Launcher | Comments | 2 | | :-------| :------- | :-------- |:-------- | 3 | | Self Localization Selector | Situation awareness |self_localization_selector_process.launch | Selector of self localization method | 4 | | Visual markers localizer | Situation awareness |droneVisualMarkersLocalizerROSModule.launch |Self-localization by Aruco visual markers | 5 | | Obstacle detector visual marks |Situation awareness |droneObstacleProcessor2d VisualMarksROSModule.launch |Self-localization by Aruco visual markers | 6 | | Obstacle distance calculator | Situation awareness |droneObstacleDistance CalculationROSModule.launch |Self-localization by Aruco visual markers | 7 | | Self localizer | Situation awareness |droneEKFStateEstimatorROSModule.launch | Self-localization by Aruco visual markers| -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/Setup-Communications.md: -------------------------------------------------------------------------------- 1 | Here you can find how to do the following tasks: 2 | * [[Setup the Communication Network]] 3 | * [[Wi Fi Communication with Multiple Drones]] -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/_Footer.md: -------------------------------------------------------------------------------- 1 | **Contact** 2 | 3 | We thank and welcome any suggestion or comment about Aerostack. For any question or bug report you can read and/or write at the [issues page](https://github.com/Vision4UAV/Aerostack/issues). 4 | 5 | You can also contact the team support at the following address: aerostack.vision4uav@gmail.com -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_levant_2.1/wiki_aerostack_levant_2.1/_Sidebar.md: -------------------------------------------------------------------------------- 1 | **Getting started** 2 | * [[What is Aerostack]] 3 | * [[Install Aerostack]] 4 | * [[Launch Real Flight]] 5 | * [[License]] 6 | * [[List of Distributions]] 7 | 8 | **Components** 9 | * [[Aerostack Architecture]] 10 | * [[Graphical User Interface]] 11 | * [[Mission Plan Languages]] 12 | * [[Catalog of Behaviors]] 13 | * [[Memory of Beliefs]] 14 | 15 | **Tutorials** 16 | * [[Execute Missions]] 17 | * [[Program New Behaviors]] 18 | * [[Add New Hardware]] 19 | * [[Setup Communications]] 20 | 21 | **International competitions** 22 | * [1st prize at IMAV 2013](http://www.vision4uav.eu/?q=swarm "http://www.vision4uav.eu") 23 | * [[4th place at IMAV 2016]] 24 | * [2nd prize at IMAV 2017](https://www.youtube.com/watch?v=HOR8kDi8EDI) 25 | 26 | **More information** 27 | * [[Publications]] 28 | * [Research Group CVAR](https://www.researchgate.net/lab/Computer-Vision-and-Aerial-Robotics-Pascual-Campoy) -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0.pdf -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/4th-place-at-IMAV-2016.md: -------------------------------------------------------------------------------- 1 | This page shows some videos corresponding to the International Competition at IMAV 2016, where our group achieved the 4th place. 2 | 3 | Entering the house: 4 | 5 | [![](https://img.youtube.com/vi/9_06GtO4-70/0.jpg)](https://www.youtube.com/watch?v=9_06GtO4-70) 6 | 7 | Autonomous landing: 8 | 9 | [![](https://img.youtube.com/vi/qon8UK0fvwk/0.jpg)](https://www.youtube.com/watch?v=qon8UK0fvwk) 10 | 11 | In the house: 12 | 13 | [![](https://img.youtube.com/vi/XhwO3w2bxFA/0.jpg)](https://www.youtube.com/watch?v=XhwO3w2bxFA) 14 | 15 | Experimental flights: 16 | 17 | [![](https://img.youtube.com/vi/y9Bj3deT-Kw/0.jpg)](https://www.youtube.com/watch?v=y9Bj3deT-Kw) -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Add-new-hardware.md: -------------------------------------------------------------------------------- 1 | Here you can find how to do the following tasks: 2 | 3 | * [[Calibrate Controllers]] 4 | * [[Add a New Camera]] 5 | * [[Add a GPS Sensor]] 6 | * [[Use Aerostack for a New Physical Platform]] -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/Architecture.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/Architecture.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/BehaviorTreeEditor.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/BehaviorTreeEditor.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/BehaviorTreeNodeOptions.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/BehaviorTreeNodeOptions.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/BehaviorTreeVariables.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/BehaviorTreeVariables.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/BlocksDiagram.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/BlocksDiagram.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/CameraManager.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/CameraManager.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/CoverPageSirocco.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/CoverPageSirocco.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/CreatingNewMap.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/CreatingNewMap.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/CreatingNewObject.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/CreatingNewObject.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/EditEnvironment.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/EditEnvironment.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/EnvironmentMapEditor.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/EnvironmentMapEditor.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ExampleProjects.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ExampleProjects.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIBehaviorTree.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIBehaviorTree.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIBehaviorTreeControlWindow.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIBehaviorTreeControlWindow.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIBehaviorTreeEditor.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIBehaviorTreeEditor.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUICameraViewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUICameraViewer.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIComplexBTExample.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIComplexBTExample.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIDynamicsViewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIDynamicsViewer.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIEnvironmentEditor.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIEnvironmentEditor.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIEnvironmentViewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIEnvironmentViewer.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIExecutionViewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIExecutionViewer.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIFirstPersonViewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIFirstPersonViewer.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIGraphicalTeleoperationWindow.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIGraphicalTeleoperationWindow.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUILayoutAlphanumericInterface.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUILayoutAlphanumericInterface.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUILayoutBehaviorTreeControl.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUILayoutBehaviorTreeControl.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUILayoutGraphicalTeleoperation.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUILayoutGraphicalTeleoperation.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUILayoutPythonMissionControl.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUILayoutPythonMissionControl.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIMenuBarAerostack.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIMenuBarAerostack.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIParametersViewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/GUIParametersViewer.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/LogoBSD.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/LogoBSD.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/MapComplete.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/MapComplete.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/MapDimensions.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/MapDimensions.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/MapObstacles.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/MapObstacles.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/MessageToOperator.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/MessageToOperator.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/OperatorAssistanceRequest.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/OperatorAssistanceRequest.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/PhotoMBZIRC2020_1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/PhotoMBZIRC2020_1.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/PhotoMBZIRC2020_2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/PhotoMBZIRC2020_2.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProcessMonitor.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProcessMonitor.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBIRSBehaviorTree.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBIRSBehaviorTree.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBIRSCamera.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBIRSCamera.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBIRSGazebo.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBIRSGazebo.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBLRSExecutionViewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBLRSExecutionViewer.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBLRSGazebo.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBLRSGazebo.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBLRSOccupancyGrid.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBLRSOccupancyGrid.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBMDSArVizDroneSimulator.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBMDSArVizDroneSimulator.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBMDSExecutionViewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBMDSExecutionViewer.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBMRSExecutionViewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBMRSExecutionViewer.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBMRSGazebo.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBMRSGazebo.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBTDSArVizDroneSimulator.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBTDSArVizDroneSimulator.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBTDSBehaviorTree.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBTDSBehaviorTree.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBTDSExecutionViewer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectBTDSExecutionViewer.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectTDSArVizDroneSimulator.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectTDSArVizDroneSimulator.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectTDSDroneAlphanumericInterface.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectTDSDroneAlphanumericInterface.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectTRSAlphanumericInterface.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectTRSAlphanumericInterface.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectTRSGazebo.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectTRSGazebo.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectWRSCameraView.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectWRSCameraView.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectWRSGazebo1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectWRSGazebo1.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectWRSGazebo2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectWRSGazebo2.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectWRSGazebo3.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectWRSGazebo3.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectWRSOccupancyGrid.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ProjectWRSOccupancyGrid.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ROSNetworkConfig.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ROSNetworkConfig.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/RobotEnvironment.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/RobotEnvironment.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/RvizMainView.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/RvizMainView.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/SensorGPS.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/SensorGPS.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ShellUserInterface.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/ShellUserInterface.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/StateTransitionDiagram.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/StateTransitionDiagram.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/TerminalsView.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/TerminalsView.png -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/wiki_aerostack_gregale.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/wiki_aerostack_gregale.pdf -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/wiki_aerostack_levant_2.0.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/wiki_aerostack_levant_2.0.pdf -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/wiki_aerostack_levant_2.1.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Files/wiki_aerostack_levant_2.1.pdf -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Mission-Plan-Languages.md: -------------------------------------------------------------------------------- 1 | The operator can specify a mission plan using two alternative options: 2 | 3 | - [[Behavior tree]]. In this case, a graphical editor can be used to specify missions using a visual modeling language. 4 | 5 | - [[Python language]]. Python language can be used (with a library of functions) to specify a mission plan. 6 | -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/Setup-Communications.md: -------------------------------------------------------------------------------- 1 | Here you can find how to do the following tasks: 2 | * [[Setup the Communication Network]] 3 | * [[Wi Fi Communication with Multiple Drones]] -------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/_Footer.md: -------------------------------------------------------------------------------- 1 | **Contact:** We thank and welcome any suggestion or comment about Aerostack. For any question or bug report you can read and/or write at the [issues page](https://github.com/Vision4UAV/Aerostack/issues). You can also contact the team support at the following address: aerostack.upm@gmail.com 2 | 3 |

The content of the Aerostack wiki is licensed under Creative Commons license CC BY 4.0

-------------------------------------------------------------------------------- /doc/wiki/wiki_aerostack_sirocco_3.0/wiki_aerostack_sirocco_3.0/_Sidebar.md: -------------------------------------------------------------------------------- 1 | **Getting started** 2 | * [[What is Aerostack]] 3 | * [[Install Aerostack]] 4 | * [[License]] 5 | * [[List of Distributions]] 6 | 7 | **Components** 8 | * [[Aerostack Architecture]] 9 | * [[Graphical User Interface]] 10 | * [[Mission Plan Languages]] 11 | * [[Catalog of Behaviors]] 12 | * [[Memory of Beliefs]] 13 | 14 | **Tutorials** 15 | * [[Example Projects]] 16 | * [[Program New Behaviors]] 17 | * [[Add New Hardware]] 18 | * [[Setup Communications]] 19 | 20 | **International competitions** 21 | * [[3rd place at MBZIRC 2020]] 22 | * [2nd prize at IMAV 2017](https://www.youtube.com/watch?v=HOR8kDi8EDI) 23 | * [[4th place at IMAV 2016]] 24 | * [1st prize at IMAV 2013](https://www.youtube.com/watch?v=xUff0iAjF8s) 25 | 26 | **More information** 27 | * [[Publications]] 28 | * [Research Group CVAR](https://www.researchgate.net/lab/Computer-Vision-and-Aerial-Robotics-Pascual-Campoy) -------------------------------------------------------------------------------- /installation/installers/installStack.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | #AEROSTACK_STACK 4 | echo "export AEROSTACK_STACK=`pwd`" >> $HOME/.bashrc 5 | -------------------------------------------------------------------------------- /installation/installers/installWS.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | #AEROSTACK_WORKSPACE 4 | echo "export AEROSTACK_WORKSPACE=`pwd`" >> $HOME/.bashrc 5 | 6 | -------------------------------------------------------------------------------- /installation/installers/linux 18/README.md: -------------------------------------------------------------------------------- 1 | #MANUAL FIXES 2 | 3 | -Compilation error in $AEROSTACK_STACK/hardware_interface/drivers_platforms/driver_bebop/bebop_autonomy/bebop_driver/include/bebop_driver/autogenerated/common_state_callbacks.h: Change in lines 1230 and 1260 ‘ARCONTROLLER_DICTIONARY_KEY_COMMON_MAVLINKSTATE_MISSONITEMEXECUTED’ to ‘ARCONTROLLER_DICTIONARY_KEY_COMMON_MAVLINKSTATE_MISSIONITEMEXECUTED’ and ‘ARCONTROLLER_DICTIONARY_KEY_COMMON_MAVLINKSTATE_MISSONITEMEXECUTED_IDX' to ‘ARCONTROLLER_DICTIONARY_KEY_COMMON_MAVLINKSTATE_MISSIONITEMEXECUTED_IDX'. Then compile again. 4 | 5 | -Behavior coordinator crashes when executing GUI: in $AEROSTACK_STACK/configs/general/behavior_catalog.yaml comment lines 59 and 98 (SELF_LOCALIZE_BY ODOMETRY and KEEP_HOVERING default:yes) 6 | 7 | -Error in home/alejandro/workspace/ros/aerostack_catkin_ws/src/aerostack_stack/stack/ground_control_system/rviz/droneArchitectureRvizInterfaceROSModule when isntalling in ubuntu 18: uncomment line 13 (-std=c++11) and comment line 14 (-std=c++03) 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /launchers/ardrone_launch/ardrone_indoors_hriday.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | -------------------------------------------------------------------------------- /launchers/ardrone_launch/launch_files/opentld_gui_for_IBVSController.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /launchers/ardrone_launch/sh_files/run_IBVS_controller.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneIBVSControllerROSModule DroneIBVSControllerROSModule.launch --wait drone_id_int:="1" drone_id_namespace:="drone1"& 6 | roslaunch droneTrackerEyeROSModule droneTrackerEyeROSModule.launch --wait drone_id_int:="1" drone_id_namespace:="drone1" 7 | -------------------------------------------------------------------------------- /launchers/ardrone_launch/sh_files/run_ardrone_autonomy.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch ${AEROSTACK_STACK}/launchers/ardrone_launch/ardrone_indoors.launch --wait drone_id_int:="1" drone_id_namespace:="drone1" 6 | -------------------------------------------------------------------------------- /launchers/ardrone_launch/sh_files/run_driver_parrot.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch driverParrotARDroneROSModule driverParrotARDroneROSModule.launch --wait drone_id_int:="1" drone_id_namespace:="drone1" 6 | -------------------------------------------------------------------------------- /launchers/ardrone_launch/sh_files/run_ekf_odometry.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneEKFStateEstimatorROSModule droneEKFStateEstimatorROSModule.launch --wait drone_id_int:="1" drone_id_namespace:="drone1" 6 | -------------------------------------------------------------------------------- /launchers/ardrone_launch/sh_files/run_interface_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneInterfaceROSModule droneInterface_jp_ROSModule.launch --wait drone_id_int:="1" drone_id_namespace:="drone1" 6 | 7 | -------------------------------------------------------------------------------- /launchers/ardrone_launch/sh_files/run_opentld_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch ${AEROSTACK_STACK}/launchers/ardrone_launch/launch_files/opentld_for_IBVSController.launch --wait drone_id_int:="1" drone_id_namespace:="drone1" & 6 | roslaunch ${AEROSTACK_STACK}/launchers/ardrone_launch/launch_files/opentld_gui_for_IBVSController.launch --wait drone_id_int:="1" drone_id_namespace:="drone1" & 7 | roslaunch droneOpenTLDTranslatorROS droneOpenTLDTranslatorROSModule.launch --wait drone_id_int:="1" drone_id_namespace:="drone1" 8 | -------------------------------------------------------------------------------- /launchers/ardrone_launch/sh_files/run_supervisor_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch performance_monitor performance_monitor.launch --wait drone_id_int:="1" drone_id_namespace:="drone1" 6 | 7 | -------------------------------------------------------------------------------- /launchers/ardrone_launch/sh_files/run_trajectory_controller.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneTrajectoryControllerROSModule droneTrajectoryControllerROSModule.launch --wait drone_id_int:="1" drone_id_namespace:="drone1" 6 | -------------------------------------------------------------------------------- /launchers/ardrone_launch/stop.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | pkill -SIGINT roslaunch 4 | -------------------------------------------------------------------------------- /launchers/bebop_launchers/bebop_realflight_instructions.md: -------------------------------------------------------------------------------- 1 | screen -AmdS bebop -t terminal bash 2 | screen -S bebop -X screen -t roscore ${DRONE_STACK}/launchers/screen_launchers/start_roscore.sh 3 | screen -S bebop -X screen -t Bebop_Autonomy ${DRONE_STACK}/launchers/bebop_launchers/sh_files/run_bebop_autonomy.sh 4 | screen -S bebop -X screen -t Driver_Bebop ${DRONE_STACK}/launchers/bebop_launchers/sh_files/run_driver_bebop.sh 5 | screen -S bebop -X screen -t EKF ${DRONE_STACK}/launchers/bebop_launchers/sh_files/run_ekf_odometry.sh 6 | screen -S bebop -X screen -t trajectory_ctrl ${DRONE_STACK}/launchers/bebop_launchers/sh_files/run_trajectory_controller.sh 7 | screen -S bebop -X screen -t supervisor ${DRONE_STACK}/launchers/bebop_launchers/sh_files/run_supervisor_node.sh 8 | screen -S bebop -X screen -t Opentld_node ${DRONE_STACK}/launchers/bebop_launchers/sh_files/run_opentld_node.sh 9 | screen -S bebop -X screen -t IBVS_Controller ${DRONE_STACK}/launchers/bebop_launchers/sh_files/run_IBVS_controller.sh 10 | screen -S bebop -X screen -t drone_interface ${DRONE_STACK}/launchers/bebop_launchers/sh_files/run_interface_node.sh 11 | -------------------------------------------------------------------------------- /launchers/bebop_launchers/launch_files/opentld_gui_for_IBVSController.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /launchers/bebop_launchers/sh_files/run_IBVS_controller.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch droneIBVSControllerROSModule DroneIBVSControllerROSModule.launch --wait drone_id_int:="4" drone_id_namespace:="drone4" & 6 | roslaunch droneTrackerEyeROSModule droneTrackerEyeROSModule.launch --wait drone_id_int:="4" drone_id_namespace:="drone4" 7 | -------------------------------------------------------------------------------- /launchers/bebop_launchers/sh_files/run_bebop_autonomy.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/launchers/bebop_launchers/launch_files/bebop_node.launch --wait drone_id_int:="4" drone_id_namespace:="drone4" 6 | -------------------------------------------------------------------------------- /launchers/bebop_launchers/sh_files/run_driver_bebop.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch driverBebopROSModule driverBebopROSModule.launch --wait drone_id_int:="4" drone_id_namespace:="drone4" 6 | -------------------------------------------------------------------------------- /launchers/bebop_launchers/sh_files/run_ekf_odometry.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch droneEKFStateEstimatorROSModule droneEKFStateEstimatorROSModule.launch --wait drone_id_int:="4" drone_id_namespace:="drone4" 6 | -------------------------------------------------------------------------------- /launchers/bebop_launchers/sh_files/run_interface_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch droneInterfaceROSModule droneInterface_jp_ROSModule.launch --wait drone_id_int:="4" drone_id_namespace:="drone4" 6 | 7 | -------------------------------------------------------------------------------- /launchers/bebop_launchers/sh_files/run_opentld_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/launchers/bebop_launchers/launch_files/opentld_for_IBVSController.launch --wait drone_id_int:="4" drone_id_namespace:="drone4" & 6 | roslaunch ${DRONE_STACK}/launchers/bebop_launchers/launch_files/opentld_gui_for_IBVSController.launch --wait drone_id_int:="4" drone_id_namespace:="drone4" & 7 | roslaunch droneOpenTLDTranslatorROS droneOpenTLDTranslatorROSModule.launch --wait drone_id_int:="4" drone_id_namespace:="drone4" 8 | -------------------------------------------------------------------------------- /launchers/bebop_launchers/sh_files/run_supervisor_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch performance_monitor performance_monitor.launch --wait drone_id_int:="4" drone_id_namespace:="drone4" 6 | 7 | -------------------------------------------------------------------------------- /launchers/bebop_launchers/sh_files/run_trajectory_controller.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch droneTrajectoryControllerROSModule droneTrajectoryControllerROSModule.launch --wait drone_id_int:="4" drone_id_namespace:="drone4" 6 | -------------------------------------------------------------------------------- /launchers/bebop_launchers/stop.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | pkill -SIGINT roslaunch 4 | -------------------------------------------------------------------------------- /launchers/dji_launchers/matrice_100/launch_files/dji_sdk_client.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | -------------------------------------------------------------------------------- /launchers/dji_launchers/matrice_100/launch_files/guidance_node.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /launchers/dji_launchers/matrice_100/launch_files/hector_imu.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | -------------------------------------------------------------------------------- /launchers/dji_launchers/matrice_100/launch_files/hector_slam.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | -------------------------------------------------------------------------------- /launchers/dji_launchers/matrice_100/launch_files/hokuyo_node.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | -------------------------------------------------------------------------------- /launchers/dji_launchers/matrice_100/launch_files/lightware_altitude_node.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /launchers/dji_launchers/matrice_100/launch_files/sdk.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /launchers/dji_launchers/matrice_100/launch_files/sdk_manifold.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /launchers/dji_launchers/matrice_100/launch_files/usb_cam-test.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 14 | 15 | -------------------------------------------------------------------------------- /launchers/dji_launchers/matrice_100/sdk_manifold.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /launchers/dji_launchers/matrice_100/stop.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | pkill -SIGINT roslaunch 4 | -------------------------------------------------------------------------------- /launchers/dji_launchers/matrice_210/launch_files/sdk.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /launchers/dji_launchers/matrice_210/launch_files/usb_cam.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /launchers/dji_launchers/matrice_210/stop.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | pkill -SIGINT roslaunch 4 | -------------------------------------------------------------------------------- /launchers/hector_slam_launchers/hector_imu.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | -------------------------------------------------------------------------------- /launchers/hector_slam_launchers/hector_slam.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/launch_files/EKFSimulatorRvizROSModule.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/launch_files/SimulatorRvizROSModule.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/launch_files/driver_px4flow_interface_ROSModule.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/launch_files/driver_px4flow_interface_ROSModule_lidar.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/launch_files/droneLoggerROSModule.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/launch_files/joy.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/launch_files/joyConverterToDrvOktoCmdNode.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/launch_files/laser_altimeter.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/sh_files/okto_EKF_simulator.sh: -------------------------------------------------------------------------------- 1 | cd $DRONE_STACK 2 | source setup.sh odroid 3 | roslaunch ${DRONE_STACK}/launchers/mikrokopter_launchers/launch_files/EKFSimulatorRvizROSModule.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" 4 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/sh_files/run_droneLogger_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh mastermind 5 | roslaunch ${DRONE_STACK}/launchers/mikrokopter_launchers/launch_files/droneLoggerROSModule.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" 6 | 7 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/sh_files/run_ekf_odometry.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch droneEKFStateEstimatorROSModule droneEKFStateEstimatorROSModule.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" 6 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/sh_files/run_interface_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh odroid 5 | roslaunch droneInterfaceROSModule droneInterface_jp_ROSModule.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" 6 | 7 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/sh_files/run_joy_converter_okto_command_node_js0.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | cd $DRONE_STACK 3 | source setup.sh 4 | 5 | roslaunch ${DRONE_STACK}/launchers/mikrokopter_launchers/launch_files/joyConverterToDrvOktoCmdNode.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" joy_device_name:="/dev/input/js1" 6 | 7 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/sh_files/run_joy_converter_okto_command_node_js0_odroid.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh odroid 5 | 6 | roslaunch ${DRONE_STACK}/launchers/mikrokopter_launchers/launch_files/joyConverterToDrvOktoCmdNode.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" joy_device_name:="/dev/input/js0" 7 | 8 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/sh_files/run_laser_altimeter.sh: -------------------------------------------------------------------------------- 1 | cd $DRONE_STACK 2 | source setup.sh 3 | roslaunch ${DRONE_STACK}/launchers/mikrokopter_launchers/launch_files/laser_altimeter.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" 4 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/sh_files/run_midlevelautopilot_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch droneMidLevelAutopilotROSModule droneMidLevelAutopilotROSModule.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" 6 | 7 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/sh_files/run_mikrokopter_driver.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch mikrokopter_driver mikrokopter_driver_launcher.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" comm_port:="/dev/ttyUSB0" 6 | 7 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/sh_files/run_mikrokopter_driver_ros_module.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/launchers/mikrokopter_launchers/launch_files/mikrocopter_driver_ros_module.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" 6 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/sh_files/run_mikrokopter_sub.sh: -------------------------------------------------------------------------------- 1 | cd $DRONE_STACK 2 | source setup.sh 3 | roslaunch ${DRONE_STACK}/launchers/mikrokopter_launchers/launch_files/mikrocopter_subscriber.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" 4 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/sh_files/run_px4flow_interface.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/launchers/mikrokopter_launchers/launch_files/driver_px4flow_interface_ROSModule.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" 6 | 7 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/sh_files/run_px4flow_interface_lidar.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/launchers/mikrokopter_launchers/launch_files/driver_px4flow_interface_ROSModule_lidar.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" 6 | 7 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/sh_files/run_px4flow_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/launchers/okto_launchers/launch_files/px4flow.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" 6 | 7 | 8 | -------------------------------------------------------------------------------- /launchers/mikrokopter_launchers/sh_files/run_trajectory_controller.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch droneTrajectoryControllerROSModule droneTrajectoryControllerROSModule.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" 6 | -------------------------------------------------------------------------------- /launchers/msf_localization/msf_localization_interface.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /launchers/msf_localization/stop.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | pkill -SIGINT roslaunch 4 | -------------------------------------------------------------------------------- /launchers/okto_launchers/launch_files/driver_px4flow_interface_ROSModule.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /launchers/okto_launchers/launch_files/px4flow.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /launchers/okto_launchers/okto_date_update.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | ./time_update.sh `date +%s` 4 | -------------------------------------------------------------------------------- /launchers/okto_launchers/sh_files/run_driverOktoROSModule.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/launchers/okto_launchers/launch_files/driverOktoROSModule.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" 6 | -------------------------------------------------------------------------------- /launchers/okto_launchers/sh_files/run_ekf_odometry.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch droneEKFStateEstimatorROSModule droneEKFStateEstimatorROSModule.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" 6 | -------------------------------------------------------------------------------- /launchers/okto_launchers/sh_files/run_interface_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch droneInterfaceROSModule droneInterface_jp_ROSModule.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" 6 | 7 | -------------------------------------------------------------------------------- /launchers/okto_launchers/sh_files/run_joy_converter_driver_okto_command_node_js0.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/driverOktoROSModule/launch/joyConverterToDrvOktoCmdNode.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" joy_device_name:="/dev/input/js0" 6 | 7 | -------------------------------------------------------------------------------- /launchers/okto_launchers/sh_files/run_joy_converter_driver_okto_command_node_js1.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/driverOktoROSModule/launch/joyConverterToDrvOktoCmdNode.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" joy_device_name:="/dev/input/js1" 6 | 7 | -------------------------------------------------------------------------------- /launchers/okto_launchers/sh_files/run_joy_converter_midlevelautopilot_test_js0.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/droneMidLevelAutopilotROSModule/launch/joyConverterToMidlevelAutopilot.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" joy_device_name:="/dev/input/js0" 6 | 7 | -------------------------------------------------------------------------------- /launchers/okto_launchers/sh_files/run_joy_converter_midlevelautopilot_test_js1.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/droneMidLevelAutopilotROSModule/launch/joyConverterToMidlevelAutopilot.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" joy_device_name:="/dev/input/js1" 6 | 7 | -------------------------------------------------------------------------------- /launchers/okto_launchers/sh_files/run_joy_converter_okto_command_node_js0.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/droneOktoSimulatorROSModule/launch/joyConverterToOktoCmdNode.launch --wait joy_device_name:="/dev/input/js0" drone_id_int:="2" drone_id_namespace:="drone2" 6 | 7 | -------------------------------------------------------------------------------- /launchers/okto_launchers/sh_files/run_joy_converter_okto_command_node_js1.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/droneOktoSimulatorROSModule/launch/joyConverterToOktoCmdNode.launch --wait joy_device_name:="/dev/input/js1" drone_id_int:="2" drone_id_namespace:="drone2" 6 | 7 | -------------------------------------------------------------------------------- /launchers/okto_launchers/sh_files/run_midlevelautopilot_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch droneMidLevelAutopilotROSModule droneMidLevelAutopilotROSModule.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" 6 | 7 | -------------------------------------------------------------------------------- /launchers/okto_launchers/sh_files/run_okto_driver.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch okto_driver okto_driver_launcher.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" comm_port:="/dev/ttyUSB0" 6 | #roslaunch okto_driver okto_driver_launcher.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" comm_port:="/dev/ttyUSB2" # For running on Asctec AtomBoard 7 | 8 | -------------------------------------------------------------------------------- /launchers/okto_launchers/sh_files/run_okto_simulator.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/droneOktoSimulatorROSModule/launch/droneOktoSimulatorROSModule.launch --wait drone_sim_config_filename:="okto_like_model.xml" drone_id_int:="2" drone_id_namespace:="drone2" 6 | -------------------------------------------------------------------------------- /launchers/okto_launchers/sh_files/run_px4flow_interface.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/launchers/okto_launchers/launch_files/driver_px4flow_interface_ROSModule.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" 6 | 7 | -------------------------------------------------------------------------------- /launchers/okto_launchers/sh_files/run_px4flow_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/launchers/okto_launchers/launch_files/px4flow.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" 6 | 7 | -------------------------------------------------------------------------------- /launchers/okto_launchers/sh_files/run_rviz_interface_for_okto_simulator.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/launchers/okto_launchers/launch_files/rviz_visualizations_jp.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" 6 | 7 | -------------------------------------------------------------------------------- /launchers/okto_launchers/sh_files/run_trajectory_controller.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $DRONE_STACK 4 | source setup.sh 5 | roslaunch droneTrajectoryControllerROSModule droneTrajectoryControllerROSModule.launch --wait drone_id_int:="2" drone_id_namespace:="drone2" 6 | -------------------------------------------------------------------------------- /launchers/okto_launchers/time_update.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | if [ $# -ne 1 ] 4 | then 5 | echo "Usage - prueba_date.sh 'date'" 6 | exit 1 7 | fi 8 | echo $1 9 | ssh -t okto@okto-wlan sudo date --set='@'+$1 +%s # Atom 10 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/launch_files/driver_px4flow_interface_ROSModule.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/launch_files/driver_px4flow_interface_ROSModule_lidar.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/launch_files/droneInterface_jp_ROSModule.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | _image_transport: compressed 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/launch_files/laser_altimeter.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/launch_files/opentld_gui_for_IBVSController.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/launch_files/px4flow.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_IBVS_controller.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneIBVSControllerROSModule DroneIBVSControllerROSModule.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" & 6 | roslaunch droneTrackerEyeROSModule droneTrackerEyeROSModule.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" 7 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_arucoeye_front.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh mastermind 5 | roslaunch droneArucoEyeROSModule droneArucoEyeROSModule.launch --wait drone_aruco_eye_ros_module_name:="droneArucoEyeROSModule" camera_calibration_file:="front.yaml" drone_image_topic_name:="camera/front/image" camera_number:="0" 6 | 7 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_arucoeye_left.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneArucoEyeROSModule droneArucoEyeROSModule.launch --wait drone_aruco_eye_ros_module_name:="droneArucoEyeROSModuleLeftCam" camera_calibration_file:="left.yaml" drone_image_topic_name:="camera/left/image_raw" camera_number:="1" 6 | 7 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_arucoeye_right.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneArucoEyeROSModule droneArucoEyeROSModule.launch --wait drone_aruco_eye_ros_module_name:="droneArucoEyeROSModuleRightCam" camera_calibration_file:="right.yaml" drone_image_topic_name:="camera/right/image_raw" camera_number:="2" 6 | 7 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_communication_manager.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneCommunicationManagerROSModule droneCommunicationManagerROSModule.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" 6 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_cvg_ueye_02_front.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/launchers/pelican_launchers/launch_files/ueye_cvg_cam.launch --wait camera_id_num:=2 camera_name_str:="front" config_file:="small_camera_RGB24_HUB.ini" 6 | 7 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_cvg_ueye_02_left.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/launchers/pelican_launchers/launch_files/ueye_cvg_cam.launch --wait camera_id_num:=2 camera_name_str:="left" config_file:="small_camera_RGB24_HUB.ini" 6 | 7 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_cvg_ueye_04_front_IBVS.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/launchers/pelican_launchers/launch_files/ueye_cvg_cam.launch --wait camera_id_num:=3 camera_name_str:="front" config_file:="small_camera_RGB24_HUB.ini" 6 | 7 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_cvg_ueye_04_right.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/launchers/pelican_launchers/launch_files/ueye_cvg_cam.launch --wait camera_id_num:=4 camera_name_str:="right" config_file:="small_camera_RGB24_HUB.ini" 6 | 7 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_driverPelicanROSModule.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/launchers/pelican_launchers/launch_files/driverPelicanROSModule.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" 6 | 7 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_ekf_odometry.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneEKFStateEstimatorROSModule droneEKFStateEstimatorROSModule.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" 6 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_interface_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh mastermind 5 | roslaunch ${DRONE_STACK}/launchers/pelican_launchers/launch_files/droneInterface_jp_ROSModule.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" 6 | 7 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_laser_altimeter.sh: -------------------------------------------------------------------------------- 1 | cd $AEROSTACK_STACK 2 | source setup.sh 3 | roslaunch ${AEROSTACK_STACK}/launchers/pelican_launchers/launch_files/laser_altimeter.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" 4 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_localizer.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneVisualMarkersLocalizerROSModule droneVisualMarkersLocalizerROSModule.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" 6 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_logger.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh mastermind 5 | roslaunch dronePelicanLoggerROSModule dronePelicanLoggerROSModule.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" 6 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_manager.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneManagerOfActionsROSModule droneManagerOfActionsROSModule.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" 6 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_midlevelautopilot_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneMidLevelAutopilotROSModule droneMidLevelAutopilotROSModule.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" 6 | 7 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_mission_scheduler.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneMissionScheduleProcessorROSModule droneMissionSheduleProcessorROSModule.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" drone_Estimated_Pose_Topic_Name:=ArucoSlam_EstimatedPose mission_config_file:=missionSchedule.xml 6 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_obstacle_distance_calculator.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneObstacleDistanceCalculatorROSModule droneObstacleDistanceCalculationROSModule.launch --wait drone_id_namespace:="drone0" drone_id_int:="0" sdrone_pose_topic_name:=ArucoSlam_EstimatedPose 6 | 7 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_obstacle_processor.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneObstacleProcessorVisualMarksROSModule droneObstacleProcessor2dVisualMarksROSModule.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" 6 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_opentld_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh mastermind 5 | roslaunch ${AEROSTACK_STACK}/launchers/pelican_launchers/launch_files/opentld_for_IBVSController.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" & 6 | roslaunch ${AEROSTACK_STACK}/launchers/pelican_launchers/launch_files/opentld_gui_for_IBVSController.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" & 7 | roslaunch droneOpenTLDTranslatorROS droneOpenTLDTranslatorROSModule.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" 8 | 9 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_pelican_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch ${AEROSTACK_STACK}/launchers/pelican_launchers/launch_files/asctec_driver_node.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" 6 | 7 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_px4flow_interface_lidar.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch ${AEROSTACK_STACK}/launchers/pelican_launchers/launch_files/driver_px4flow_interface_ROSModule_lidar.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" 6 | 7 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_px4flow_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch ${AEROSTACK_STACK}/launchers/pelican_launchers/launch_files/px4flow.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" 6 | 7 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_supervisor_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch performance_monitor performance_monitor.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" 6 | 7 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_trajectory_controller.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneTrajectoryControllerROSModule droneTrajectoryControllerROSModule.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" 6 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_trajectory_planner.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneTrajectoryPlannerROSModule droneTrajectoryPlanner2dROSModule.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" drone_pose_topic_name:=ArucoSlam_EstimatedPose 6 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/run_yaw_commander.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneYawCommanderROSModule droneYawCommanderROSModule.launch --wait drone_id_int:="0" drone_id_namespace:="drone0" drone_pose_topic_name:=ArucoSlam_EstimatedPose 6 | -------------------------------------------------------------------------------- /launchers/pelican_launchers/sh_files/start_roscore.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roscore 6 | 7 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/launch_files/apm.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/launch_files/bottom_cam.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/launch_files/driver_px4flow_interface_ROSModule.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/launch_files/driver_px4flow_interface_ROSModule_wo_altitude.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/launch_files/hector_imu.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/launch_files/hector_slam.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/launch_files/hector_slam_new.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/launch_files/hokuyo_node.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/launch_files/lightware_altitude_node.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/launch_files/px4_pluginlists.yaml: -------------------------------------------------------------------------------- 1 | plugin_blacklist: 2 | # common 3 | - safety_area 4 | # extras 5 | - image_pub 6 | - vibration 7 | - global_position 8 | 9 | plugin_whitelist: [] 10 | #- 'sys_*' 11 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/launch_files/px4flow.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/launch_files/ros_tld_gui.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/launch_files/rosserial.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/launch_files/teleop.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/launch_files/usb_cam.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/sh_files/run_driver_pixhawk.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch driverPixhawkROSModule driverPixhawkROSModule.launch --wait drone_id_int:="3" drone_id_namespace:="drone3" 6 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/sh_files/run_ekf_odometry.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneEKFStateEstimatorROSModule droneEKFStateEstimatorROSModule.launch --wait drone_id_int:="3" drone_id_namespace:="drone3" 6 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/sh_files/run_interface_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh odroid 5 | roslaunch droneInterfaceROSModule droneInterface_jp_ROSModule.launch --wait drone_id_int:="3" drone_id_namespace:="drone3" 6 | 7 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/sh_files/run_joy_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch driverPixhawkROSModule joyConverterToDrvPixhawkCmdNode.launch --wait drone_id_int:="3" drone_id_namespace:="drone3" joy_device_name:="/dev/input/js0" 6 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/sh_files/run_mavros_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch ${AEROSTACK_STACK}/launchers/pixhawk_launchers/launch_files/px4.launch --wait drone_id_int:="3" drone_id_namespace:="drone3" 6 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/sh_files/run_mavros_node_simulator.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch ${AEROSTACK_STACK}/launchers/pixhawk_launchers/launch_files/px4_SITL.launch --wait drone_id_int:="3" drone_id_namespace:="drone3" 6 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/sh_files/run_midlevelautopilot_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneMidLevelAutopilotROSModule droneMidLevelAutopilotROSModule.launch --wait drone_id_int:="3" drone_id_namespace:="drone3" 6 | 7 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/sh_files/run_px4flow_interface.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch ${AEROSTACK_STACK}/launchers/pixhawk_launchers/launch_files/driver_px4flow_interface_ROSModule.launch --wait drone_id_int:="3" drone_id_namespace:="drone3" 6 | 7 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/sh_files/run_px4flow_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch ${AEROSTACK_STACK}/launchers/pixhawk_launchers/launch_files/px4flow.launch --wait drone_id_int:="3" drone_id_namespace:="drone3" serial_port:="/dev/ttyACM0" 6 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/sh_files/run_supervisor_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch performance_monitor performance_monitor.launch --wait drone_id_int:="3" drone_id_namespace:="drone3" 6 | 7 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/sh_files/run_trajectory_controller.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneTrajectoryControllerROSModule droneTrajectoryControllerROSModule.launch --wait drone_id_int:="3" drone_id_namespace:="drone3" 6 | -------------------------------------------------------------------------------- /launchers/pixhawk_launchers/stop.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | pkill -SIGINT roslaunch 4 | -------------------------------------------------------------------------------- /launchers/pixhawk_simulation_launchers/launch_files/hector_imu.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | -------------------------------------------------------------------------------- /launchers/pixhawk_simulation_launchers/launch_files/px4.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | -------------------------------------------------------------------------------- /launchers/pixhawk_simulation_launchers/launch_files/px4flow.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /launchers/pixhawk_simulation_launchers/launch_files/tutorial.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | -------------------------------------------------------------------------------- /launchers/pixhawk_simulation_launchers/pixhawk_simflight_instructions.md: -------------------------------------------------------------------------------- 1 | screen -AmdS pixhawk -t terminal bash 2 | screen -S pixhawk -X screen -t roscore ${DRONE_STACK}/launchers/screen_launchers/start_roscore.sh 3 | 4 | screen -S pixhawk -X screen -t mavros ${DRONE_STACK}/launchers/pixhawk_simulation_launchers/sh_files/run_mavros_node_simulator.sh 5 | screen -S pixhawk -X screen -t driver_Pixhawk ${DRONE_STACK}/launchers/pixhawk_simulation_launchers/sh_files/run_driver_pixhawk.sh 6 | screen -S pixhawk -X screen -t midlevel_node ${DRONE_STACK}/launchers/pixhawk_simulation_launchers/sh_files/run_midlevelautopilot_node.sh 7 | screen -S pixhawk -X screen -t supervisor ${DRONE_STACK}/launchers/pixhawk_simulation_launchers/sh_files/run_supervisor_node.sh 8 | screen -S pixhawk -X screen -t ekf_odometry ${DRONE_STACK}/launchers/pixhawk_simulation_launchers/sh_files/run_ekf_odometry.sh 9 | screen -S pixhawk -X screen -t trajectory_ctrl ${DRONE_STACK}/launchers/pixhawk_simulation_launchers/sh_files/run_trajectory_controller.sh 10 | 11 | screen -S pixhawk -X screen -t drone_interface ${DRONE_STACK}/launchers/pixhawk_simulation_launchers/sh_files/run_interface_node.sh 12 | -------------------------------------------------------------------------------- /launchers/pixhawk_simulation_launchers/pre_takeoff.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | rosservice call /drone5/droneRobotLocalizationROSModuleNode/start 4 | rosservice call /drone5/mavros/set_mode "base_mode: 0 5 | custom_mode: 'OFFBOARD'" 6 | rosservice call /drone5/mavros/cmd/arming "value: true" 7 | #rosservice call /drone5/droneSubMissionPlanner/start 8 | -------------------------------------------------------------------------------- /launchers/pixhawk_simulation_launchers/sh_files/run_driver_pixhawk.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch driverPixhawkROSModule driverPixhawkROSModuleSim.launch --wait drone_id_int:="5" drone_id_namespace:="drone5" 6 | -------------------------------------------------------------------------------- /launchers/pixhawk_simulation_launchers/sh_files/run_ekf_odometry.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneEKFStateEstimatorROSModule droneEKFStateEstimatorROSModule.launch --wait drone_id_int:="5" drone_id_namespace:="drone5" 6 | -------------------------------------------------------------------------------- /launchers/pixhawk_simulation_launchers/sh_files/run_interface_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneInterfaceROSModule droneInterface_jp_ROSModule.launch --wait drone_id_int:="5" drone_id_namespace:="drone5" 6 | 7 | -------------------------------------------------------------------------------- /launchers/pixhawk_simulation_launchers/sh_files/run_mavros_node_simulator.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch ${DRONE_STACK}/launchers/pixhawk_simulation_launchers/launch_files/px4_SITL.launch --wait drone_id_int:="5" drone_id_namespace:="drone5" 6 | -------------------------------------------------------------------------------- /launchers/pixhawk_simulation_launchers/sh_files/run_midlevelautopilot_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneMidLevelAutopilotROSModule droneMidLevelAutopilotROSModule.launch --wait drone_id_int:="5" drone_id_namespace:="drone5" 6 | 7 | -------------------------------------------------------------------------------- /launchers/pixhawk_simulation_launchers/sh_files/run_supervisor_node.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch performance_monitor performance_monitor.launch --wait drone_id_int:="5" drone_id_namespace:="drone5" 6 | 7 | -------------------------------------------------------------------------------- /launchers/pixhawk_simulation_launchers/sh_files/run_trajectory_controller.sh: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | cd $AEROSTACK_STACK 4 | source setup.sh 5 | roslaunch droneTrajectoryControllerROSModule droneTrajectoryControllerROSModule.launch --wait drone_id_int:="5" drone_id_namespace:="drone5" 6 | -------------------------------------------------------------------------------- /launchers/pixhawk_simulation_launchers/stop.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | pkill -SIGINT roslaunch 4 | -------------------------------------------------------------------------------- /stack_deprecated/utils/CATKIN_IGNORE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/cvar-upm/aerostack/74ee4951d07f5bb7b2c1f0ec17c538cf88dba506/stack_deprecated/utils/CATKIN_IGNORE --------------------------------------------------------------------------------