aboutsummaryrefslogtreecommitdiff
path: root/apps/uORB/topics/vehicle_status.h
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2012-08-19 14:14:55 +0200
committerThomas Gubler <thomasgubler@gmail.com>2012-08-19 14:14:55 +0200
commitb440b687aa2155a0ae0676236a80db9587a50190 (patch)
tree8cb9eded12ea8b5a253f8d26e7dec967360080e4 /apps/uORB/topics/vehicle_status.h
parent1cf92ad605f6270c76f701321059dc7fe4f91d8a (diff)
parent2a5fcd917428fa6e549214f8066690672b453af0 (diff)
downloadpx4-firmware-b440b687aa2155a0ae0676236a80db9587a50190.tar.gz
px4-firmware-b440b687aa2155a0ae0676236a80db9587a50190.tar.bz2
px4-firmware-b440b687aa2155a0ae0676236a80db9587a50190.zip
Merge branch 'master' of https://github.com/PX4/Firmware
Diffstat (limited to 'apps/uORB/topics/vehicle_status.h')
-rw-r--r--apps/uORB/topics/vehicle_status.h40
1 files changed, 27 insertions, 13 deletions
diff --git a/apps/uORB/topics/vehicle_status.h b/apps/uORB/topics/vehicle_status.h
index 8b2b6525c..c378b05f1 100644
--- a/apps/uORB/topics/vehicle_status.h
+++ b/apps/uORB/topics/vehicle_status.h
@@ -87,9 +87,16 @@ enum VEHICLE_MODE_FLAG {
}; /**< Same as MAV_MODE_FLAG of MAVLink 1.0 protocol */
enum VEHICLE_FLIGHT_MODE {
- VEHICLE_FLIGHT_MODE_MANUAL,
- VEHICLE_FLIGHT_MODE_STABILIZED,
- VEHICLE_FLIGHT_MODE_AUTO
+ VEHICLE_FLIGHT_MODE_MANUAL = 0, /**< direct manual control, same as VEHICLE_FLIGHT_MODE_ATTITUDE for multirotors */
+ VEHICLE_FLIGHT_MODE_ATTITUDE, /**< attitude or rate stabilization, as defined by VEHICLE_ATTITUDE_MODE */
+ VEHICLE_FLIGHT_MODE_STABILIZED, /**< attitude or rate stabilization plus velocity or position stabilization */
+ VEHICLE_FLIGHT_MODE_AUTO /**< attitude or rate stabilization plus absolute position control and waypoints */
+};
+
+enum VEHICLE_ATTITUDE_MODE {
+ VEHICLE_ATTITUDE_MODE_DIRECT, /**< no attitude control, direct stick input mixing (only fixed wing) */
+ VEHICLE_ATTITUDE_MODE_RATES, /**< body rates control mode */
+ VEHICLE_ATTITUDE_MODE_ATTITUDE /**< tait-bryan attitude control mode */
};
/**
@@ -106,14 +113,21 @@ struct vehicle_status_s
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_ATTITUDE_MODE attitute_mode; /**< Current attitude control mode, as defined by VEHICLE_ATTITUDE_MODE enum */
+
+ // uint8_t mode;
+
+
+ /* system flags - these represent the state predicates */
- uint8_t mode;
+ bool flag_system_armed; /**< True is motors / actuators are armed */
+ bool flag_control_manual_enabled; /**< true if manual input is mixed in */
+ bool flag_hil_enabled; /**< True if hardware in the loop simulation is enabled */
- bool control_manual_enabled; /**< true if manual input is mixed in */
- bool control_rates_enabled; /**< true if rates are stabilized */
- bool control_attitude_enabled; /**< true if attitude stabilization is mixed in */
- bool control_speed_enabled; /**< true if speed (implies direction) is controlled */
- bool control_position_enabled; /**< true if position is controlled */
+ // bool flag_control_rates_enabled; /**< true if rates are stabilized */
+ // bool flag_control_attitude_enabled; *< true if attitude stabilization is mixed in
+ // bool control_speed_enabled; /**< true if speed (implies direction) is controlled */
+ // bool control_position_enabled; /**< true if position is controlled */
bool preflight_gyro_calibration; /**< true if gyro calibration is requested */
bool preflight_mag_calibration; /**< true if mag calibration is requested */
@@ -126,10 +140,10 @@ struct vehicle_status_s
uint32_t onboard_control_sensors_present;
uint32_t onboard_control_sensors_enabled;
uint32_t onboard_control_sensors_health;
- uint16_t load;
- uint16_t voltage_battery;
- int16_t current_battery;
- int8_t battery_remaining;
+ float load;
+ float voltage_battery;
+ float current_battery;
+ float battery_remaining;
uint16_t drop_rate_comm;
uint16_t errors_comm;
uint16_t errors_count1;