From bd9509548ccf6adf963b919dcee7392684e4e76a Mon Sep 17 00:00:00 2001 From: Gone4Dirt Date: Thu, 25 Jan 2024 17:25:40 +0000 Subject: [PATCH] Copter: Autorotation mode: minor tidy ups --- ArduCopter/mode.h | 4 ++-- ArduCopter/mode_autorotate.cpp | 3 +-- 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 1a4cd881e65ba3..8b7c89adbf4aa7 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -1935,8 +1935,8 @@ class ModeAutorotate : public Mode { float _target_climb_rate_adjust;// Target vertical acceleration used during bail out phase float _target_pitch_adjust; // Target pitch rate used during bail out phase uint32_t _touchdown_time_ms; - bool hover_autorotation; - bool initial_energy_check; + bool hover_autorotation; + bool initial_energy_check; float time_to_impact; enum class Autorotation_Phase { diff --git a/ArduCopter/mode_autorotate.cpp b/ArduCopter/mode_autorotate.cpp index 9a9ee2a05c5b58..a161939fe03e35 100644 --- a/ArduCopter/mode_autorotate.cpp +++ b/ArduCopter/mode_autorotate.cpp @@ -98,8 +98,7 @@ void ModeAutorotate::run() g2.arot._using_rfnd = false; } - // Initialise internal variables - float curr_vel_z = inertial_nav.get_velocity_z_up_cms(); // Current vertical descent + float curr_vel_z = inertial_nav.get_velocity_z_up_cms(); // Update time to impact only if we are not in the touch down phase. This must be updated before the state machine. if (phase_switch != Autorotation_Phase::TOUCH_DOWN) {