removed mpu6050_scale cli since it's now autodetected.
the value is now printed in the status command, after MPU6050 as MPU6050.n = new revision, MPU6050.o = old revision. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@278 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
fc185b8e15
commit
bc627783f8
7332
obj/baseflight.hex
7332
obj/baseflight.hex
File diff suppressed because it is too large
Load Diff
|
@ -156,7 +156,6 @@ const clivalue_t valueTable[] = {
|
|||
{ "acc_trim_roll", VAR_INT16, &cfg.angleTrim[ROLL], -300, 300 },
|
||||
{ "gyro_lpf", VAR_UINT16, &cfg.gyro_lpf, 0, 256 },
|
||||
{ "gyro_cmpf_factor", VAR_UINT16, &cfg.gyro_cmpf_factor, 100, 1000 },
|
||||
{ "mpu6050_scale", VAR_UINT8, &cfg.mpu6050_scale, 0, 1 },
|
||||
{ "baro_tab_size", VAR_UINT8, &cfg.baro_tab_size, 0, BARO_TAB_SIZE_MAX },
|
||||
{ "baro_noise_lpf", VAR_FLOAT, &cfg.baro_noise_lpf, 0, 1 },
|
||||
{ "baro_cf", VAR_FLOAT, &cfg.baro_cf, 0, 1 },
|
||||
|
@ -748,8 +747,11 @@ static void cliStatus(char *cmdline)
|
|||
if (mask & (1 << i))
|
||||
printf("%s ", sensorNames[i]);
|
||||
}
|
||||
if (sensors(SENSOR_ACC))
|
||||
if (sensors(SENSOR_ACC)) {
|
||||
printf("ACCHW: %s", accNames[accHardware]);
|
||||
if (accHardware == ACC_MPU6050)
|
||||
printf(".%c", cfg.mpu6050_scale ? 'n' : 'o');
|
||||
}
|
||||
uartPrint("\r\n");
|
||||
|
||||
printf("Cycle Time: %d, I2C Errors: %d\r\n", cycleTime, i2cGetErrorCounter());
|
||||
|
|
|
@ -145,7 +145,7 @@ int16_t dmpGyroData[3];
|
|||
extern uint16_t acc_1G;
|
||||
static uint8_t mpuAccelHalf = 0;
|
||||
|
||||
bool mpu6050Detect(sensor_t * acc, sensor_t * gyro, uint8_t scale)
|
||||
bool mpu6050Detect(sensor_t * acc, sensor_t * gyro, uint8_t *scale)
|
||||
{
|
||||
bool ack;
|
||||
uint8_t sig, rev;
|
||||
|
@ -195,6 +195,10 @@ bool mpu6050Detect(sensor_t * acc, sensor_t * gyro, uint8_t scale)
|
|||
gyro->read = mpu6050GyroRead;
|
||||
gyro->align = mpu6050GyroAlign;
|
||||
|
||||
// give halfacc (old revision) back to system
|
||||
if (scale)
|
||||
*scale = mpuAccelHalf;
|
||||
|
||||
#ifdef MPU6050_DMP
|
||||
mpu6050DmpInit();
|
||||
#endif
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
#pragma once
|
||||
|
||||
bool mpu6050Detect(sensor_t * acc, sensor_t * gyro, uint8_t scale);
|
||||
bool mpu6050Detect(sensor_t * acc, sensor_t * gyro, uint8_t *scale);
|
||||
void mpu6050DmpLoop(void);
|
||||
void mpu6050DmpResetFifo(void);
|
||||
|
|
|
@ -36,7 +36,7 @@ void sensorsAutodetect(void)
|
|||
bool havel3g4200d = false;
|
||||
|
||||
// Autodetect gyro hardware. We have MPU3050 or MPU6050.
|
||||
if (mpu6050Detect(&acc, &gyro, cfg.mpu6050_scale)) {
|
||||
if (mpu6050Detect(&acc, &gyro, &cfg.mpu6050_scale)) {
|
||||
// this filled up acc.* struct with init values
|
||||
haveMpu6k = true;
|
||||
} else if (l3g4200dDetect(&gyro)) {
|
||||
|
@ -60,7 +60,7 @@ retry:
|
|||
; // fallthrough
|
||||
case 2: // MPU6050
|
||||
if (haveMpu6k) {
|
||||
mpu6050Detect(&acc, &gyro, cfg.mpu6050_scale); // yes, i'm rerunning it again. re-fill acc struct
|
||||
mpu6050Detect(&acc, &gyro, &cfg.mpu6050_scale); // yes, i'm rerunning it again. re-fill acc struct
|
||||
accHardware = ACC_MPU6050;
|
||||
if (cfg.acc_hardware == ACC_MPU6050)
|
||||
break;
|
||||
|
|
Loading…
Reference in New Issue