AP_Motors: Support autorotation windows on external governors
This commit is contained in:
parent
23e7e2d193
commit
b2d2bf61da
@ -240,6 +240,13 @@ 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_SPEED_SETPOINT || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH) {
|
||||
_main_rotor.set_ext_gov_arot_bail(_main_rotor._ext_gov_arot_pct.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));
|
||||
@ -335,6 +342,12 @@ void AP_MotorsHeli_Dual::calculate_armed_scalars()
|
||||
|
||||
// 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._ext_gov_arot_pct.get() > 0 && (_main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_SPEED_SETPOINT || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_SPEED_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_autorotaion_flag(_heliflags.in_autorotation);
|
||||
}
|
||||
}
|
||||
|
||||
// calculate_scalars
|
||||
|
@ -60,6 +60,13 @@ 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_SPEED_SETPOINT || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH) {
|
||||
_main_rotor.set_ext_gov_arot_bail(_main_rotor._ext_gov_arot_pct.get());
|
||||
} else {
|
||||
_main_rotor.set_ext_gov_arot_bail(0);
|
||||
}
|
||||
|
||||
_flags.initialised_ok = true;
|
||||
|
||||
return true;
|
||||
@ -123,6 +130,12 @@ void AP_MotorsHeli_Quad::calculate_armed_scalars()
|
||||
|
||||
// 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._ext_gov_arot_pct.get() > 0 && (_main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_SPEED_SETPOINT || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_SPEED_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_autorotaion_flag(_heliflags.in_autorotation);
|
||||
}
|
||||
}
|
||||
|
||||
// calculate_scalars
|
||||
|
@ -170,6 +170,17 @@ 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.
|
||||
// @Range: 0 40
|
||||
// @Units: %
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("AROT_PCT", 18, AP_MotorsHeli_RSC, _ext_gov_arot_pct, 0),
|
||||
#endif
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
@ -226,8 +237,13 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
|
||||
// set rotor ramp to decrease speed to zero
|
||||
update_rotor_ramp(0.0f, dt);
|
||||
|
||||
// set rotor control speed to idle speed parameter, this happens instantly and ignore ramping
|
||||
_control_output = get_idle_output();
|
||||
if (_in_autorotaion) {
|
||||
// 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);
|
||||
} else {
|
||||
// set rotor control speed to idle speed parameter, this happens instantly and ignores ramping
|
||||
_control_output = get_idle_output();
|
||||
}
|
||||
break;
|
||||
|
||||
case ROTOR_CONTROL_ACTIVE:
|
||||
|
@ -120,6 +120,12 @@ public:
|
||||
// use bailout ramp time
|
||||
void use_bailout_ramp_time(bool enable) { _use_bailout_ramp = enable; }
|
||||
|
||||
// use external governor autorotation window
|
||||
void set_autorotaion_flag(bool flag) { _in_autorotaion = 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; }
|
||||
|
||||
// output - update value to send to ESC/Servo
|
||||
void output(RotorControlState state);
|
||||
|
||||
@ -133,6 +139,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
|
||||
|
||||
private:
|
||||
uint64_t _last_update_us;
|
||||
@ -154,6 +161,8 @@ private:
|
||||
float _governor_output; // governor output for rotor speed control
|
||||
bool _governor_engage; // RSC governor status flag for soft-start
|
||||
bool _use_bailout_ramp; // true if allowing RSC to quickly ramp up engine
|
||||
bool _in_autorotaion; // true if vehicle is currently in an autorotaion
|
||||
int16_t _rsc_arot_bailout_pct; // the throttle percentage sent to the external governor to signal that autorotation bailout ramp should be used
|
||||
|
||||
// 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);
|
||||
|
@ -29,7 +29,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = {
|
||||
// @Param: TAIL_TYPE
|
||||
// @DisplayName: Tail Type
|
||||
// @Description: Tail type selection. Simpler yaw controller used if external gyro is selected. Direct Drive Variable Pitch is used for tails that have a motor that is governed at constant speed by an ESC. Tail pitch is still accomplished with a servo. Direct Drive Fixed Pitch (DDFP) CW is used for helicopters with a rotor that spins clockwise when viewed from above. Direct Drive Fixed Pitch (DDFP) CCW is used for helicopters with a rotor that spins counter clockwise when viewed from above. In both DDFP cases, no servo is used for the tail and the tail motor esc is controlled by the yaw axis.
|
||||
// @Values: 0:Servo only,1:Servo with ExtGyro,2:DirectDrive VarPitch,3:DirectDrive FixedPitch CW,4:DirectDrive FixedPitch CCW
|
||||
// @Values: 0:Servo only,1:Servo with ExtGyro,2:DirectDrive VarPitch,3:DirectDrive FixedPitch CW,4:DirectDrive FixedPitch CCW,5:DDVP with external governor
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("TAIL_TYPE", 4, AP_MotorsHeli_Single, _tail_type, AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO),
|
||||
|
||||
@ -176,7 +176,7 @@ bool AP_MotorsHeli_Single::init_outputs()
|
||||
// initialize main rotor servo
|
||||
_main_rotor.init_servo();
|
||||
|
||||
if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH) {
|
||||
if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV) {
|
||||
_tail_rotor.init_servo();
|
||||
} else if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) {
|
||||
// external gyro output
|
||||
@ -184,6 +184,21 @@ 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_SPEED_SETPOINT || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH) {
|
||||
_main_rotor.set_ext_gov_arot_bail(_main_rotor._ext_gov_arot_pct.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._ext_gov_arot_pct.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);
|
||||
@ -287,6 +302,18 @@ void AP_MotorsHeli_Single::calculate_armed_scalars()
|
||||
// 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_SPEED_SETPOINT || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH) {
|
||||
_main_rotor.set_autorotaion_flag(_heliflags.in_autorotation);
|
||||
}
|
||||
if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV) {
|
||||
_tail_rotor.set_autorotaion_flag(_heliflags.in_autorotation);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// calculate_scalars - recalculates various scalers used.
|
||||
@ -311,7 +338,7 @@ void AP_MotorsHeli_Single::calculate_scalars()
|
||||
calculate_armed_scalars();
|
||||
|
||||
// send setpoints to DDVP rotor controller and trigger recalculation of scalars
|
||||
if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH) {
|
||||
if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV) {
|
||||
_tail_rotor.set_control_mode(ROTOR_CONTROL_MODE_SPEED_SETPOINT);
|
||||
_tail_rotor.set_ramp_time(_main_rotor._ramp_time.get());
|
||||
_tail_rotor.set_runup_time(_main_rotor._runup_time.get());
|
||||
@ -342,7 +369,7 @@ uint16_t AP_MotorsHeli_Single::get_motor_mask()
|
||||
mask |= 1U << AP_MOTORS_HELI_SINGLE_EXTGYRO;
|
||||
}
|
||||
|
||||
if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH) {
|
||||
if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV) {
|
||||
mask |= 1U << AP_MOTORS_HELI_SINGLE_TAILRSC;
|
||||
}
|
||||
|
||||
|
@ -19,6 +19,7 @@
|
||||
#define AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH 2
|
||||
#define AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW 3
|
||||
#define AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW 4
|
||||
#define AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV 5
|
||||
|
||||
|
||||
// direct-drive variable pitch defaults
|
||||
|
Loading…
Reference in New Issue
Block a user