AP_Motors:Heli_RSC - throttle curve _control_output does not need a constrain_float

- change lower limit of governor enaged output to 150% of idle speed
- add governor_reset() function
- remove governor defaults from header
- rearrange governor metadata in alphabetical order, assign new eeprom slot for rpm
This commit is contained in:
MidwestAire 2021-02-10 14:45:07 -06:00 committed by Bill Geyer
parent 77f0fdf112
commit 22c2329063
2 changed files with 52 additions and 71 deletions

View File

@ -125,16 +125,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
// @User: Standard
AP_GROUPINFO("THRCRV_100", 12, AP_MotorsHeli_RSC, _thrcrv[4], AP_MOTORS_HELI_RSC_THRCRV_100_DEFAULT),
// @Param: GOV_RPM
// @DisplayName: Rotor RPM Setting
// @Description: Main rotor RPM that governor maintains when engaged
// @Range: 800 3500
// @Units: RPM
// @Increment: 10
// @User: Standard
AP_GROUPINFO("GOV_RPM", 13, AP_MotorsHeli_RSC, _governor_rpm, AP_MOTORS_HELI_RSC_GOVERNOR_RPM_DEFAULT),
// Indices 14 thru 17 have been re-assigned and should not be used in the future
// Indices 13 thru 17 have been re-assigned and should not be used in the future
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
// @Param: AROT_PCT
@ -147,14 +138,14 @@ const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
AP_GROUPINFO("AROT_PCT", 18, AP_MotorsHeli_RSC, _ext_gov_arot_pct, 0),
#endif
// @Param: GOV_TORQUE
// @DisplayName: Governor Torque Limiter
// @Description: Adjusts the engine's percentage of torque rise on autothrottle during ramp-up to governor speed. The torque rise will determine how fast the rotor speed will ramp up when the throttle switch is turned on. 30% torque rise is a good starting setting to adjust the autothrottle ramp-in for piston and turbine engines. The sequence of events engaging the governor is as follows: Throttle ramp time will engage the clutch and start the main rotor turning. The collective should be at feather pitch and the throttle curve set to provide at least 50% of normal Rrpm at feather pitch. The autothrottle torque limiter will automatically activate and start accelerating the main rotor. Note that if the engine fails to respond during autothrottle ramp-in to governed speed due to external factors such as the tail rotor suddenly drawing too much torque, or the engine is not running properly, the torque limiter will pause and wait for the condition to clear before proceeding with ramp-in to governor speed. If the autothrottle consistently fails to accelerate the main rotor during ramp-in due to engine tune or other factors, then increase the torque limiter setting. Raising the collective during runup will increase how fast the autothrottle ramps up, but may cause the helicopter to become unstable on the ground due to producing thrust before the rotor reaches full speed. NOTE: Having the throttle ramp time and throttle curve set properly is very important, so these things should be tuned using MODE Throttle Curve before using MODE AutoThrottle
// @Range: 10 60
// @Units: %
// @Param: GOV_CLDWN
// @DisplayName: AutoThrottle Cooldown Time
// @Description: Will provide a fast idle for engine cooldown by raising the Ground Idle speed setting by 50% for the number of seconds the timer is set for. A setting of zero disables the fast idle. This feature will only apply after the governor and autothrottle have been engaged (throttle switch on and rotor rpm at least 100% of normal speed). At any time during fast idle, disarming will shut the engine down.
// @Range: 0 120
// @Units: s
// @Increment: 1
// @User: Standard
AP_GROUPINFO("GOV_TORQUE", 19, AP_MotorsHeli_RSC, _governor_torque, AP_MOTORS_HELI_RSC_GOVERNOR_TORQUE_DEFAULT),
AP_GROUPINFO("GOV_CLDWN", 19, AP_MotorsHeli_RSC, _autothrottle_cooldown, 0),
// @Param: GOV_COMP
// @DisplayName: Governor Torque Compensator
@ -172,25 +163,34 @@ const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
// @Units: %
// @Increment: 1
// @User: Standard
AP_GROUPINFO("GOV_DROOP", 21, AP_MotorsHeli_RSC, _governor_droop_response, AP_MOTORS_HELI_RSC_GOVERNOR_DROOP_DEFAULT),
AP_GROUPINFO("GOV_DROOP", 21, AP_MotorsHeli_RSC, _governor_droop_response, 25),
// @Param: GOV_FF
// @DisplayName: Governor Feedforward
// @Description: Feedforward governor gain to throttle response during sudden loading/unloading of the rotor system. If Rrpm drops excessively during full collective climb with the droop response set correctly, increase the governor feedforward. If Rrpm drops excessively under heavy load also inspect the setting for maximum collective pitch to ensure that the pitch setting corresponds to maximum available power from the engine. Setting the maximum pitch to where the rotor draws more power than the engine can produce is called over-pitching and can lead to loss of control. The governor is not able to compensate for over-pitching if the throttle is wide open and the engine can't produce more power to maintain rotor speed. So maximum collective pitch must be matched to available maximum engine power.
// @Description: Feedforward governor gain to throttle response during sudden loading/unloading of the rotor system. If Rrpm drops excessively during full collective climb with the droop response set correctly, increase the governor feedforward.
// @Range: 0 100
// @Units: %
// @Increment: 1
// @User: Standard
AP_GROUPINFO("GOV_FF", 22, AP_MotorsHeli_RSC, _governor_ff, AP_MOTORS_HELI_RSC_GOVERNOR_FF_DEFAULT),
AP_GROUPINFO("GOV_FF", 22, AP_MotorsHeli_RSC, _governor_ff, 50),
// @Param: GOV_CLDWN
// @DisplayName: AutoThrottle Cooldown Time
// @Description: Will provide a fast idle for engine cooldown by raising the Ground Idle speed setting by 50% for the number of seconds the timer is set for. Can be set up to 120 seconds. A setting of zero disables the fast idle. This feature will only apply after the governor and autothrottle have been engaged (throttle switch on and rotor rpm at least 100% of normal speed). Upon initial startup of the engine after arming, normal Ground Idle is used. It will provide a 50% bump to Ground Idle speed for practice autorotation to ensure the engine doesn't quit. It will provide a 50% bump to Ground Idle speed to cool down a hot engine upon landing. At any time during fast idle, disarming will shut the engine down
// @Range: 0 120
// @Units: s
// @Param: GOV_RPM
// @DisplayName: Rotor RPM Setting
// @Description: Main rotor RPM that governor maintains when engaged
// @Range: 800 3500
// @Units: RPM
// @Increment: 10
// @User: Standard
AP_GROUPINFO("GOV_RPM", 23, AP_MotorsHeli_RSC, _governor_rpm, 1500),
// @Param: GOV_TORQUE
// @DisplayName: Governor Torque Limiter
// @Description: Adjusts the engine's percentage of torque rise on autothrottle during ramp-up to governor speed. The torque rise will determine how fast the rotor speed will ramp up when rotor speed reaches 50% of the rotor rpm setting. The sequence of events engaging the governor is as follows: Throttle ramp time will engage the clutch and start the main rotor turning. The collective should be at feather pitch and the throttle curve set to provide at least 50% of normal Rrpm at feather pitch. The autothrottle torque limiter will automatically activate and start accelerating the main rotor. If the autothrottle consistently fails to accelerate the main rotor during ramp-in due to engine tune or other factors, then increase the torque limiter setting. NOTE: throttle ramp time and throttle curve should be tuned using MODE Throttle Curve before using MODE AutoThrottle
// @Range: 10 60
// @Units: %
// @Increment: 1
// @User: Standard
AP_GROUPINFO("GOV_CLDWN", 23, AP_MotorsHeli_RSC, _autothrottle_cooldown, 0),
AP_GROUPINFO("GOV_TORQUE", 24, AP_MotorsHeli_RSC, _governor_torque, 30),
AP_GROUPEND
};
@ -249,23 +249,19 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
// control output forced to zero
_control_output = 0.0f;
// governor is forced to disengage status and ensure governor outputs are reset
// governor is forced to disengage status and reset outputs
governor_reset();
_autothrottle = false;
_governor_engage = false;
_governor_fault = false;
_governor_output = 0.0f;
_governor_torque_reference = 0.0f;
break;
case ROTOR_CONTROL_IDLE:
// set rotor ramp to decrease speed to zero
update_rotor_ramp(0.0f, dt);
// set rotor control speed to engine idle and ensure governor is not engaged, if used
_governor_engage = false;
// set rotor control speed to engine idle and ensure governor is reset, if used
governor_reset();
_governor_fault = false;
_governor_output = 0.0f;
_governor_torque_reference = 0.0f;
if (!_autothrottle) {
if (_in_autorotation) {
// if in autorotation and using an external governor, set the output to tell the governor to use bailout ramp
@ -443,17 +439,15 @@ void AP_MotorsHeli_RSC::autothrottle_run()
_governor_torque_reference -= get_governor_compensator();
}
// throttle output uses droop + torque compensation to maintain proper rotor speed
_control_output = constrain_float((_governor_torque_reference + _governor_output), throttlecurve * get_governor_ff(), 1.0f);
_control_output = constrain_float((_governor_torque_reference + _governor_output), (get_idle_output() * 1.5f), 1.0f);
// governor and speed sensor fault detection - must maintain Rrpm -3/+2%
// speed fault detector will allow a fault to persist for 200 contiguous governor updates
// this is failsafe for bad speed sensor or severely mis-adjusted governor
if ((_rotor_rpm <= (_governor_rpm * 0.97f)) || (_rotor_rpm >= (_governor_rpm * 1.02f))) {
_governor_fault_count += 1.0f;
if (_governor_fault_count > 200.0f) {
governor_reset();
_governor_fault = true;
_governor_engage = false;
_governor_output = 0.0f;
_governor_torque_reference = 0.0f;
if (_rotor_rpm >= (_governor_rpm * 1.02f)) {
gcs().send_text(MAV_SEVERITY_WARNING, "Governor Fault: Rotor Overspeed");
} else {
@ -477,19 +471,26 @@ void AP_MotorsHeli_RSC::autothrottle_run()
}
} else {
// temporary use of throttle curve and ramp timer to accelerate rotor to governor min torque rise speed
_control_output = constrain_float(get_idle_output() + (_rotor_ramp_output * (throttlecurve - get_idle_output())), 0.0f, 1.0f);
_control_output = get_idle_output() + (_rotor_ramp_output * (throttlecurve - get_idle_output()));
}
} else {
// failsafe - if governor has faulted use throttle curve
_control_output = constrain_float(get_idle_output() + (_rotor_ramp_output * (throttlecurve - get_idle_output())), 0.0f, 1.0f);
_control_output = get_idle_output() + (_rotor_ramp_output * (throttlecurve - get_idle_output()));
}
// if governor is not engaged and rotor is overspeeding by more than 2% due to misconfigured
// throttle curve or stuck throttle, set a fault and governor will not operate
if (!_governor_engage && !_governor_fault && (_rotor_rpm > (_governor_rpm * 1.02f))) {
_governor_fault = true;
_governor_output = 0.0f;
_governor_torque_reference = 0.0f;
governor_reset();
gcs().send_text(MAV_SEVERITY_WARNING, "Governor Fault: Rotor Overspeed");
}
}
// governor_reset - disengages governor and resets outputs
void AP_MotorsHeli_RSC::governor_reset()
{
_governor_output = 0.0f;
_governor_torque_reference = 0.0f;
_governor_engage = false;
}

View File

@ -27,12 +27,6 @@
#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_RPM_DEFAULT 1500
#define AP_MOTORS_HELI_RSC_GOVERNOR_TORQUE_DEFAULT 30
#define AP_MOTORS_HELI_RSC_GOVERNOR_DROOP_DEFAULT 25
#define AP_MOTORS_HELI_RSC_GOVERNOR_FF_DEFAULT 50
// rotor controller states
enum RotorControlState {
ROTOR_CONTROL_STOP = 0,
@ -78,48 +72,35 @@ public:
// set_critical_speed
void set_critical_speed(float critical_speed) { _critical_speed = critical_speed; }
// set_idle_output
void set_idle_output(float idle_output) { _idle_output = idle_output; }
// set rotor speed governor parameters
void set_governor_output(float governor_output) {_governor_output = governor_output; }
// get_desired_speed
float get_desired_speed() const { return _desired_speed; }
// set_desired_speed - this requires input to be 0-1
void set_desired_speed(float desired_speed) { _desired_speed = desired_speed; }
// get_control_speed
float get_control_output() const { return _control_output; }
// get_rotor_speed - estimated rotor speed when no governor or rpm sensor is used
float get_rotor_speed() const;
// get_governor_output
// functions for autothrottle, throttle curve, governor, idle speed, output to servo
void set_governor_output(float governor_output) {_governor_output = governor_output; }
float get_governor_output() const { return _governor_output; }
void governor_reset();
float get_control_output() const { return _control_output; }
void set_idle_output(float idle_output) { _idle_output = idle_output; }
void autothrottle_run();
void set_throttle_curve();
// is_runup_complete
// functions for ramp and runup timers, runup_complete flag
void set_ramp_time(int8_t ramp_time) { _ramp_time = ramp_time; }
void set_runup_time(int8_t runup_time) { _runup_time = runup_time; }
bool is_runup_complete() const { return _runup_complete; }
// is_spooldown_complete
bool is_spooldown_complete() const { return _spooldown_complete; }
// set_ramp_time
void set_ramp_time(int8_t ramp_time) { _ramp_time = ramp_time; }
// set_runup_time
void set_runup_time(int8_t runup_time) { _runup_time = runup_time; }
// set_throttle_curve
void set_throttle_curve();
// set_collective. collective for throttle curve calculation
void set_collective(float collective) { _collective_in = collective; }
// calculate autothrottle output
void autothrottle_run();
// use bailout ramp time
void use_bailout_ramp_time(bool enable) { _use_bailout_ramp = enable; }
@ -204,4 +185,3 @@ private:
float get_governor_ff() { return _governor_ff * 0.01; }
};