aboutsummaryrefslogtreecommitdiff
path: root/apps/commander/state_machine_helper.c
diff options
context:
space:
mode:
authortnaegeli <naegelit@student.ethz.ch>2012-10-09 16:31:04 +0200
committertnaegeli <naegelit@student.ethz.ch>2012-10-09 16:31:04 +0200
commit613e12fcac07a17e6b9d25b05f58c8a1b9587f5e (patch)
treeb6ce6ef89c1f4bbef7ada6f32a3342bb727d4d61 /apps/commander/state_machine_helper.c
parentf292b03772ddf9a0ae72615248c65959a110d8e2 (diff)
downloadpx4-firmware-613e12fcac07a17e6b9d25b05f58c8a1b9587f5e.tar.gz
px4-firmware-613e12fcac07a17e6b9d25b05f58c8a1b9587f5e.tar.bz2
px4-firmware-613e12fcac07a17e6b9d25b05f58c8a1b9587f5e.zip
working offboard
Diffstat (limited to 'apps/commander/state_machine_helper.c')
-rw-r--r--apps/commander/state_machine_helper.c6
1 files changed, 3 insertions, 3 deletions
diff --git a/apps/commander/state_machine_helper.c b/apps/commander/state_machine_helper.c
index 1e82bc417..57512bfd5 100644
--- a/apps/commander/state_machine_helper.c
+++ b/apps/commander/state_machine_helper.c
@@ -503,7 +503,7 @@ void update_state_machine_mode_manual(int status_pub, struct vehicle_status_s *c
current_status->flight_mode = VEHICLE_FLIGHT_MODE_MANUAL;
current_status->flag_control_manual_enabled = true; //XXX
/* enable attitude control per default */
- current_status->flag_control_attitude_enabled = false;
+ current_status->flag_control_attitude_enabled = true;
current_status->flag_control_rates_enabled = true;
if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd);
@@ -518,7 +518,7 @@ 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_attitude_enabled = false;
+ current_status->flag_control_attitude_enabled = true;
current_status->flag_control_rates_enabled = true;
if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd);
@@ -533,7 +533,7 @@ 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_attitude_enabled = false;
+ current_status->flag_control_attitude_enabled = true;
current_status->flag_control_rates_enabled = true;
if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd);