From e436c24fb6b852828c79e94d262c4e68c23788ad Mon Sep 17 00:00:00 2001 From: jflyper Date: Tue, 18 Jul 2017 17:42:17 +0900 Subject: [PATCH] pBusdev to busdev --- src/main/drivers/accgyro/accgyro_spi_bmi160.c | 4 +- src/main/drivers/barometer/barometer_bmp085.c | 22 +++--- src/main/drivers/barometer/barometer_bmp280.c | 54 +++++++------- src/main/drivers/barometer/barometer_ms5611.c | 74 +++++++++---------- 4 files changed, 77 insertions(+), 77 deletions(-) diff --git a/src/main/drivers/accgyro/accgyro_spi_bmi160.c b/src/main/drivers/accgyro/accgyro_spi_bmi160.c index 21ecee6fbe..5dc9d02908 100644 --- a/src/main/drivers/accgyro/accgyro_spi_bmi160.c +++ b/src/main/drivers/accgyro/accgyro_spi_bmi160.c @@ -269,12 +269,12 @@ static int32_t BMI160_do_foc(const busDevice_t *bus) static int32_t BMI160_WriteReg(const busDevice_t *bus, uint8_t reg, uint8_t data) { - IOLo(pBusdev->busdev_u.spi.csnPin); // Enable + IOLo(busdev->busdev_u.spi.csnPin); // Enable spiTransferByte(BMI160_SPI_INSTANCE, 0x7f & reg); spiTransferByte(BMI160_SPI_INSTANCE, data); - IOHi(pBusdev->busdev_u.spi.csnPin); // Disable + IOHi(busdev->busdev_u.spi.csnPin); // Disable return 0; } diff --git a/src/main/drivers/barometer/barometer_bmp085.c b/src/main/drivers/barometer/barometer_bmp085.c index c67250dd9a..9cc973205d 100644 --- a/src/main/drivers/barometer/barometer_bmp085.c +++ b/src/main/drivers/barometer/barometer_bmp085.c @@ -121,7 +121,7 @@ static bool bmp085InitDone = false; STATIC_UNIT_TESTED uint16_t bmp085_ut; // static result of temperature measurement STATIC_UNIT_TESTED uint32_t bmp085_up; // static result of pressure measurement -static void bmp085_get_cal_param(busDevice_t *pBusdev); +static void bmp085_get_cal_param(busDevice_t *busdev); static void bmp085_start_ut(baroDev_t *baro); static void bmp085_get_ut(baroDev_t *baro); static void bmp085_start_up(baroDev_t *baro); @@ -156,14 +156,14 @@ void bmp085Disable(const bmp085Config_t *config) BMP085_OFF; } -bool bmp085ReadRegister(busDevice_t *pBusdev, uint8_t cmd, uint8_t len, uint8_t *data) +bool bmp085ReadRegister(busDevice_t *busdev, uint8_t cmd, uint8_t len, uint8_t *data) { - return i2cReadRegisterBuffer(pBusdev, cmd, len, data); + return i2cReadRegisterBuffer(busdev, cmd, len, data); } -bool bmp085WriteRegister(busDevice_t *pBusdev, uint8_t cmd, uint8_t byte) +bool bmp085WriteRegister(busDevice_t *busdev, uint8_t cmd, uint8_t byte) { - return i2cWriteRegister(pBusdev, cmd, byte); + return i2cWriteRegister(busdev, cmd, byte); } bool bmp085Detect(const bmp085Config_t *config, baroDev_t *baro) @@ -196,18 +196,18 @@ bool bmp085Detect(const bmp085Config_t *config, baroDev_t *baro) delay(20); // datasheet says 10ms, we'll be careful and do 20. - busDevice_t *pBusdev = &baro->busdev; + busDevice_t *busdev = &baro->busdev; - ack = bmp085ReadRegister(pBusdev, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */ + ack = bmp085ReadRegister(busdev, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */ if (ack) { bmp085.chip_id = BMP085_GET_BITSLICE(data, BMP085_CHIP_ID); bmp085.oversampling_setting = 3; if (bmp085.chip_id == BMP085_CHIP_ID) { /* get bitslice */ - bmp085ReadRegister(pBusdev, BMP085_VERSION_REG, 1, &data); /* read Version reg */ + bmp085ReadRegister(busdev, BMP085_VERSION_REG, 1, &data); /* read Version reg */ bmp085.ml_version = BMP085_GET_BITSLICE(data, BMP085_ML_VERSION); /* get ML Version */ bmp085.al_version = BMP085_GET_BITSLICE(data, BMP085_AL_VERSION); /* get AL Version */ - bmp085_get_cal_param(pBusdev); /* readout bmp085 calibparam structure */ + bmp085_get_cal_param(busdev); /* readout bmp085 calibparam structure */ baro->ut_delay = UT_DELAY; baro->up_delay = UP_DELAY; baro->start_ut = bmp085_start_ut; @@ -354,10 +354,10 @@ STATIC_UNIT_TESTED void bmp085_calculate(int32_t *pressure, int32_t *temperature *temperature = temp; } -static void bmp085_get_cal_param(busDevice_t *pBusdev) +static void bmp085_get_cal_param(busDevice_t *busdev) { uint8_t data[22]; - bmp085ReadRegister(pBusdev, BMP085_PROM_START__ADDR, BMP085_PROM_DATA__LEN, data); + bmp085ReadRegister(busdev, BMP085_PROM_START__ADDR, BMP085_PROM_DATA__LEN, data); /*parameters AC1-AC6*/ bmp085.cal_param.ac1 = (data[0] << 8) | data[1]; diff --git a/src/main/drivers/barometer/barometer_bmp280.c b/src/main/drivers/barometer/barometer_bmp280.c index f970113d0c..a4a3d15693 100644 --- a/src/main/drivers/barometer/barometer_bmp280.c +++ b/src/main/drivers/barometer/barometer_bmp280.c @@ -65,60 +65,60 @@ static void bmp280_get_up(baroDev_t *baro); STATIC_UNIT_TESTED void bmp280_calculate(int32_t *pressure, int32_t *temperature); -bool bmp280ReadRegister(busDevice_t *pBusdev, uint8_t reg, uint8_t length, uint8_t *data) +bool bmp280ReadRegister(busDevice_t *busdev, uint8_t reg, uint8_t length, uint8_t *data) { - switch (pBusdev->bustype) { + switch (busdev->bustype) { #ifdef USE_BARO_SPI_BMP280 case BUSTYPE_SPI: - return spiReadRegisterBuffer(pBusdev, reg | 0x80, length, data); + return spiReadRegisterBuffer(busdev, reg | 0x80, length, data); #endif #ifdef USE_BARO_BMP280 case BUSTYPE_I2C: - return i2cReadRegisterBuffer(pBusdev, reg, length, data); + return i2cReadRegisterBuffer(busdev, reg, length, data); #endif } return false; } -bool bmp280WriteRegister(busDevice_t *pBusdev, uint8_t reg, uint8_t data) +bool bmp280WriteRegister(busDevice_t *busdev, uint8_t reg, uint8_t data) { - switch (pBusdev->bustype) { + switch (busdev->bustype) { #ifdef USE_BARO_SPI_BMP280 case BUSTYPE_SPI: - return spiWriteRegister(pBusdev, reg & 0x7f, data); + return spiWriteRegister(busdev, reg & 0x7f, data); #endif #ifdef USE_BARO_BMP280 case BUSTYPE_I2C: - return i2cWriteRegister(pBusdev, reg, data); + return i2cWriteRegister(busdev, reg, data); #endif } return false; } -void bmp280BusInit(busDevice_t *pBusdev) +void bmp280BusInit(busDevice_t *busdev) { #ifdef USE_BARO_SPI_BMP280 - if (pBusdev->bustype == BUSTYPE_SPI) { - IOInit(pBusdev->busdev_u.spi.csnPin, OWNER_BARO_CS, 0); - IOConfigGPIO(pBusdev->busdev_u.spi.csnPin, IOCFG_OUT_PP); - IOHi((pBusdev)->busdev_u.spi.csnPin); // Disable - spiSetDivisor(pBusdev->busdev_u.spi.instance, SPI_CLOCK_STANDARD); // XXX + if (busdev->bustype == BUSTYPE_SPI) { + IOInit(busdev->busdev_u.spi.csnPin, OWNER_BARO_CS, 0); + IOConfigGPIO(busdev->busdev_u.spi.csnPin, IOCFG_OUT_PP); + IOHi((busdev)->busdev_u.spi.csnPin); // Disable + spiSetDivisor(busdev->busdev_u.spi.instance, SPI_CLOCK_STANDARD); // XXX } #else - UNUSED(pBusdev); + UNUSED(busdev); #endif } -void bmp280BusDeinit(busDevice_t *pBusdev) +void bmp280BusDeinit(busDevice_t *busdev) { #ifdef USE_BARO_SPI_BMP280 - if (pBusdev->bustype == BUSTYPE_SPI) { - IOConfigGPIO(pBusdev->busdev_u.spi.csnPin, IOCFG_IPU); - IORelease(pBusdev->busdev_u.spi.csnPin); - IOInit(pBusdev->busdev_u.spi.csnPin, OWNER_SPI_PREINIT, 0); + if (busdev->bustype == BUSTYPE_SPI) { + IOConfigGPIO(busdev->busdev_u.spi.csnPin, IOCFG_IPU); + IORelease(busdev->busdev_u.spi.csnPin); + IOInit(busdev->busdev_u.spi.csnPin, OWNER_SPI_PREINIT, 0); } #else - UNUSED(pBusdev); + UNUSED(busdev); #endif } @@ -126,22 +126,22 @@ bool bmp280Detect(baroDev_t *baro) { delay(20); - busDevice_t *pBusdev = &baro->busdev; + busDevice_t *busdev = &baro->busdev; - bmp280BusInit(pBusdev); + bmp280BusInit(busdev); - bmp280ReadRegister(pBusdev, BMP280_CHIP_ID_REG, 1, &bmp280_chip_id); /* read Chip Id */ + bmp280ReadRegister(busdev, BMP280_CHIP_ID_REG, 1, &bmp280_chip_id); /* read Chip Id */ if (bmp280_chip_id != BMP280_DEFAULT_CHIP_ID) { - bmp280BusDeinit(pBusdev); + bmp280BusDeinit(busdev); return false; } // read calibration - bmp280ReadRegister(pBusdev, BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG, 24, (uint8_t *)&bmp280_cal); + bmp280ReadRegister(busdev, BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG, 24, (uint8_t *)&bmp280_cal); // set oversampling + power mode (forced), and start sampling - bmp280WriteRegister(pBusdev, BMP280_CTRL_MEAS_REG, BMP280_MODE); + bmp280WriteRegister(busdev, BMP280_CTRL_MEAS_REG, BMP280_MODE); // these are dummy as temperature is measured as part of pressure baro->ut_delay = 0; diff --git a/src/main/drivers/barometer/barometer_ms5611.c b/src/main/drivers/barometer/barometer_ms5611.c index 55425a78f2..50cb628e8e 100644 --- a/src/main/drivers/barometer/barometer_ms5611.c +++ b/src/main/drivers/barometer/barometer_ms5611.c @@ -46,10 +46,10 @@ #define CMD_PROM_RD 0xA0 // Prom read command #define PROM_NB 8 -static void ms5611_reset(busDevice_t *pBusdev); -static uint16_t ms5611_prom(busDevice_t *pBusdev, int8_t coef_num); +static void ms5611_reset(busDevice_t *busdev); +static uint16_t ms5611_prom(busDevice_t *busdev, int8_t coef_num); STATIC_UNIT_TESTED int8_t ms5611_crc(uint16_t *prom); -static uint32_t ms5611_read_adc(busDevice_t *pBusdev); +static uint32_t ms5611_read_adc(busDevice_t *busdev); static void ms5611_start_ut(baroDev_t *baro); static void ms5611_get_ut(baroDev_t *baro); static void ms5611_start_up(baroDev_t *baro); @@ -61,60 +61,60 @@ STATIC_UNIT_TESTED uint32_t ms5611_up; // static result of pressure measurement STATIC_UNIT_TESTED uint16_t ms5611_c[PROM_NB]; // on-chip ROM static uint8_t ms5611_osr = CMD_ADC_4096; -bool ms5611ReadCommand(busDevice_t *pBusdev, uint8_t cmd, uint8_t len, uint8_t *data) +bool ms5611ReadCommand(busDevice_t *busdev, uint8_t cmd, uint8_t len, uint8_t *data) { - switch (pBusdev->bustype) { + switch (busdev->bustype) { #ifdef USE_BARO_SPI_MS5611 case BUSTYPE_SPI: - return spiReadRegisterBuffer(pBusdev, cmd | 0x80, len, data); + return spiReadRegisterBuffer(busdev, cmd | 0x80, len, data); #endif #ifdef USE_BARO_MS5611 case BUSTYPE_I2C: - return i2cReadRegisterBuffer(pBusdev, cmd, len, data); + return i2cReadRegisterBuffer(busdev, cmd, len, data); #endif } return false; } -bool ms5611WriteCommand(busDevice_t *pBusdev, uint8_t cmd, uint8_t byte) +bool ms5611WriteCommand(busDevice_t *busdev, uint8_t cmd, uint8_t byte) { - switch (pBusdev->bustype) { + switch (busdev->bustype) { #ifdef USE_BARO_SPI_MS5611 case BUSTYPE_SPI: - return spiWriteRegister(pBusdev, cmd & 0x7f, byte); + return spiWriteRegister(busdev, cmd & 0x7f, byte); #endif #ifdef USE_BARO_MS5611 case BUSTYPE_I2C: - return i2cWriteRegister(pBusdev, cmd, byte); + return i2cWriteRegister(busdev, cmd, byte); #endif } return false; } -void ms5611BusInit(busDevice_t *pBusdev) +void ms5611BusInit(busDevice_t *busdev) { #ifdef USE_BARO_SPI_MS5611 - if (pBusdev->bustype == BUSTYPE_SPI) { - IOInit(pBusdev->busdev_u.spi.csnPin, OWNER_BARO_CS, 0); - IOConfigGPIO(pBusdev->busdev_u.spi.csnPin, IOCFG_OUT_PP); - IOHi(pBusdev->busdev_u.spi.csnPin); // Disable - spiSetDivisor(pBusdev->busdev_u.spi.csnPin, SPI_CLOCK_STANDARD); + if (busdev->bustype == BUSTYPE_SPI) { + IOInit(busdev->busdev_u.spi.csnPin, OWNER_BARO_CS, 0); + IOConfigGPIO(busdev->busdev_u.spi.csnPin, IOCFG_OUT_PP); + IOHi(busdev->busdev_u.spi.csnPin); // Disable + spiSetDivisor(busdev->busdev_u.spi.csnPin, SPI_CLOCK_STANDARD); } #else - UNUSED(pBusdev); + UNUSED(busdev); #endif } -void ms5611BusDeinit(busDevice_t *pBusdev) +void ms5611BusDeinit(busDevice_t *busdev) { #ifdef USE_BARO_SPI_MS5611 - if (pBusdev->bustype == BUSTYPE_SPI) { - IOConfigGPIO(pBusdev->busdev_u.spi.csnPin, IOCFG_IPU); - IORelease(pBusdev->busdev_u.spi.csnPin); - IOInit(pBusdev->busdev_u.spi.csnPin, OWNER_SPI_PREINIT, 0); + if (busdev->bustype == BUSTYPE_SPI) { + IOConfigGPIO(busdev->busdev_u.spi.csnPin, IOCFG_IPU); + IORelease(busdev->busdev_u.spi.csnPin); + IOInit(busdev->busdev_u.spi.csnPin, OWNER_SPI_PREINIT, 0); } #else - UNUSED(pBusdev); + UNUSED(busdev); #endif } @@ -125,24 +125,24 @@ bool ms5611Detect(baroDev_t *baro) delay(10); // No idea how long the chip takes to power-up, but let's make it 10ms - busDevice_t *pBusdev = &baro->busdev; + busDevice_t *busdev = &baro->busdev; - ms5611BusInit(pBusdev); + ms5611BusInit(busdev); - if (!ms5611ReadCommand(pBusdev, CMD_PROM_RD, 1, &sig) || sig == 0xFF) { - ms5611BusDeinit(pBusdev); + if (!ms5611ReadCommand(busdev, CMD_PROM_RD, 1, &sig) || sig == 0xFF) { + ms5611BusDeinit(busdev); return false; } - ms5611_reset(pBusdev); + ms5611_reset(busdev); // read all coefficients for (i = 0; i < PROM_NB; i++) - ms5611_c[i] = ms5611_prom(pBusdev, i); + ms5611_c[i] = ms5611_prom(busdev, i); // check crc, bail out if wrong - we are probably talking to BMP085 w/o XCLR line! if (ms5611_crc(ms5611_c) != 0) { - ms5611BusDeinit(pBusdev); + ms5611BusDeinit(busdev); return false; } @@ -158,18 +158,18 @@ bool ms5611Detect(baroDev_t *baro) return true; } -static void ms5611_reset(busDevice_t *pBusdev) +static void ms5611_reset(busDevice_t *busdev) { - ms5611WriteCommand(pBusdev, CMD_RESET, 1); + ms5611WriteCommand(busdev, CMD_RESET, 1); delayMicroseconds(2800); } -static uint16_t ms5611_prom(busDevice_t *pBusdev, int8_t coef_num) +static uint16_t ms5611_prom(busDevice_t *busdev, int8_t coef_num) { uint8_t rxbuf[2] = { 0, 0 }; - ms5611ReadCommand(pBusdev, CMD_PROM_RD + coef_num * 2, 2, rxbuf); // send PROM READ command + ms5611ReadCommand(busdev, CMD_PROM_RD + coef_num * 2, 2, rxbuf); // send PROM READ command return rxbuf[0] << 8 | rxbuf[1]; } @@ -204,11 +204,11 @@ STATIC_UNIT_TESTED int8_t ms5611_crc(uint16_t *prom) return -1; } -static uint32_t ms5611_read_adc(busDevice_t *pBusdev) +static uint32_t ms5611_read_adc(busDevice_t *busdev) { uint8_t rxbuf[3]; - ms5611ReadCommand(pBusdev, CMD_ADC_READ, 3, rxbuf); // read ADC + ms5611ReadCommand(busdev, CMD_ADC_READ, 3, rxbuf); // read ADC return (rxbuf[0] << 16) | (rxbuf[1] << 8) | rxbuf[2]; }