diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp index 41ef4f2bd3..54754cfc60 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp @@ -362,7 +362,7 @@ void AP_MotorsHeli_Dual::calculate_armed_scalars() // allow use of external governor autorotation bailout window on main rotor if (_main_rotor._ext_gov_arot_pct.get() > 0 && (_main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_SPEED_SETPOINT || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH)){ // RSC only needs to know that the vehicle is in an autorotation if using the bailout window on an external governor - _main_rotor.set_autorotaion_flag(_heliflags.in_autorotation); + _main_rotor.set_autorotation_flag(_heliflags.in_autorotation); } } diff --git a/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp b/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp index dd6bcd0e9f..21a38aa7cb 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp @@ -134,7 +134,7 @@ void AP_MotorsHeli_Quad::calculate_armed_scalars() // allow use of external governor autorotation bailout window on main rotor if (_main_rotor._ext_gov_arot_pct.get() > 0 && (_main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_SPEED_SETPOINT || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH)){ // RSC only needs to know that the vehicle is in an autorotation if using the bailout window on an external governor - _main_rotor.set_autorotaion_flag(_heliflags.in_autorotation); + _main_rotor.set_autorotation_flag(_heliflags.in_autorotation); } } diff --git a/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp b/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp index d05356b188..adcd64ebb0 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp @@ -237,7 +237,7 @@ void AP_MotorsHeli_RSC::output(RotorControlState state) // set rotor ramp to decrease speed to zero update_rotor_ramp(0.0f, dt); - if (_in_autorotaion) { + if (_in_autorotation) { // if in autorotation and using an external governor, set the output to tell the governor to use bailout ramp _control_output = constrain_float( _rsc_arot_bailout_pct/100.0f , 0.0f, 0.4f); } else { diff --git a/libraries/AP_Motors/AP_MotorsHeli_RSC.h b/libraries/AP_Motors/AP_MotorsHeli_RSC.h index ca0635d138..72bf9f5dfb 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_RSC.h +++ b/libraries/AP_Motors/AP_MotorsHeli_RSC.h @@ -121,7 +121,7 @@ public: void use_bailout_ramp_time(bool enable) { _use_bailout_ramp = enable; } // use external governor autorotation window - void set_autorotaion_flag(bool flag) { _in_autorotaion = flag; } + void set_autorotation_flag(bool flag) { _in_autorotation = flag; } // set the throttle percentage to be sent to external governor to signal that autorotation bailout ramp should be used within this instance of Heli_RSC void set_ext_gov_arot_bail(int16_t pct) { _rsc_arot_bailout_pct = pct; } @@ -161,7 +161,7 @@ private: float _governor_output; // governor output for rotor speed control bool _governor_engage; // RSC governor status flag for soft-start bool _use_bailout_ramp; // true if allowing RSC to quickly ramp up engine - bool _in_autorotaion; // true if vehicle is currently in an autorotaion + bool _in_autorotation; // true if vehicle is currently in an autorotation int16_t _rsc_arot_bailout_pct; // the throttle percentage sent to the external governor to signal that autorotation bailout ramp should be used // update_rotor_ramp - slews rotor output scalar between 0 and 1, outputs float scalar to _rotor_ramp_output diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index e1a2b5c8a6..9821dfe99c 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -307,10 +307,10 @@ void AP_MotorsHeli_Single::calculate_armed_scalars() if (_main_rotor._ext_gov_arot_pct.get() > 0) { // RSC only needs to know that the vehicle is in an autorotation if using the bailout window on an external governor if (_main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_SPEED_SETPOINT || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH) { - _main_rotor.set_autorotaion_flag(_heliflags.in_autorotation); + _main_rotor.set_autorotation_flag(_heliflags.in_autorotation); } if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV) { - _tail_rotor.set_autorotaion_flag(_heliflags.in_autorotation); + _tail_rotor.set_autorotation_flag(_heliflags.in_autorotation); } }