mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: re-implement flaperons
implement as scaled output instead of PWM output this will break some peoples setups, but gives much easier setup and more consistent behaviour
This commit is contained in:
parent
6b3bb29398
commit
c9e4423997
@ -843,17 +843,10 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
|
||||
// @Param: FLAP_IN_CHANNEL
|
||||
// @DisplayName: Flap input channel
|
||||
// @Description: An RC input channel to use for flaps control. If this is set to a RC channel number then that channel will be used for manual flaps control. When enabled, the percentage of flaps is taken as the percentage travel from the TRIM value of the channel to the MIN value of the channel. A value above the TRIM values will give inverse flaps (spoilers). This option needs to be enabled in conjunction with a FUNCTION setting on an output channel to one of the flap functions. When a FLAP_IN_CHANNEL is combined with auto-flaps the higher of the two flap percentages is taken. You must also enable a FLAPERON_OUTPUT flaperon mixer setting if using flaperons.
|
||||
// @Description: An RC input channel to use for flaps control. If this is set to a RC channel number then that channel will be used for manual flaps control. When enabled, the percentage of flaps is taken as the percentage travel from the TRIM value of the channel to the MIN value of the channel. A value above the TRIM values will give inverse flaps (spoilers). This option needs to be enabled in conjunction with a FUNCTION setting on an output channel to one of the flap functions. When a FLAP_IN_CHANNEL is combined with auto-flaps the higher of the two flap percentages is taken.
|
||||
// @User: User
|
||||
GSCALAR(flapin_channel, "FLAP_IN_CHANNEL", 0),
|
||||
|
||||
// @Param: FLAPERON_OUTPUT
|
||||
// @DisplayName: Flaperon output
|
||||
// @Description: Enable flaperon output in software. If enabled then the APM will provide software flaperon mixing on the FLAPERON1 and FLAPERON2 output channels specified using the FUNCTION on two auxiliary channels. There are 8 different mixing modes available, which refer to the 8 ways the flap and aileron outputs can be mapped to the two flaperon servos. Please also see the MIXING_GAIN parameter for the output gain of the mixer. FLAPERON_OUTPUT cannot be combined with ELEVON_OUTPUT or ELEVON_MIXING.
|
||||
// @Values: 0:Disabled,1:UpUp,2:UpDown,3:DownUp,4:DownDown,5:UpUpSwap,6:UpDownSwap,7:DownUpSwap,8:DownDownSwap
|
||||
// @User: User
|
||||
GSCALAR(flaperon_output, "FLAPERON_OUTPUT", 0),
|
||||
|
||||
// @Param: FLAP_1_PERCNT
|
||||
// @DisplayName: Flap 1 percentage
|
||||
// @Description: The percentage change in flap position when FLAP_1_SPEED is reached. Use zero to disable flaps
|
||||
|
@ -105,7 +105,7 @@ public:
|
||||
k_param_BoardConfig,
|
||||
k_param_rssi_range, // unused, replaced by rssi_ library parameters
|
||||
k_param_flapin_channel,
|
||||
k_param_flaperon_output,
|
||||
k_param_flaperon_output, // unused
|
||||
k_param_gps,
|
||||
k_param_autotune_level,
|
||||
k_param_rally,
|
||||
@ -497,7 +497,6 @@ public:
|
||||
AP_Float takeoff_pitch_limit_reduction_sec;
|
||||
AP_Int8 level_roll_limit;
|
||||
AP_Int8 flapin_channel;
|
||||
AP_Int8 flaperon_output;
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
AP_Int8 terrain_follow;
|
||||
AP_Int16 terrain_lookahead;
|
||||
|
@ -99,8 +99,8 @@ uint16_t Plane::create_mixer(char *buf, uint16_t buf_size, const char *filename)
|
||||
rev = false;
|
||||
mix = mix_max*mixmul[g.elevon_output][0];
|
||||
} else if (function == SRV_Channel::k_aileron ||
|
||||
function == SRV_Channel::k_flaperon1 ||
|
||||
function == SRV_Channel::k_flaperon2) {
|
||||
function == SRV_Channel::k_flaperon_left ||
|
||||
function == SRV_Channel::k_flaperon_right) {
|
||||
// a secondary aileron. We don't mix flap input in yet for flaperons
|
||||
c1 = rcmap.roll()-1;
|
||||
} else if (function == SRV_Channel::k_elevator) {
|
||||
|
@ -255,29 +255,20 @@ void Plane::channel_function_mixer(SRV_Channel::Aux_servo_function_t func1_in, S
|
||||
*/
|
||||
void Plane::flaperon_update(int8_t flap_percent)
|
||||
{
|
||||
if (!SRV_Channels::function_assigned(SRV_Channel::k_flaperon1) ||
|
||||
!SRV_Channels::function_assigned(SRV_Channel::k_flaperon2)) {
|
||||
if (!SRV_Channels::function_assigned(SRV_Channel::k_flaperon_left) &&
|
||||
!SRV_Channels::function_assigned(SRV_Channel::k_flaperon_right)) {
|
||||
return;
|
||||
}
|
||||
uint16_t ch1, ch2;
|
||||
/*
|
||||
flaperons are implemented as a mixer between aileron and a
|
||||
percentage of flaps. Flap input can come from a manual channel
|
||||
or from auto flaps.
|
||||
|
||||
Use k_flaperon1 and k_flaperon2 channel trims to center servos.
|
||||
Then adjust aileron trim for level flight (note that aileron trim is affected
|
||||
by mixing gain). flapin_channel's trim is not used.
|
||||
*/
|
||||
|
||||
if (!SRV_Channels::get_output_pwm(SRV_Channel::k_aileron, ch1)) {
|
||||
return;
|
||||
}
|
||||
// The *5 is to take a percentage to a value from -500 to 500 for the mixer
|
||||
ch2 = 1500 - flap_percent * 5;
|
||||
channel_output_mixer_pwm(g.flaperon_output, ch1, ch2);
|
||||
SRV_Channels::set_output_pwm_trimmed(SRV_Channel::k_flaperon1, ch1);
|
||||
SRV_Channels::set_output_pwm_trimmed(SRV_Channel::k_flaperon2, ch2);
|
||||
float aileron = SRV_Channels::get_output_scaled(SRV_Channel::k_aileron);
|
||||
float flaperon_left = constrain_float(aileron + flap_percent * 45, -4500, 4500);
|
||||
float flaperon_right = constrain_float(aileron - flap_percent * 45, -4500, 4500);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_flaperon_left, flaperon_left);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_flaperon_right, flaperon_right);
|
||||
}
|
||||
|
||||
/*
|
||||
@ -579,9 +570,8 @@ void Plane::set_servos_flaps(void)
|
||||
SRV_Channels::limit_slew_rate(SRV_Channel::k_flap, g.flap_slewrate, G_Dt);
|
||||
}
|
||||
|
||||
if (g.flaperon_output != MIXING_DISABLED && g.elevon_output == MIXING_DISABLED && g.mix_mode == 0) {
|
||||
flaperon_update(auto_flap_percent);
|
||||
}
|
||||
// output to flaperons, if any
|
||||
flaperon_update(auto_flap_percent);
|
||||
}
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user