Plane: make rudder differnal thrust global

This commit is contained in:
IamPete1 2018-12-29 15:42:22 +00:00 committed by Andrew Tridgell
parent 8fd8ae660b
commit eaed0a2d47
2 changed files with 10 additions and 7 deletions

View File

@ -796,7 +796,10 @@ private:
// the crc of the last created PX4Mixer
int32_t last_mixer_crc = -1;
#endif // CONFIG_HAL_BOARD
// rudder mixing gain for differential thrust (0 - 1)
float rudder_dt;
void adjust_nav_pitch_throttle(void);
void update_load_factor(void);
void send_fence_status(mavlink_channel_t chan);

View File

@ -559,25 +559,25 @@ void Plane::servos_twin_engine_mix(void)
{
float throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle);
float rud_gain = float(plane.g2.rudd_dt_gain) / 100;
float rudder = rud_gain * SRV_Channels::get_output_scaled(SRV_Channel::k_rudder) / float(SERVO_MAX);
rudder_dt = rud_gain * SRV_Channels::get_output_scaled(SRV_Channel::k_rudder) / float(SERVO_MAX);
if (afs.should_crash_vehicle()) {
// when in AFS failsafe force rudder input for differential thrust to zero
rudder = 0;
rudder_dt = 0;
}
float throttle_left, throttle_right;
if (throttle < 0 && have_reverse_thrust() && allow_reverse_thrust()) {
// doing reverse thrust
throttle_left = constrain_float(throttle + 50 * rudder, -100, 0);
throttle_right = constrain_float(throttle - 50 * rudder, -100, 0);
throttle_left = constrain_float(throttle + 50 * rudder_dt, -100, 0);
throttle_right = constrain_float(throttle - 50 * rudder_dt, -100, 0);
} else if (throttle <= 0) {
throttle_left = throttle_right = 0;
} else {
// doing forward thrust
throttle_left = constrain_float(throttle + 50 * rudder, 0, 100);
throttle_right = constrain_float(throttle - 50 * rudder, 0, 100);
throttle_left = constrain_float(throttle + 50 * rudder_dt, 0, 100);
throttle_right = constrain_float(throttle - 50 * rudder_dt, 0, 100);
}
if (!hal.util->get_soft_armed()) {
if (arming.arming_required() == AP_Arming::YES_ZERO_PWM) {