aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/mavlink_messages.cpp
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2014-05-27 21:56:32 +0200
committerJulian Oes <julian@oes.ch>2014-05-27 21:56:32 +0200
commited6c2a5168ca891f20594687acfd3c6bbf7e1cf9 (patch)
treeb71c7b12719a3d4535615aee2cf95a034bc87b13 /src/modules/mavlink/mavlink_messages.cpp
parent063caba36bd2fe26eb4bfa8e546e9551ccc05519 (diff)
downloadpx4-firmware-ed6c2a5168ca891f20594687acfd3c6bbf7e1cf9.tar.gz
px4-firmware-ed6c2a5168ca891f20594687acfd3c6bbf7e1cf9.tar.bz2
px4-firmware-ed6c2a5168ca891f20594687acfd3c6bbf7e1cf9.zip
commander and navigator: lot's of changes, failsafe handling in commander, navigator only for execution (WIP)
Diffstat (limited to 'src/modules/mavlink/mavlink_messages.cpp')
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp86
1 files changed, 53 insertions, 33 deletions
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 70087cf3e..31c0c8f79 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -118,51 +118,71 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
union px4_custom_mode custom_mode;
custom_mode.data = 0;
- if (pos_sp_triplet->nav_state == NAV_STATE_NONE_ON_GROUND
- || pos_sp_triplet->nav_state == NAV_STATE_NONE_IN_AIR) {
- /* use main state when navigator is not active */
- if (status->main_state == MAIN_STATE_MANUAL) {
- *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | (status->is_rotary_wing ? MAV_MODE_FLAG_STABILIZE_ENABLED : 0);
- custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL;
-
- } else if (status->main_state == MAIN_STATE_ALTCTL) {
- *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED;
- custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_ALTCTL;
+ switch (status->set_nav_state) {
- } else if (status->main_state == MAIN_STATE_POSCTL) {
- *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
- custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_POSCTL;
-
- } else if (status->main_state == MAIN_STATE_AUTO) {
- *mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
- custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
- custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_READY;
+ case NAVIGATION_STATE_MANUAL:
+ *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED
+ | (status->is_rotary_wing ? MAV_MODE_FLAG_STABILIZE_ENABLED : 0);
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL;
+ break;
- } else if (status->main_state == MAIN_STATE_ACRO) {
+ case NAVIGATION_STATE_ACRO:
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_ACRO;
- }
-
- } else {
- /* use navigation state when navigator is active */
- *mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
- custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
+ break;
- if (pos_sp_triplet->nav_state == NAV_STATE_AUTO_ON_GROUND) {
- custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_READY;
+ case NAVIGATION_STATE_ALTCTL:
+ *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED
+ | MAV_MODE_FLAG_STABILIZE_ENABLED;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_ALTCTL;
+ break;
- } else if (pos_sp_triplet->nav_state == NAV_STATE_LOITER) {
- custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
+ case NAVIGATION_STATE_POSCTL:
+ *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED
+ | MAV_MODE_FLAG_STABILIZE_ENABLED
+ | MAV_MODE_FLAG_GUIDED_ENABLED;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_POSCTL;
+ break;
- } else if (pos_sp_triplet->nav_state == NAV_STATE_MISSION) {
+ case NAVIGATION_STATE_AUTO_MISSION:
+ *mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
+ | MAV_MODE_FLAG_STABILIZE_ENABLED
+ | MAV_MODE_FLAG_GUIDED_ENABLED;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
+ break;
- } else if (pos_sp_triplet->nav_state == NAV_STATE_RTL) {
+ case NAVIGATION_STATE_AUTO_LOITER:
+ *mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
+ | MAV_MODE_FLAG_STABILIZE_ENABLED
+ | MAV_MODE_FLAG_GUIDED_ENABLED;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
+ custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
+ break;
+
+ case NAVIGATION_STATE_AUTO_RTL:
+ case NAVIGATION_STATE_AUTO_RTL_RC:
+ case NAVIGATION_STATE_AUTO_RTL_DL:
+ *mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
+ | MAV_MODE_FLAG_STABILIZE_ENABLED
+ | MAV_MODE_FLAG_GUIDED_ENABLED;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_RTL;
+ break;
- } else if (pos_sp_triplet->nav_state == NAV_STATE_LAND) {
+ case NAVIGATION_STATE_LAND:
+ *mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
+ | MAV_MODE_FLAG_STABILIZE_ENABLED
+ | MAV_MODE_FLAG_GUIDED_ENABLED;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_LAND;
- }
+ break;
+
+ case NAVIGATION_STATE_TERMINATION:
+ *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL;
+ break;
+
}
*mavlink_custom_mode = custom_mode.data;