Copter: circle uses AP_Motors set_desired_spool_state

This commit is contained in:
Randy Mackay 2016-02-02 21:18:27 +09:00
parent 10f8e36f9b
commit 83ae78b38e
1 changed files with 2 additions and 2 deletions

View File

@ -49,7 +49,7 @@ void Copter::circle_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
@ -78,7 +78,7 @@ void Copter::circle_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 circle controller
circle_nav.update();