aboutsummaryrefslogtreecommitdiff
path: root/src/modules/uORB/topics/vehicle_status.h
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/uORB/topics/vehicle_status.h')
-rw-r--r--src/modules/uORB/topics/vehicle_status.h155
1 files changed, 93 insertions, 62 deletions
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index c7c1048f6..2bcd57f4b 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -59,21 +59,58 @@
*/
/* State Machine */
-typedef enum
-{
- SYSTEM_STATE_PREFLIGHT = 0,
- SYSTEM_STATE_STANDBY = 1,
- SYSTEM_STATE_GROUND_READY = 2,
- SYSTEM_STATE_MANUAL = 3,
- SYSTEM_STATE_STABILIZED = 4,
- SYSTEM_STATE_AUTO = 5,
- SYSTEM_STATE_MISSION_ABORT = 6,
- SYSTEM_STATE_EMCY_LANDING = 7,
- SYSTEM_STATE_EMCY_CUTOFF = 8,
- SYSTEM_STATE_GROUND_ERROR = 9,
- SYSTEM_STATE_REBOOT= 10,
-
-} commander_state_machine_t;
+typedef enum {
+ NAVIGATION_STATE_INIT=0,
+ NAVIGATION_STATE_MANUAL_STANDBY,
+ NAVIGATION_STATE_MANUAL,
+ NAVIGATION_STATE_SEATBELT_STANDBY,
+ NAVIGATION_STATE_SEATBELT,
+ NAVIGATION_STATE_SEATBELT_DESCENT,
+ NAVIGATION_STATE_AUTO_STANDBY,
+ NAVIGATION_STATE_AUTO_READY,
+ NAVIGATION_STATE_AUTO_TAKEOFF,
+ NAVIGATION_STATE_AUTO_LOITER,
+ NAVIGATION_STATE_AUTO_MISSION,
+ NAVIGATION_STATE_AUTO_RTL,
+ NAVIGATION_STATE_AUTO_LAND
+} navigation_state_t;
+
+typedef enum {
+ MANUAL_STANDBY = 0,
+ MANUAL_READY,
+ MANUAL_IN_AIR
+} manual_state_t;
+
+typedef enum {
+ ARMING_STATE_INIT = 0,
+ ARMING_STATE_STANDBY,
+ ARMING_STATE_ARMED,
+ ARMING_STATE_ARMED_ERROR,
+ ARMING_STATE_STANDBY_ERROR,
+ ARMING_STATE_REBOOT,
+ ARMING_STATE_IN_AIR_RESTORE
+} arming_state_t;
+
+typedef enum {
+ HIL_STATE_OFF = 0,
+ HIL_STATE_ON
+} hil_state_t;
+
+typedef enum {
+ MODE_SWITCH_MANUAL = 0,
+ MODE_SWITCH_SEATBELT,
+ MODE_SWITCH_AUTO
+} mode_switch_pos_t;
+
+typedef enum {
+ RETURN_SWITCH_NONE = 0,
+ RETURN_SWITCH_RETURN
+} return_switch_pos_t;
+
+typedef enum {
+ MISSION_SWITCH_NONE = 0,
+ MISSION_SWITCH_MISSION
+} mission_switch_pos_t;
enum VEHICLE_MODE_FLAG {
VEHICLE_MODE_FLAG_SAFETY_ARMED = 128,
@@ -86,26 +123,6 @@ enum VEHICLE_MODE_FLAG {
VEHICLE_MODE_FLAG_CUSTOM_MODE_ENABLED = 1
}; /**< Same as MAV_MODE_FLAG of MAVLink 1.0 protocol */
-enum VEHICLE_FLIGHT_MODE {
- VEHICLE_FLIGHT_MODE_MANUAL = 0, /**< direct manual control, exact mode determined by VEHICLE_MANUAL_CONTROL_MODE */
- VEHICLE_FLIGHT_MODE_STAB, /**< attitude or rate stabilization plus velocity or position stabilization */
- VEHICLE_FLIGHT_MODE_HOLD, /**< hold current position (hover or loiter around position when switched) */
- VEHICLE_FLIGHT_MODE_AUTO /**< attitude or rate stabilization plus absolute position control and waypoints */
-};
-
-enum VEHICLE_MANUAL_CONTROL_MODE {
- VEHICLE_MANUAL_CONTROL_MODE_DIRECT = 0, /**< no attitude control, direct stick input mixing (only fixed wing) */
- VEHICLE_MANUAL_CONTROL_MODE_RATES, /**< body rates control mode */
- VEHICLE_MANUAL_CONTROL_MODE_SAS /**< stability augmented system (SAS) mode */
-};
-
-enum VEHICLE_MANUAL_SAS_MODE {
- VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS = 0, /**< roll, pitch and yaw absolute */
- VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_RATE, /**< roll and pitch absolute, yaw rate */
- VEHICLE_MANUAL_SAS_MODE_SIMPLE, /**< simple mode (includes altitude hold) */
- VEHICLE_MANUAL_SAS_MODE_ALTITUDE /**< altitude hold */
-};
-
/**
* Should match 1:1 MAVLink's MAV_TYPE ENUM
*/
@@ -134,7 +151,7 @@ enum VEHICLE_TYPE {
enum VEHICLE_BATTERY_WARNING {
VEHICLE_BATTERY_WARNING_NONE = 0, /**< no battery low voltage warning active */
VEHICLE_BATTERY_WARNING_WARNING, /**< warning of low voltage 1. stage */
- VEHICLE_BATTERY_WARNING_ALERT /**< aleting of low voltage 2. stage */
+ VEHICLE_BATTERY_WARNING_ALERT /**< alerting of low voltage 2. stage */
};
@@ -150,32 +167,55 @@ struct vehicle_status_s
uint16_t counter; /**< incremented by the writing thread everytime new data is stored */
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
uint64_t failsave_lowlevel_start_time; /**< time when the lowlevel failsafe flag was set */
- //uint64_t failsave_highlevel_begin; TO BE COMPLETED
+// uint64_t failsave_highlevel_begin; TO BE COMPLETED
+
+ navigation_state_t navigation_state; /**< current system state */
+ arming_state_t arming_state; /**< current arming state */
+ hil_state_t hil_state; /**< current hil state */
- commander_state_machine_t state_machine; /**< current flight state, main state machine */
- enum VEHICLE_FLIGHT_MODE flight_mode; /**< current flight mode, as defined by mode switch */
- enum VEHICLE_MANUAL_CONTROL_MODE manual_control_mode; /**< current attitude control mode, as defined by VEHICLE_ATTITUDE_MODE enum */
- enum VEHICLE_MANUAL_SAS_MODE manual_sas_mode; /**< current stabilization mode */
int32_t system_type; /**< system type, inspired by MAVLink's VEHICLE_TYPE enum */
int32_t system_id; /**< system id, inspired by MAVLink's system ID field */
int32_t component_id; /**< subsystem / component id, inspired by MAVLink's component ID field */
/* system flags - these represent the state predicates */
- bool flag_system_armed; /**< true is motors / actuators are armed */
- bool flag_control_manual_enabled; /**< true if manual input is mixed in */
- bool flag_control_offboard_enabled; /**< true if offboard control input is on */
+ mode_switch_pos_t mode_switch;
+ return_switch_pos_t return_switch;
+ mission_switch_pos_t mission_switch;
+
+
+ bool condition_system_emergency;
+ bool condition_system_in_air_restore; /**< true if we can restore in mid air */
+ bool condition_system_sensors_initialized;
+ bool condition_system_returned_to_home;
+ bool condition_auto_mission_available;
+ bool condition_global_position_valid; /**< set to true by the commander app if the quality of the gps signal is good enough to use it in the position estimator */
+ bool condition_launch_position_valid; /**< indicates a valid launch position */
+ bool condition_home_position_valid; /**< indicates a valid home position (a valid home position is not always a valid launch) */
+ bool condition_local_position_valid;
+ bool condition_airspeed_valid; /**< set to true by the commander app if there is a valid airspeed measurement available */
+
+ // bool condition_auto_flight_mode_ok; /**< conditions of auto flight mode apply plus a valid takeoff position lock has been aquired */
+ bool flag_external_manual_override_ok; /**< external override non-fatal for system. Only true for fixed wing */
+
bool flag_hil_enabled; /**< true if hardware in the loop simulation is enabled */
+ //bool flag_armed; /**< true is motors / actuators are armed */
+ //bool flag_safety_off; /**< true if safety is off */
+ bool flag_system_emergency;
+ bool flag_preflight_calibration;
- bool flag_control_rates_enabled; /**< true if rates are stabilized */
- bool flag_control_attitude_enabled; /**< true if attitude stabilization is mixed in */
- bool flag_control_velocity_enabled; /**< true if speed (implies direction) is controlled */
- bool flag_control_position_enabled; /**< true if position is controlled */
+ // bool flag_control_manual_enabled; /**< true if manual input is mixed in */
+ // bool flag_control_offboard_enabled; /**< true if offboard control input is on */
+ // bool flag_auto_enabled;
+ // bool flag_control_rates_enabled; /**< true if rates are stabilized */
+ // bool flag_control_attitude_enabled; /**< true if attitude stabilization is mixed in */
+ // bool flag_control_velocity_enabled; /**< true if speed (implies direction) is controlled */
+ // bool flag_control_position_enabled; /**< true if position is controlled */
- bool flag_preflight_gyro_calibration; /**< true if gyro calibration is requested */
- bool flag_preflight_mag_calibration; /**< true if mag calibration is requested */
- bool flag_preflight_accel_calibration;
- bool flag_preflight_airspeed_calibration;
+ // bool flag_preflight_gyro_calibration; /**< true if gyro calibration is requested */
+ // bool flag_preflight_mag_calibration; /**< true if mag calibration is requested */
+ // bool flag_preflight_accel_calibration;
+ // bool flag_preflight_airspeed_calibration;
bool rc_signal_found_once;
bool rc_signal_lost; /**< true if RC reception is terminally lost */
@@ -188,7 +228,7 @@ struct vehicle_status_s
uint64_t offboard_control_signal_lost_interval; /**< interval in microseconds without an offboard control message */
bool failsave_lowlevel; /**< Set to true if low-level failsafe mode is enabled */
- //bool failsave_highlevel;
+ bool failsave_highlevel;
/* see SYS_STATUS mavlink message for the following */
uint32_t onboard_control_sensors_present;
@@ -205,15 +245,6 @@ struct vehicle_status_s
uint16_t errors_count2;
uint16_t errors_count3;
uint16_t errors_count4;
-
- bool flag_global_position_valid; /**< set to true by the commander app if the quality of the gps signal is good enough to use it in the position estimator */
- bool flag_local_position_valid;
- bool flag_vector_flight_mode_ok; /**< position estimation, battery voltage and other critical subsystems are good for autonomous flight */
- bool flag_auto_flight_mode_ok; /**< conditions of vector flight mode apply plus a valid takeoff position lock has been aquired */
- bool flag_external_manual_override_ok; /**< external override non-fatal for system. Only true for fixed wing */
- bool flag_valid_launch_position; /**< indicates a valid launch position */
- bool flag_valid_home_position; /**< indicates a valid home position (a valid home position is not always a valid launch) */
- bool flag_airspeed_valid; /**< set to true by the commander app if there is a valid airspeed measurement available */
};
/**