SITL: FlightAxis: Fix helidemix

This commit is contained in:
Gone4Dirt 2024-02-22 17:57:27 +00:00 committed by Andrew Tridgell
parent dac1b2e99c
commit 749c7428dd
1 changed files with 3 additions and 1 deletions

View File

@ -316,10 +316,12 @@ void FlightAxis::exchange_data(const struct sitl_input &input)
float swash3 = scaled_servos[2];
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[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;