mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
Sub: Added roll trim using gamepad buttons.
This commit is contained in:
parent
077b0283f3
commit
12464ab5b2
@ -148,6 +148,7 @@ void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t
|
|||||||
float throttleScale = 0.8;
|
float throttleScale = 0.8;
|
||||||
int16_t rpyCenter = 1500;
|
int16_t rpyCenter = 1500;
|
||||||
int16_t throttleBase = 1500-500*throttleScale;
|
int16_t throttleBase = 1500-500*throttleScale;
|
||||||
|
int16_t rollTrim = 0;
|
||||||
static int16_t mode;
|
static int16_t mode;
|
||||||
|
|
||||||
static int16_t camTilt = 1500;
|
static int16_t camTilt = 1500;
|
||||||
@ -156,12 +157,20 @@ void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t
|
|||||||
init_arm_motors(true);
|
init_arm_motors(true);
|
||||||
} else if ( buttons & (1 << 5) ) {
|
} else if ( buttons & (1 << 5) ) {
|
||||||
init_disarm_motors();
|
init_disarm_motors();
|
||||||
} else if ( buttons & (1 << 0) ) {
|
}
|
||||||
|
|
||||||
|
if ( buttons & (1 << 0) ) {
|
||||||
camTilt = constrain_float(camTilt+20,800,2200);
|
camTilt = constrain_float(camTilt+20,800,2200);
|
||||||
} else if ( buttons & (1 << 1) ) {
|
} else if ( buttons & (1 << 1) ) {
|
||||||
camTilt = constrain_float(camTilt-20,800,2200);
|
camTilt = constrain_float(camTilt-20,800,2200);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if ( (buttons & ( 1 << 14 )) && rollTrim > -200 ) {
|
||||||
|
rollTrim -= 10;
|
||||||
|
} else if ( (buttons & ( 1 << 15 )) && rollTrim < 200 ) {
|
||||||
|
rollTrim += 10;
|
||||||
|
}
|
||||||
|
|
||||||
if ( buttons & (1 << 14) ) {
|
if ( buttons & (1 << 14) ) {
|
||||||
mode = 2000;
|
mode = 2000;
|
||||||
} else if ( buttons & (1 << 12)) {
|
} else if ( buttons & (1 << 12)) {
|
||||||
@ -169,7 +178,7 @@ void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t
|
|||||||
}
|
}
|
||||||
|
|
||||||
channels[0] = 1500; // pitch
|
channels[0] = 1500; // pitch
|
||||||
channels[1] = 1500; // roll
|
channels[1] = 1500 + rollTrim; // roll
|
||||||
channels[2] = z*throttleScale+throttleBase; // throttle
|
channels[2] = z*throttleScale+throttleBase; // throttle
|
||||||
channels[3] = r*rpyScale+rpyCenter; // yaw
|
channels[3] = r*rpyScale+rpyCenter; // yaw
|
||||||
channels[4] = mode; // for testing only
|
channels[4] = mode; // for testing only
|
||||||
|
Loading…
Reference in New Issue
Block a user