diff options
author | daregger <daregger@student.ethz.ch> | 2012-10-16 16:49:45 +0200 |
---|---|---|
committer | daregger <daregger@student.ethz.ch> | 2012-10-16 16:49:45 +0200 |
commit | b50bc7798ac463de3e0c3147df46a3f7227df8c3 (patch) | |
tree | 7a7823cf52632136814214509f8f1d07192b8915 /apps/commander | |
parent | 0b26ca84d451adfdf80e956fc1b199def17aafd9 (diff) | |
download | px4-firmware-b50bc7798ac463de3e0c3147df46a3f7227df8c3.tar.gz px4-firmware-b50bc7798ac463de3e0c3147df46a3f7227df8c3.tar.bz2 px4-firmware-b50bc7798ac463de3e0c3147df46a3f7227df8c3.zip |
Wip on inner rate loop
Diffstat (limited to 'apps/commander')
-rw-r--r-- | apps/commander/state_machine_helper.c | 6 |
1 files changed, 3 insertions, 3 deletions
diff --git a/apps/commander/state_machine_helper.c b/apps/commander/state_machine_helper.c index 7d766bcdb..b21f3858f 100644 --- a/apps/commander/state_machine_helper.c +++ b/apps/commander/state_machine_helper.c @@ -504,7 +504,7 @@ void update_state_machine_mode_manual(int status_pub, struct vehicle_status_s *c 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 = false; // XXX + current_status->flag_control_rates_enabled = true; 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) { @@ -519,7 +519,7 @@ void update_state_machine_mode_stabilized(int status_pub, struct vehicle_status_ current_status->flight_mode = VEHICLE_FLIGHT_MODE_STABILIZED; current_status->flag_control_manual_enabled = true; current_status->flag_control_attitude_enabled = true; - current_status->flag_control_rates_enabled = false; // XXX + current_status->flag_control_rates_enabled = true; 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) { @@ -534,7 +534,7 @@ void update_state_machine_mode_auto(int status_pub, struct vehicle_status_s *cur current_status->flight_mode = VEHICLE_FLIGHT_MODE_AUTO; current_status->flag_control_manual_enabled = true; current_status->flag_control_attitude_enabled = true; - current_status->flag_control_rates_enabled = false; // XXX + current_status->flag_control_rates_enabled = true; 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) { |