mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Sub: Fixed joystick to camera tilt control direction
This commit is contained in:
parent
3af1dc8c93
commit
fc6f793aab
@ -157,9 +157,9 @@ void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t
|
|||||||
} else if ( mode & (1 << 5) ) {
|
} else if ( mode & (1 << 5) ) {
|
||||||
init_disarm_motors();
|
init_disarm_motors();
|
||||||
} else if ( mode & (1 << 0) ) {
|
} else if ( mode & (1 << 0) ) {
|
||||||
camTilt = constrain_float(camTilt-20,800,2200);
|
|
||||||
} else if ( mode & (1 << 1) ) {
|
|
||||||
camTilt = constrain_float(camTilt+20,800,2200);
|
camTilt = constrain_float(camTilt+20,800,2200);
|
||||||
|
} else if ( mode & (1 << 1) ) {
|
||||||
|
camTilt = constrain_float(camTilt-20,800,2200);
|
||||||
}
|
}
|
||||||
|
|
||||||
channels[0] = 1500; // pitch
|
channels[0] = 1500; // pitch
|
||||||
|
Loading…
Reference in New Issue
Block a user