aboutsummaryrefslogtreecommitdiff
path: root/apps/uORB/topics/vehicle_status.h
diff options
context:
space:
mode:
Diffstat (limited to 'apps/uORB/topics/vehicle_status.h')
-rw-r--r--apps/uORB/topics/vehicle_status.h7
1 files changed, 5 insertions, 2 deletions
diff --git a/apps/uORB/topics/vehicle_status.h b/apps/uORB/topics/vehicle_status.h
index 06b4c5ca5..893e34537 100644
--- a/apps/uORB/topics/vehicle_status.h
+++ b/apps/uORB/topics/vehicle_status.h
@@ -156,7 +156,9 @@ struct vehicle_status_s
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 MAVLinks VEHICLE_TYPE enum */
+ 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 */
@@ -171,7 +173,7 @@ struct vehicle_status_s
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_mag_calibration; /**< true if mag calibration is requested */
bool flag_preflight_accel_calibration;
bool rc_signal_found_once;
@@ -209,6 +211,7 @@ struct vehicle_status_s
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) */
};
/**