mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
Plane: removed ancient "mix_mode" type elevon mixing
this has been deprecated for a long time
This commit is contained in:
parent
725244ff8a
commit
51b39ea3a1
@ -692,35 +692,6 @@ const AP_Param::Info Plane::var_info[] = {
|
|||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(auto_trim, "TRIM_AUTO", AUTO_TRIM),
|
GSCALAR(auto_trim, "TRIM_AUTO", AUTO_TRIM),
|
||||||
|
|
||||||
// @Param: ELEVON_MIXING
|
|
||||||
// @DisplayName: Elevon mixing
|
|
||||||
// @Description: This enables an older form of elevon mixing which is now deprecated. Please see the ELEVON_OUTPUT option for setting up elevons. The ELEVON_MIXING option should be set to 0 for elevon planes except for backwards compatibility with older setups.
|
|
||||||
// @Values: 0:Disabled,1:Enabled
|
|
||||||
// @User: User
|
|
||||||
GSCALAR(mix_mode, "ELEVON_MIXING", ELEVON_MIXING),
|
|
||||||
|
|
||||||
// @Param: ELEVON_REVERSE
|
|
||||||
// @DisplayName: Elevon reverse
|
|
||||||
// @Description: Reverse elevon mixing
|
|
||||||
// @Values: 0:Disabled,1:Enabled
|
|
||||||
// @User: User
|
|
||||||
GSCALAR(reverse_elevons, "ELEVON_REVERSE", ELEVON_REVERSE),
|
|
||||||
|
|
||||||
|
|
||||||
// @Param: ELEVON_CH1_REV
|
|
||||||
// @DisplayName: Elevon reverse
|
|
||||||
// @Description: Reverse elevon channel 1
|
|
||||||
// @Values: -1:Disabled,1:Enabled
|
|
||||||
// @User: User
|
|
||||||
GSCALAR(reverse_ch1_elevon, "ELEVON_CH1_REV", ELEVON_CH1_REVERSE),
|
|
||||||
|
|
||||||
// @Param: ELEVON_CH2_REV
|
|
||||||
// @DisplayName: Elevon reverse
|
|
||||||
// @Description: Reverse elevon channel 2
|
|
||||||
// @Values: -1:Disabled,1:Enabled
|
|
||||||
// @User: User
|
|
||||||
GSCALAR(reverse_ch2_elevon, "ELEVON_CH2_REV", ELEVON_CH2_REVERSE),
|
|
||||||
|
|
||||||
// @Param: VTAIL_OUTPUT
|
// @Param: VTAIL_OUTPUT
|
||||||
// @DisplayName: 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 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.
|
// @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.
|
||||||
|
@ -60,9 +60,9 @@ public:
|
|||||||
k_param_log_bitmask_old, // unused
|
k_param_log_bitmask_old, // unused
|
||||||
k_param_pitch_trim_cd,
|
k_param_pitch_trim_cd,
|
||||||
k_param_mix_mode,
|
k_param_mix_mode,
|
||||||
k_param_reverse_elevons,
|
k_param_reverse_elevons, // unused
|
||||||
k_param_reverse_ch1_elevon,
|
k_param_reverse_ch1_elevon, // unused
|
||||||
k_param_reverse_ch2_elevon,
|
k_param_reverse_ch2_elevon, // unused
|
||||||
k_param_flap_1_percent,
|
k_param_flap_1_percent,
|
||||||
k_param_flap_1_speed,
|
k_param_flap_1_speed,
|
||||||
k_param_flap_2_percent,
|
k_param_flap_2_percent,
|
||||||
@ -457,14 +457,10 @@ public:
|
|||||||
// Misc
|
// Misc
|
||||||
//
|
//
|
||||||
AP_Int8 auto_trim;
|
AP_Int8 auto_trim;
|
||||||
AP_Int8 mix_mode;
|
|
||||||
AP_Int8 vtail_output;
|
AP_Int8 vtail_output;
|
||||||
AP_Int8 elevon_output;
|
AP_Int8 elevon_output;
|
||||||
AP_Int8 rudder_only;
|
AP_Int8 rudder_only;
|
||||||
AP_Float mixing_gain;
|
AP_Float mixing_gain;
|
||||||
AP_Int8 reverse_elevons;
|
|
||||||
AP_Int8 reverse_ch1_elevon;
|
|
||||||
AP_Int8 reverse_ch2_elevon;
|
|
||||||
AP_Int16 mixing_offset;
|
AP_Int16 mixing_offset;
|
||||||
AP_Int16 dspoiler_rud_rate;
|
AP_Int16 dspoiler_rud_rate;
|
||||||
AP_Int16 num_resets;
|
AP_Int16 num_resets;
|
||||||
|
@ -187,15 +187,8 @@ void Plane::read_radio()
|
|||||||
elevon.ch2_temp = channel_pitch->read();
|
elevon.ch2_temp = channel_pitch->read();
|
||||||
uint16_t pwm_roll, pwm_pitch;
|
uint16_t pwm_roll, pwm_pitch;
|
||||||
|
|
||||||
if (g.mix_mode == 0) {
|
pwm_roll = elevon.ch1_temp;
|
||||||
pwm_roll = elevon.ch1_temp;
|
pwm_pitch = elevon.ch2_temp;
|
||||||
pwm_pitch = elevon.ch2_temp;
|
|
||||||
}else{
|
|
||||||
pwm_roll = BOOL_TO_SIGN(g.reverse_elevons) * (BOOL_TO_SIGN(g.reverse_ch2_elevon) * int16_t(elevon.ch2_temp - elevon.trim2)
|
|
||||||
- BOOL_TO_SIGN(g.reverse_ch1_elevon) * int16_t(elevon.ch1_temp - elevon.trim1)) / 2 + 1500;
|
|
||||||
pwm_pitch = (BOOL_TO_SIGN(g.reverse_ch2_elevon) * int16_t(elevon.ch2_temp - elevon.trim2)
|
|
||||||
+ BOOL_TO_SIGN(g.reverse_ch1_elevon) * int16_t(elevon.ch1_temp - elevon.trim1)) / 2 + 1500;
|
|
||||||
}
|
|
||||||
|
|
||||||
RC_Channels::set_pwm_all();
|
RC_Channels::set_pwm_all();
|
||||||
|
|
||||||
|
@ -356,25 +356,6 @@ void Plane::set_servos_manual_passthrough(void)
|
|||||||
SRV_Channels::copy_radio_in_out(SRV_Channel::k_elevator_with_input);
|
SRV_Channels::copy_radio_in_out(SRV_Channel::k_elevator_with_input);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
|
||||||
old (deprecated) elevon support
|
|
||||||
*/
|
|
||||||
void Plane::set_servos_old_elevons(void)
|
|
||||||
{
|
|
||||||
/*Elevon mode*/
|
|
||||||
float ch1;
|
|
||||||
float ch2;
|
|
||||||
int16_t roll = SRV_Channels::get_output_scaled(SRV_Channel::k_aileron);
|
|
||||||
int16_t pitch = SRV_Channels::get_output_scaled(SRV_Channel::k_elevator);
|
|
||||||
ch1 = pitch - (BOOL_TO_SIGN(g.reverse_elevons) * roll);
|
|
||||||
ch2 = pitch + (BOOL_TO_SIGN(g.reverse_elevons) * roll);
|
|
||||||
|
|
||||||
// directly set the radio_out values for elevon mode
|
|
||||||
SRV_Channels::set_output_pwm_first(SRV_Channel::k_aileron, elevon.trim1 + (BOOL_TO_SIGN(g.reverse_ch1_elevon) * (ch1 * 500.0f/ SERVO_MAX)));
|
|
||||||
SRV_Channels::set_output_pwm_first(SRV_Channel::k_elevator, elevon.trim2 + (BOOL_TO_SIGN(g.reverse_ch2_elevon) * (ch2 * 500.0f/ SERVO_MAX)));
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
calculate any throttle limits based on the watt limiter
|
calculate any throttle limits based on the watt limiter
|
||||||
*/
|
*/
|
||||||
@ -430,17 +411,13 @@ void Plane::throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle)
|
|||||||
*/
|
*/
|
||||||
void Plane::set_servos_controlled(void)
|
void Plane::set_servos_controlled(void)
|
||||||
{
|
{
|
||||||
if (g.mix_mode != 0) {
|
// both types of secondary aileron are slaved to the roll servo out
|
||||||
set_servos_old_elevons();
|
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron_with_input,
|
||||||
} else {
|
SRV_Channels::get_output_scaled(SRV_Channel::k_aileron));
|
||||||
// both types of secondary aileron are slaved to the roll servo out
|
|
||||||
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron_with_input,
|
|
||||||
SRV_Channels::get_output_scaled(SRV_Channel::k_aileron));
|
|
||||||
|
|
||||||
// both types of secondary elevator are slaved to the pitch servo out
|
// both types of secondary elevator are slaved to the pitch servo out
|
||||||
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator_with_input,
|
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator_with_input,
|
||||||
SRV_Channels::get_output_scaled(SRV_Channel::k_elevator));
|
SRV_Channels::get_output_scaled(SRV_Channel::k_elevator));
|
||||||
}
|
|
||||||
|
|
||||||
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND) {
|
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND) {
|
||||||
// allow landing to override servos if it would like to
|
// allow landing to override servos if it would like to
|
||||||
|
Loading…
Reference in New Issue
Block a user