#include "gpsUtils.h"#include <common_msgs/state.h>#include <common_msgs/target.h>#include <diagnostic_msgs/DiagnosticArray.h>#include <diagnostic_msgs/DiagnosticStatus.h>#include <fstream>#include <geometry_msgs/Point.h>#include <geometry_msgs/Polygon.h>#include <geometry_msgs/PoseStamped.h>#include <geometry_msgs/TransformStamped.h>#include <mavros_msgs/CommandBool.h>#include <mavros_msgs/CommandHome.h>#include <mavros_msgs/CommandTOL.h>#include <mavros_msgs/HomePosition.h>#include <mavros_msgs/PositionTarget.h>#include <mavros_msgs/SetMode.h>#include <mavros_msgs/State.h>#include <ros/ros.h>#include <sensor_msgs/NavSatFix.h>#include <sstream>#include <std_msgs/Bool.h>#include <std_msgs/Byte.h>#include <std_srvs/Empty.h>#include <std_srvs/Trigger.h>#include <string>#include <tf/tf.h>

Go to the source code of this file.
Classes | |
| class | TaskManager |
| Task manager is used as a central module to communicate with other modules. More... | |
Macros | |
| #define | ENGINE0 0 |
| #define | HOVER 4 |
| #define | LAND 5 |
| #define | MISSION 2 |
| #define | POS_CONTROL 0 |
| #define | SWARM 3 |
| #define | TAKEOFF 1 |
| #define | VEL_CONTROL 1 |
Enumerations | |
| enum | InFlightCheck { kDisarmed, kArmed, kSoftGeoViolated, kHardGeoViolated, kReturnHomeActivated, kLandActivated, kReserved, kBatteryLow, kGPSFail, kAttituteOutofRange } |
| errors_count4: inflight check More... | |
| enum | PreFlightCheck { kAttitudeRollError, kAttitudePitchError, kMagNError, kMagEError, kMagDError, kAccNError, kAccEError, kAccDError, kGPSEphError, kGPSEpvError, kGPSVelNError, kGPSVelEError, kGPSVelDError, kGPSTError, kImuError, kHealth } |
| errors_count3: preflight check (By bits) More... | |
| enum | UavTaskState { kIdle, kReady, kTakeOff, kHover, kMission, kSwarm, kLand } |
| State machine elements. More... | |
| #define ENGINE0 0 |
Definition at line 37 of file ddrone_task_manager.h.
| #define HOVER 4 |
Definition at line 41 of file ddrone_task_manager.h.
| #define LAND 5 |
Definition at line 42 of file ddrone_task_manager.h.
| #define MISSION 2 |
Definition at line 39 of file ddrone_task_manager.h.
| #define POS_CONTROL 0 |
Definition at line 43 of file ddrone_task_manager.h.
| #define SWARM 3 |
Definition at line 40 of file ddrone_task_manager.h.
| #define TAKEOFF 1 |
Definition at line 38 of file ddrone_task_manager.h.
| #define VEL_CONTROL 1 |
Definition at line 44 of file ddrone_task_manager.h.
| enum InFlightCheck |
errors_count4: inflight check
Definition at line 88 of file ddrone_task_manager.h.
| enum PreFlightCheck |
errors_count3: preflight check (By bits)
Definition at line 65 of file ddrone_task_manager.h.
| enum UavTaskState |
State machine elements.
| Enumerator | |
|---|---|
| kIdle | |
| kReady | |
| kTakeOff | |
| kHover | |
| kMission | |
| kSwarm | |
| kLand | |
Definition at line 50 of file ddrone_task_manager.h.