Browse Source

Plane: disable quad motors in TRAINING and ACRO too

mission-4.1.18
Andrew Tridgell 9 years ago
parent
commit
71b0d5fb6d
  1. 6
      ArduPlane/quadplane.cpp

6
ArduPlane/quadplane.cpp

@ -659,8 +659,10 @@ float QuadPlane::desired_yaw_rate_cds(void) @@ -659,8 +659,10 @@ float QuadPlane::desired_yaw_rate_cds(void)
*/
void QuadPlane::update_transition(void)
{
if (plane.control_mode == MANUAL) {
// in manual mode quad motors are always off
if (plane.control_mode == MANUAL ||
plane.control_mode == ACRO ||
plane.control_mode == TRAINING) {
// in manual modes quad motors are always off
motors->output_min();
transition_state = TRANSITION_DONE;
return;

Loading…
Cancel
Save