AP_Motors: Support for Autorotation implementation

-enables faster re-spool(user settable timer) after power engagement
-flare&touchdown controllers;
-rangefinder for distance from ground evaluation;
-higher refresh rate for rangefinder;
-attitude targets implementation for "guided" autorotation;
-retrieve zero lift collective position
This commit is contained in:
Ferruccio1984 2022-03-24 08:39:41 -07:00 committed by Bill Geyer
parent 000c39ed27
commit e935913f95
4 changed files with 64 additions and 29 deletions

View File

@ -144,6 +144,9 @@ public:
// set land complete flag
void set_land_complete(bool landed) { _heliflags.land_complete = landed; }
//return zero lift collective position
float get_coll_mid() const { return _collective_zero_thrust_pct; }
// enum for heli optional features
enum class HeliOption {

View File

@ -137,7 +137,6 @@ 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),
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
// @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.
@ -145,8 +144,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
// @Units: %
// @Increment: 1
// @User: Standard
AP_GROUPINFO("AROT_PCT", 18, AP_MotorsHeli_RSC, _ext_gov_arot_pct, 0),
#endif
AP_GROUPINFO("AROT_PCT", 18, AP_MotorsHeli_RSC, _ext_gov_arot_pct, AP_MOTORS_HELI_RSC_AROT_PCT),
// @Param: CLDWN_TIME
// @DisplayName: Cooldown Time
@ -201,6 +199,15 @@ const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
// @Increment: 1
// @User: Standard
AP_GROUPINFO("GOV_TORQUE", 24, AP_MotorsHeli_RSC, _governor_torque, 30),
// @Param: BLOUT_TIME
// @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("BLOUT_TIME", 25, AP_MotorsHeli_RSC, _rsc_bailout_time, AP_MOTORS_HELI_RSC_BAILOUT_TIME),
AP_GROUPEND
};
@ -275,6 +282,8 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
_governor_fault = false;
//turbine start flag on
_starting = true;
_autorotating = false;
_bailing_out = false;
break;
case ROTOR_CONTROL_IDLE:
@ -287,7 +296,11 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
_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
_control_output = constrain_float( _rsc_arot_bailout_pct/100.0f , 0.0f, 0.4f);
_control_output = constrain_float( _ext_gov_arot_pct/100.0f , 0.0f, 0.4f);
if(!_autorotating){
gcs().send_text(MAV_SEVERITY_CRITICAL, "Autorotation");
_autorotating =true;
}
} else {
// set rotor control speed to idle speed parameter, this happens instantly and ignores ramping
if (_turbine_start && _starting == true ) {
@ -307,6 +320,7 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
} else {
_control_output = get_idle_output();
}
_use_bailout_ramp = false;
}
}
break;
@ -317,6 +331,7 @@ 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
@ -348,23 +363,35 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
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 (_use_bailout_ramp || _ramp_time <= 0) {
if (_ramp_time <= 0) {
ramp_time = 1;
} else {
ramp_time = _ramp_time;
}
if (_rsc_bailout_time <= 0) {
bailout_time = 1;
} else {
bailout_time = _rsc_bailout_time;
}
// ramp output upwards towards target
if (_rotor_ramp_output < rotor_ramp_input) {
// allow control output to jump to estimated speed
if (_rotor_ramp_output < _rotor_runup_output) {
_rotor_ramp_output = _rotor_runup_output;
if (_use_bailout_ramp){
if(!_bailing_out){
gcs().send_text(MAV_SEVERITY_CRITICAL, "bailing_out");
_bailing_out = true;
}
_rotor_ramp_output += (dt / bailout_time);
}else{
_rotor_ramp_output += (dt / ramp_time);
}
// ramp up slowly to target
_rotor_ramp_output += (dt / ramp_time);
if (_rotor_ramp_output > rotor_ramp_input) {
_rotor_ramp_output = rotor_ramp_input;
_rotor_ramp_output = rotor_ramp_input;
_bailing_out = false;
_use_bailout_ramp = false;
}
}else{
// ramping down happens instantly
@ -396,10 +423,7 @@ void AP_MotorsHeli_RSC::update_rotor_runup(float dt)
_rotor_runup_output = _rotor_ramp_output;
}
}else{
_rotor_runup_output -= runup_increment;
if (_rotor_runup_output < _rotor_ramp_output) {
_rotor_runup_output = _rotor_ramp_output;
}
_rotor_runup_output = _rotor_ramp_output;
}
// update run-up complete flag

View File

@ -18,6 +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_BAILOUT_TIME 1 // time in seconds to ramp motors when bailing out of autorotation
#define AP_MOTORS_HELI_RSC_AROT_PCT 0
// Throttle Curve Defaults
#define AP_MOTORS_HELI_RSC_THRCRV_0_DEFAULT 25
@ -129,6 +130,7 @@ public:
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_Int8 _rsc_bailout_time; // time in seconds for power recovery
private:
uint64_t _last_update_us;
@ -160,6 +162,8 @@ private:
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;
bool _bailing_out;
// 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);

View File

@ -289,22 +289,26 @@ void AP_MotorsHeli_Single::calculate_armed_scalars()
_main_rotor._rsc_mode.save();
_heliflags.save_rsc_mode = false;
}
// set bailout ramp time
_main_rotor.use_bailout_ramp_time(_heliflags.enable_bailout);
_tail_rotor.use_bailout_ramp_time(_heliflags.enable_bailout);
// allow use of external governor autorotation bailout
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_SETPOINT || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_PASSTHROUGH) {
_main_rotor.set_autorotation_flag(_heliflags.in_autorotation);
}
if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV) {
_tail_rotor.set_autorotation_flag(_heliflags.in_autorotation);
}
if (_heliflags.start_engine) {
_main_rotor.set_turbine_start(true);
} else {
_main_rotor.set_turbine_start(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);
_tail_rotor.use_bailout_ramp_time(_heliflags.enable_bailout);
if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV) {
_tail_rotor.set_autorotation_flag(_heliflags.in_autorotation);
_tail_rotor.use_bailout_ramp_time(_heliflags.enable_bailout);
}
}else {
_main_rotor.set_autorotation_flag(false);
}
}
// calculate_scalars - recalculates various scalers used.