mirror of https://github.com/ArduPilot/ardupilot
Copter: acro uses AP_Motors set_desired_spool_state
This commit is contained in:
parent
56f05e6a96
commit
668561ff0e
|
@ -28,7 +28,7 @@ void Copter::acro_run()
|
|||
|
||||
// if not armed set throttle to zero and exit immediately
|
||||
if (!motors.armed() || ap.throttle_zero || !motors.get_interlock()) {
|
||||
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_SPIN_WHEN_ARMED);
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
// slow start if landed
|
||||
if (ap.land_complete) {
|
||||
|
@ -37,7 +37,7 @@ void Copter::acro_run()
|
|||
return;
|
||||
}
|
||||
|
||||
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED);
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
|
||||
// convert the input to the desired body frame rate
|
||||
get_pilot_desired_angle_rates(channel_roll->control_in, channel_pitch->control_in, channel_yaw->control_in, target_roll, target_pitch, target_yaw);
|
||||
|
|
Loading…
Reference in New Issue