Sub: initialize scale factor for dead zones correctly

This commit is contained in:
Jacob Walser 2016-10-13 19:41:56 -04:00 committed by Andrew Tridgell
parent 330d31189e
commit e49f6fb8a6
3 changed files with 5 additions and 1 deletions

View File

@ -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

View File

@ -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;

View File

@ -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);