1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-24 00:35:34 +03:00

added max_angle_inclination to CLI to configure (default) 50 degree max inclination. configurable between 10 and 90 (100..900 in cli)

This commit is contained in:
dongie 2014-02-18 15:23:02 +09:00
parent 9d421b4a67
commit 202fc17608
4 changed files with 7 additions and 4 deletions

View file

@ -13,7 +13,7 @@ master_t mcfg; // master config struct with data independent from profiles
config_t cfg; // profile config struct
const char rcChannelLetters[] = "AERT1234";
static const uint8_t EEPROM_CONF_VERSION = 57;
static const uint8_t EEPROM_CONF_VERSION = 58;
static uint32_t enabledSensors = 0;
static void resetConf(void);
@ -184,6 +184,7 @@ static void resetConf(void)
mcfg.board_align_pitch = 0;
mcfg.board_align_yaw = 0;
mcfg.acc_hardware = ACC_DEFAULT; // default/autodetect
mcfg.max_angle_inclination = 500; // 50 degrees
mcfg.yaw_control_direction = 1;
mcfg.moron_threshold = 32;
mcfg.gyro_smoothing_factor = 0x00141403; // default factors of 20, 20, 3 for R/P/Y