mirror of https://github.com/ArduPilot/ardupilot
AP_MotorsHeli: patch for manual autorotation
This commit is contained in:
parent
0ff53fa634
commit
78720e9816
|
@ -249,13 +249,6 @@ 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._arot_idle_output.get());
|
||||
} else {
|
||||
_main_rotor.set_ext_gov_arot_bail(0);
|
||||
}
|
||||
|
||||
// reset swash servo range and endpoints
|
||||
for (uint8_t i=0; i<AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS; i++) {
|
||||
reset_swash_servo(SRV_Channels::get_motor_function(i));
|
||||
|
@ -338,13 +331,12 @@ void AP_MotorsHeli_Dual::calculate_armed_scalars()
|
|||
_heliflags.save_rsc_mode = false;
|
||||
}
|
||||
|
||||
// set bailout ramp time
|
||||
_main_rotor.use_bailout_ramp_time(_heliflags.enable_bailout);
|
||||
|
||||
// allow use of external governor autorotation bailout window on main rotor
|
||||
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
|
||||
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);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -60,13 +60,6 @@ bool AP_MotorsHeli_Quad::init_outputs()
|
|||
// set rotor servo range
|
||||
_main_rotor.init_servo();
|
||||
|
||||
// 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._arot_idle_output.get());
|
||||
} else {
|
||||
_main_rotor.set_ext_gov_arot_bail(0);
|
||||
}
|
||||
|
||||
set_initialised_ok(_frame_class == MOTOR_FRAME_HELI_QUAD);
|
||||
|
||||
return true;
|
||||
|
@ -117,13 +110,12 @@ void AP_MotorsHeli_Quad::calculate_armed_scalars()
|
|||
_heliflags.save_rsc_mode = false;
|
||||
}
|
||||
|
||||
// set bailout ramp time
|
||||
_main_rotor.use_bailout_ramp_time(_heliflags.enable_bailout);
|
||||
|
||||
// allow use of external governor autorotation bailout window on main rotor
|
||||
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
|
||||
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);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -110,9 +110,15 @@ public:
|
|||
// use external governor autorotation window
|
||||
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; }
|
||||
|
||||
// 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); }
|
||||
|
||||
// turbine start initialize sequence
|
||||
void set_turbine_start(bool turbine_start) {_turbine_start = turbine_start; }
|
||||
|
||||
|
@ -158,7 +164,6 @@ private:
|
|||
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
|
||||
int16_t _rsc_arot_bailout_pct; // the throttle percentage sent to the external governor to signal that autorotation bailout ramp should be used
|
||||
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
|
||||
|
|
|
@ -186,21 +186,6 @@ 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._arot_idle_output.get());
|
||||
} else {
|
||||
_main_rotor.set_ext_gov_arot_bail(0);
|
||||
}
|
||||
|
||||
// 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._arot_idle_output.get());
|
||||
} else {
|
||||
_tail_rotor.set_ext_gov_arot_bail(0);
|
||||
}
|
||||
|
||||
if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) {
|
||||
// External Gyro uses PWM output thus servo endpoints are forced
|
||||
SRV_Channels::set_output_min_max(SRV_Channels::get_motor_function(AP_MOTORS_HELI_SINGLE_EXTGYRO), 1000, 2000);
|
||||
|
@ -290,24 +275,20 @@ void AP_MotorsHeli_Single::calculate_armed_scalars()
|
|||
_heliflags.save_rsc_mode = false;
|
||||
}
|
||||
|
||||
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) {
|
||||
if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH || _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);
|
||||
if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV) {
|
||||
_tail_rotor.set_autorotation_flag(false);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -350,12 +331,18 @@ 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);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue