Browse Source

Sub: Minor bug fix in radio.

master
Rustom Jehangir 9 years ago committed by Andrew Tridgell
parent
commit
321e92cf4c
  1. 7
      ArduSub/radio.cpp

7
ArduSub/radio.cpp

@ -148,9 +148,8 @@ void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t @@ -148,9 +148,8 @@ void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t
float throttleScale = 0.8;
int16_t rpyCenter = 1500;
int16_t throttleBase = 1500-500*throttleScale;
int16_t rollTrim = 0;
static int16_t rollTrim = 0;
static int16_t mode;
static int16_t camTilt = 1500;
if ( buttons & (1 << 4) ) {
@ -165,9 +164,9 @@ void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t @@ -165,9 +164,9 @@ void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t
camTilt = constrain_float(camTilt-20,800,2200);
}
if ( (buttons & ( 1 << 14 )) && rollTrim > -200 ) {
if ( (buttons & ( 1 << 2 )) && rollTrim > -200 ) {
rollTrim -= 10;
} else if ( (buttons & ( 1 << 15 )) && rollTrim < 200 ) {
} else if ( (buttons & ( 1 << 3 )) && rollTrim < 200 ) {
rollTrim += 10;
}

Loading…
Cancel
Save