added mincheck, maxcheck, vbatscale to settings configurable via cli

git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@120 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
timecop 2012-03-18 06:06:45 +00:00
parent c1cb4287b7
commit 8bcbf5e41e
7 changed files with 2280 additions and 2768 deletions

View File

@ -519,10 +519,10 @@
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<ColumnNumber>31</ColumnNumber>
<ColumnNumber>1</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>1</TopLine>
<CurrentLine>11</CurrentLine>
<CurrentLine>14</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\config.c</PathWithFileName>
<FilenameWithoutPath>config.c</FilenameWithoutPath>
@ -561,10 +561,10 @@
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<ColumnNumber>19</ColumnNumber>
<ColumnNumber>0</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>61</TopLine>
<CurrentLine>79</CurrentLine>
<TopLine>266</TopLine>
<CurrentLine>279</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\mixer.c</PathWithFileName>
<FilenameWithoutPath>mixer.c</FilenameWithoutPath>
@ -575,10 +575,10 @@
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<ColumnNumber>9</ColumnNumber>
<ColumnNumber>50</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>130</TopLine>
<CurrentLine>130</CurrentLine>
<TopLine>1</TopLine>
<CurrentLine>1</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\mw.c</PathWithFileName>
<FilenameWithoutPath>mw.c</FilenameWithoutPath>
@ -589,10 +589,10 @@
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<ColumnNumber>41</ColumnNumber>
<ColumnNumber>72</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>0</TopLine>
<CurrentLine>0</CurrentLine>
<TopLine>235</TopLine>
<CurrentLine>253</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\sensors.c</PathWithFileName>
<FilenameWithoutPath>sensors.c</FilenameWithoutPath>
@ -603,10 +603,10 @@
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<ColumnNumber>0</ColumnNumber>
<ColumnNumber>18</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>43</TopLine>
<CurrentLine>43</CurrentLine>
<CurrentLine>74</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\serial.c</PathWithFileName>
<FilenameWithoutPath>serial.c</FilenameWithoutPath>
@ -694,10 +694,10 @@
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<ColumnNumber>0</ColumnNumber>
<ColumnNumber>23</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>0</TopLine>
<CurrentLine>0</CurrentLine>
<TopLine>13</TopLine>
<CurrentLine>21</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\drv_hmc5883l.c</PathWithFileName>
<FilenameWithoutPath>drv_hmc5883l.c</FilenameWithoutPath>
@ -722,10 +722,10 @@
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<ColumnNumber>32</ColumnNumber>
<ColumnNumber>0</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>0</TopLine>
<CurrentLine>0</CurrentLine>
<TopLine>1</TopLine>
<CurrentLine>1</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>.\src\drv_mpu3050.c</PathWithFileName>
<FilenameWithoutPath>drv_mpu3050.c</FilenameWithoutPath>

File diff suppressed because it is too large Load Diff

View File

@ -71,6 +71,9 @@ const clivalue_t valueTable[] = {
{ "minthrottle", VAR_UINT16, &cfg.minthrottle, 0, 2000 },
{ "maxthrottle", VAR_UINT16, &cfg.maxthrottle, 0, 2000 },
{ "mincommand", VAR_UINT16, &cfg.mincommand, 0, 2000 },
{ "mincheck", VAR_UINT16, &cfg.mincheck, 0, 2000 },
{ "maxcheck", VAR_UINT16, &cfg.maxcheck, 0, 2000 },
{ "vbatscale", VAR_UINT8, &cfg.vbatscale, 10, 200 },
{ "yaw_direction", VAR_INT8, &cfg.yaw_direction, -1, 1 },
{ "wing_left_mid", VAR_UINT16, &cfg.wing_left_mid, 0, 2000 },
{ "wing_right_mid", VAR_UINT16, &cfg.wing_right_mid, 0, 2000 },
@ -273,7 +276,7 @@ static void cliSave(char *cmdline)
static void cliPrintVar(const clivalue_t *var)
{
int32_t value;
int32_t value = 0;
char buf[16];
switch (var->type) {
@ -338,7 +341,7 @@ static void cliSet(char *cmdline)
uartPrint("\r\n");
delay(10);
}
} else if (eqptr = strstr(cmdline, "=")) {
} else if ((eqptr = strstr(cmdline, "="))) {
// has equal, set var
eqptr++;
len--;

View File

@ -8,7 +8,7 @@
config_t cfg;
static uint32_t enabledSensors = 0;
static uint8_t checkNewConf = 4;
static uint8_t checkNewConf = 5;
void readEEPROM(void)
{
@ -102,10 +102,13 @@ void checkFirstTime(bool reset)
cfg.accTrim[1] = 0;
cfg.gyro_smoothing_factor = 0x00141403; // default factors of 20, 20, 3 for R/P/Y
cfg.powerTrigger1 = 0;
cfg.vbatscale = 110;
// Radio/ESC
cfg.deadband = 0;
cfg.midrc = 1500;
cfg.mincheck = 1100;
cfg.maxcheck = 1900;
cfg.minthrottle = 1150;
cfg.maxthrottle = 1850;
cfg.mincommand = 1000;

View File

@ -276,7 +276,7 @@ void mixTable(void)
if (maxMotor > cfg.maxthrottle) // this is a way to still have good gyro corrections if at least one motor reaches its max.
motor[i] -= maxMotor - cfg.maxthrottle;
motor[i] = constrain(motor[i], cfg.minthrottle, cfg.maxthrottle);
if ((rcData[THROTTLE]) < MINCHECK) {
if ((rcData[THROTTLE]) < cfg.mincheck) {
if (!feature(FEATURE_MOTOR_STOP))
motor[i] = cfg.minthrottle;
else

View File

@ -149,7 +149,7 @@ void annexCode(void)
if (rcData[axis] < cfg.midrc)
rcCommand[axis] = -rcCommand[axis];
}
rcCommand[THROTTLE] = cfg.minthrottle + (int32_t) (cfg.maxthrottle - cfg.minthrottle) * (rcData[THROTTLE] - MINCHECK) / (2000 - MINCHECK);
rcCommand[THROTTLE] = cfg.minthrottle + (int32_t) (cfg.maxthrottle - cfg.minthrottle) * (rcData[THROTTLE] - cfg.mincheck) / (2000 - cfg.mincheck);
if (headFreeMode) {
float radDiff = (heading - headFreeModeHold) * 0.0174533f; // where PI/180 ~= 0.0174533
@ -180,7 +180,7 @@ void annexCode(void)
vbatRawArray[(ind++) % 8] = adcGetBattery();
for (i = 0; i < 8; i++)
vbatRaw += vbatRawArray[i];
vbat = (((vbatRaw / 8) * 3.3f) / 4095) * 110; // result is Vbatt in 0.1V steps. 3.3V = ADC Vref, 4095 = 12bit adc, 110 = 11:1 voltage divider (10k:1k) * 10 for 0.1V
vbat = (((vbatRaw / 8) * 3.3f) / 4095) * cfg.vbatscale; // result is Vbatt in 0.1V steps. 3.3V = ADC Vref, 4095 = 12bit adc, 110 = 11:1 voltage divider (10k:1k) * 10 for 0.1V
}
if (rcOptions[BOXBEEPERON]) { // unconditional beeper on via AUXn switch
buzzerFreq = 7;
@ -352,17 +352,17 @@ void loop(void)
failsafeCnt++;
#endif
// end of failsave routine - next change is made with RcOptions setting
if (rcData[THROTTLE] < MINCHECK) {
if (rcData[THROTTLE] < cfg.mincheck) {
errorGyroI[ROLL] = 0;
errorGyroI[PITCH] = 0;
errorGyroI[YAW] = 0;
errorAngleI[ROLL] = 0;
errorAngleI[PITCH] = 0;
rcDelayCommand++;
if (rcData[YAW] < MINCHECK && rcData[PITCH] < MINCHECK && armed == 0) {
if (rcData[YAW] < cfg.mincheck && rcData[PITCH] < cfg.mincheck && armed == 0) {
if (rcDelayCommand == 20)
calibratingG = 400;
} else if (rcData[YAW] > MAXCHECK && rcData[PITCH] > MAXCHECK && armed == 0) {
} else if (rcData[YAW] > cfg.maxcheck && rcData[PITCH] > cfg.maxcheck && armed == 0) {
if (rcDelayCommand == 20) {
if (cfg.mixerConfiguration == MULTITYPE_TRI) {
servo[5] = 1500; // we center the yaw servo in conf mode
@ -377,7 +377,7 @@ void loop(void)
#endif
previousTime = micros();
}
} else if (feature(FEATURE_INFLIGHT_ACC_CAL) && (armed == 0 && rcData[YAW] < MINCHECK && rcData[PITCH] > MAXCHECK && rcData[ROLL] > MAXCHECK)) {
} else if (feature(FEATURE_INFLIGHT_ACC_CAL) && (armed == 0 && rcData[YAW] < cfg.mincheck && rcData[PITCH] > cfg.maxcheck && rcData[ROLL] > cfg.maxcheck)) {
if (rcDelayCommand == 20) {
if (AccInflightCalibrationMeasurementDone) { //trigger saving into eeprom after landing
AccInflightCalibrationMeasurementDone = 0;
@ -398,18 +398,18 @@ void loop(void)
} else if (armed)
armed = 0;
rcDelayCommand = 0;
} else if ((rcData[YAW] < MINCHECK || rcData[ROLL] < MINCHECK)
} else if ((rcData[YAW] < cfg.mincheck || rcData[ROLL] < cfg.mincheck)
&& armed == 1) {
if (rcDelayCommand == 20)
armed = 0; // rcDelayCommand = 20 => 20x20ms = 0.4s = time to wait for a specific RC command to be acknowledged
} else if ((rcData[YAW] > MAXCHECK || rcData[ROLL] > MAXCHECK)
&& rcData[PITCH] < MAXCHECK && armed == 0 && calibratingG == 0 && calibratedACC == 1) {
} else if ((rcData[YAW] > cfg.maxcheck || rcData[ROLL] > cfg.maxcheck)
&& rcData[PITCH] < cfg.maxcheck && armed == 0 && calibratingG == 0 && calibratedACC == 1) {
if (rcDelayCommand == 20) {
armed = 1;
headFreeModeHold = heading;
}
#ifdef LCD_TELEMETRY_AUTO
} else if (rcData[ROLL] < MINCHECK && rcData[PITCH] > MAXCHECK && armed == 0) {
} else if (rcData[ROLL] < cfg.mincheck && rcData[PITCH] > cfg.maxcheck && armed == 0) {
if (rcDelayCommand == 20) {
if (telemetry_auto) {
telemetry_auto = 0;
@ -420,31 +420,31 @@ void loop(void)
#endif
} else
rcDelayCommand = 0;
} else if (rcData[THROTTLE] > MAXCHECK && armed == 0) {
if (rcData[YAW] < MINCHECK && rcData[PITCH] < MINCHECK) { //throttle=max, yaw=left, pitch=min
} else if (rcData[THROTTLE] > cfg.maxcheck && armed == 0) {
if (rcData[YAW] < cfg.mincheck && rcData[PITCH] < cfg.mincheck) { //throttle=max, yaw=left, pitch=min
if (rcDelayCommand == 20)
calibratingA = 400;
rcDelayCommand++;
} else if (rcData[YAW] > MAXCHECK && rcData[PITCH] < MINCHECK) { //throttle=max, yaw=right, pitch=min
} else if (rcData[YAW] > cfg.maxcheck && rcData[PITCH] < cfg.mincheck) { //throttle=max, yaw=right, pitch=min
if (rcDelayCommand == 20)
calibratingM = 1; // MAG calibration request
rcDelayCommand++;
} else if (rcData[PITCH] > MAXCHECK) {
} else if (rcData[PITCH] > cfg.maxcheck) {
cfg.accTrim[PITCH] += 2;
writeParams();
if (feature(FEATURE_LED_RING))
ledringBlink();
} else if (rcData[PITCH] < MINCHECK) {
} else if (rcData[PITCH] < cfg.mincheck) {
cfg.accTrim[PITCH] -= 2;
writeParams();
if (feature(FEATURE_LED_RING))
ledringBlink();
} else if (rcData[ROLL] > MAXCHECK) {
} else if (rcData[ROLL] > cfg.maxcheck) {
cfg.accTrim[ROLL] += 2;
writeParams();
if (feature(FEATURE_LED_RING))
ledringBlink();
} else if (rcData[ROLL] < MINCHECK) {
} else if (rcData[ROLL] < cfg.mincheck) {
cfg.accTrim[ROLL] -= 2;
writeParams();
if (feature(FEATURE_LED_RING))
@ -461,7 +461,7 @@ void loop(void)
#endif
if (feature(FEATURE_INFLIGHT_ACC_CAL)) {
if (AccInflightCalibrationArmed && armed == 1 && rcData[THROTTLE] > MINCHECK && !rcOptions[BOXARM]) { // Copter is airborne and you are turning it off via boxarm : start measurement
if (AccInflightCalibrationArmed && armed == 1 && rcData[THROTTLE] > cfg.mincheck && !rcOptions[BOXARM]) { // Copter is airborne and you are turning it off via boxarm : start measurement
InflightcalibratingA = 50;
AccInflightCalibrationArmed = 0;
}

View File

@ -1,12 +1,5 @@
#pragma once
#define MINCHECK 1100
#define MAXCHECK 1900
/* this is the value for the ESCs when they are not armed
in some cases, this value must be lowered down to 900 for some specific ESCs */
// #define MINCOMMAND 1000
/* This option should be uncommented if ACC Z is accurate enough when motors are running*/
/* should now be ok with BMA020 and BMA180 ACC */
#define TRUSTED_ACCZ
@ -62,7 +55,6 @@
with R1=33k and R2=51k
vbat = [0;1023]*16/VBATSCALE */
#define VBATFREQ 6 // to read battery voltage - keep equal to PSENSORFREQ (6) unless you know what you are doing
#define VBATSCALE 160 // change this value if readed Battery voltage is different than real voltage
#define VBATLEVEL1_3S 107 // 10,7V
#define VBATLEVEL2_3S 103 // 10,3V
#define VBATLEVEL3_3S 99 // 9.9V
@ -162,10 +154,13 @@ typedef struct config_t {
uint8_t activate1[CHECKBOXITEMS];
uint8_t activate2[CHECKBOXITEMS];
uint8_t powerTrigger1; // trigger for alarm based on power consumption
uint8_t vbatscale; // adjust this to match battery voltage to reported value
// Radio/ESC-related configuration
uint8_t deadband; // introduce a deadband around the stick center. Must be greater than zero
uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
uint16_t mincheck; // minimum rc end
uint16_t maxcheck; // maximum rc end
uint16_t minthrottle; // Set the minimum throttle command sent to the ESC (Electronic Speed Controller). This is the minimum value that allow motors to run at a idle speed.
uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000
uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs