diff options
author | Julian Oes <julian@oes.ch> | 2014-05-26 20:19:11 +0200 |
---|---|---|
committer | Julian Oes <julian@oes.ch> | 2014-05-26 20:19:11 +0200 |
commit | 063caba36bd2fe26eb4bfa8e546e9551ccc05519 (patch) | |
tree | d8ea5015111793800d945fbc33505088cf5fe12d /src/modules/mavlink/mavlink_messages.cpp | |
parent | 68352cb923d366b66bb68c8d946c4960b6f7ff1a (diff) | |
parent | 36495cdb62e21b30a5a1851ec802c9f6a40c1171 (diff) | |
download | px4-firmware-063caba36bd2fe26eb4bfa8e546e9551ccc05519.tar.gz px4-firmware-063caba36bd2fe26eb4bfa8e546e9551ccc05519.tar.bz2 px4-firmware-063caba36bd2fe26eb4bfa8e546e9551ccc05519.zip |
Merge branch 'master' into navigator_rewrite
Conflicts:
src/drivers/gps/gps.cpp
src/drivers/gps/mtk.cpp
src/modules/commander/commander.cpp
src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
src/modules/navigator/mission.cpp
src/modules/navigator/mission.h
src/modules/navigator/navigator_main.cpp
src/modules/navigator/navigator_state.h
src/modules/position_estimator_inav/position_estimator_inav_main.c
Diffstat (limited to 'src/modules/mavlink/mavlink_messages.cpp')
-rw-r--r-- | src/modules/mavlink/mavlink_messages.cpp | 20 |
1 files changed, 12 insertions, 8 deletions
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index ec90cf599..70087cf3e 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -125,18 +125,22 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set *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_SEATBELT) { + } 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_SEATBELT; + custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_ALTCTL; - } else if (status->main_state == MAIN_STATE_EASY) { + } 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_EASY; + 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; + + } else if (status->main_state == MAIN_STATE_ACRO) { + *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED; + custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_ACRO; } } else { @@ -1139,10 +1143,10 @@ protected: if (manual_sub->update(t)) { mavlink_msg_manual_control_send(_channel, mavlink_system.sysid, - manual->roll * 1000, - manual->pitch * 1000, - manual->yaw * 1000, - manual->throttle * 1000, + manual->x * 1000, + manual->y * 1000, + manual->z * 1000, + manual->r * 1000, 0); } } |