AP_MotorsHeli: Consolidate all autorotation state into its own class within RSC

This commit is contained in:
Gone4Dirt 2024-07-29 07:33:39 +01:00 committed by Peter Barker
parent 969979cd17
commit 431cc25dca
8 changed files with 141 additions and 205 deletions

View File

@ -18,6 +18,7 @@
#include "AP_MotorsHeli.h"
#include <GCS_MAVLink/GCS.h>
#include <AP_Logger/AP_Logger.h>
#include <AC_Autorotation/RSC_Autorotation.h>
extern const AP_HAL::HAL& hal;
@ -147,6 +148,10 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
// @User: Standard
AP_GROUPINFO("COL_LAND_MIN", 32, AP_MotorsHeli, _collective_land_min_deg, AP_MOTORS_HELI_COLLECTIVE_LAND_MIN),
// @Group: RSC_AROT_
// @Path: ../AC_Autorotation/RSC_Autorotation.cpp
AP_SUBGROUPINFO(_main_rotor.autorotation, "RSC_AROT_", 33, AP_MotorsHeli, RSC_Autorotation),
AP_GROUPEND
};
@ -554,6 +559,10 @@ bool AP_MotorsHeli::arming_checks(size_t buflen, char *buffer) const
return false;
}
if (!_main_rotor.autorotation.arming_checks(buflen, buffer)) {
return false;
}
return true;
}
@ -606,7 +615,7 @@ void AP_MotorsHeli::set_rotor_runup_complete(bool new_value)
#if HAL_LOGGING_ENABLED
if (!_heliflags.rotor_runup_complete && new_value) {
LOGGER_WRITE_EVENT(LogEvent::ROTOR_RUNUP_COMPLETE);
} else if (_heliflags.rotor_runup_complete && !new_value && !_heliflags.in_autorotation) {
} else if (_heliflags.rotor_runup_complete && !new_value && !_main_rotor.in_autorotation()) {
LOGGER_WRITE_EVENT(LogEvent::ROTOR_SPEED_BELOW_CRITICAL);
}
#endif
@ -623,3 +632,19 @@ float AP_MotorsHeli::get_cyclic_angle_scaler(void) const {
return ((float)(_collective_max-_collective_min))*1e-3 * (_collective_max_deg.get() - _collective_min_deg.get()) * 2.0;
}
#endif
// Helper function for param conversions to be done in motors class
void AP_MotorsHeli::heli_motors_param_conversions(void)
{
// PARAMETER_CONVERSION - Added: Sep-2024
// move autorotation related parameters within the RSC into their own class
const AP_Param::ConversionInfo rsc_arot_conversion_info[] = {
{ 90, 108096, AP_PARAM_INT8, "H_RSC_AROT_ENBL" },
{ 90, 104000, AP_PARAM_INT8, "H_RSC_AROT_RAMP" },
{ 90, 112192, AP_PARAM_INT16, "H_RSC_AROT_IDLE" },
};
uint8_t table_size = ARRAY_SIZE(rsc_arot_conversion_info);
for (uint8_t i=0; i<table_size; i++) {
AP_Param::convert_old_parameter(&rsc_arot_conversion_info[i], 1.0);
}
}

View File

@ -81,9 +81,6 @@ public:
// get_rsc_setpoint - gets contents of _rsc_setpoint parameter (0~1)
float get_rsc_setpoint() const { return _main_rotor._rsc_setpoint.get() * 0.01f; }
// arot_man_enabled - gets contents of manual_autorotation_enabled parameter
bool arot_man_enabled() const { return (_main_rotor._rsc_arot_man_enable.get() == 1) ? true : false; }
// set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1
virtual void set_desired_rotor_speed(float desired_speed);
@ -121,14 +118,17 @@ public:
// support passing init_targets_on_arming flag to greater code
bool init_targets_on_arming() const override { return _heliflags.init_targets_on_arming; }
// set_in_autorotation - allows main code to set when aircraft is in autorotation.
void set_in_autorotation(bool autorotation) { _heliflags.in_autorotation = autorotation; }
// helper for vehicle code to request autorotation states in the RSC.
void set_autorotation_active(bool tf) { _main_rotor.autorotation.set_active(tf, false); }
// get_in_autorotation - allows main code to determine when aircraft is in autorotation.
bool get_in_autorotation() { return _heliflags.in_autorotation; }
// helper to force the RSC autorotation state to deactivated
void force_deactivate_autorotation(void) { _main_rotor.autorotation.set_active(false, true); }
// set_enable_bailout - allows main code to set when RSC can immediately ramp engine instantly
void set_enable_bailout(bool bailout) { _heliflags.enable_bailout = bailout; }
// true if RSC is actively autorotating or bailing out
bool in_autorotation(void) const { return _main_rotor.in_autorotation(); }
// true if bailing out autorotation
bool autorotation_bailout(void) const { return _main_rotor.autorotation.bailing_out(); }
// set land complete flag
void set_land_complete(bool landed) { _heliflags.land_complete = landed; }
@ -154,7 +154,7 @@ public:
void _output_test_seq(uint8_t motor_seq, int16_t pwm) override {};
// Helper function for param conversions to be done in motors class
virtual void heli_motors_param_conversions(void) { return; }
virtual void heli_motors_param_conversions(void);
// var_info for holding Parameter information
static const struct AP_Param::GroupInfo var_info[];
@ -248,8 +248,6 @@ protected:
uint8_t rotor_runup_complete : 1; // true if the rotors have had enough time to wind up
uint8_t init_targets_on_arming : 1; // 0 if targets were initialized, 1 if targets were not initialized after arming
uint8_t save_rsc_mode : 1; // used to determine the rsc mode needs to be saved while disarmed
uint8_t in_autorotation : 1; // true if aircraft is in autorotation
uint8_t enable_bailout : 1; // true if allowing RSC to quickly ramp up engine
uint8_t servo_test_running : 1; // true if servo_test is running
uint8_t land_complete : 1; // true if aircraft is landed
uint8_t takeoff_collective : 1; // true if collective is above 30% between H_COL_MID and H_COL_MAX

View File

@ -248,14 +248,6 @@ void AP_MotorsHeli_Dual::calculate_armed_scalars()
_main_rotor._rsc_mode.save();
_heliflags.save_rsc_mode = false;
}
if (_heliflags.in_autorotation) {
_main_rotor.set_autorotation_flag(_heliflags.in_autorotation);
// set bailout ramp time
_main_rotor.use_bailout_ramp_time(_heliflags.enable_bailout);
}else {
_main_rotor.set_autorotation_flag(false);
}
}
// calculate_scalars

View File

@ -80,14 +80,6 @@ void AP_MotorsHeli_Quad::calculate_armed_scalars()
_main_rotor._rsc_mode.save();
_heliflags.save_rsc_mode = false;
}
if (_heliflags.in_autorotation) {
_main_rotor.set_autorotation_flag(_heliflags.in_autorotation);
// set bailout ramp time
_main_rotor.use_bailout_ramp_time(_heliflags.enable_bailout);
}else {
_main_rotor.set_autorotation_flag(false);
}
}
// calculate_scalars

View File

@ -20,6 +20,30 @@
#include <AP_RPM/AP_RPM.h>
#include <AP_Logger/AP_Logger.h>
// default main rotor speed (ch8 out) as a number from 0 ~ 100
#define AP_MOTORS_HELI_RSC_SETPOINT 70
// default main rotor critical speed
#define AP_MOTORS_HELI_RSC_CRITICAL 50
// RSC output defaults
#define AP_MOTORS_HELI_RSC_IDLE_DEFAULT 0
// default main rotor ramp up time in seconds
#define AP_MOTORS_HELI_RSC_RAMP_TIME 1 // 1 second to ramp output to main rotor ESC to setpoint
#define AP_MOTORS_HELI_RSC_RUNUP_TIME 10 // 10 seconds for rotor to reach full speed
// Throttle Curve Defaults
#define AP_MOTORS_HELI_RSC_THRCRV_0_DEFAULT 25
#define AP_MOTORS_HELI_RSC_THRCRV_25_DEFAULT 32
#define AP_MOTORS_HELI_RSC_THRCRV_50_DEFAULT 38
#define AP_MOTORS_HELI_RSC_THRCRV_75_DEFAULT 50
#define AP_MOTORS_HELI_RSC_THRCRV_100_DEFAULT 100
// RSC governor defaults
#define AP_MOTORS_HELI_RSC_GOVERNOR_RANGE_DEFAULT 100
extern const AP_HAL::HAL& hal;
const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
@ -194,30 +218,11 @@ const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
// @User: Standard
AP_GROUPINFO("GOV_TORQUE", 24, AP_MotorsHeli_RSC, _governor_torque, 30),
// @Param: AROT_ENG_T
// @DisplayName: Time for in-flight power re-engagement
// @Description: amount of seconds to move throttle output from idle to throttle curve position during manual autorotations
// @Range: 0 10
// @Units: %
// @Increment: 0.5
// @User: Standard
AP_GROUPINFO("AROT_ENG_T", 25, AP_MotorsHeli_RSC, _rsc_arot_engage_time, AP_MOTORS_HELI_RSC_AROT_ENGAGE_TIME),
// 25 was AROT_ENG_T, has been moved to AROT_RAMP in RSC autorotation sub group
// @Param: AROT_MN_EN
// @DisplayName: Enable Manual Autorotations
// @Description: Allows you to enable (1) or disable (0) the manual autorotation capability.
// @Values: 0:Disabled,1:Enabled
// @User: Standard
AP_GROUPINFO("AROT_MN_EN", 26, AP_MotorsHeli_RSC, _rsc_arot_man_enable, 0),
// 26 was AROT_MN_EN, moved to H_RSC_AROT_ENBL in RSC autorotation sub group
// @Param: AROT_IDLE
// @DisplayName: Idle Throttle Percentage during Autorotation
// @Description: Idle throttle used for all RSC modes. For external governors, this would be set to signal it to enable fast spool-up, when bailing out of an autorotation. Set 0 to disable. If also using a tail rotor of type DDVP with external governor then this value must lie within the autorotation window of both governors.
// @Range: 0 40
// @Units: %
// @Increment: 1
// @User: Standard
AP_GROUPINFO("AROT_IDLE", 27, AP_MotorsHeli_RSC, _arot_idle_output, AP_MOTORS_HELI_RSC_AROT_IDLE),
// 27 was AROT_IDLE, moved to RSC autorotation sub group
AP_GROUPEND
};
@ -247,6 +252,8 @@ void AP_MotorsHeli_RSC::set_throttle_curve()
// output - update value to send to ESC/Servo
void AP_MotorsHeli_RSC::output(RotorControlState state)
{
// Store rsc state for logging
_rsc_state = state;
// _rotor_RPM available to the RSC output
#if AP_RPM_ENABLED
const AP_RPM *rpm = AP_RPM::get_singleton();
@ -289,9 +296,9 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
_governor_fault = false;
//turbine start flag on
_starting = true;
_autorotating = false;
_bailing_out = false;
_gov_bailing_out = false;
// ensure we always deactivate the autorotation state if we disarm
autorotation.set_active(false, true);
// ensure _idle_throttle not set to invalid value
_idle_throttle = get_idle_output();
@ -309,44 +316,36 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
governor_reset();
_autothrottle = false;
_governor_fault = false;
if (_in_autorotation) {
// if in autorotation, set the output to idle for autorotation. This will tell an external governor to use fast ramp for spool up.
// if autorotation idle is set to zero then default to the RSC idle value.
if (_arot_idle_output == 0) {
// turbine start sequence
if (_turbine_start && _starting == true ) {
_idle_throttle += 0.001f;
if (_control_output >= 1.0f) {
_idle_throttle = get_idle_output();
} else {
_idle_throttle = constrain_float( get_arot_idle_output(), 0.0f, 0.4f);
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Turbine startup");
_starting = false;
}
if (!_autorotating) {
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Autorotation");
_autorotating =true;
}
} else {
if (_autorotating) {
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Autorotation Stopped");
_autorotating =false;
}
// set rotor control speed to idle speed parameter, this happens instantly and ignores ramping
if (_turbine_start && _starting == true ) {
_idle_throttle += 0.001f;
if (_control_output >= 1.0f) {
_idle_throttle = get_idle_output();
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Turbine startup");
_starting = false;
}
} else {
_idle_throttle = get_idle_output();
if (_fast_idle_timer > 0.0) {
// running at fast idle for engine cool down
_idle_throttle *= 1.5;
_fast_idle_timer -= dt;
}
}
// this resets the bailout feature if the aircraft has landed.
_use_bailout_ramp = false;
_bailing_out = false;
_gov_bailing_out = false;
_control_output = _idle_throttle;
break;
}
// all other idle throttle functions below this require idle throttle to be reset to H_RSC_IDLE on each call
_idle_throttle = get_idle_output();
// check if we need to use autorotation idle throttle
if (autorotation.get_idle_throttle(_idle_throttle)) {
// if we are here then we are autorotating
_control_output = _idle_throttle;
break;
}
// check if we need to use engine cooldown
if (_fast_idle_timer > 0.0) {
// running at fast idle for engine cool down
_idle_throttle *= 1.5;
_fast_idle_timer -= dt;
}
_control_output = _idle_throttle;
break;
@ -365,7 +364,6 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
}
// if turbine engine started without using start sequence, set starting flag just to be sure it can't be triggered when back in idle
_starting = false;
_autorotating = false;
if ((_control_mode == ROTOR_CONTROL_MODE_PASSTHROUGH) || (_control_mode == ROTOR_CONTROL_MODE_SETPOINT)) {
// set control rotor speed to ramp slewed value between idle and desired speed
@ -396,38 +394,20 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
// update_rotor_ramp - slews rotor output scalar between 0 and 1, outputs float scalar to _rotor_ramp_output
void AP_MotorsHeli_RSC::update_rotor_ramp(float rotor_ramp_input, float dt)
{
int8_t ramp_time;
int8_t bailout_time;
// sanity check ramp time and enable bailout if set
if (_ramp_time <= 0) {
ramp_time = 1;
} else {
ramp_time = _ramp_time;
}
float ramp_time = MAX(float(_ramp_time.get()), 1.0);
if (_rsc_arot_engage_time <= 0) {
bailout_time = 1;
} else {
bailout_time = _rsc_arot_engage_time;
// check if we need to use the bailout ramp up rate for the autorotation case
if (autorotation.bailing_out()) {
ramp_time = autorotation.get_bailout_ramp();
}
// ramp output upwards towards target
if (_rotor_ramp_output < rotor_ramp_input) {
if (_use_bailout_ramp) {
if (!_bailing_out) {
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "bailing_out");
_bailing_out = true;
if (_control_mode == ROTOR_CONTROL_MODE_AUTOTHROTTLE) {_gov_bailing_out = true;}
}
_rotor_ramp_output += (dt / bailout_time);
} else {
_rotor_ramp_output += (dt / ramp_time);
}
if (_rotor_ramp_output > rotor_ramp_input) {
_rotor_ramp_output = rotor_ramp_input;
_bailing_out = false;
_use_bailout_ramp = false;
}
_rotor_ramp_output += (dt / ramp_time);
// Do not allow output to exceed requested input
_rotor_ramp_output = MIN(_rotor_ramp_output, rotor_ramp_input);
} else {
// ramping down happens instantly
_rotor_ramp_output = rotor_ramp_input;
@ -437,14 +417,13 @@ void AP_MotorsHeli_RSC::update_rotor_ramp(float rotor_ramp_input, float dt)
// update_rotor_runup - function to slew rotor runup scalar, outputs float scalar to _rotor_runup_ouptut
void AP_MotorsHeli_RSC::update_rotor_runup(float dt)
{
int8_t runup_time = _runup_time;
float runup_time = _runup_time;
// sanity check runup time
runup_time = MAX(_ramp_time+1,runup_time);
// adjust rotor runup when bailing out
if (_use_bailout_ramp) {
// maintain same delta as set in parameters
runup_time = _runup_time-_ramp_time+1;
// adjust rotor runup when in autorotation or bailing out
if (in_autorotation()) {
runup_time = autorotation.get_runup_time();
}
// protect against divide by zero
@ -465,7 +444,7 @@ void AP_MotorsHeli_RSC::update_rotor_runup(float dt)
}
// if in autorotation, don't let rotor_runup_output go less than critical speed to keep
// runup complete flag from being set to false
if (_autorotating && !rotor_speed_above_critical()) {
if (in_autorotation() && !rotor_speed_above_critical()) {
_rotor_runup_output = get_critical_speed();
}
@ -574,7 +553,7 @@ void AP_MotorsHeli_RSC::autothrottle_run()
} else if (!_governor_engage && !_governor_fault) {
// if governor is not engaged and rotor is overspeeding by more than governor range due to
// misconfigured throttle curve or stuck throttle, set a fault and governor will not operate
if (_rotor_rpm > (_governor_rpm + _governor_range) && !_gov_bailing_out) {
if (_rotor_rpm > (_governor_rpm + _governor_range) && !autorotation.bailing_out()) {
_governor_fault = true;
governor_reset();
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Governor Fault: Rotor Overspeed");
@ -582,7 +561,7 @@ void AP_MotorsHeli_RSC::autothrottle_run()
// when performing power recovery from autorotation, this waits for user to load rotor in order to
// engage the governor
} else if (_rotor_rpm > _governor_rpm && _gov_bailing_out) {
} else if (_rotor_rpm > _governor_rpm && autorotation.bailing_out()) {
_governor_output = 0.0f;
// torque rise limiter accelerates rotor to the reference speed
@ -593,7 +572,6 @@ void AP_MotorsHeli_RSC::autothrottle_run()
if (_rotor_rpm >= ((float)_governor_rpm - torque_ref_error_rpm)) {
_governor_engage = true;
_autothrottle = true;
_gov_bailing_out = false;
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Governor Engaged");
}
} else {
@ -629,18 +607,29 @@ void AP_MotorsHeli_RSC::write_log(void) const
// @Field: ERRPM: Estimated rotor speed
// @Field: Gov: Governor Output
// @Field: Throt: Throttle output
// @Field: Ramp: throttle ramp up
// @Field: Stat: RSC state
// Write to data flash log
AP::logger().WriteStreaming("HRSC",
"TimeUS,I,DRRPM,ERRPM,Gov,Throt",
"s#----",
"F-----",
"QBffff",
"TimeUS,I,DRRPM,ERRPM,Gov,Throt,Ramp,Stat",
"s#------",
"F-------",
"QBfffffB",
AP_HAL::micros64(),
_instance,
get_desired_speed(),
_rotor_runup_output,
_governor_output,
get_control_output());
get_control_output(),
_rotor_ramp_output,
uint8_t(_rsc_state));
}
#endif
// considered to be "in an autorotation" if active or bailing out
bool AP_MotorsHeli_RSC::in_autorotation(void) const
{
return autorotation.active() || autorotation.bailing_out();
}

View File

@ -5,31 +5,7 @@
#include <RC_Channel/RC_Channel.h>
#include <SRV_Channel/SRV_Channel.h>
#include <AP_Logger/AP_Logger_config.h>
// default main rotor speed (ch8 out) as a number from 0 ~ 100
#define AP_MOTORS_HELI_RSC_SETPOINT 70
// default main rotor critical speed
#define AP_MOTORS_HELI_RSC_CRITICAL 50
// RSC output defaults
#define AP_MOTORS_HELI_RSC_IDLE_DEFAULT 0
// default main rotor ramp up time in seconds
#define AP_MOTORS_HELI_RSC_RAMP_TIME 1 // 1 second to ramp output to main rotor ESC to setpoint
#define AP_MOTORS_HELI_RSC_RUNUP_TIME 10 // 10 seconds for rotor to reach full speed
#define AP_MOTORS_HELI_RSC_AROT_ENGAGE_TIME 1 // time in seconds to ramp motors when bailing out of autorotation
#define AP_MOTORS_HELI_RSC_AROT_IDLE 0
// Throttle Curve Defaults
#define AP_MOTORS_HELI_RSC_THRCRV_0_DEFAULT 25
#define AP_MOTORS_HELI_RSC_THRCRV_25_DEFAULT 32
#define AP_MOTORS_HELI_RSC_THRCRV_50_DEFAULT 38
#define AP_MOTORS_HELI_RSC_THRCRV_75_DEFAULT 50
#define AP_MOTORS_HELI_RSC_THRCRV_100_DEFAULT 100
// RSC governor defaults
#define AP_MOTORS_HELI_RSC_GOVERNOR_RANGE_DEFAULT 100
#include <AC_Autorotation/RSC_Autorotation.h>
// rotor control modes
enum RotorControlMode {
@ -103,20 +79,8 @@ public:
// set_collective. collective for throttle curve calculation
void set_collective(float collective) { _collective_in = collective; }
// use bailout ramp time
void use_bailout_ramp_time(bool enable) { _use_bailout_ramp = enable; }
// use external governor autorotation window
void set_autorotation_flag(bool flag) { _in_autorotation = flag; }
// set the throttle percentage to be used during autorotation for this instance of Heli_RSC
void set_arot_idle_output(int16_t idle) { _arot_idle_output.set(idle); }
// set the manual autorotation option for this instance of Heli_RSC
void set_rsc_arot_man_enable(int8_t enable) { _rsc_arot_man_enable.set(enable); }
// set the autorotation power recovery time for this instance of Heli_RSC
void set_rsc_arot_engage_time(int8_t eng_time) { _rsc_arot_engage_time.set(eng_time); }
// true if we are considered to be autorotating or bailing out of an autorotation
bool in_autorotation(void) const;
// turbine start initialize sequence
void set_turbine_start(bool turbine_start) {_turbine_start = turbine_start; }
@ -135,6 +99,8 @@ public:
void write_log(void) const;
#endif
RSC_Autorotation autorotation;
// var_info for holding Parameter information
static const struct AP_Param::GroupInfo var_info[];
@ -145,9 +111,6 @@ public:
AP_Int8 _runup_time; // Time in seconds for the main rotor to reach full speed. Must be longer than _rsc_ramp_time
AP_Int16 _critical_speed; // Rotor speed below which flight is not possible
AP_Int16 _idle_output; // Rotor control output while at idle
AP_Int16 _arot_idle_output; // Percent value used when in autorotation
AP_Int8 _rsc_arot_engage_time; // time in seconds for in-flight power re-engagement
AP_Int8 _rsc_arot_man_enable; // enables manual autorotation
private:
uint64_t _last_update_us;
@ -173,16 +136,13 @@ private:
bool _governor_engage; // RSC governor status flag
bool _autothrottle; // autothrottle status flag
bool _governor_fault; // governor fault status flag
bool _use_bailout_ramp; // true if allowing RSC to quickly ramp up engine
bool _in_autorotation; // true if vehicle is currently in an autorotation
bool _spooldown_complete; // flag for determining if spooldown is complete
float _fast_idle_timer; // cooldown timer variable
uint8_t _governor_fault_count; // variable for tracking governor speed sensor faults
float _governor_torque_reference; // governor reference for load calculations
bool _autorotating; // flag that holds the status of autorotation
bool _bailing_out; // flag that holds the status of bail out(power engagement)
float _idle_throttle; // current idle throttle setting
bool _gov_bailing_out; // flag that holds the status of governor bail out
RotorControlState _rsc_state;
// update_rotor_ramp - slews rotor output scalar between 0 and 1, outputs float scalar to _rotor_ramp_output
void update_rotor_ramp(float rotor_ramp_input, float dt);
@ -212,5 +172,5 @@ private:
float get_idle_output() const { return _idle_output * 0.01; }
float get_governor_torque() const { return _governor_torque * 0.01; }
float get_governor_compensator() const { return _governor_compensator * 0.000001; }
float get_arot_idle_output() const { return _arot_idle_output * 0.01; }
};

View File

@ -270,22 +270,6 @@ void AP_MotorsHeli_Single::calculate_armed_scalars()
_main_rotor._rsc_mode.save();
_heliflags.save_rsc_mode = false;
}
// allow use of external governor autorotation bailout
if (_heliflags.in_autorotation) {
_main_rotor.set_autorotation_flag(_heliflags.in_autorotation);
// set bailout ramp time
_main_rotor.use_bailout_ramp_time(_heliflags.enable_bailout);
if (use_tail_RSC()) {
_tail_rotor.set_autorotation_flag(_heliflags.in_autorotation);
_tail_rotor.use_bailout_ramp_time(_heliflags.enable_bailout);
}
} else {
_main_rotor.set_autorotation_flag(false);
if (use_tail_RSC()) {
_tail_rotor.set_autorotation_flag(false);
}
}
}
// calculate_scalars - recalculates various scalers used.
@ -326,18 +310,12 @@ void AP_MotorsHeli_Single::calculate_scalars()
_tail_rotor.set_runup_time(_main_rotor._runup_time.get());
_tail_rotor.set_critical_speed(_main_rotor._critical_speed.get());
_tail_rotor.set_idle_output(_main_rotor._idle_output.get());
_tail_rotor.set_arot_idle_output(_main_rotor._arot_idle_output.get());
_tail_rotor.set_rsc_arot_man_enable(_main_rotor._rsc_arot_man_enable.get());
_tail_rotor.set_rsc_arot_engage_time(_main_rotor._rsc_arot_engage_time.get());
} else {
_tail_rotor.set_control_mode(ROTOR_CONTROL_MODE_DISABLED);
_tail_rotor.set_ramp_time(0);
_tail_rotor.set_runup_time(0);
_tail_rotor.set_critical_speed(0);
_tail_rotor.set_idle_output(0);
_tail_rotor.set_arot_idle_output(0);
_tail_rotor.set_rsc_arot_man_enable(0);
_tail_rotor.set_rsc_arot_engage_time(0);
}
}
@ -410,10 +388,9 @@ void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float
}
// ensure not below landed/landing collective
if (_heliflags.landing_collective && collective_out < _collective_land_min_pct && !_heliflags.in_autorotation) {
if (_heliflags.landing_collective && collective_out < _collective_land_min_pct && !_main_rotor.in_autorotation()) {
collective_out = _collective_land_min_pct;
limit.throttle_lower = true;
}
// updates below land min collective flag
@ -469,7 +446,7 @@ float AP_MotorsHeli_Single::get_yaw_offset(float collective)
return 0.0;
}
if (_heliflags.in_autorotation || (_main_rotor.get_control_output() <= _main_rotor.get_idle_output())) {
if (_main_rotor.autorotation.active() || (_main_rotor.get_control_output() <= _main_rotor.get_idle_output())) {
// Motor is stopped or at idle, and thus not creating torque
return 0.0;
}
@ -656,6 +633,9 @@ bool AP_MotorsHeli_Single::arming_checks(size_t buflen, char *buffer) const
// Called from system.cpp
void AP_MotorsHeli_Single::heli_motors_param_conversions(void)
{
// Run common conversions from base class
AP_MotorsHeli::heli_motors_param_conversions();
// PARAMETER_CONVERSION - Added: Nov-2023
// Convert trim for DDFP tails
// Previous DDFP configs used servo trim for setting the yaw trim, which no longer works with thrust linearisation. Convert servo trim

View File

@ -243,7 +243,7 @@ void setup()
::printf("autorotation only supported by heli frame types, got %i\n", frame_class);
exit(1);
}
motors_heli->set_in_autorotation(!is_zero(value));
motors_heli->set_autorotation_active(!is_zero(value));
} else {
::printf("Expected \"frame_class\", \"yaw_headroom\" or \"throttle_avg_max\"\n");