mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 12:25:20 +03:00
fixed acczero offsets to 0 on initial eeprom cleanup
added fifo mode to adxl345 driver, currently disabled. work in progress. fixed output for PWM 5-8 when used with PPM + camstab + abovequad configs. fixed baro, now alt-hold actually works. silly copypaste typo. trashed all remaining parts of power meter and lcd configuration stuff. useless. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@145 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
9e5504acd8
commit
cb334ecf47
13 changed files with 2849 additions and 3020 deletions
|
@ -33,10 +33,6 @@ void readEEPROM(void)
|
|||
// Read flash
|
||||
memcpy(&cfg, (char *)FLASH_WRITE_ADDR, sizeof(config_t));
|
||||
|
||||
#if defined(POWERMETER)
|
||||
pAlarm = (uint32_t) cfg.powerTrigger1 *(uint32_t) PLEVELSCALE *(uint32_t) PLEVELDIV; // need to cast before multiplying
|
||||
#endif
|
||||
|
||||
for (i = 0; i < 7; i++)
|
||||
lookupRX[i] = (2500 + cfg.rcExpo8 * (i * i - 25)) * i * (int32_t) cfg.rcRate8 / 1250;
|
||||
|
||||
|
@ -116,10 +112,12 @@ void checkFirstTime(bool reset)
|
|||
}
|
||||
cfg.accTrim[0] = 0;
|
||||
cfg.accTrim[1] = 0;
|
||||
cfg.accZero[0] = 0;
|
||||
cfg.accZero[1] = 0;
|
||||
cfg.accZero[2] = 0;
|
||||
cfg.acc_lpf_factor = 4;
|
||||
cfg.gyro_lpf = 42;
|
||||
cfg.gyro_smoothing_factor = 0x00141403; // default factors of 20, 20, 3 for R/P/Y
|
||||
cfg.powerTrigger1 = 0;
|
||||
cfg.vbatscale = 110;
|
||||
cfg.vbatmaxcellvoltage = 43;
|
||||
cfg.vbatmincellvoltage = 33;
|
||||
|
|
|
@ -3,6 +3,7 @@
|
|||
// ADXL345, Alternative address mode 0x53
|
||||
#define ADXL345_ADDRESS 0x53
|
||||
|
||||
// Registers
|
||||
#define ADXL345_BW_RATE 0x2C
|
||||
#define ADXL345_POWER_CTL 0x2D
|
||||
#define ADXL345_INT_ENABLE 0x2E
|
||||
|
@ -10,16 +11,32 @@
|
|||
#define ADXL345_DATA_OUT 0x32
|
||||
#define ADXL345_FIFO_CTL 0x38
|
||||
|
||||
#define ADXL345_BW_RATE_200 0x0B
|
||||
// BW_RATE values
|
||||
#define ADXL345_RATE_50 0x09
|
||||
#define ADXL345_RATE_100 0x0A
|
||||
#define ADXL345_RATE_200 0x0B
|
||||
#define ADXL345_RATE_400 0x0C
|
||||
#define ADXL345_RATE_800 0x0D
|
||||
#define ADXL345_RATE_1600 0x0E
|
||||
#define ADXL345_RATE_3200 0x0F
|
||||
|
||||
// various register values
|
||||
#define ADXL345_POWER_MEAS 0x08
|
||||
#define ADXL345_FULL_RANGE 0x08
|
||||
#define ADXL345_RANGE_2G 0x00
|
||||
#define ADXL345_RANGE_4G 0x01
|
||||
#define ADXL345_RANGE_8G 0x02
|
||||
#define ADXL345_RANGE_16G 0x03
|
||||
#define ADXL345_FIFO_STREAM 0x80
|
||||
|
||||
|
||||
static void adxl345Init(void);
|
||||
static void adxl345Read(int16_t *accelData);
|
||||
static void adxl345Align(int16_t *accelData);
|
||||
|
||||
bool adxl345Detect(sensor_t *acc)
|
||||
static bool useFifo = false;
|
||||
|
||||
bool adxl345Detect(drv_adxl345_config_t *init, sensor_t *acc)
|
||||
{
|
||||
bool ack = false;
|
||||
uint8_t sig = 0;
|
||||
|
@ -28,48 +45,61 @@ bool adxl345Detect(sensor_t *acc)
|
|||
if (!ack || sig != 0xE5)
|
||||
return false;
|
||||
|
||||
// use ADXL345's fifo to filter data or not
|
||||
useFifo = init->useFifo;
|
||||
|
||||
acc->init = adxl345Init;
|
||||
acc->read = adxl345Read;
|
||||
acc->align = adxl345Align;
|
||||
return true;
|
||||
}
|
||||
|
||||
#define ADXL_RATE_100 0x0A
|
||||
#define ADXL_RATE_200 0x0B
|
||||
#define ADXL_RATE_400 0x0C
|
||||
#define ADXL_RATE_800 0x0D
|
||||
#define ADXL_RATE_1600 0x0E
|
||||
#define ADXL_RATE_3200 0x0F
|
||||
#define ADXL_FULL_RES 0x08
|
||||
#define ADXL_RANGE_2G 0x00
|
||||
#define ADXL_RANGE_4G 0x01
|
||||
#define ADXL_RANGE_8G 0x02
|
||||
#define ADXL_RANGE_16G 0x03
|
||||
|
||||
static void adxl345Init(void)
|
||||
{
|
||||
#ifdef FREEFLIGHT
|
||||
i2cWrite(ADXL345_ADDRESS, ADXL345_BW_RATE, ADXL345_BW_RATE_200);
|
||||
i2cWrite(ADXL345_ADDRESS, ADXL345_POWER_CTL, ADXL345_POWER_MEAS);
|
||||
i2cWrite(ADXL345_ADDRESS, ADXL345_INT_ENABLE, 0);
|
||||
i2cWrite(ADXL345_ADDRESS, ADXL345_DATA_FORMAT, ADXL345_FULL_RANGE | ADXL345_RANGE_16G);
|
||||
i2cWrite(ADXL345_ADDRESS, ADXL345_FIFO_CTL, 0);
|
||||
#else
|
||||
// MWC defaults
|
||||
i2cWrite(ADXL345_ADDRESS, ADXL345_POWER_CTL, 1 << 3); // register: Power CTRL -- value: Set measure bit 3 on
|
||||
i2cWrite(ADXL345_ADDRESS, ADXL345_DATA_FORMAT, 0x0B); // register: DATA_FORMAT -- value: Set bits 3(full range) and 1 0 on (+/- 16g-range)
|
||||
i2cWrite(ADXL345_ADDRESS, ADXL345_BW_RATE, 0x09); // register: BW_RATE -- value: rate=50hz, bw=20hz
|
||||
#endif /* FreeFlight */
|
||||
if (useFifo) {
|
||||
uint8_t fifoDepth = 16;
|
||||
i2cWrite(ADXL345_ADDRESS, ADXL345_POWER_CTL, ADXL345_POWER_MEAS);
|
||||
i2cWrite(ADXL345_ADDRESS, ADXL345_DATA_FORMAT, ADXL345_FULL_RANGE | ADXL345_RANGE_8G);
|
||||
i2cWrite(ADXL345_ADDRESS, ADXL345_BW_RATE, ADXL345_RATE_400);
|
||||
i2cWrite(ADXL345_ADDRESS, ADXL345_FIFO_CTL, (fifoDepth & 0x1F) | ADXL345_FIFO_STREAM);
|
||||
} else {
|
||||
i2cWrite(ADXL345_ADDRESS, ADXL345_POWER_CTL, ADXL345_POWER_MEAS);
|
||||
i2cWrite(ADXL345_ADDRESS, ADXL345_DATA_FORMAT, ADXL345_FULL_RANGE | ADXL345_RANGE_8G);
|
||||
i2cWrite(ADXL345_ADDRESS, ADXL345_BW_RATE, ADXL345_RATE_100);
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t acc_samples = 0;
|
||||
|
||||
static void adxl345Read(int16_t *accelData)
|
||||
{
|
||||
static uint8_t buf[6];
|
||||
uint8_t buf[8];
|
||||
|
||||
i2cRead(ADXL345_ADDRESS, ADXL345_DATA_OUT, 6, buf);
|
||||
accelData[0] = buf[0] + (buf[1] << 8);
|
||||
accelData[1] = buf[2] + (buf[3] << 8);
|
||||
accelData[2] = buf[4] + (buf[5] << 8);
|
||||
if (useFifo) {
|
||||
int32_t x = 0;
|
||||
int32_t y = 0;
|
||||
int32_t z = 0;
|
||||
uint8_t i = 0;
|
||||
uint8_t samples_remaining;
|
||||
|
||||
do {
|
||||
i++;
|
||||
i2cRead(ADXL345_ADDRESS, ADXL345_DATA_OUT, 8, buf);
|
||||
x += (int16_t)(buf[0] + (buf[1] << 8));
|
||||
y += (int16_t)(buf[2] + (buf[3] << 8));
|
||||
z += (int16_t)(buf[4] + (buf[5] << 8));
|
||||
samples_remaining = buf[7] & 0x7F;
|
||||
} while ((i < 32) && (samples_remaining > 0));
|
||||
accelData[0] = x / i;
|
||||
accelData[1] = y / i;
|
||||
accelData[2] = z / i;
|
||||
acc_samples = i;
|
||||
} else {
|
||||
i2cRead(ADXL345_ADDRESS, ADXL345_DATA_OUT, 6, buf);
|
||||
accelData[0] = buf[0] + (buf[1] << 8);
|
||||
accelData[1] = buf[2] + (buf[3] << 8);
|
||||
accelData[2] = buf[4] + (buf[5] << 8);
|
||||
}
|
||||
}
|
||||
|
||||
static void adxl345Align(int16_t *accData)
|
||||
|
|
|
@ -1,3 +1,8 @@
|
|||
#pragma once
|
||||
|
||||
bool adxl345Detect(sensor_t *acc);
|
||||
typedef struct drv_adxl345_config_t {
|
||||
bool useFifo;
|
||||
uint16_t dataRate;
|
||||
} drv_adxl345_config_t;
|
||||
|
||||
bool adxl345Detect(drv_adxl345_config_t *init, sensor_t *acc);
|
||||
|
|
|
@ -353,6 +353,13 @@ bool pwmInit(drv_pwm_config_t *init)
|
|||
// turn on more motor outputs if we're using ppm / not using pwm input
|
||||
if (!init->enableInput || init->usePPM) {
|
||||
// PWM 7,8,9,10
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1;
|
||||
GPIO_Init(GPIOB, &GPIO_InitStructure);
|
||||
|
||||
TIM_TimeBaseStructure.TIM_Period = (1000000 / init->motorPwmRate) - 1;
|
||||
TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure);
|
||||
|
||||
|
|
|
@ -246,8 +246,8 @@ void getEstimatedAltitude(void)
|
|||
static uint32_t deadLine = INIT_DELAY;
|
||||
static int16_t BaroHistTab[BARO_TAB_SIZE];
|
||||
static int8_t BaroHistIdx;
|
||||
int32_t BaroHigh = 0;
|
||||
int32_t BaroLow = 0;
|
||||
static int32_t BaroHigh = 0;
|
||||
static int32_t BaroLow = 0;
|
||||
int32_t temp32;
|
||||
int16_t last;
|
||||
|
||||
|
|
|
@ -101,10 +101,6 @@ int main(void)
|
|||
|
||||
previousTime = micros();
|
||||
calibratingG = 400;
|
||||
#if defined(POWERMETER)
|
||||
for (i = 0; i <= PMOTOR_SUM; i++)
|
||||
pMeter[i] = 0;
|
||||
#endif
|
||||
|
||||
// loopy
|
||||
while (1) {
|
||||
|
|
20
src/mixer.c
20
src/mixer.c
|
@ -285,24 +285,4 @@ void mixTable(void)
|
|||
if (armed == 0)
|
||||
motor[i] = cfg.mincommand;
|
||||
}
|
||||
|
||||
#if (LOG_VALUES == 2) || defined(POWERMETER_SOFT)
|
||||
uint32_t amp;
|
||||
/* true cubic function; when divided by vbat_max=126 (12.6V) for 3 cell battery this gives maximum value of ~ 500 */
|
||||
/* Lookup table moved to PROGMEM 11/21/2001 by Danal */
|
||||
static uint16_t amperes[64] = {
|
||||
0, 2, 6, 15, 30, 52, 82, 123, 175, 240, 320, 415, 528, 659, 811, 984, 1181, 1402, 1648, 1923, 2226, 2559, 2924, 3322, 3755, 4224, 4730, 5276, 5861, 6489, 7160, 7875, 8637, 9446, 10304, 11213, 12173, 13187, 14256, 15381, 16564, 17805, 19108, 20472, 21900, 23392, 24951, 26578, 28274, 30041, 31879, 33792, 35779, 37843, 39984, 42205, 44507, 46890, 49358, 51910, 54549, 57276, 60093, 63000};
|
||||
|
||||
if (vbat) { // by all means - must avoid division by zero
|
||||
for (i = 0; i < NUMBER_MOTOR; i++) {
|
||||
amp = amperes[((motor[i] - 1000) >> 4)] / vbat; // range mapped from [1000:2000] => [0:1000]; then break that up into 64 ranges; lookup amp
|
||||
#if (LOG_VALUES == 2)
|
||||
pMeter[i] += amp; // sum up over time the mapped ESC input
|
||||
#endif
|
||||
#if defined(POWERMETER_SOFT)
|
||||
pMeter[PMOTOR_SUM] += amp; // total sum over all motors
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
|
93
src/mw.c
93
src/mw.c
|
@ -60,15 +60,7 @@ uint16_t AccInflightCalibrationMeasurementDone = 0;
|
|||
uint16_t AccInflightCalibrationSavetoEEProm = 0;
|
||||
uint16_t AccInflightCalibrationActive = 0;
|
||||
|
||||
// **********************
|
||||
// power meter
|
||||
// **********************
|
||||
#define PMOTOR_SUM 8 // index into pMeter[] for sum
|
||||
uint32_t pMeter[PMOTOR_SUM + 1]; // we use [0:7] for eight motors,one extra for sum
|
||||
uint8_t pMeterV; // dummy to satisfy the paramStruct logic in ConfigurationLoop()
|
||||
uint32_t pAlarm; // we scale the eeprom value from [0:255] to this value we can directly compare to the sum in pMeter[6]
|
||||
uint16_t powerValue = 0; // last known current
|
||||
uint16_t intPowerMeterSum, intPowerTrigger1;
|
||||
// Battery monitoring stuff
|
||||
uint8_t batteryCellCount = 3; // cell count
|
||||
uint16_t batteryWarningVoltage; // annoying buzzer after this one, battery ready to be dead
|
||||
|
||||
|
@ -91,19 +83,9 @@ void blinkLED(uint8_t num, uint8_t wait, uint8_t repeat)
|
|||
void annexCode(void)
|
||||
{
|
||||
static uint32_t buzzerTime, calibratedAccTime;
|
||||
#if defined(LCD_TELEMETRY)
|
||||
static uint16_t telemetryTimer = 0, telemetryAutoTimer = 0, psensorTimer = 0;
|
||||
#endif
|
||||
#if defined(LCD_TELEMETRY)
|
||||
static uint8_t telemetryAutoIndex = 0;
|
||||
static char telemetryAutoSequence[] = LCD_TELEMETRY_AUTO;
|
||||
#endif
|
||||
static uint8_t vbatTimer = 0;
|
||||
static uint8_t buzzerFreq; //delay between buzzer ring
|
||||
uint8_t axis, prop1, prop2;
|
||||
#if defined(POWERMETER_HARD)
|
||||
uint16_t pMeterRaw; //used for current reading
|
||||
#endif
|
||||
static uint8_t ind = 0;
|
||||
uint16_t vbatRaw = 0;
|
||||
static uint16_t vbatRawArray[8];
|
||||
|
@ -159,21 +141,6 @@ void annexCode(void)
|
|||
rcCommand[ROLL] = rcCommand[ROLL] * cosDiff - rcCommand[PITCH] * sinDiff;
|
||||
rcCommand[PITCH] = rcCommand_PITCH;
|
||||
}
|
||||
#if defined(POWERMETER_HARD)
|
||||
if (!(++psensorTimer % PSENSORFREQ)) {
|
||||
pMeterRaw = analogRead(PSENSORPIN);
|
||||
powerValue = (PSENSORNULL > pMeterRaw ? PSENSORNULL - pMeterRaw : pMeterRaw - PSENSORNULL); // do not use abs(), it would induce implicit cast to uint and overrun
|
||||
if (powerValue < 333) { // only accept reasonable values. 333 is empirical
|
||||
#ifdef LOG_VALUES
|
||||
if (powerValue > powerMax)
|
||||
powerMax = powerValue;
|
||||
#endif
|
||||
} else {
|
||||
powerValue = 333;
|
||||
}
|
||||
pMeter[PMOTOR_SUM] += (uint32_t) powerValue;
|
||||
}
|
||||
#endif
|
||||
|
||||
if (feature(FEATURE_VBAT)) {
|
||||
if (!(++vbatTimer % VBATFREQ)) {
|
||||
|
@ -184,18 +151,10 @@ void annexCode(void)
|
|||
}
|
||||
if (rcOptions[BOXBEEPERON]) { // unconditional beeper on via AUXn switch
|
||||
buzzerFreq = 7;
|
||||
} else if (((vbat > batteryWarningVoltage)
|
||||
#if defined(POWERMETER)
|
||||
&& ((pMeter[PMOTOR_SUM] < pAlarm) || (pAlarm == 0))
|
||||
#endif
|
||||
) || (vbat < cfg.vbatmincellvoltage)) { //VBAT ok AND powermeter ok, buzzer off
|
||||
} else if ((vbat > batteryWarningVoltage) || (vbat < cfg.vbatmincellvoltage)) { //VBAT ok, buzzer off
|
||||
buzzerFreq = 0;
|
||||
buzzerState = 0;
|
||||
BEEP_OFF;
|
||||
#if defined(POWERMETER)
|
||||
} else if (pMeter[PMOTOR_SUM] > pAlarm) { // sound alarm for powermeter
|
||||
buzzerFreq = 4;
|
||||
#endif
|
||||
} else
|
||||
buzzerFreq = 4; // low battery
|
||||
if (buzzerFreq) {
|
||||
|
@ -241,28 +200,6 @@ void annexCode(void)
|
|||
|
||||
serialCom();
|
||||
|
||||
#if defined(POWERMETER)
|
||||
intPowerMeterSum = (pMeter[PMOTOR_SUM] / PLEVELDIV);
|
||||
intPowerTrigger1 = cfg.powerTrigger1 * PLEVELSCALE;
|
||||
#endif
|
||||
|
||||
#ifdef LCD_TELEMETRY_AUTO
|
||||
if ((telemetry_auto)
|
||||
&& (!(++telemetryAutoTimer % LCD_TELEMETRY_AUTO_FREQ))) {
|
||||
telemetry = telemetryAutoSequence[++telemetryAutoIndex % strlen(telemetryAutoSequence)];
|
||||
LCDclear(); // make sure to clear away remnants
|
||||
}
|
||||
#endif
|
||||
#ifdef LCD_TELEMETRY
|
||||
if (!(++telemetryTimer % LCD_TELEMETRY_FREQ)) {
|
||||
#if (LCD_TELEMETRY_DEBUG+0 > 0)
|
||||
telemetry = LCD_TELEMETRY_DEBUG;
|
||||
#endif
|
||||
if (telemetry)
|
||||
lcd_telemetry();
|
||||
}
|
||||
#endif
|
||||
|
||||
if (sensors(SENSOR_GPS)) {
|
||||
static uint32_t GPSLEDTime;
|
||||
if (currentTime > GPSLEDTime && (GPS_fix_home == 1)) {
|
||||
|
@ -353,21 +290,6 @@ void loop(void)
|
|||
if (rcData[YAW] < cfg.mincheck && rcData[PITCH] < cfg.mincheck && armed == 0) {
|
||||
if (rcDelayCommand == 20)
|
||||
calibratingG = 400;
|
||||
} 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
|
||||
writeServos();
|
||||
} else if (cfg.mixerConfiguration == MULTITYPE_FLYING_WING) {
|
||||
servo[0] = cfg.wing_left_mid;
|
||||
servo[1] = cfg.wing_right_mid;
|
||||
writeServos();
|
||||
}
|
||||
#if defined(LCD_CONF)
|
||||
configurationLoop(); //beginning LCD configuration
|
||||
#endif
|
||||
previousTime = micros();
|
||||
}
|
||||
} 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
|
||||
|
@ -397,16 +319,6 @@ void loop(void)
|
|||
armed = 1;
|
||||
headFreeModeHold = heading;
|
||||
}
|
||||
#ifdef LCD_TELEMETRY_AUTO
|
||||
} else if (rcData[ROLL] < cfg.mincheck && rcData[PITCH] > cfg.maxcheck && armed == 0) {
|
||||
if (rcDelayCommand == 20) {
|
||||
if (telemetry_auto) {
|
||||
telemetry_auto = 0;
|
||||
telemetry = 0;
|
||||
} else
|
||||
telemetry_auto = 1;
|
||||
}
|
||||
#endif
|
||||
} else
|
||||
rcDelayCommand = 0;
|
||||
} else if (rcData[THROTTLE] > cfg.maxcheck && armed == 0) {
|
||||
|
@ -502,6 +414,7 @@ void loop(void)
|
|||
} else
|
||||
baroMode = 0;
|
||||
}
|
||||
|
||||
if (sensors(SENSOR_MAG)) {
|
||||
if (rcOptions[BOXMAG]) {
|
||||
if (magMode == 0) {
|
||||
|
|
13
src/mw.h
13
src/mw.h
|
@ -106,13 +106,10 @@ typedef enum MultiType
|
|||
#define CHECKBOXITEMS 11
|
||||
#define PIDITEMS 8
|
||||
|
||||
// #define ACC_ORIENTATION(X, Y, Z) { accADC[ROLL] = Y; accADC[PITCH] = -X; accADC[YAW] = Z; }
|
||||
// #define GYRO_ORIENTATION(X, Y, Z) { gyroADC[ROLL] = -Y; gyroADC[PITCH] = X; gyroADC[YAW] = Z; }
|
||||
|
||||
#define min(a,b) ((a)<(b)?(a):(b))
|
||||
#define max(a,b) ((a)>(b)?(a):(b))
|
||||
#define abs(x) ((x)>0?(x):-(x))
|
||||
#define constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt)))
|
||||
#define min(a, b) ((a) < (b) ? (a) : (b))
|
||||
#define max(a, b) ((a) > (b) ? (a) : (b))
|
||||
#define abs(x) ((x) > 0 ? (x) : -(x))
|
||||
#define constrain(amt, low, high) ((amt) < (low) ? (low) : ((amt) > (high) ? (high) : (amt)))
|
||||
|
||||
typedef struct config_t {
|
||||
uint8_t version;
|
||||
|
@ -140,7 +137,6 @@ 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
|
||||
uint8_t vbatmaxcellvoltage; // maximum voltage per cell, used for auto-detecting battery voltage in 0.1V units, default is 43 (4.3V)
|
||||
uint8_t vbatmincellvoltage; // minimum voltage per cell, this triggers battery out alarms, in 0.1V units, default is 33 (3.3V)
|
||||
|
@ -224,7 +220,6 @@ extern int16_t rcData[8];
|
|||
extern uint8_t accMode;
|
||||
extern uint8_t magMode;
|
||||
extern uint8_t baroMode;
|
||||
extern uint16_t intPowerMeterSum, intPowerTrigger1;
|
||||
extern int32_t GPS_latitude, GPS_longitude;
|
||||
extern int32_t GPS_latitude_home, GPS_longitude_home;
|
||||
extern int32_t GPS_latitude_hold, GPS_longitude_hold;
|
||||
|
|
|
@ -21,8 +21,14 @@ sensor_t gyro; // gyro access functions
|
|||
|
||||
void sensorsAutodetect(void)
|
||||
{
|
||||
drv_adxl345_config_t acc_params;
|
||||
|
||||
// configure parameters for ADXL345 driver
|
||||
acc_params.useFifo = false;
|
||||
acc_params.dataRate = 800; // unused currently
|
||||
|
||||
// Detect what's available
|
||||
if (!adxl345Detect(&acc))
|
||||
if (!adxl345Detect(&acc_params, &acc))
|
||||
sensorsClear(SENSOR_ACC);
|
||||
if (!bmp085Init())
|
||||
sensorsClear(SENSOR_BARO);
|
||||
|
|
116
src/serial.c
116
src/serial.c
|
@ -23,7 +23,7 @@ void serialInit(uint32_t baudrate)
|
|||
void serialCom(void)
|
||||
{
|
||||
uint8_t i;
|
||||
|
||||
|
||||
// in cli mode, all uart stuff goes to here. enter cli mode by sending #
|
||||
if (cliMode) {
|
||||
cliProcess();
|
||||
|
@ -35,109 +35,14 @@ void serialCom(void)
|
|||
case '#':
|
||||
cliProcess();
|
||||
break;
|
||||
|
||||
#ifdef BTSERIAL
|
||||
case 'K': //receive RC data from Bluetooth Serial adapter as a remote
|
||||
case 'K': // receive RC data from Bluetooth Serial adapter as a remote
|
||||
rcData[THROTTLE] = (SerialRead(0) * 4) + 1000;
|
||||
rcData[ROLL] = (SerialRead(0) * 4) + 1000;
|
||||
rcData[PITCH] = (SerialRead(0) * 4) + 1000;
|
||||
rcData[YAW] = (SerialRead(0) * 4) + 1000;
|
||||
rcData[AUX1] = (SerialRead(0) * 4) + 1000;
|
||||
break;
|
||||
#endif
|
||||
#ifdef LCD_TELEMETRY
|
||||
case 'A': // button A press
|
||||
case '1':
|
||||
if (telemetry == 1)
|
||||
telemetry = 0;
|
||||
else {
|
||||
telemetry = 1;
|
||||
LCDclear();
|
||||
}
|
||||
break;
|
||||
case 'B': // button B press
|
||||
case '2':
|
||||
if (telemetry == 2)
|
||||
telemetry = 0;
|
||||
else {
|
||||
telemetry = 2;
|
||||
LCDclear();
|
||||
}
|
||||
break;
|
||||
case 'C': // button C press
|
||||
case '3':
|
||||
if (telemetry == 3)
|
||||
telemetry = 0;
|
||||
else {
|
||||
telemetry = 3;
|
||||
LCDclear();
|
||||
#if defined(LOG_VALUES) && defined(DEBUG)
|
||||
cycleTimeMax = 0; // reset min/max on transition on->off
|
||||
cycleTimeMin = 65535;
|
||||
#endif
|
||||
}
|
||||
break;
|
||||
case 'D': // button D press
|
||||
case '4':
|
||||
if (telemetry == 4)
|
||||
telemetry = 0;
|
||||
else {
|
||||
telemetry = 4;
|
||||
LCDclear();
|
||||
}
|
||||
break;
|
||||
case '5':
|
||||
if (telemetry == 5)
|
||||
telemetry = 0;
|
||||
else {
|
||||
telemetry = 5;
|
||||
LCDclear();
|
||||
}
|
||||
break;
|
||||
case '6':
|
||||
if (telemetry == 6)
|
||||
telemetry = 0;
|
||||
else {
|
||||
telemetry = 6;
|
||||
LCDclear();
|
||||
}
|
||||
break;
|
||||
case '7':
|
||||
if (telemetry == 7)
|
||||
telemetry = 0;
|
||||
else {
|
||||
telemetry = 7;
|
||||
LCDclear();
|
||||
}
|
||||
break;
|
||||
#if defined(LOG_VALUES) && defined(DEBUG)
|
||||
case 'R':
|
||||
//Reset logvalues
|
||||
if (telemetry == 'R')
|
||||
telemetry = 0;
|
||||
else {
|
||||
telemetry = 'R';
|
||||
LCDclear();
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
#ifdef DEBUG
|
||||
case 'F':
|
||||
{
|
||||
if (telemetry == 'F')
|
||||
telemetry = 0;
|
||||
else {
|
||||
telemetry = 'F';
|
||||
LCDclear();
|
||||
}
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
case 'a': // button A release
|
||||
case 'b': // button B release
|
||||
case 'c': // button C release
|
||||
case 'd': // button D release
|
||||
break;
|
||||
#endif
|
||||
case 'M': // Multiwii @ arduino to GUI all data
|
||||
serialize8('M');
|
||||
|
@ -181,15 +86,14 @@ void serialCom(void)
|
|||
for (i = 0; i < CHECKBOXITEMS; i++) {
|
||||
serialize8(cfg.activate1[i]);
|
||||
serialize8(cfg.activate2[i] | (rcOptions[i] << 7)); // use highest bit to transport state in mwc
|
||||
|
||||
}
|
||||
serialize16(GPS_distanceToHome);
|
||||
serialize16(GPS_directionToHome + 180);
|
||||
serialize8(GPS_numSat);
|
||||
serialize8(GPS_fix);
|
||||
serialize8(GPS_update);
|
||||
serialize16(intPowerMeterSum);
|
||||
serialize16(intPowerTrigger1);
|
||||
serialize16(0); // power meter, removed
|
||||
serialize16(0); // power meter, removed
|
||||
serialize8(vbat);
|
||||
serialize16(BaroAlt / 10); // 4 variables are here for general monitoring purpose
|
||||
serialize16(debug2); // debug2
|
||||
|
@ -245,18 +149,14 @@ void serialCom(void)
|
|||
cfg.activate1[i] = uartReadPoll();
|
||||
cfg.activate2[i] = uartReadPoll();
|
||||
}
|
||||
#if defined(POWERMETER)
|
||||
cfg.powerTrigger1 = (uartReadPoll() + 256 * uartReadPoll()) / PLEVELSCALE; // we rely on writeParams() to compute corresponding pAlarm value
|
||||
#else
|
||||
uartReadPoll();
|
||||
uartReadPoll(); //7 so we unload the two bytes
|
||||
#endif
|
||||
uartReadPoll(); // power meter crap, removed
|
||||
uartReadPoll(); // power meter crap, removed
|
||||
writeParams();
|
||||
break;
|
||||
case 'S': //GUI to arduino ACC calibration request
|
||||
case 'S': // GUI to arduino ACC calibration request
|
||||
calibratingA = 400;
|
||||
break;
|
||||
case 'E': //GUI to arduino MAG calibration request
|
||||
case 'E': // GUI to arduino MAG calibration request
|
||||
calibratingM = 1;
|
||||
break;
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue