Copter: Rename set_attitude_target_to_current_attitude

This commit is contained in:
Leonard Hall 2021-05-25 09:12:49 +09:30 committed by Randy Mackay
parent 359cf8ed0e
commit 017b267fee
2 changed files with 4 additions and 4 deletions

View File

@ -27,13 +27,13 @@ void ModeAcro::run()
switch (motors->get_spool_state()) {
case AP_Motors::SpoolState::SHUT_DOWN:
// Motors Stopped
attitude_control->set_attitude_target_to_current_attitude();
attitude_control->reset_target_and_rate();
attitude_control->reset_rate_controller_I_terms();
break;
case AP_Motors::SpoolState::GROUND_IDLE:
// Landed
attitude_control->set_attitude_target_to_current_attitude();
attitude_control->reset_target_and_rate();
attitude_control->reset_rate_controller_I_terms_smoothly();
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->set_attitude_target_to_current_attitude();
attitude_control->reset_target_and_rate();
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->set_attitude_target_to_current_attitude();
attitude_control->reset_target_and_rate();
attitude_control->reset_rate_controller_I_terms_smoothly();
}
break;