mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
Plane: added FLAP_SLEWRATE parameter
makes for smoother transition of flaps
This commit is contained in:
parent
f66039c9b4
commit
5af4cefff3
@ -513,6 +513,26 @@ static void throttle_slew_limit(int16_t last_throttle)
|
||||
}
|
||||
}
|
||||
|
||||
/*****************************************
|
||||
Flap slew limit
|
||||
*****************************************/
|
||||
static void flap_slew_limit(int8_t &last_value, int8_t &new_value)
|
||||
{
|
||||
uint8_t slewrate = g.flap_slewrate;
|
||||
// if slew limit rate is set to zero then do not slew limit
|
||||
if (slewrate) {
|
||||
// limit flap change by the given percentage per second
|
||||
float temp = slewrate * G_Dt;
|
||||
// allow a minimum change of 1% per cycle. This means the
|
||||
// slowest flaps we can do is full change over 2 seconds
|
||||
if (temp < 1) {
|
||||
temp = 1;
|
||||
}
|
||||
new_value = constrain_int16(new_value, last_value - temp, last_value + temp);
|
||||
}
|
||||
last_value = new_value;
|
||||
}
|
||||
|
||||
|
||||
|
||||
/**
|
||||
@ -819,8 +839,10 @@ static void set_servos(void)
|
||||
}
|
||||
|
||||
// Auto flap deployment
|
||||
uint8_t auto_flap_percent = 0;
|
||||
int8_t auto_flap_percent = 0;
|
||||
int8_t manual_flap_percent = 0;
|
||||
static int8_t last_auto_flap;
|
||||
static int8_t last_manual_flap;
|
||||
|
||||
// work out any manual flap input
|
||||
RC_Channel *flapin = RC_Channel::rc_channel(g.flapin_channel-1);
|
||||
@ -869,6 +891,9 @@ static void set_servos(void)
|
||||
auto_flap_percent = manual_flap_percent;
|
||||
}
|
||||
|
||||
flap_slew_limit(last_auto_flap, auto_flap_percent);
|
||||
flap_slew_limit(last_manual_flap, manual_flap_percent);
|
||||
|
||||
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_flap_auto, auto_flap_percent);
|
||||
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_flap, manual_flap_percent);
|
||||
|
||||
|
@ -126,6 +126,7 @@ public:
|
||||
k_param_rangefinder_landing,
|
||||
k_param_land_flap_percent,
|
||||
k_param_takeoff_flap_percent,
|
||||
k_param_flap_slewrate,
|
||||
|
||||
// 100: Arming parameters
|
||||
k_param_arming = 100,
|
||||
@ -464,6 +465,7 @@ public:
|
||||
AP_Int16 glide_slope_threshold;
|
||||
AP_Int8 fbwa_tdrag_chan;
|
||||
AP_Int8 rangefinder_landing;
|
||||
AP_Int8 flap_slewrate;
|
||||
|
||||
// RC channels
|
||||
RC_Channel rc_1;
|
||||
|
@ -459,6 +459,15 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @User: Standard
|
||||
ASCALAR(throttle_slewrate, "THR_SLEWRATE", 100),
|
||||
|
||||
// @Param: FLAP_SLEWRATE
|
||||
// @DisplayName: Flap slew rate
|
||||
// @Description: maximum percentage change in flap output per second. A setting of 25 means to not change the flap by more than 25% of the full flap range in one second. A value of 0 means no rate limiting.
|
||||
// @Units: Percent
|
||||
// @Range: 0 100
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
GSCALAR(flap_slewrate, "FLAP_SLEWRATE", 75),
|
||||
|
||||
// @Param: THR_SUPP_MAN
|
||||
// @DisplayName: Throttle suppress manual passthru
|
||||
// @Description: When throttle is supressed in auto mode it is normally forced to zero. If you enable this option, then while suppressed it will be manual throttle. This is useful on petrol engines to hold the idle throttle manually while waiting for takeoff
|
||||
|
Loading…
Reference in New Issue
Block a user