Merge pull request #2462 from mstrinzha/spi_drivers

MS5611 and HMC5883 SPI drivers
This commit is contained in:
J Blackman 2017-02-24 18:46:36 +11:00 committed by GitHub
commit bd8dd7481f
8 changed files with 271 additions and 1 deletions

View File

@ -23,6 +23,7 @@
#include "build/build_config.h"
#include "barometer.h"
#include "barometer_spi_ms5611.h"
#include "gpio.h"
#include "system.h"
@ -66,8 +67,15 @@ bool ms5611Detect(baroDev_t *baro)
delay(10); // No idea how long the chip takes to power-up, but let's make it 10ms
#ifdef USE_BARO_SPI_MS5611
ms5611SpiInit();
ms5611SpiReadCommand(CMD_PROM_RD, 1, &sig);
if (sig == 0xFF)
return false;
#else
if (!i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_PROM_RD, 1, &sig))
return false;
#endif
ms5611_reset();
// read all coefficients
@ -91,14 +99,22 @@ bool ms5611Detect(baroDev_t *baro)
static void ms5611_reset(void)
{
#ifdef USE_BARO_SPI_MS5611
ms5611SpiWriteCommand(CMD_RESET, 1);
#else
i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_RESET, 1);
#endif
delayMicroseconds(2800);
}
static uint16_t ms5611_prom(int8_t coef_num)
{
uint8_t rxbuf[2] = { 0, 0 };
#ifdef USE_BARO_SPI_MS5611
ms5611SpiReadCommand(CMD_PROM_RD + coef_num * 2, 2, rxbuf); // send PROM READ command
#else
i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_PROM_RD + coef_num * 2, 2, rxbuf); // send PROM READ command
#endif
return rxbuf[0] << 8 | rxbuf[1];
}
@ -135,13 +151,21 @@ STATIC_UNIT_TESTED int8_t ms5611_crc(uint16_t *prom)
static uint32_t ms5611_read_adc(void)
{
uint8_t rxbuf[3];
#ifdef USE_BARO_SPI_MS5611
ms5611SpiReadCommand(CMD_ADC_READ, 3, rxbuf); // read ADC
#else
i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_READ, 3, rxbuf); // read ADC
#endif
return (rxbuf[0] << 16) | (rxbuf[1] << 8) | rxbuf[2];
}
static void ms5611_start_ut(void)
{
#ifdef USE_BARO_SPI_MS5611
ms5611SpiWriteCommand(CMD_ADC_CONV + CMD_ADC_D2 + ms5611_osr, 1); // D2 (temperature) conversion start!
#else
i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D2 + ms5611_osr, 1); // D2 (temperature) conversion start!
#endif
}
static void ms5611_get_ut(void)
@ -151,7 +175,11 @@ static void ms5611_get_ut(void)
static void ms5611_start_up(void)
{
#ifdef USE_BARO_SPI_MS5611
ms5611SpiWriteCommand(CMD_ADC_CONV + CMD_ADC_D2 + ms5611_osr, 1); // D2 (temperature) conversion start!
#else
i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D1 + ms5611_osr, 1); // D1 (pressure) conversion start!
#endif
}
static void ms5611_get_up(void)

View File

@ -0,0 +1,74 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "io.h"
#include "bus_spi.h"
#include "barometer.h"
#include "barometer_ms5611.h"
#ifdef USE_BARO_SPI_MS5611
#define DISABLE_MS5611 IOHi(ms5611CsPin)
#define ENABLE_MS5611 IOLo(ms5611CsPin)
static IO_t ms5611CsPin = IO_NONE;
bool ms5611SpiWriteCommand(uint8_t reg, uint8_t data)
{
ENABLE_MS5611;
spiTransferByte(MS5611_SPI_INSTANCE, reg & 0x7F);
spiTransferByte(MS5611_SPI_INSTANCE, data);
DISABLE_MS5611;
return true;
}
bool ms5611SpiReadCommand(uint8_t reg, uint8_t length, uint8_t *data)
{
ENABLE_MS5611;
spiTransferByte(MS5611_SPI_INSTANCE, reg | 0x80);
spiTransfer(MS5611_SPI_INSTANCE, data, NULL, length);
DISABLE_MS5611;
return true;
}
void ms5611SpiInit(void)
{
static bool hardwareInitialised = false;
if (hardwareInitialised) {
return;
}
ms5611CsPin = IOGetByTag(IO_TAG(MS5611_CS_PIN));
IOInit(ms5611CsPin, OWNER_BARO_CS, 0);
IOConfigGPIO(ms5611CsPin, IOCFG_OUT_PP);
DISABLE_MS5611;
spiSetDivisor(MS5611_SPI_INSTANCE, SPI_CLOCK_STANDARD);
hardwareInitialised = true;
}
#endif

View File

@ -0,0 +1,22 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
void ms5611SpiInit(void);
bool ms5611SpiReadCommand(uint8_t reg, uint8_t length, uint8_t *data);
bool ms5611SpiWriteCommand(uint8_t reg, uint8_t data);

View File

@ -40,6 +40,7 @@
#include "compass.h"
#include "compass_hmc5883l.h"
#include "compass_spi_hmc5883l.h"
//#define DEBUG_MAG_DATA_READY_INTERRUPT
@ -167,13 +168,17 @@ static void hmc5883lConfigureDataReadyInterruptHandling(void)
static bool hmc5883lRead(int16_t *magData)
{
uint8_t buf[6];
#ifdef USE_MAG_SPI_HMC5883
bool ack = hmc5883SpiReadCommand(MAG_DATA_REGISTER, 6, buf);
#else
bool ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, MAG_DATA_REGISTER, 6, buf);
#endif
if (!ack) {
return false;
}
// During calibration, magGain is 1.0, so the read returns normal non-calibrated values.
// After calibration is done, magGain is set to calculated gain values.
magData[X] = (int16_t)(buf[0] << 8 | buf[1]) * magGain[X];
magData[Z] = (int16_t)(buf[2] << 8 | buf[3]) * magGain[Z];
magData[Y] = (int16_t)(buf[4] << 8 | buf[5]) * magGain[Y];
@ -189,15 +194,27 @@ static bool hmc5883lInit(void)
bool bret = true; // Error indicator
delay(50);
#ifdef USE_MAG_SPI_HMC5883
hmc5883SpiWriteCommand(HMC58X3_R_CONFA, 0x010 + HMC_POS_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to pos bias
#else
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_POS_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to pos bias
#endif
// Note that the very first measurement after a gain change maintains the same gain as the previous setting.
// The new gain setting is effective from the second measurement and on.
#ifdef USE_MAG_SPI_HMC5883
hmc5883SpiWriteCommand(HMC58X3_R_CONFB, 0x60); // Set the Gain to 2.5Ga (7:5->011)
#else
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFB, 0x60); // Set the Gain to 2.5Ga (7:5->011)
#endif
delay(100);
hmc5883lRead(magADC);
for (i = 0; i < 10; i++) { // Collect 10 samples
#ifdef USE_MAG_SPI_HMC5883
hmc5883SpiWriteCommand(HMC58X3_R_MODE, 1);
#else
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 1);
#endif
delay(50);
hmc5883lRead(magADC); // Get the raw values in case the scales have already been changed.
@ -215,9 +232,17 @@ static bool hmc5883lInit(void)
}
// Apply the negative bias. (Same gain)
#ifdef USE_MAG_SPI_HMC5883
hmc5883SpiWriteCommand(HMC58X3_R_CONFA, 0x010 + HMC_NEG_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to negative bias.
#else
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_NEG_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to negative bias.
#endif
for (i = 0; i < 10; i++) {
#ifdef USE_MAG_SPI_HMC5883
hmc5883SpiWriteCommand(HMC58X3_R_MODE, 1);
#else
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 1);
#endif
delay(50);
hmc5883lRead(magADC); // Get the raw values in case the scales have already been changed.
@ -239,9 +264,15 @@ static bool hmc5883lInit(void)
magGain[Z] = fabsf(660.0f * HMC58X3_Z_SELF_TEST_GAUSS * 2.0f * 10.0f / xyz_total[Z]);
// leave test mode
#ifdef USE_MAG_SPI_HMC5883
hmc5883SpiWriteCommand(HMC58X3_R_CONFA, 0x70); // Configuration Register A -- 0 11 100 00 num samples: 8 ; output rate: 15Hz ; normal measurement mode
hmc5883SpiWriteCommand(HMC58X3_R_CONFB, 0x20); // Configuration Register B -- 001 00000 configuration gain 1.3Ga
hmc5883SpiWriteCommand(HMC58X3_R_MODE, 0x00); // Mode register -- 000000 00 continuous Conversion Mode
#else
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x70); // Configuration Register A -- 0 11 100 00 num samples: 8 ; output rate: 15Hz ; normal measurement mode
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFB, 0x20); // Configuration Register B -- 001 00000 configuration gain 1.3Ga
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 0x00); // Mode register -- 000000 00 continuous Conversion Mode
#endif
delay(100);
if (!bret) { // Something went wrong so get a best guess
@ -263,7 +294,12 @@ bool hmc5883lDetect(magDev_t* mag, ioTag_t interruptTag)
#endif
uint8_t sig = 0;
#ifdef USE_MAG_SPI_HMC5883
hmc5883SpiInit();
bool ack = hmc5883SpiReadCommand(0x0A, 1, &sig);
#else
bool ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, 0x0A, 1, &sig);
#endif
if (!ack || sig != 'H')
return false;

View File

@ -0,0 +1,86 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <platform.h>
#include "io.h"
#include "bus_spi.h"
#include "compass.h"
#include "compass_hmc5883l.h"
#ifdef USE_MAG_SPI_HMC5883
#define DISABLE_HMC5883 IOHi(hmc5883CsPin)
#define ENABLE_HMC5883 IOLo(hmc5883CsPin)
static IO_t hmc5883CsPin = IO_NONE;
bool hmc5883SpiWriteCommand(uint8_t reg, uint8_t data)
{
uint8_t buf[32];
buf[0] = reg & 0x7F;
buf[1] = data;
ENABLE_HMC5883;
//spiTransferByte(HMC5883_SPI_INSTANCE, reg & 0x7F);
//spiTransferByte(HMC5883_SPI_INSTANCE, data);
spiTransfer(HMC5883_SPI_INSTANCE, NULL, buf, 2);
DISABLE_HMC5883;
return true;
}
bool hmc5883SpiReadCommand(uint8_t reg, uint8_t length, uint8_t *data)
{
uint8_t buf[32];
buf[0] = reg | 0x80 | 0x40;
ENABLE_HMC5883;
spiTransfer(HMC5883_SPI_INSTANCE, buf, buf, length + 1);
DISABLE_HMC5883;
memcpy(data, &buf[1], length);
return true;
}
void hmc5883SpiInit(void)
{
static bool hardwareInitialised = false;
if (hardwareInitialised) {
return;
}
hmc5883CsPin = IOGetByTag(IO_TAG(HMC5883_CS_PIN));
IOInit(hmc5883CsPin, OWNER_COMPASS_CS, 0);
IOConfigGPIO(hmc5883CsPin, IOCFG_OUT_PP);
DISABLE_HMC5883;
spiSetDivisor(HMC5883_SPI_INSTANCE, SPI_CLOCK_STANDARD);
hardwareInitialised = true;
}
#endif

View File

@ -0,0 +1,22 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
void hmc5883SpiInit(void);
bool hmc5883SpiReadCommand(uint8_t reg, uint8_t length, uint8_t *data);
bool hmc5883SpiWriteCommand(uint8_t reg, uint8_t data);

View File

@ -61,5 +61,6 @@ const char * const ownerNames[OWNER_TOTAL_COUNT] = {
"LED_STRIP",
"TRANSPONDER",
"VTX",
"COMPASS_CS"
};

View File

@ -61,6 +61,7 @@ typedef enum {
OWNER_LED_STRIP,
OWNER_TRANSPONDER,
OWNER_VTX,
OWNER_COMPASS_CS,
OWNER_TOTAL_COUNT
} resourceOwner_e;