Safer fixed wing mode switching

This commit is contained in:
Lorenz Meier 2012-12-29 11:18:49 +01:00
parent c652f718c0
commit b240e31c1c
1 changed files with 1 additions and 1 deletions

View File

@ -240,7 +240,7 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
/* set flaps to zero */ /* set flaps to zero */
actuators.control[4] = 0.0f; actuators.control[4] = 0.0f;
} else { } else if (vstatus.state_machine == SYSTEM_STATE_MANUAL) {
if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) { if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) {
/* if the RC signal is lost, try to stay level and go slowly back down to ground */ /* if the RC signal is lost, try to stay level and go slowly back down to ground */