mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
sub: fixup joystick changes according to review
https://github.com/ArduPilot/ardupilot/pull/11861
This commit is contained in:
parent
ee65aa2993
commit
9c6a63b55b
@ -94,16 +94,20 @@ void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t
|
||||
|
||||
uint32_t tnow = AP_HAL::millis();
|
||||
|
||||
int16_t zTot = z + zTrim;
|
||||
int16_t yTot = y + yTrim;
|
||||
int16_t xTot = x + xTrim;
|
||||
int16_t zTot;
|
||||
int16_t yTot;
|
||||
int16_t xTot;
|
||||
|
||||
if (!controls_reset_since_input_hold) {
|
||||
zTot = zTrim + 500; // 500 is neutral for throttle
|
||||
yTot = yTrim;
|
||||
xTot = xTrim;
|
||||
// if all 3 axes return to neutral, than we're ready to accept input again
|
||||
controls_reset_since_input_hold = (z == 500 && y == 0 && x == 0);
|
||||
controls_reset_since_input_hold = (abs(z - 500) < 50) && (abs(y) < 50) && (abs(x) < 50);
|
||||
} else {
|
||||
zTot = z + zTrim;
|
||||
yTot = y + yTrim;
|
||||
xTot = x + xTrim;
|
||||
}
|
||||
|
||||
RC_Channels::set_override(0, constrain_int16(pitchTrim + rpyCenter,1100,1900), tnow); // pitch
|
||||
|
Loading…
Reference in New Issue
Block a user