aboutsummaryrefslogtreecommitdiff
path: root/apps/commander/commander.c
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-09-21 14:42:57 +0200
committerLorenz Meier <lm@inf.ethz.ch>2012-09-21 14:42:57 +0200
commit8a11f76994f74e4b38e861d559b305c707d78190 (patch)
tree69c9f0c05e9b28be2d108c51f8f6604fd505c1b5 /apps/commander/commander.c
parenteaa431e5ceaaab033510a522ffaf7a72e44e7ae6 (diff)
downloadpx4-firmware-8a11f76994f74e4b38e861d559b305c707d78190.tar.gz
px4-firmware-8a11f76994f74e4b38e861d559b305c707d78190.tar.bz2
px4-firmware-8a11f76994f74e4b38e861d559b305c707d78190.zip
Updated C files for attitude estimator
Diffstat (limited to 'apps/commander/commander.c')
-rw-r--r--apps/commander/commander.c6
1 files changed, 6 insertions, 0 deletions
diff --git a/apps/commander/commander.c b/apps/commander/commander.c
index 011a7be97..578bcd875 100644
--- a/apps/commander/commander.c
+++ b/apps/commander/commander.c
@@ -1365,12 +1365,18 @@ int commander_thread_main(int argc, char *argv[])
//printf("RC: y:%i/t:%i s:%i chans: %i\n", rc_yaw_scale, rc_throttle_scale, mode_switch_rc_value, rc.chan_count);
if (sp_man.override_mode_switch > STICK_ON_OFF_LIMIT) {
+ current_status.flag_control_attitude_enabled = true;
+ current_status.flag_control_rates_enabled = false;
update_state_machine_mode_manual(stat_pub, &current_status, mavlink_fd);
} else if (sp_man.override_mode_switch < -STICK_ON_OFF_LIMIT) {
+ current_status.flag_control_attitude_enabled = true;
+ current_status.flag_control_rates_enabled = false;
update_state_machine_mode_auto(stat_pub, &current_status, mavlink_fd);
} else {
+ current_status.flag_control_attitude_enabled = true;
+ current_status.flag_control_rates_enabled = false;
update_state_machine_mode_stabilized(stat_pub, &current_status, mavlink_fd);
}