aboutsummaryrefslogtreecommitdiff
path: root/apps/commander/state_machine_helper.c
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-12-30 09:53:45 +0100
committerLorenz Meier <lm@inf.ethz.ch>2012-12-30 09:53:45 +0100
commit62a95bf8e6592b31ae7e84e53b654bc5e6b71cd1 (patch)
tree07d27e3f0c56bb34c2d505fdafcce4490bf1b17e /apps/commander/state_machine_helper.c
parent0298714db53c44a28ab19d5ba01d70de28dd39b3 (diff)
downloadpx4-firmware-62a95bf8e6592b31ae7e84e53b654bc5e6b71cd1.tar.gz
px4-firmware-62a95bf8e6592b31ae7e84e53b654bc5e6b71cd1.tar.bz2
px4-firmware-62a95bf8e6592b31ae7e84e53b654bc5e6b71cd1.zip
Stabilization enabling / switching
Diffstat (limited to 'apps/commander/state_machine_helper.c')
-rw-r--r--apps/commander/state_machine_helper.c21
1 files changed, 18 insertions, 3 deletions
diff --git a/apps/commander/state_machine_helper.c b/apps/commander/state_machine_helper.c
index a8cef8c01..f30fd975b 100644
--- a/apps/commander/state_machine_helper.c
+++ b/apps/commander/state_machine_helper.c
@@ -520,9 +520,24 @@ 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;
- /* enable attitude control per default */
- current_status->flag_control_attitude_enabled = true;
- current_status->flag_control_rates_enabled = true;
+
+ /* set behaviour based on airframe */
+ if ((current_status.system_type == MAV_TYPE_QUADROTOR) ||
+ (current_status.system_type == MAV_TYPE_HEXAROTOR) ||
+ (current_status.system_type == MAV_TYPE_OCTOROTOR)) {
+
+ /* assuming a rotary wing, set to SAS */
+ current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS;
+ current_status.flag_control_attitude_enabled = true;
+ current_status.flag_control_rates_enabled = true;
+ } else {
+
+ /* assuming a fixed wing, set to direct pass-through */
+ current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_DIRECT;
+ current_status.flag_control_attitude_enabled = false;
+ current_status.flag_control_rates_enabled = false;
+ }
+
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) {