From 3091e51b29d6f5461517394c236172c768a264a1 Mon Sep 17 00:00:00 2001 From: Gone4Dirt Date: Sun, 24 Mar 2024 13:13:58 +0000 Subject: [PATCH] AP_MotorsHeli: Whitespace and comments fixups --- libraries/AP_Motors/AP_MotorsHeli.h | 3 +++ libraries/AP_Motors/AP_MotorsHeli_Dual.cpp | 2 +- libraries/AP_Motors/AP_MotorsHeli_Single.cpp | 2 +- 3 files changed, 5 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index 2ac1ff3c832953..5aab005fc8274f 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -286,8 +286,11 @@ class AP_MotorsHeli : public AP_Motors { AP_Float _cyclic_angle_max_deg; // The blade pitch angle angle contribution in degrees of the cyclic output contribution // internal variables + float _collective_zero_thrust_pct; // collective zero thrust parameter value converted to 0 ~ 1 range + float _collective_land_min_pct; // collective land min parameter value converted to 0 ~ 1 range float _coll_ang_deg[AP_MOTORS_HELI_MAX_INDEPENDENT_COLL]; // collective blade pitch angle contributions for each swashplate after mixing float _cyclic_ang_deg[AP_MOTORS_HELI_MAX_INDEPENDENT_CYCLIC]; // cyclic blade pitch angle contributions for each swashplate after mixing + uint8_t _servo_test_cycle_counter = 0; // number of test cycles left to run after bootup motor_frame_type _frame_type; motor_frame_class _frame_class; diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp index 96a40d7089b10f..fc12a72637368a 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp @@ -422,7 +422,7 @@ void AP_MotorsHeli_Dual::move_actuators(float roll_out, float pitch_out, float c pitch_out = _cyclic_max/4500.0f; limit.pitch = true; } - } else { + } else { // AP_MOTORS_HELI_DUAL_MODE_TANDEM if (roll_out < -_cyclic_max/4500.0f) { roll_out = -_cyclic_max/4500.0f; limit.roll = true; diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index b5769bfa631899..4e9f027a01e461 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -437,7 +437,7 @@ void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float float collective_scalar = ((float)(_collective_max-_collective_min))*0.001f; float collective_out_scaled = collective_out * collective_scalar + (_collective_min - 1000)*0.001f; - // Caculate servo positions from swashplate library + // Calculate servo positions from swashplate library _swashplate.calculate(roll_out, pitch_out, collective_out_scaled); // update the yaw rate using the tail rotor/servo