AP_MotorsHeli: Change AROT_PCT to AROT_IDLE

This commit is contained in:
Bill Geyer 2023-02-01 23:18:58 -05:00 committed by Bill Geyer
parent 08165e204e
commit 40d18f46cf
5 changed files with 26 additions and 18 deletions

View File

@ -251,7 +251,7 @@ bool AP_MotorsHeli_Dual::init_outputs()
// set signal value for main rotor external governor to know when to use autorotation bailout ramp up
if (_main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_SETPOINT || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_PASSTHROUGH) {
_main_rotor.set_ext_gov_arot_bail(_main_rotor._ext_gov_arot_pct.get());
_main_rotor.set_ext_gov_arot_bail(_main_rotor._arot_idle_output.get());
} else {
_main_rotor.set_ext_gov_arot_bail(0);
}
@ -342,7 +342,7 @@ void AP_MotorsHeli_Dual::calculate_armed_scalars()
_main_rotor.use_bailout_ramp_time(_heliflags.enable_bailout);
// 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_SETPOINT || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_PASSTHROUGH)){
if (_main_rotor._arot_idle_output.get() > 0 && (_main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_SETPOINT || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_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_autorotation_flag(_heliflags.in_autorotation);
}

View File

@ -62,7 +62,7 @@ bool AP_MotorsHeli_Quad::init_outputs()
// set signal value for main rotor external governor to know when to use autorotation bailout ramp up
if (_main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_SETPOINT || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_PASSTHROUGH) {
_main_rotor.set_ext_gov_arot_bail(_main_rotor._ext_gov_arot_pct.get());
_main_rotor.set_ext_gov_arot_bail(_main_rotor._arot_idle_output.get());
} else {
_main_rotor.set_ext_gov_arot_bail(0);
}
@ -121,7 +121,7 @@ void AP_MotorsHeli_Quad::calculate_armed_scalars()
_main_rotor.use_bailout_ramp_time(_heliflags.enable_bailout);
// 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_SETPOINT || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_PASSTHROUGH)){
if (_main_rotor._arot_idle_output.get() > 0 && (_main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_SETPOINT || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_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_autorotation_flag(_heliflags.in_autorotation);
}

View File

@ -137,14 +137,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
// @User: Standard
AP_GROUPINFO("GOV_RANGE", 17, AP_MotorsHeli_RSC, _governor_range, AP_MOTORS_HELI_RSC_GOVERNOR_RANGE_DEFAULT),
// @Param: AROT_PCT
// @DisplayName: Autorotation Throttle Percentage for External Governor
// @Description: The throttle percentage sent to external governors, signaling 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_PCT", 18, AP_MotorsHeli_RSC, _ext_gov_arot_pct, AP_MOTORS_HELI_RSC_AROT_PCT),
// Index 18 was renamed from AROT_PCT to AROT_IDLE
// @Param: CLDWN_TIME
// @DisplayName: Cooldown Time
@ -216,6 +209,15 @@ const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
// @User: Standard
AP_GROUPINFO("AROT_MN_EN", 26, AP_MotorsHeli_RSC, _rsc_arot_man_enable, 0),
// @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),
AP_GROUPEND
};
@ -305,8 +307,13 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
_autothrottle = false;
_governor_fault = false;
if (_in_autorotation) {
// if in autorotation and using an external governor, set the output to tell the governor to use bailout ramp
_idle_throttle = constrain_float( _ext_gov_arot_pct/100.0f, 0.0f, 0.4f);
// 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) {
_idle_throttle = get_idle_output();
} else {
_idle_throttle = constrain_float( get_arot_idle_output(), 0.0f, 0.4f);
}
if (!_autorotating) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "Autorotation");
_autorotating =true;

View File

@ -18,7 +18,7 @@
#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_PCT 0
#define AP_MOTORS_HELI_RSC_AROT_IDLE 0
// Throttle Curve Defaults
#define AP_MOTORS_HELI_RSC_THRCRV_0_DEFAULT 25
@ -129,7 +129,7 @@ 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 _ext_gov_arot_pct; // Percent value sent to external governor when in autorotation
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
@ -195,4 +195,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

@ -188,7 +188,7 @@ bool AP_MotorsHeli_Single::init_outputs()
// set signal value for main rotor external governor to know when to use autorotation bailout ramp up
if (_main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_SETPOINT || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_PASSTHROUGH) {
_main_rotor.set_ext_gov_arot_bail(_main_rotor._ext_gov_arot_pct.get());
_main_rotor.set_ext_gov_arot_bail(_main_rotor._arot_idle_output.get());
} else {
_main_rotor.set_ext_gov_arot_bail(0);
}
@ -196,7 +196,7 @@ bool AP_MotorsHeli_Single::init_outputs()
// set signal value for tail rotor external governor to know when to use autorotation bailout ramp up
if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV) {
// set point for tail rsc is the same as for main rotor to save on parameters
_tail_rotor.set_ext_gov_arot_bail(_main_rotor._ext_gov_arot_pct.get());
_tail_rotor.set_ext_gov_arot_bail(_main_rotor._arot_idle_output.get());
} else {
_tail_rotor.set_ext_gov_arot_bail(0);
}