mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
SITL: FlightAxis: Fix helidemix
This commit is contained in:
parent
dac1b2e99c
commit
749c7428dd
@ -316,10 +316,12 @@ void FlightAxis::exchange_data(const struct sitl_input &input)
|
|||||||
float swash3 = scaled_servos[2];
|
float swash3 = scaled_servos[2];
|
||||||
|
|
||||||
float roll_rate = swash1 - swash2;
|
float roll_rate = swash1 - swash2;
|
||||||
float pitch_rate = -((swash1+swash2) / 2.0f - swash3);
|
float pitch_rate = ((swash1+swash2) / 2.0f - swash3);
|
||||||
|
float col = (swash1 + swash2 + swash3) / 3.0;
|
||||||
|
|
||||||
scaled_servos[0] = constrain_float(roll_rate + 0.5, 0, 1);
|
scaled_servos[0] = constrain_float(roll_rate + 0.5, 0, 1);
|
||||||
scaled_servos[1] = constrain_float(pitch_rate + 0.5, 0, 1);
|
scaled_servos[1] = constrain_float(pitch_rate + 0.5, 0, 1);
|
||||||
|
scaled_servos[2] = constrain_float(col, 0, 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
const uint16_t channels = hal.scheduler->is_system_initialized()?4095:0;
|
const uint16_t channels = hal.scheduler->is_system_initialized()?4095:0;
|
||||||
|
Loading…
Reference in New Issue
Block a user