fix cpplint redundant assignment warnings
This commit is contained in:
parent
135231f289
commit
67c85c97d1
|
@ -63,10 +63,9 @@ static bool useFifo = false;
|
|||
|
||||
bool adxl345Detect(drv_adxl345_config_t *init, acc_t *acc)
|
||||
{
|
||||
bool ack = false;
|
||||
uint8_t sig = 0;
|
||||
|
||||
ack = i2cRead(MPU_I2C_INSTANCE, ADXL345_ADDRESS, 0x00, 1, &sig);
|
||||
bool ack = i2cRead(MPU_I2C_INSTANCE, ADXL345_ADDRESS, 0x00, 1, &sig);
|
||||
|
||||
if (!ack || sig != 0xE5)
|
||||
return false;
|
||||
|
||||
|
|
|
@ -37,10 +37,9 @@ static bool bma280Read(int16_t *accelData);
|
|||
|
||||
bool bma280Detect(acc_t *acc)
|
||||
{
|
||||
bool ack = false;
|
||||
uint8_t sig = 0;
|
||||
bool ack = i2cRead(MPU_I2C_INSTANCE, BMA280_ADDRESS, 0x00, 1, &sig);
|
||||
|
||||
ack = i2cRead(MPU_I2C_INSTANCE, BMA280_ADDRESS, 0x00, 1, &sig);
|
||||
if (!ack || sig != 0xFB)
|
||||
return false;
|
||||
|
||||
|
|
|
@ -86,10 +86,9 @@ static bool mma8452Read(int16_t *accelData);
|
|||
|
||||
bool mma8452Detect(acc_t *acc)
|
||||
{
|
||||
bool ack = false;
|
||||
uint8_t sig = 0;
|
||||
bool ack = i2cRead(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_WHO_AM_I, 1, &sig);
|
||||
|
||||
ack = i2cRead(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_WHO_AM_I, 1, &sig);
|
||||
if (!ack || (sig != MMA8452_DEVICE_SIGNATURE && sig != MMA8451_DEVICE_SIGNATURE))
|
||||
return false;
|
||||
|
||||
|
|
|
@ -97,27 +97,24 @@ static void mpu6050AccInit(acc_t *acc)
|
|||
|
||||
static void mpu6050GyroInit(uint8_t lpf)
|
||||
{
|
||||
bool ack;
|
||||
|
||||
mpuIntExtiInit();
|
||||
|
||||
ack = mpuConfiguration.write(MPU_RA_PWR_MGMT_1, 0x80); //PWR_MGMT_1 -- DEVICE_RESET 1
|
||||
mpuConfiguration.write(MPU_RA_PWR_MGMT_1, 0x80); //PWR_MGMT_1 -- DEVICE_RESET 1
|
||||
delay(100);
|
||||
ack = mpuConfiguration.write(MPU_RA_PWR_MGMT_1, 0x03); //PWR_MGMT_1 -- SLEEP 0; CYCLE 0; TEMP_DIS 0; CLKSEL 3 (PLL with Z Gyro reference)
|
||||
ack = mpuConfiguration.write(MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops()); //SMPLRT_DIV -- SMPLRT_DIV = 0 Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV)
|
||||
mpuConfiguration.write(MPU_RA_PWR_MGMT_1, 0x03); //PWR_MGMT_1 -- SLEEP 0; CYCLE 0; TEMP_DIS 0; CLKSEL 3 (PLL with Z Gyro reference)
|
||||
mpuConfiguration.write(MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops()); //SMPLRT_DIV -- SMPLRT_DIV = 0 Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV)
|
||||
delay(15); //PLL Settling time when changing CLKSEL is max 10ms. Use 15ms to be sure
|
||||
ack = mpuConfiguration.write(MPU_RA_CONFIG, lpf); //CONFIG -- EXT_SYNC_SET 0 (disable input pin for data sync) ; default DLPF_CFG = 0 => ACC bandwidth = 260Hz GYRO bandwidth = 256Hz)
|
||||
ack = mpuConfiguration.write(MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3); //GYRO_CONFIG -- FS_SEL = 3: Full scale set to 2000 deg/sec
|
||||
mpuConfiguration.write(MPU_RA_CONFIG, lpf); //CONFIG -- EXT_SYNC_SET 0 (disable input pin for data sync) ; default DLPF_CFG = 0 => ACC bandwidth = 260Hz GYRO bandwidth = 256Hz)
|
||||
mpuConfiguration.write(MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3); //GYRO_CONFIG -- FS_SEL = 3: Full scale set to 2000 deg/sec
|
||||
|
||||
// ACC Init stuff.
|
||||
// Accel scale 8g (4096 LSB/g)
|
||||
ack = mpuConfiguration.write(MPU_RA_ACCEL_CONFIG, INV_FSR_16G << 3);
|
||||
mpuConfiguration.write(MPU_RA_ACCEL_CONFIG, INV_FSR_16G << 3);
|
||||
|
||||
ack = mpuConfiguration.write(MPU_RA_INT_PIN_CFG,
|
||||
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
|
||||
|
||||
#ifdef USE_MPU_DATA_READY_SIGNAL
|
||||
ack = mpuConfiguration.write(MPU_RA_INT_ENABLE, MPU_RF_DATA_RDY_EN);
|
||||
mpuConfiguration.write(MPU_RA_INT_ENABLE, MPU_RF_DATA_RDY_EN);
|
||||
#endif
|
||||
UNUSED(ack);
|
||||
}
|
||||
|
|
|
@ -61,14 +61,12 @@ static uint8_t ms5611_osr = CMD_ADC_4096;
|
|||
|
||||
bool ms5611Detect(baro_t *baro)
|
||||
{
|
||||
bool ack = false;
|
||||
uint8_t sig;
|
||||
int i;
|
||||
|
||||
delay(10); // No idea how long the chip takes to power-up, but let's make it 10ms
|
||||
|
||||
ack = i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_PROM_RD, 1, &sig);
|
||||
if (!ack)
|
||||
if (!i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_PROM_RD, 1, &sig))
|
||||
return false;
|
||||
|
||||
ms5611_reset();
|
||||
|
|
|
@ -190,24 +190,23 @@ bool ak8963SensorWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
|
|||
|
||||
bool ak8963Detect(mag_t *mag)
|
||||
{
|
||||
bool ack = false;
|
||||
uint8_t sig = 0;
|
||||
|
||||
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
|
||||
// initialze I2C master via SPI bus (MPU9250)
|
||||
|
||||
ack = verifympu9250WriteRegister(MPU_RA_INT_PIN_CFG, 0x10); // INT_ANYRD_2CLEAR
|
||||
verifympu9250WriteRegister(MPU_RA_INT_PIN_CFG, 0x10); // INT_ANYRD_2CLEAR
|
||||
delay(10);
|
||||
|
||||
ack = verifympu9250WriteRegister(MPU_RA_I2C_MST_CTRL, 0x0D); // I2C multi-master / 400kHz
|
||||
verifympu9250WriteRegister(MPU_RA_I2C_MST_CTRL, 0x0D); // I2C multi-master / 400kHz
|
||||
delay(10);
|
||||
|
||||
ack = verifympu9250WriteRegister(MPU_RA_USER_CTRL, 0x30); // I2C master mode, SPI mode only
|
||||
verifympu9250WriteRegister(MPU_RA_USER_CTRL, 0x30); // I2C master mode, SPI mode only
|
||||
delay(10);
|
||||
#endif
|
||||
|
||||
// check for AK8963
|
||||
ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_WHO_AM_I, 1, &sig);
|
||||
bool ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_WHO_AM_I, 1, &sig);
|
||||
if (ack && sig == AK8963_Device_ID) // 0x48 / 01001000 / 'H'
|
||||
{
|
||||
mag->init = ak8963Init;
|
||||
|
@ -220,36 +219,34 @@ bool ak8963Detect(mag_t *mag)
|
|||
|
||||
void ak8963Init()
|
||||
{
|
||||
bool ack;
|
||||
UNUSED(ack);
|
||||
uint8_t calibration[3];
|
||||
uint8_t status;
|
||||
|
||||
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down before entering fuse mode
|
||||
ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down before entering fuse mode
|
||||
delay(20);
|
||||
|
||||
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_FUSE_ROM); // Enter Fuse ROM access mode
|
||||
ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_FUSE_ROM); // Enter Fuse ROM access mode
|
||||
delay(10);
|
||||
|
||||
ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_ASAX, sizeof(calibration), calibration); // Read the x-, y-, and z-axis calibration values
|
||||
ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_ASAX, sizeof(calibration), calibration); // Read the x-, y-, and z-axis calibration values
|
||||
delay(10);
|
||||
|
||||
magGain[X] = (((((float)(int8_t)calibration[X] - 128) / 256) + 1) * 30);
|
||||
magGain[Y] = (((((float)(int8_t)calibration[Y] - 128) / 256) + 1) * 30);
|
||||
magGain[Z] = (((((float)(int8_t)calibration[Z] - 128) / 256) + 1) * 30);
|
||||
|
||||
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down after reading.
|
||||
ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down after reading.
|
||||
delay(10);
|
||||
|
||||
// Clear status registers
|
||||
ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1, &status);
|
||||
ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS2, 1, &status);
|
||||
ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1, &status);
|
||||
ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS2, 1, &status);
|
||||
|
||||
// Trigger first measurement
|
||||
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
|
||||
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_CONT1);
|
||||
ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_CONT1);
|
||||
#else
|
||||
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE);
|
||||
ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -59,10 +59,9 @@
|
|||
|
||||
bool ak8975Detect(mag_t *mag)
|
||||
{
|
||||
bool ack = false;
|
||||
uint8_t sig = 0;
|
||||
bool ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_WHO_AM_I, 1, &sig);
|
||||
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_WHO_AM_I, 1, &sig);
|
||||
if (!ack || sig != 'H') // 0x48 / 01001000 / 'H'
|
||||
return false;
|
||||
|
||||
|
@ -78,30 +77,27 @@ bool ak8975Detect(mag_t *mag)
|
|||
|
||||
void ak8975Init()
|
||||
{
|
||||
bool ack;
|
||||
uint8_t buffer[3];
|
||||
uint8_t status;
|
||||
|
||||
UNUSED(ack);
|
||||
|
||||
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x00); // power down before entering fuse mode
|
||||
i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x00); // power down before entering fuse mode
|
||||
delay(20);
|
||||
|
||||
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x0F); // Enter Fuse ROM access mode
|
||||
i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x0F); // Enter Fuse ROM access mode
|
||||
delay(10);
|
||||
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975A_ASAX, 3, &buffer[0]); // Read the x-, y-, and z-axis calibration values
|
||||
i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975A_ASAX, 3, &buffer[0]); // Read the x-, y-, and z-axis calibration values
|
||||
delay(10);
|
||||
|
||||
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x00); // power down after reading.
|
||||
i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x00); // power down after reading.
|
||||
delay(10);
|
||||
|
||||
// Clear status registers
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS1, 1, &status);
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS2, 1, &status);
|
||||
i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS1, 1, &status);
|
||||
i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS2, 1, &status);
|
||||
|
||||
// Trigger first measurement
|
||||
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01);
|
||||
i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01);
|
||||
}
|
||||
|
||||
#define BIT_STATUS1_REG_DATA_READY (1 << 0)
|
||||
|
@ -112,7 +108,6 @@ void ak8975Init()
|
|||
bool ak8975Read(int16_t *magData)
|
||||
{
|
||||
bool ack;
|
||||
UNUSED(ack);
|
||||
uint8_t status;
|
||||
uint8_t buf[6];
|
||||
|
||||
|
@ -121,16 +116,7 @@ bool ak8975Read(int16_t *magData)
|
|||
return false;
|
||||
}
|
||||
|
||||
#if 1 // USE_I2C_SINGLE_BYTE_READS
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_HXL, 6, buf); // read from AK8975_MAG_REG_HXL to AK8975_MAG_REG_HZH
|
||||
#else
|
||||
for (uint8_t i = 0; i < 6; i++) {
|
||||
ack = i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_HXL + i, 1, &buf[i]); // read from AK8975_MAG_REG_HXL to AK8975_MAG_REG_HZH
|
||||
if (!ack) {
|
||||
return false
|
||||
}
|
||||
}
|
||||
#endif
|
||||
i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_HXL, 6, buf); // read from AK8975_MAG_REG_HXL to AK8975_MAG_REG_HZH
|
||||
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS2, 1, &status);
|
||||
if (!ack) {
|
||||
|
@ -150,7 +136,7 @@ bool ak8975Read(int16_t *magData)
|
|||
magData[Z] = -(int16_t)(buf[5] << 8 | buf[4]) * 4;
|
||||
|
||||
|
||||
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01); // start reading again
|
||||
i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01); // start reading again
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -169,12 +169,11 @@ static void hmc5883lConfigureDataReadyInterruptHandling(void)
|
|||
|
||||
bool hmc5883lDetect(mag_t* mag, const hmc5883Config_t *hmc5883ConfigToUse)
|
||||
{
|
||||
bool ack = false;
|
||||
uint8_t sig = 0;
|
||||
|
||||
hmc5883Config = hmc5883ConfigToUse;
|
||||
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, 0x0A, 1, &sig);
|
||||
uint8_t sig = 0;
|
||||
bool ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, 0x0A, 1, &sig);
|
||||
|
||||
if (!ack || sig != 'H')
|
||||
return false;
|
||||
|
||||
|
|
|
@ -141,7 +141,7 @@
|
|||
RCC_ClkInitTypeDef RCC_ClkInitStruct;
|
||||
RCC_OscInitTypeDef RCC_OscInitStruct;
|
||||
RCC_PeriphCLKInitTypeDef PeriphClkInitStruct;
|
||||
HAL_StatusTypeDef ret = HAL_OK;
|
||||
HAL_StatusTypeDef ret;
|
||||
|
||||
__HAL_RCC_PWR_CLK_ENABLE();
|
||||
|
||||
|
|
Loading…
Reference in New Issue