mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: use zero_throttle_and_relax_ac in stab, guided, acro and auto
This commit is contained in:
parent
8d658e1dbc
commit
114628afe4
@ -26,8 +26,7 @@ void Copter::ModeAcro::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_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
attitude_control->set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
zero_throttle_and_relax_ac();
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -803,15 +803,7 @@ bool Copter::ModeAuto::payload_place_run_should_run()
|
||||
void Copter::ModeAuto::payload_place_run()
|
||||
{
|
||||
if (!payload_place_run_should_run()) {
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(0, 0, 0, get_smoothing_gain());
|
||||
attitude_control->set_throttle_out(0,false,g.throttle_filt);
|
||||
#else
|
||||
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
|
||||
zero_throttle_and_relax_ac();
|
||||
// set target to current position
|
||||
wp_nav->init_loiter_target();
|
||||
return;
|
||||
|
@ -363,15 +363,7 @@ void Copter::ModeGuided::takeoff_run()
|
||||
if (!motors->armed() || !ap.auto_armed || !motors->get_interlock()) {
|
||||
// initialise wpnav targets
|
||||
wp_nav->shift_wp_origin_to_current_pos();
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(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
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
// reset attitude control targets
|
||||
attitude_control->set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
#endif
|
||||
zero_throttle_and_relax_ac();
|
||||
// clear i term when we're taking off
|
||||
set_throttle_takeoff();
|
||||
return;
|
||||
|
@ -28,8 +28,7 @@ void Copter::ModeStabilize::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_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
attitude_control->set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
zero_throttle_and_relax_ac();
|
||||
return;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user