mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 02:33:58 -04:00
Plane: deprecate old aileron_with_input and elevator_with_input
these have very rarely been used and don't work well with new trimming mechanisms. Now treat them as ordinary ailerons/elevators
This commit is contained in:
parent
1d41dc034d
commit
2cb511c049
@ -82,8 +82,6 @@ void Plane::failsafe_check(void)
|
||||
// setup secondary output channels that do have
|
||||
// corresponding input channels
|
||||
SRV_Channels::copy_radio_in_out(SRV_Channel::k_manual, true);
|
||||
SRV_Channels::copy_radio_in_out(SRV_Channel::k_aileron_with_input, true);
|
||||
SRV_Channels::copy_radio_in_out(SRV_Channel::k_elevator_with_input, true);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_flap, 0);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_flap_auto, 0);
|
||||
|
||||
|
@ -100,10 +100,12 @@ uint16_t Plane::create_mixer(char *buf, uint16_t buf_size, const char *filename)
|
||||
mix = mix_max*mixmul[g.elevon_output][0];
|
||||
} else if (function == SRV_Channel::k_aileron ||
|
||||
function == SRV_Channel::k_flaperon_left ||
|
||||
function == SRV_Channel::k_flaperon_right) {
|
||||
function == SRV_Channel::k_flaperon_right ||
|
||||
function == SRV_Channel::k_aileron_with_input) {
|
||||
// a secondary aileron. We don't mix flap input in yet for flaperons
|
||||
c1 = rcmap.roll()-1;
|
||||
} else if (function == SRV_Channel::k_elevator) {
|
||||
} else if (function == SRV_Channel::k_elevator ||
|
||||
function == SRV_Channel::k_elevator_with_input) {
|
||||
// a secondary elevator
|
||||
c1 = rcmap.pitch()-1;
|
||||
} else if (function == SRV_Channel::k_rudder ||
|
||||
@ -116,8 +118,6 @@ uint16_t Plane::create_mixer(char *buf, uint16_t buf_size, const char *filename)
|
||||
// a flap output channel, and we have a manual flap input channel
|
||||
c1 = g.flapin_channel-1;
|
||||
} else if (i < 4 ||
|
||||
function == SRV_Channel::k_elevator_with_input ||
|
||||
function == SRV_Channel::k_aileron_with_input ||
|
||||
function == SRV_Channel::k_manual) {
|
||||
// a pass-thru channel
|
||||
c1 = i;
|
||||
|
@ -348,12 +348,6 @@ void Plane::set_servos_manual_passthrough(void)
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, channel_pitch->get_control_in_zero_dz());
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, channel_rudder->get_control_in_zero_dz());
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, channel_throttle->get_control_in_zero_dz());
|
||||
|
||||
// this variant assumes you have the corresponding
|
||||
// input channel setup in your transmitter for manual control
|
||||
// of the 2nd aileron
|
||||
SRV_Channels::copy_radio_in_out(SRV_Channel::k_aileron_with_input);
|
||||
SRV_Channels::copy_radio_in_out(SRV_Channel::k_elevator_with_input);
|
||||
}
|
||||
|
||||
/*
|
||||
@ -411,14 +405,6 @@ void Plane::throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle)
|
||||
*/
|
||||
void Plane::set_servos_controlled(void)
|
||||
{
|
||||
// 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
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator_with_input,
|
||||
SRV_Channels::get_output_scaled(SRV_Channel::k_elevator));
|
||||
|
||||
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND) {
|
||||
// allow landing to override servos if it would like to
|
||||
landing.override_servos();
|
||||
@ -582,6 +568,10 @@ void Plane::servo_output_mixers(void)
|
||||
channel_function_mixer(SRV_Channel::k_aileron, SRV_Channel::k_elevator, SRV_Channel::k_elevon_left, SRV_Channel::k_elevon_right);
|
||||
channel_function_mixer(SRV_Channel::k_rudder, SRV_Channel::k_elevator, SRV_Channel::k_vtail_right, SRV_Channel::k_vtail_left);
|
||||
|
||||
// copy aileron to deprecated aileron_with_input and elevator to deprecated elevator_with_input
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron_with_input, SRV_Channels::get_output_scaled(SRV_Channel::k_aileron));
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator_with_input, SRV_Channels::get_output_scaled(SRV_Channel::k_elevator));
|
||||
|
||||
// implement differential spoilers
|
||||
dspoiler_update();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user