From 017b267fee3af8e593e0d1f52468aaab5b66b319 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Tue, 25 May 2021 09:12:49 +0930 Subject: [PATCH] Copter: Rename set_attitude_target_to_current_attitude --- ArduCopter/mode_acro.cpp | 4 ++-- ArduCopter/mode_acro_heli.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/mode_acro.cpp b/ArduCopter/mode_acro.cpp index 0f0e61aa6d..3af360a1df 100644 --- a/ArduCopter/mode_acro.cpp +++ b/ArduCopter/mode_acro.cpp @@ -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; diff --git a/ArduCopter/mode_acro_heli.cpp b/ArduCopter/mode_acro_heli.cpp index 04af9cf66d..89f256c2f6 100644 --- a/ArduCopter/mode_acro_heli.cpp +++ b/ArduCopter/mode_acro_heli.cpp @@ -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;