Sub: Minor bug fix in radio.
This commit is contained in:
parent
539bfde015
commit
e441a51313
@ -139,9 +139,8 @@ 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 rollTrim = 0;
|
||||||
static int16_t mode;
|
static int16_t mode;
|
||||||
|
|
||||||
static int16_t camTilt = 1500;
|
static int16_t camTilt = 1500;
|
||||||
|
|
||||||
if ( buttons & (1 << 4) ) {
|
if ( buttons & (1 << 4) ) {
|
||||||
@ -156,9 +155,9 @@ void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t
|
|||||||
camTilt = constrain_float(camTilt-20,800,2200);
|
camTilt = constrain_float(camTilt-20,800,2200);
|
||||||
}
|
}
|
||||||
|
|
||||||
if ( (buttons & ( 1 << 14 )) && rollTrim > -200 ) {
|
if ( (buttons & ( 1 << 2 )) && rollTrim > -200 ) {
|
||||||
rollTrim -= 10;
|
rollTrim -= 10;
|
||||||
} else if ( (buttons & ( 1 << 15 )) && rollTrim < 200 ) {
|
} else if ( (buttons & ( 1 << 3 )) && rollTrim < 200 ) {
|
||||||
rollTrim += 10;
|
rollTrim += 10;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user