diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2012-10-13 12:25:30 +0200 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2012-10-13 12:25:30 +0200 |
commit | 4dbf7befe369ba00a73945a0193f0a061c271dc3 (patch) | |
tree | 63327c7c8984f6f0bc521525de0c410c3d9f0121 /apps/commander/state_machine_helper.c | |
parent | d62ec78ab835153ef3ba480a5a4110465ba34372 (diff) | |
download | px4-firmware-4dbf7befe369ba00a73945a0193f0a061c271dc3.tar.gz px4-firmware-4dbf7befe369ba00a73945a0193f0a061c271dc3.tar.bz2 px4-firmware-4dbf7befe369ba00a73945a0193f0a061c271dc3.zip |
Disable rate control, disable offset estimation
Diffstat (limited to 'apps/commander/state_machine_helper.c')
-rw-r--r-- | apps/commander/state_machine_helper.c | 12 |
1 files changed, 6 insertions, 6 deletions
diff --git a/apps/commander/state_machine_helper.c b/apps/commander/state_machine_helper.c index 57512bfd5..7d766bcdb 100644 --- a/apps/commander/state_machine_helper.c +++ b/apps/commander/state_machine_helper.c @@ -501,10 +501,10 @@ void update_state_machine_mode_manual(int status_pub, struct vehicle_status_s *c { int old_mode = current_status->flight_mode; current_status->flight_mode = VEHICLE_FLIGHT_MODE_MANUAL; - current_status->flag_control_manual_enabled = true; //XXX + current_status->flag_control_manual_enabled = true; /* enable attitude control per default */ current_status->flag_control_attitude_enabled = true; - current_status->flag_control_rates_enabled = true; + current_status->flag_control_rates_enabled = false; // XXX if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd); if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_STABILIZED || current_status->state_machine == SYSTEM_STATE_AUTO) { @@ -517,9 +517,9 @@ void update_state_machine_mode_stabilized(int status_pub, struct vehicle_status_ { int old_mode = current_status->flight_mode; current_status->flight_mode = VEHICLE_FLIGHT_MODE_STABILIZED; - current_status->flag_control_manual_enabled = true; //XXX + current_status->flag_control_manual_enabled = true; current_status->flag_control_attitude_enabled = true; - current_status->flag_control_rates_enabled = true; + current_status->flag_control_rates_enabled = false; // XXX if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd); if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_MANUAL || current_status->state_machine == SYSTEM_STATE_AUTO) { @@ -532,9 +532,9 @@ void update_state_machine_mode_auto(int status_pub, struct vehicle_status_s *cur { int old_mode = current_status->flight_mode; current_status->flight_mode = VEHICLE_FLIGHT_MODE_AUTO; - current_status->flag_control_manual_enabled = true; //XXX + current_status->flag_control_manual_enabled = true; current_status->flag_control_attitude_enabled = true; - current_status->flag_control_rates_enabled = true; + current_status->flag_control_rates_enabled = false; // XXX if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd); if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_MANUAL || current_status->state_machine == SYSTEM_STATE_STABILIZED) { |