mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
Plane: re-implement MIXING_OFFSET
this was lost in the conversion of SRV_Channels
This commit is contained in:
parent
996df23a7f
commit
301b97df61
@ -717,8 +717,8 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
// @Param: DSPOILR_RUD_RATE
|
||||
// @DisplayName: Differential spoilers rudder rate
|
||||
// @Description: Sets the amount of deflection that the rudder output will apply to the differential spoilers, as a percentage. The default value of 100 results in full rudder applying full deflection. A value of 0 will result in the differential spoilers exactly following the elevons (no rudder effect).
|
||||
// @Units: d%
|
||||
// @Range: -1000 1000
|
||||
// @Units: %
|
||||
// @Range: -100 100
|
||||
// @User: User
|
||||
GSCALAR(dspoiler_rud_rate, "DSPOILR_RUD_RATE", DSPOILR_RUD_RATE_DEFAULT),
|
||||
|
||||
|
@ -243,6 +243,14 @@ void Plane::channel_function_mixer(SRV_Channel::Aux_servo_function_t func1_in, S
|
||||
// reversal as needed
|
||||
float in1 = SRV_Channels::get_output_scaled(func1_in);
|
||||
float in2 = SRV_Channels::get_output_scaled(func2_in);
|
||||
|
||||
// apply MIXING_OFFSET to input channels
|
||||
if (g.mixing_offset < 0) {
|
||||
in2 *= (100 - g.mixing_offset) * 0.01;
|
||||
} else if (g.mixing_offset > 0) {
|
||||
in1 *= (100 + g.mixing_offset) * 0.01;
|
||||
}
|
||||
|
||||
float out1 = constrain_float((in2 - in1) * g.mixing_gain, -4500, 4500);
|
||||
float out2 = constrain_float((in2 + in1) * g.mixing_gain, -4500, 4500);
|
||||
SRV_Channels::set_output_scaled(func1_out, out1);
|
||||
@ -286,7 +294,8 @@ void Plane::dspoiler_update(void)
|
||||
}
|
||||
float elevon_left = SRV_Channels::get_output_scaled(SRV_Channel::k_elevon_left);
|
||||
float elevon_right = SRV_Channels::get_output_scaled(SRV_Channel::k_elevon_right);
|
||||
float rudder = SRV_Channels::get_output_scaled(SRV_Channel::k_rudder);
|
||||
float rudder_rate = g.dspoiler_rud_rate * 0.01f;
|
||||
float rudder = SRV_Channels::get_output_scaled(SRV_Channel::k_rudder) * rudder_rate;
|
||||
float dspoiler1_left = elevon_left;
|
||||
float dspoiler2_left = elevon_left;
|
||||
float dspoiler1_right = elevon_right;
|
||||
|
Loading…
Reference in New Issue
Block a user