Plane: added ELEVON_OUTPUT option
this is like the vtail mixer, but for elevons
This commit is contained in:
parent
76d0f7f74d
commit
3d7a4d0e6e
@ -485,37 +485,37 @@ static bool suppress_throttle(void)
|
||||
}
|
||||
|
||||
/*
|
||||
implement a software VTail mixer. There are 4 different mixing modes
|
||||
implement a software VTail or elevon mixer. There are 4 different mixing modes
|
||||
*/
|
||||
static void vtail_output_mixing(void)
|
||||
static void channel_output_mixer(uint8_t mixing_type, int16_t &chan1_out, int16_t &chan2_out)
|
||||
{
|
||||
int16_t elevator, rudder;
|
||||
int16_t c1, c2;
|
||||
int16_t v1, v2;
|
||||
|
||||
// first get desired elevator and rudder as -500..500 values
|
||||
elevator = g.channel_pitch.radio_out - 1500;
|
||||
rudder = g.channel_rudder.radio_out - 1500;
|
||||
c1 = chan1_out - 1500;
|
||||
c2 = chan2_out - 1500;
|
||||
|
||||
v1 = (elevator - rudder)/2;
|
||||
v2 = (elevator + rudder)/2;
|
||||
v1 = (c1 - c2)/2;
|
||||
v2 = (c1 + c2)/2;
|
||||
|
||||
// now map to vtail output
|
||||
switch (g.vtail_output) {
|
||||
case VTAIL_DISABLED:
|
||||
// now map to mixed output
|
||||
switch (mixing_type) {
|
||||
case MIXING_DISABLED:
|
||||
return;
|
||||
|
||||
case VTAIL_UPUP:
|
||||
case MIXING_UPUP:
|
||||
break;
|
||||
|
||||
case VTAIL_UPDN:
|
||||
case MIXING_UPDN:
|
||||
v2 = -v2;
|
||||
break;
|
||||
|
||||
case VTAIL_DNUP:
|
||||
case MIXING_DNUP:
|
||||
v1 = -v1;
|
||||
break;
|
||||
|
||||
case VTAIL_DNDN:
|
||||
case MIXING_DNDN:
|
||||
v1 = -v1;
|
||||
v2 = -v2;
|
||||
break;
|
||||
@ -525,8 +525,8 @@ static void vtail_output_mixing(void)
|
||||
v2 = constrain_int16(v2, -500, 500);
|
||||
|
||||
// scale for a 1500 center and 1000..2000 range, symmetric
|
||||
g.channel_pitch.radio_out = 1500 + v1;
|
||||
g.channel_rudder.radio_out = 1500 + v2;
|
||||
chan1_out = 1500 + v1;
|
||||
chan2_out = 1500 + v2;
|
||||
}
|
||||
|
||||
/*****************************************
|
||||
@ -538,7 +538,7 @@ static void set_servos(void)
|
||||
|
||||
if (control_mode == MANUAL) {
|
||||
// do a direct pass through of radio values
|
||||
if (g.mix_mode == 0) {
|
||||
if (g.mix_mode == 0 || g.elevon_output != MIXING_DISABLED) {
|
||||
g.channel_roll.radio_out = g.channel_roll.radio_in;
|
||||
g.channel_pitch.radio_out = g.channel_pitch.radio_in;
|
||||
} else {
|
||||
@ -572,7 +572,7 @@ static void set_servos(void)
|
||||
// copy flap control from transmitter
|
||||
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_flap_auto);
|
||||
|
||||
if (g.mix_mode != 0) {
|
||||
if (g.mix_mode == 0 && g.elevon_output == MIXING_DISABLED) {
|
||||
// set any differential spoilers to follow the elevons in
|
||||
// manual mode.
|
||||
RC_Channel_aux::set_radio(RC_Channel_aux::k_dspoiler1, g.channel_roll.radio_out);
|
||||
@ -710,8 +710,10 @@ static void set_servos(void)
|
||||
}
|
||||
#endif
|
||||
|
||||
if (g.vtail_output != VTAIL_DISABLED) {
|
||||
vtail_output_mixing();
|
||||
if (g.vtail_output != MIXING_DISABLED) {
|
||||
channel_output_mixer(g.vtail_output, g.channel_pitch.radio_out, g.channel_rudder.radio_out);
|
||||
} else if (g.elevon_output != MIXING_DISABLED) {
|
||||
channel_output_mixer(g.elevon_output, g.channel_pitch.radio_out, g.channel_roll.radio_out);
|
||||
}
|
||||
|
||||
// send values to the PWM timers for output
|
||||
|
@ -85,6 +85,7 @@ public:
|
||||
k_param_hil_servos,
|
||||
k_param_vtail_output,
|
||||
k_param_nav_controller,
|
||||
k_param_elevon_output,
|
||||
|
||||
// 110: Telemetry control
|
||||
//
|
||||
@ -329,6 +330,7 @@ public:
|
||||
AP_Int8 auto_trim;
|
||||
AP_Int8 mix_mode;
|
||||
AP_Int8 vtail_output;
|
||||
AP_Int8 elevon_output;
|
||||
AP_Int8 reverse_elevons;
|
||||
AP_Int8 reverse_ch1_elevon;
|
||||
AP_Int8 reverse_ch2_elevon;
|
||||
|
@ -440,7 +440,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
|
||||
// @Param: ELEVON_MIXING
|
||||
// @DisplayName: Elevon mixing
|
||||
// @Description: Enable elevon mixing on both input and output
|
||||
// @Description: Enable elevon mixing on both input and output. To enable just output mixing see the ELEVON_OUTPUT option.
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @User: User
|
||||
GSCALAR(mix_mode, "ELEVON_MIXING", ELEVON_MIXING),
|
||||
@ -474,6 +474,13 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @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.
|
||||
// @Values: 0:Disabled,1:UpUp,2:UpDown,3:DownUp,4:DownDown
|
||||
// @User: User
|
||||
GSCALAR(elevon_output, "ELEVON_OUTPUT", 0),
|
||||
|
||||
// @Param: SYS_NUM_RESETS
|
||||
// @DisplayName: Num Resets
|
||||
// @Description: Number of APM board resets
|
||||
|
@ -82,12 +82,12 @@ enum StickMixing {
|
||||
STICK_MIXING_DIRECT = 2
|
||||
};
|
||||
|
||||
enum VTailMixing {
|
||||
VTAIL_DISABLED = 0,
|
||||
VTAIL_UPUP = 1,
|
||||
VTAIL_UPDN = 2,
|
||||
VTAIL_DNUP = 3,
|
||||
VTAIL_DNDN = 4
|
||||
enum ChannelMixing {
|
||||
MIXING_DISABLED = 0,
|
||||
MIXING_UPUP = 1,
|
||||
MIXING_UPDN = 2,
|
||||
MIXING_DNUP = 3,
|
||||
MIXING_DNDN = 4
|
||||
};
|
||||
|
||||
// Commands - Note that APM now uses a subset of the MAVLink protocol
|
||||
|
@ -43,8 +43,10 @@ void failsafe_check(uint32_t tnow)
|
||||
g.channel_pitch.radio_out = hal.rcin->read(CH_2);
|
||||
g.channel_throttle.radio_out = hal.rcin->read(CH_3);
|
||||
g.channel_rudder.radio_out = hal.rcin->read(CH_4);
|
||||
if (g.vtail_output != VTAIL_DISABLED) {
|
||||
vtail_output_mixing();
|
||||
if (g.vtail_output != MIXING_DISABLED) {
|
||||
channel_output_mixer(g.vtail_output, g.channel_pitch.radio_out, g.channel_rudder.radio_out);
|
||||
} else if (g.elevon_output != MIXING_DISABLED) {
|
||||
channel_output_mixer(g.elevon_output, g.channel_pitch.radio_out, g.channel_roll.radio_out);
|
||||
}
|
||||
if (!demoing_servos) {
|
||||
servo_write(CH_1, g.channel_roll.radio_out);
|
||||
|
Loading…
Reference in New Issue
Block a user