AP_Motors:Heli - remove H_LAND_COL_MIN and replace with H_COL_MID
This commit is contained in:
parent
fb3f761fc7
commit
fc84995fb9
@ -81,14 +81,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("RSC_MODE", 8, AP_MotorsHeli, _rsc_mode, (int8_t)ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH),
|
||||
|
||||
// @Param: LAND_COL_MIN
|
||||
// @DisplayName: Landing Collective Minimum
|
||||
// @Description: Minimum collective position in PWM microseconds while landed or landing
|
||||
// @Range: 0 500
|
||||
// @Units: PWM
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("LAND_COL_MIN", 9, AP_MotorsHeli, _land_collective_min, AP_MOTORS_HELI_LAND_COLLECTIVE_MIN),
|
||||
// index 9 was LAND_COL_MIN. Do not use this index in the future.
|
||||
|
||||
// @Param: RSC_RAMP_TIME
|
||||
// @DisplayName: RSC Ramp Time
|
||||
|
@ -20,9 +20,6 @@
|
||||
#define AP_MOTORS_HELI_COLLECTIVE_MAX 1750
|
||||
#define AP_MOTORS_HELI_COLLECTIVE_MID 1500
|
||||
|
||||
// swash min while landed or landing (as a number from 0 ~ 1000
|
||||
#define AP_MOTORS_HELI_LAND_COLLECTIVE_MIN 0
|
||||
|
||||
// default main rotor speed (ch8 out) as a number from 0 ~ 1000
|
||||
#define AP_MOTORS_HELI_RSC_SETPOINT 700
|
||||
|
||||
@ -217,7 +214,6 @@ protected:
|
||||
AP_Int8 _rsc_mode; // Which main rotor ESC control mode is active
|
||||
AP_Int8 _rsc_ramp_time; // Time in seconds for the output to the main rotor's ESC to reach setpoint
|
||||
AP_Int8 _rsc_runup_time; // Time in seconds for the main rotor to reach full speed. Must be longer than _rsc_ramp_time
|
||||
AP_Int16 _land_collective_min; // Minimum collective when landed or landing
|
||||
AP_Int16 _rsc_critical; // Rotor speed below which flight is not possible
|
||||
AP_Int16 _rsc_idle_output; // Rotor control output while at idle
|
||||
AP_Int16 _rsc_slewrate; // throttle slew rate (percentage per second)
|
||||
|
@ -440,8 +440,8 @@ void AP_MotorsHeli_Dual::move_actuators(float roll_out, float pitch_out, float c
|
||||
}
|
||||
|
||||
// ensure not below landed/landing collective
|
||||
if (_heliflags.landing_collective && collective_out < (_land_collective_min*0.001f)) {
|
||||
collective_out = _land_collective_min*0.001f;
|
||||
if (_heliflags.landing_collective && collective_out < _collective_mid_pct) {
|
||||
collective_out = _collective_mid_pct;
|
||||
limit.throttle_lower = true;
|
||||
}
|
||||
|
||||
|
@ -228,8 +228,8 @@ void AP_MotorsHeli_Quad::move_actuators(float roll_out, float pitch_out, float c
|
||||
}
|
||||
|
||||
// ensure not below landed/landing collective
|
||||
if (_heliflags.landing_collective && collective_out < (_land_collective_min*0.001f)) {
|
||||
collective_out = _land_collective_min*0.001f;
|
||||
if (_heliflags.landing_collective && collective_out < _collective_mid_pct) {
|
||||
collective_out = _collective_mid_pct;
|
||||
limit.throttle_lower = true;
|
||||
}
|
||||
|
||||
|
@ -365,8 +365,8 @@ void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float
|
||||
}
|
||||
|
||||
// ensure not below landed/landing collective
|
||||
if (_heliflags.landing_collective && collective_out < (_land_collective_min*0.001f)) {
|
||||
collective_out = (_land_collective_min*0.001f);
|
||||
if (_heliflags.landing_collective && collective_out < _collective_mid_pct) {
|
||||
collective_out = _collective_mid_pct;
|
||||
limit.throttle_lower = true;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user