Merge pull request #241 from borisbstyle/acc_scale_increased
Accelerometer Range Increased to 16G
This commit is contained in:
commit
a31bf0f43f
|
@ -88,10 +88,10 @@ static void mpu6050AccInit(void)
|
|||
|
||||
switch (mpuDetectionResult.resolution) {
|
||||
case MPU_HALF_RESOLUTION:
|
||||
acc_1G = 256 * 8;
|
||||
acc_1G = 256 * 4;
|
||||
break;
|
||||
case MPU_FULL_RESOLUTION:
|
||||
acc_1G = 512 * 8;
|
||||
acc_1G = 512 * 4;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
@ -112,7 +112,7 @@ static void mpu6050GyroInit(uint8_t lpf)
|
|||
|
||||
// ACC Init stuff.
|
||||
// Accel scale 8g (4096 LSB/g)
|
||||
ack = mpuConfiguration.write(MPU_RA_ACCEL_CONFIG, INV_FSR_8G << 3);
|
||||
ack = mpuConfiguration.write(MPU_RA_ACCEL_CONFIG, INV_FSR_16G << 3);
|
||||
|
||||
ack = mpuConfiguration.write(MPU_RA_INT_PIN_CFG,
|
||||
0 << 7 | 0 << 6 | 0 << 5 | 0 << 4 | 0 << 3 | 0 << 2 | 1 << 1 | 0 << 0); // INT_PIN_CFG -- INT_LEVEL_HIGH, INT_OPEN_DIS, LATCH_INT_DIS, INT_RD_CLEAR_DIS, FSYNC_INT_LEVEL_HIGH, FSYNC_INT_DIS, I2C_BYPASS_EN, CLOCK_DIS
|
||||
|
|
|
@ -69,7 +69,7 @@ void mpu6500AccInit(void)
|
|||
{
|
||||
mpuIntExtiInit();
|
||||
|
||||
acc_1G = 512 * 8;
|
||||
acc_1G = 512 * 4;
|
||||
}
|
||||
|
||||
void mpu6500GyroInit(uint8_t lpf)
|
||||
|
@ -101,7 +101,7 @@ void mpu6500GyroInit(uint8_t lpf)
|
|||
delay(15);
|
||||
mpuConfiguration.write(MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3);
|
||||
delay(15);
|
||||
mpuConfiguration.write(MPU_RA_ACCEL_CONFIG, INV_FSR_8G << 3);
|
||||
mpuConfiguration.write(MPU_RA_ACCEL_CONFIG, INV_FSR_16G << 3);
|
||||
delay(15);
|
||||
mpuConfiguration.write(MPU_RA_CONFIG, lpf);
|
||||
delay(15);
|
||||
|
|
|
@ -144,7 +144,7 @@ void mpu6000SpiAccInit(void)
|
|||
{
|
||||
mpuIntExtiInit();
|
||||
|
||||
acc_1G = 512 * 8;
|
||||
acc_1G = 512 * 4;
|
||||
}
|
||||
|
||||
bool mpu6000SpiDetect(void)
|
||||
|
@ -229,7 +229,7 @@ static void mpu6000AccAndGyroInit(void) {
|
|||
delayMicroseconds(15);
|
||||
|
||||
// Accel +/- 8 G Full Scale
|
||||
mpu6000WriteRegister(MPU_RA_ACCEL_CONFIG, INV_FSR_8G << 3);
|
||||
mpu6000WriteRegister(MPU_RA_ACCEL_CONFIG, INV_FSR_16G << 3);
|
||||
delayMicroseconds(15);
|
||||
|
||||
|
||||
|
|
Loading…
Reference in New Issue