mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
AP_MotorsHeli: add Critical Rotor Speed param, use to switch off runup_complete
This commit is contained in:
parent
62079226ff
commit
0c92565d23
@ -204,6 +204,14 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = {
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("TAIL_SPEED", 21, AP_MotorsHeli, _direct_drive_tailspeed, AP_MOTOR_HELI_DDTAIL_DEFAULT),
|
||||
|
||||
// @Param: RSC_CRITICAL
|
||||
// @DisplayName: Critical Rotor Speed
|
||||
// @Description: Rotor speed below which flight is not possible
|
||||
// @Range: 0 1000
|
||||
// @Increment: 10
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("RSC_CRITICAL", 22, AP_MotorsHeli, _rsc_critical, AP_MOTORS_HELI_RSC_CRITICAL),
|
||||
|
||||
// parameters 1 ~ 29 reserved for tradheli
|
||||
// parameters 30 ~ 39 reserved for tricopter
|
||||
// parameters 40 ~ 49 for single copter and coax copter (these have identical parameter files)
|
||||
@ -748,7 +756,7 @@ void AP_MotorsHeli::rotor_ramp(int16_t rotor_target)
|
||||
if (!_heliflags.rotor_runup_complete && rotor_target > 0 && _rotor_speed_estimate >= rotor_target) {
|
||||
_heliflags.rotor_runup_complete = true;
|
||||
}
|
||||
if (_heliflags.rotor_runup_complete && rotor_target == 0 && _rotor_speed_estimate <= 0) {
|
||||
if (_heliflags.rotor_runup_complete && _rotor_speed_estimate <= _rsc_critical) {
|
||||
_heliflags.rotor_runup_complete = false;
|
||||
}
|
||||
|
||||
|
@ -70,6 +70,9 @@
|
||||
// default main rotor speed (ch8 out) as a number from 0 ~ 1000
|
||||
#define AP_MOTORS_HELI_RSC_SETPOINT 700
|
||||
|
||||
// default main rotor critical speed
|
||||
#define AP_MOTORS_HELI_RSC_CRITICAL 500
|
||||
|
||||
// default main rotor ramp up time in seconds
|
||||
#define AP_MOTORS_HELI_RSC_RAMP_TIME 1 // 1 second to ramp output to main rotor ESC to full power (most people use exterrnal govenors so we can ramp up quickly)
|
||||
#define AP_MOTORS_HELI_RSC_RUNUP_TIME 10 // 10 seconds for rotor to reach full speed
|
||||
@ -292,6 +295,7 @@ private:
|
||||
AP_Int8 _flybar_mode; // Flybar present or not. Affects attitude controller used during ACRO flight mode
|
||||
AP_Int16 _land_collective_min; // Minimum collective when landed or landing
|
||||
AP_Int16 _direct_drive_tailspeed; // Direct Drive VarPitch Tail ESC speed (0 ~ 1000)
|
||||
AP_Int16 _rsc_critical; // Rotor speed below which flight is not possible
|
||||
|
||||
// internal variables
|
||||
float _rollFactor[AP_MOTORS_HELI_NUM_SWASHPLATE_SERVOS];
|
||||
|
Loading…
Reference in New Issue
Block a user