From e49f6fb8a63bcb7caffe0c36b2038a33480f47bc Mon Sep 17 00:00:00 2001 From: Jacob Walser Date: Thu, 13 Oct 2016 19:41:56 -0400 Subject: [PATCH] Sub: initialize scale factor for dead zones correctly --- ArduSub/defines.h | 2 ++ ArduSub/joystick.cpp | 2 +- ArduSub/radio.cpp | 2 ++ 3 files changed, 5 insertions(+), 1 deletion(-) diff --git a/ArduSub/defines.h b/ArduSub/defines.h index f8c371ba50..293a961474 100644 --- a/ArduSub/defines.h +++ b/ArduSub/defines.h @@ -507,3 +507,5 @@ enum ThrowModeState { #define THR_BEHAVE_FEEDBACK_FROM_MID_STICK (1<<0) #define THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND (1<<1) #define THR_BEHAVE_DISARM_ON_LAND_DETECT (1<<2) + +#define JOYSTICK_INITIAL_GAIN 0.5 diff --git a/ArduSub/joystick.cpp b/ArduSub/joystick.cpp index 6bf09fbc14..2db69f6f52 100644 --- a/ArduSub/joystick.cpp +++ b/ArduSub/joystick.cpp @@ -21,7 +21,7 @@ namespace { int16_t video_switch = 1100; int16_t x_last, y_last, z_last; uint16_t buttons_prev; - float gain = 0.5; + float gain = JOYSTICK_INITIAL_GAIN; float maxGain = 1.0; float minGain = 0.25; int8_t numGainSettings = 4; diff --git a/ArduSub/radio.cpp b/ArduSub/radio.cpp index 6eb8deb2d4..26c5611cbf 100644 --- a/ArduSub/radio.cpp +++ b/ArduSub/radio.cpp @@ -56,6 +56,8 @@ void Sub::init_rc_in() ch->save_eeprom(); } + RC_Channel::scale_dead_zones(JOYSTICK_INITIAL_GAIN); + //set auxiliary servo ranges // g.rc_5.set_range(0,1000); // g.rc_6.set_range(0,1000);