1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 00:05:33 +03:00

bring back flying wing w/all configuration options

config version bumped, settings cleared.

git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@213 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
timecop@gmail.com 2012-09-09 11:35:35 +00:00
parent b94c13b1c5
commit 70884d69d5
5 changed files with 2850 additions and 2783 deletions

View file

@ -13,7 +13,7 @@ config_t cfg;
const char rcChannelLetters[] = "AERT1234";
static uint32_t enabledSensors = 0;
uint8_t checkNewConf = 28;
uint8_t checkNewConf = 29;
void parseRcChannels(const char *input)
{
@ -155,7 +155,7 @@ void checkFirstTime(bool reset)
cfg.retarded_arm = 0; // disable arm/disarm on roll left/right
// Failsafe Variables
cfg.failsafe_delay = 10; // 1sec
cfg.failsafe_delay = 10; // 1sec
cfg.failsafe_off_delay = 200; // 20sec
cfg.failsafe_throttle = 1200; // decent default which should always be below hover throttle for people.
@ -172,6 +172,18 @@ void checkFirstTime(bool reset)
cfg.tri_yaw_min = 1020;
cfg.tri_yaw_max = 2000;
// flying wing
cfg.wing_left_min = 1020;
cfg.wing_left_mid = 1500;
cfg.wing_left_max = 2000;
cfg.wing_right_min = 1020;
cfg.wing_right_mid = 1500;
cfg.wing_right_max = 2000;
cfg.pitch_direction_l = 1;
cfg.pitch_direction_r = -1;
cfg.roll_direction_l = 1;
cfg.roll_direction_r = 1;
// gimbal
cfg.gimbal_pitch_gain = 10;
cfg.gimbal_roll_gain = 10;