Browse Source

Plane: Quadplane tailsit transition to FW throttle level change

c415-sdk
Henry Wurzburg 5 years ago committed by Andrew Tridgell
parent
commit
3397bce235
  1. 3
      ArduPlane/quadplane.cpp

3
ArduPlane/quadplane.cpp

@ -1711,7 +1711,8 @@ void QuadPlane::update_transition(void)
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd, attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd,
plane.nav_pitch_cd, plane.nav_pitch_cd,
0); 0);
attitude_control->set_throttle_out(motors->get_throttle_hover(), true, 0); // set throttle at either hover throttle or current throttle, whichever is higher, through the transition
attitude_control->set_throttle_out(MAX(motors->get_throttle_hover(),motors->get_throttle()), true, 0);
break; break;
} }

Loading…
Cancel
Save