mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Copter: circle sets desired spool state
This commit is contained in:
parent
cce426dcb8
commit
f71157c508
@ -42,13 +42,15 @@ void Copter::circle_run()
|
||||
pos_control.set_accel_z(g.pilot_accel_z);
|
||||
|
||||
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
|
||||
if(!ap.auto_armed || ap.land_complete || !motors.get_interlock()) {
|
||||
if (!motors.armed() || !ap.auto_armed || ap.land_complete || !motors.get_interlock()) {
|
||||
// To-Do: add some initialisation of position controllers
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
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 // multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
#else
|
||||
motors.set_desired_spool_state(AP_MotorsMulticopter::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
|
||||
pos_control.set_alt_target_to_current_alt();
|
||||
@ -75,6 +77,9 @@ void Copter::circle_run()
|
||||
}
|
||||
}
|
||||
|
||||
// set motors to full range
|
||||
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED);
|
||||
|
||||
// run circle controller
|
||||
circle_nav.update();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user