aboutsummaryrefslogtreecommitdiff
path: root/apps/commander/state_machine_helper.c
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-10-04 10:56:55 +0200
committerLorenz Meier <lm@inf.ethz.ch>2012-10-04 10:56:55 +0200
commit2a06b66845542b05e3cad3d21099e33adc213227 (patch)
tree3b10d28cba955525c8ac37c7d1d348d0a91ac16a /apps/commander/state_machine_helper.c
parentdfae108e6aff6e77eb05def50d99fb5c6d2c28c8 (diff)
downloadpx4-firmware-2a06b66845542b05e3cad3d21099e33adc213227.tar.gz
px4-firmware-2a06b66845542b05e3cad3d21099e33adc213227.tar.bz2
px4-firmware-2a06b66845542b05e3cad3d21099e33adc213227.zip
Fixed inner yaw rate loop
Diffstat (limited to 'apps/commander/state_machine_helper.c')
-rw-r--r--apps/commander/state_machine_helper.c13
1 files changed, 9 insertions, 4 deletions
diff --git a/apps/commander/state_machine_helper.c b/apps/commander/state_machine_helper.c
index e1d24d6a6..1e82bc417 100644
--- a/apps/commander/state_machine_helper.c
+++ b/apps/commander/state_machine_helper.c
@@ -501,9 +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;
+ current_status->flag_control_manual_enabled = true; //XXX
/* enable attitude control per default */
- current_status->flag_control_attitude_enabled = true;
+ current_status->flag_control_attitude_enabled = false;
+ 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) {
@@ -516,7 +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;
+ current_status->flag_control_manual_enabled = true; //XXX
+ current_status->flag_control_attitude_enabled = false;
+ 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) {
@@ -529,7 +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;
+ current_status->flag_control_manual_enabled = true; //XXX
+ current_status->flag_control_attitude_enabled = false;
+ 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) {