Plane: add LAND_THR_SLEW
This commit is contained in:
parent
ed6aa4ed17
commit
75be40ea59
@ -522,8 +522,13 @@ void Plane::calc_nav_roll()
|
||||
void Plane::throttle_slew_limit(int16_t last_throttle)
|
||||
{
|
||||
uint8_t slewrate = aparm.throttle_slewrate;
|
||||
if (control_mode==AUTO && auto_state.takeoff_complete == false && g.takeoff_throttle_slewrate != 0) {
|
||||
slewrate = g.takeoff_throttle_slewrate;
|
||||
if (control_mode==AUTO) {
|
||||
if (auto_state.takeoff_complete == false && g.takeoff_throttle_slewrate != 0) {
|
||||
slewrate = g.takeoff_throttle_slewrate;
|
||||
} else if (g.land_throttle_slewrate != 0 &&
|
||||
(flight_stage == AP_SpdHgtControl::FLIGHT_LAND_APPROACH || flight_stage == AP_SpdHgtControl::FLIGHT_LAND_FINAL || flight_stage == AP_SpdHgtControl::FLIGHT_LAND_PREFLARE)) {
|
||||
slewrate = g.land_throttle_slewrate;
|
||||
}
|
||||
}
|
||||
// if slew limit rate is set to zero then do not slew limit
|
||||
if (slewrate) {
|
||||
|
@ -198,6 +198,15 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
// @User: User
|
||||
GSCALAR(takeoff_throttle_slewrate, "TKOFF_THR_SLEW", 0),
|
||||
|
||||
// @Param: LAND_THR_SLEW
|
||||
// @DisplayName: Landing throttle slew rate
|
||||
// @Description: This parameter sets the slew rate for the throttle during auto landing. When this is zero the THR_SLEWRATE parameter is used during landing. The value is a percentage throttle change per second, so a value of 20 means to advance the throttle over 5 seconds on landing. Values below 50 are not recommended as it may cause a stall when airspeed is low and you can not throttle up fast enough.
|
||||
// @Units: percent
|
||||
// @Range: 0 127
|
||||
// @Increment: 1
|
||||
// @User: User
|
||||
GSCALAR(land_throttle_slewrate, "LAND_THR_SLEW", 0),
|
||||
|
||||
// @Param: TKOFF_FLAP_PCNT
|
||||
// @DisplayName: Takeoff flap percentage
|
||||
// @Description: The amount of flaps (as a percentage) to apply in automatic takeoff
|
||||
|
@ -148,6 +148,7 @@ public:
|
||||
k_param_parachute_channel,
|
||||
k_param_crash_accel_threshold,
|
||||
k_param_override_safety,
|
||||
k_param_land_throttle_slewrate, // 104
|
||||
|
||||
// 105: Extra parameters
|
||||
k_param_fence_retalt = 105,
|
||||
@ -492,6 +493,7 @@ public:
|
||||
AP_Float takeoff_tdrag_speed1;
|
||||
AP_Float takeoff_rotate_speed;
|
||||
AP_Int8 takeoff_throttle_slewrate;
|
||||
AP_Int8 land_throttle_slewrate;
|
||||
AP_Int8 level_roll_limit;
|
||||
AP_Int8 flapin_channel;
|
||||
AP_Int8 flaperon_output;
|
||||
|
Loading…
Reference in New Issue
Block a user