aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/mavlink.c
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2013-08-23 23:03:59 +0200
committerAnton Babushkin <anton.babushkin@me.com>2013-08-23 23:03:59 +0200
commit5e9b508ea0ec799ab6f8723d114c999beffc347e (patch)
tree635d8c3256b8079ac83819fad4e48dca1e7e195e /src/modules/mavlink/mavlink.c
parent330908225e5fcb1731df20e740dbfe403a7b30b9 (diff)
downloadpx4-firmware-5e9b508ea0ec799ab6f8723d114c999beffc347e.tar.gz
px4-firmware-5e9b508ea0ec799ab6f8723d114c999beffc347e.tar.bz2
px4-firmware-5e9b508ea0ec799ab6f8723d114c999beffc347e.zip
Indicate AUTO submodes in mavlink custom_mode.
Diffstat (limited to 'src/modules/mavlink/mavlink.c')
-rw-r--r--src/modules/mavlink/mavlink.c24
1 files changed, 20 insertions, 4 deletions
diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c
index 6d9ca1120..93ec36d05 100644
--- a/src/modules/mavlink/mavlink.c
+++ b/src/modules/mavlink/mavlink.c
@@ -205,19 +205,35 @@ get_mavlink_mode_and_state(uint8_t *mavlink_state, uint8_t *mavlink_base_mode, u
/* main state */
*mavlink_base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
+ union px4_custom_mode custom_mode;
+ custom_mode.data = 0;
if (v_status.main_state == MAIN_STATE_MANUAL) {
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | (v_status.is_rotary_wing ? MAV_MODE_FLAG_STABILIZE_ENABLED : 0);
- *mavlink_custom_mode = PX4_CUSTOM_MODE_MANUAL;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL;
} else if (v_status.main_state == MAIN_STATE_SEATBELT) {
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED;
- *mavlink_custom_mode = PX4_CUSTOM_MODE_SEATBELT;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_SEATBELT;
} else if (v_status.main_state == MAIN_STATE_EASY) {
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
- *mavlink_custom_mode = PX4_CUSTOM_MODE_EASY;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_EASY;
} else if (v_status.main_state == MAIN_STATE_AUTO) {
*mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
- *mavlink_custom_mode = PX4_CUSTOM_MODE_AUTO;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
+ if (v_status.navigation_state == NAVIGATION_STATE_AUTO_READY) {
+ custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_READY;
+ } else if (v_status.navigation_state == NAVIGATION_STATE_AUTO_TAKEOFF) {
+ custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF;
+ } else if (v_status.navigation_state == NAVIGATION_STATE_AUTO_LOITER) {
+ custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
+ } else if (v_status.navigation_state == NAVIGATION_STATE_AUTO_MISSION) {
+ custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
+ } else if (v_status.navigation_state == NAVIGATION_STATE_AUTO_RTL) {
+ custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_RTL;
+ } else if (v_status.navigation_state == NAVIGATION_STATE_AUTO_LAND) {
+ custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_LAND;
+ }
}
+ *mavlink_custom_mode = custom_mode.data;
/**
* Set mavlink state