Browse Source

Copter: brake uses AP_Motors set_desired_spool_state

master
Randy Mackay 9 years ago
parent
commit
10f8e36f9b
  1. 4
      ArduCopter/control_brake.cpp

4
ArduCopter/control_brake.cpp

@ -43,7 +43,7 @@ void Copter::brake_run() @@ -43,7 +43,7 @@ void Copter::brake_run()
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
attitude_control.set_throttle_out(0,false,g.throttle_filt);
#else
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_SPIN_WHEN_ARMED);
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
// multicopters do not stabilize roll/pitch/yaw when disarmed
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
#endif
@ -62,7 +62,7 @@ void Copter::brake_run() @@ -62,7 +62,7 @@ void Copter::brake_run()
}
// set motors to full range
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED);
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
// run brake controller
wp_nav.update_brake(ekfGndSpdLimit, ekfNavVelGainScaler);

Loading…
Cancel
Save