Copter: Don't reset yaw rate when disarmed or ground idle in Heli Stab and Acro

This commit is contained in:
Leonard Hall 2021-07-09 21:42:25 +09:30 committed by Randy Mackay
parent 4664ed6d7d
commit a066e1fcb1
7 changed files with 9 additions and 9 deletions

View File

@ -27,7 +27,7 @@ void ModeAcro::run()
switch (motors->get_spool_state()) {
case AP_Motors::SpoolState::SHUT_DOWN:
// Motors Stopped
attitude_control->reset_target_and_rate();
attitude_control->reset_target_and_rate(true);
attitude_control->reset_rate_controller_I_terms();
break;

View File

@ -45,14 +45,14 @@ void ModeAcro_Heli::run()
switch (motors->get_spool_state()) {
case AP_Motors::SpoolState::SHUT_DOWN:
// Motors Stopped
attitude_control->reset_target_and_rate();
attitude_control->reset_target_and_rate(false);
attitude_control->reset_rate_controller_I_terms();
break;
case AP_Motors::SpoolState::GROUND_IDLE:
// If aircraft is landed, set target heading to current and reset the integrator
// Otherwise motors could be at ground idle for practice autorotation
if ((motors->init_targets_on_arming() && motors->using_leaky_integrator()) || (copter.ap.land_complete && !motors->using_leaky_integrator())) {
attitude_control->reset_target_and_rate();
attitude_control->reset_target_and_rate(false);
attitude_control->reset_rate_controller_I_terms_smoothly();
}
break;

View File

@ -50,7 +50,7 @@ void ModeAltHold::run()
case AltHold_MotorStopped:
attitude_control->reset_rate_controller_I_terms();
attitude_control->reset_yaw_target_and_rate();
attitude_control->reset_yaw_target_and_rate(false);
pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
break;

View File

@ -91,7 +91,7 @@ void ModeDrift::run()
switch (motors->get_spool_state()) {
case AP_Motors::SpoolState::SHUT_DOWN:
// Motors Stopped
attitude_control->reset_yaw_target_and_rate();
attitude_control->reset_yaw_target_and_rate(false);
attitude_control->reset_rate_controller_I_terms();
break;

View File

@ -102,7 +102,7 @@ void ModePosHold::run()
case AltHold_MotorStopped:
attitude_control->reset_rate_controller_I_terms();
attitude_control->reset_yaw_target_and_rate();
attitude_control->reset_yaw_target_and_rate(false);
pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
loiter_nav->clear_pilot_desired_acceleration();
loiter_nav->init_target();

View File

@ -76,7 +76,7 @@ void ModeSport::run()
case AltHold_MotorStopped:
attitude_control->reset_rate_controller_I_terms();
attitude_control->reset_yaw_target_and_rate();
attitude_control->reset_yaw_target_and_rate(false);
pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
break;

View File

@ -50,14 +50,14 @@ void ModeStabilize_Heli::run()
switch (motors->get_spool_state()) {
case AP_Motors::SpoolState::SHUT_DOWN:
// Motors Stopped
attitude_control->reset_yaw_target_and_rate();
attitude_control->reset_yaw_target_and_rate(false);
attitude_control->reset_rate_controller_I_terms();
break;
case AP_Motors::SpoolState::GROUND_IDLE:
// If aircraft is landed, set target heading to current and reset the integrator
// Otherwise motors could be at ground idle for practice autorotation
if ((motors->init_targets_on_arming() && motors->using_leaky_integrator()) || (copter.ap.land_complete && !motors->using_leaky_integrator())) {
attitude_control->reset_yaw_target_and_rate();
attitude_control->reset_yaw_target_and_rate(false);
attitude_control->reset_rate_controller_I_terms_smoothly();
}
break;