mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
Copter: tidy zero_throttle_and_relax (NFC)
This commit is contained in:
parent
71ad1b5815
commit
d1201e4776
@ -264,13 +264,13 @@ bool Copter::Mode::takeoff_triggered(const float target_climb_rate) const
|
|||||||
|
|
||||||
void Copter::Mode::zero_throttle_and_relax_ac()
|
void Copter::Mode::zero_throttle_and_relax_ac()
|
||||||
{
|
{
|
||||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
// call attitude controller
|
// Helicopters always stabilize roll/pitch/yaw
|
||||||
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(0, 0, 0, get_smoothing_gain());
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(0.0f, 0.0f, 0.0f, get_smoothing_gain());
|
||||||
attitude_control->set_throttle_out(0,false,g.throttle_filt);
|
attitude_control->set_throttle_out(0.0f, false, g.throttle_filt);
|
||||||
#else
|
#else
|
||||||
motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||||
// multicopters do not stabilize roll/pitch/yaw when disarmed
|
// multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||||
attitude_control->set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
attitude_control->set_throttle_out_unstabilized(0.0f, true, g.throttle_filt);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user