mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: added swapped channel version of elevon/vtail/flaperon output
this makes it possible to setup an elevon plane without changing the transmitter reversals
This commit is contained in:
parent
ba5db0c5d8
commit
d6890495aa
@ -749,6 +749,26 @@ void Plane::channel_output_mixer(uint8_t mixing_type, int16_t & chan1_out, int16
|
||||
v1 = -v1;
|
||||
v2 = -v2;
|
||||
break;
|
||||
|
||||
case MIXING_UPUP_SWP:
|
||||
std::swap(v1, v2);
|
||||
break;
|
||||
|
||||
case MIXING_UPDN_SWP:
|
||||
v2 = -v2;
|
||||
std::swap(v1, v2);
|
||||
break;
|
||||
|
||||
case MIXING_DNUP_SWP:
|
||||
v1 = -v1;
|
||||
std::swap(v1, v2);
|
||||
break;
|
||||
|
||||
case MIXING_DNDN_SWP:
|
||||
v1 = -v1;
|
||||
v2 = -v2;
|
||||
std::swap(v1, v2);
|
||||
break;
|
||||
}
|
||||
|
||||
// scale for a 1500 center and 900..2100 range, symmetric
|
||||
|
@ -837,15 +837,15 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
|
||||
// @Param: VTAIL_OUTPUT
|
||||
// @DisplayName: VTail output
|
||||
// @Description: Enable VTail output in software. If enabled then the APM will provide software VTail mixing on the elevator and rudder channels. There are 4 different mixing modes available, which refer to the 4 ways the elevator can be mapped to the two VTail servos. Note that you must not use VTail output mixing with hardware pass-through of RC values, such as with channel 8 manual control on an APM1. So if you use an APM1 then set FLTMODE_CH to something other than 8 before you enable VTAIL_OUTPUT. Please also see the MIXING_GAIN parameter for the output gain of the mixer.
|
||||
// @Values: 0:Disabled,1:UpUp,2:UpDown,3:DownUp,4:DownDown
|
||||
// @Description: Enable VTail output in software. If enabled then the APM will provide software VTail mixing on the elevator and rudder channels. There are 8 different mixing modes available, which refer to the 8 ways the elevator can be mapped to the two VTail servos. Please also see the MIXING_GAIN parameter for the output gain of the mixer.
|
||||
// @Values: 0:Disabled,1:UpUp,2:UpDown,3:DownUp,4:DownDown,5:UpUpSwap,6:UpDownSwap,7:DownUpSwap,8:DownDownSwap
|
||||
// @User: User
|
||||
GSCALAR(vtail_output, "VTAIL_OUTPUT", 0),
|
||||
|
||||
// @Param: ELEVON_OUTPUT
|
||||
// @DisplayName: Elevon output
|
||||
// @Description: Enable software elevon output mixer. If enabled then the APM will provide software elevon mixing on the aileron and elevator channels. There are 4 different mixing modes available, which refer to the 4 ways the elevator can be mapped to the two elevon servos. Note that you must not use elevon output mixing with hardware pass-through of RC values, such as with channel 8 manual control on an APM1. So if you use an APM1 then set FLTMODE_CH to something other than 8 before you enable ELEVON_OUTPUT. Please also see the MIXING_GAIN parameter for the output gain of the mixer.
|
||||
// @Values: 0:Disabled,1:UpUp,2:UpDown,3:DownUp,4:DownDown
|
||||
// @Description: Enable software elevon output mixer. If enabled then the APM will provide software elevon mixing on the aileron and elevator channels. There are 8 different mixing modes available, which refer to the 8 ways the elevator can be mapped to the two elevon servos. Please also see the MIXING_GAIN parameter for the output gain of the mixer.
|
||||
// @Values: 0:Disabled,1:UpUp,2:UpDown,3:DownUp,4:DownDown,5:UpUpSwap,6:UpDownSwap,7:DownUpSwap,8:DownDownSwap
|
||||
// @User: User
|
||||
GSCALAR(elevon_output, "ELEVON_OUTPUT", 0),
|
||||
|
||||
@ -962,8 +962,8 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
|
||||
// @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 4 different mixing modes available, which refer to the 4 ways the flap and aileron outputs can be mapped to the two flaperon servos. Note that you must not use flaperon output mixing with hardware pass-through of RC values, such as with channel 8 manual control on an APM1. So if you use an APM1 then set FLTMODE_CH to something other than 8 before you enable FLAPERON_OUTPUT. 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
|
||||
// @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),
|
||||
|
||||
|
@ -95,7 +95,11 @@ enum ChannelMixing {
|
||||
MIXING_UPUP = 1,
|
||||
MIXING_UPDN = 2,
|
||||
MIXING_DNUP = 3,
|
||||
MIXING_DNDN = 4
|
||||
MIXING_DNDN = 4,
|
||||
MIXING_UPUP_SWP = 5,
|
||||
MIXING_UPDN_SWP = 6,
|
||||
MIXING_DNUP_SWP = 7,
|
||||
MIXING_DNDN_SWP = 8,
|
||||
};
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user