mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 12:25:20 +03:00
Added registration for bus devices.
This commit is contained in:
parent
f6b1c6a539
commit
386be8d742
25 changed files with 116 additions and 5 deletions
|
@ -61,6 +61,7 @@ bool cliMode = false;
|
|||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/adc.h"
|
||||
#include "drivers/buf_writer.h"
|
||||
#include "drivers/bus_i2c.h"
|
||||
#include "drivers/bus_spi.h"
|
||||
#include "drivers/dma.h"
|
||||
#include "drivers/dma_reqmap.h"
|
||||
|
@ -4706,6 +4707,21 @@ static void cliStatus(const char *cmdName, char *cmdline)
|
|||
|
||||
cliPrintLinef("Configuration: %s, size: %d, max available: %d", configurationStates[systemConfigMutable()->configurationState], getEEPROMConfigSize(), getEEPROMStorageSize());
|
||||
|
||||
// Devices
|
||||
#if defined(USE_SPI) || defined(USE_I2C)
|
||||
cliPrint("Devices detected:");
|
||||
#if defined(USE_SPI)
|
||||
cliPrintf(" SPI:%d", spiGetRegisteredDeviceCount());
|
||||
#if defined(USE_I2C)
|
||||
cliPrint(",");
|
||||
#endif
|
||||
#endif
|
||||
#if defined(USE_I2C)
|
||||
cliPrintf(" I2C:%d", i2cGetRegisteredDeviceCount());
|
||||
#endif
|
||||
cliPrintLinefeed();
|
||||
#endif
|
||||
|
||||
// Sensors
|
||||
cliPrint("Gyros detected:");
|
||||
bool found = false;
|
||||
|
|
|
@ -255,6 +255,7 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro, const gyro
|
|||
sensor = (gyroSpiDetectFnTable[index])(&gyro->bus);
|
||||
if (sensor != MPU_NONE) {
|
||||
gyro->mpuDetectionResult.sensor = sensor;
|
||||
busDeviceRegister(&gyro->bus);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
@ -301,6 +302,7 @@ bool mpuDetect(gyroDev_t *gyro, const gyroDeviceConfig_t *config)
|
|||
bool ack = busReadRegisterBuffer(&gyro->bus, MPU_RA_WHO_AM_I, &sig, 1);
|
||||
|
||||
if (ack) {
|
||||
busDeviceRegister(&gyro->bus);
|
||||
// If an MPU3050 is connected sig will contain 0.
|
||||
uint8_t inquiryResult;
|
||||
ack = busReadRegisterBuffer(&gyro->bus, MPU_RA_WHO_AM_I_LEGACY, &inquiryResult, 1);
|
||||
|
|
|
@ -154,8 +154,9 @@ bool bmp085Detect(const bmp085Config_t *config, baroDev_t *baro)
|
|||
bool ack;
|
||||
bool defaultAddressApplied = false;
|
||||
|
||||
if (bmp085InitDone)
|
||||
if (bmp085InitDone) {
|
||||
return true;
|
||||
}
|
||||
|
||||
bmp085InitXclrIO(config);
|
||||
BMP085_ON; // enable baro
|
||||
|
@ -188,6 +189,8 @@ bool bmp085Detect(const bmp085Config_t *config, baroDev_t *baro)
|
|||
bmp085.oversampling_setting = 3;
|
||||
|
||||
if (bmp085.chip_id == BMP085_CHIP_ID) { /* get bitslice */
|
||||
busDeviceRegister(busdev);
|
||||
|
||||
busReadRegisterBuffer(busdev, BMP085_VERSION_REG, &data, 1); /* 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 */
|
||||
|
|
|
@ -171,6 +171,8 @@ bool bmp280Detect(baroDev_t *baro)
|
|||
return false;
|
||||
}
|
||||
|
||||
busDeviceRegister(busdev);
|
||||
|
||||
// read calibration
|
||||
busReadRegisterBuffer(busdev, BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG, (uint8_t *)&bmp280_cal, sizeof(bmp280_calib_param_t));
|
||||
|
||||
|
|
|
@ -263,6 +263,8 @@ bool bmp388Detect(const bmp388Config_t *config, baroDev_t *baro)
|
|||
return false;
|
||||
}
|
||||
|
||||
busDeviceRegister(busdev);
|
||||
|
||||
#ifdef USE_EXTI
|
||||
if (baroIntIO) {
|
||||
uint8_t intCtrlValue = 1 << BMP388_INT_DRDY_EN_BIT |
|
||||
|
|
|
@ -373,6 +373,8 @@ bool baroDPS310Detect(baroDev_t *baro)
|
|||
return false;
|
||||
}
|
||||
|
||||
busDeviceRegister(busdev);
|
||||
|
||||
const uint32_t baroDelay = 1000000 / 32 / 2; // twice the sample rate to capture all new data
|
||||
|
||||
baro->ut_delay = 0;
|
||||
|
|
|
@ -258,6 +258,8 @@ bool ms5611Detect(baroDev_t *baro)
|
|||
goto fail;
|
||||
}
|
||||
|
||||
busDeviceRegister(busdev);
|
||||
|
||||
// TODO prom + CRC
|
||||
baro->ut_delay = 10000;
|
||||
baro->up_delay = 10000;
|
||||
|
|
|
@ -173,6 +173,8 @@ bool qmp6988Detect(baroDev_t *baro)
|
|||
return false;
|
||||
}
|
||||
|
||||
busDeviceRegister(busdev);
|
||||
|
||||
// SetIIR
|
||||
busWriteRegister(busdev, QMP6988_SET_IIR_REG, 0x05);
|
||||
|
||||
|
|
|
@ -227,3 +227,27 @@ uint8_t busReadRegister(const busDevice_t *busdev, uint8_t reg)
|
|||
return data;
|
||||
#endif
|
||||
}
|
||||
|
||||
void busDeviceRegister(const busDevice_t *busdev)
|
||||
{
|
||||
#if !defined(USE_SPI) && !defined(USE_I2C)
|
||||
UNUSED(busdev);
|
||||
#endif
|
||||
|
||||
switch (busdev->bustype) {
|
||||
#if defined(USE_SPI)
|
||||
case BUSTYPE_SPI:
|
||||
spiBusDeviceRegister(busdev);
|
||||
|
||||
break;
|
||||
#endif
|
||||
#if defined(USE_I2C)
|
||||
case BUSTYPE_I2C:
|
||||
i2cBusDeviceRegister(busdev);
|
||||
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -75,3 +75,4 @@ uint8_t busReadRegister(const busDevice_t *bus, uint8_t reg);
|
|||
bool busRawReadRegisterBufferStart(const busDevice_t *busdev, uint8_t reg, uint8_t *data, uint8_t length);
|
||||
bool busReadRegisterBufferStart(const busDevice_t *busdev, uint8_t reg, uint8_t *data, uint8_t length);
|
||||
bool busBusy(const busDevice_t *busdev, bool *error);
|
||||
void busDeviceRegister(const busDevice_t *busdev);
|
||||
|
|
|
@ -65,3 +65,4 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t*
|
|||
bool i2cBusy(I2CDevice device, bool *error);
|
||||
|
||||
uint16_t i2cGetErrorCounter(void);
|
||||
uint8_t i2cGetRegisteredDeviceCount(void);
|
||||
|
|
|
@ -29,6 +29,8 @@
|
|||
#include "drivers/bus.h"
|
||||
#include "drivers/bus_i2c.h"
|
||||
|
||||
static uint8_t i2cRegisteredDeviceCount = 0;
|
||||
|
||||
bool i2cBusWriteRegister(const busDevice_t *busdev, uint8_t reg, uint8_t data)
|
||||
{
|
||||
return i2cWrite(busdev->busdev_u.i2c.device, busdev->busdev_u.i2c.address, reg, data);
|
||||
|
@ -66,4 +68,15 @@ bool i2cBusBusy(const busDevice_t *busdev, bool *error)
|
|||
return i2cBusy(busdev->busdev_u.i2c.device, error);
|
||||
}
|
||||
|
||||
void i2cBusDeviceRegister(const busDevice_t *busdev)
|
||||
{
|
||||
UNUSED(busdev);
|
||||
|
||||
i2cRegisteredDeviceCount++;
|
||||
}
|
||||
|
||||
uint8_t i2cGetRegisteredDeviceCount(void)
|
||||
{
|
||||
return i2cRegisteredDeviceCount;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -26,3 +26,4 @@ bool i2cBusReadRegisterBuffer(const busDevice_t *busdev, uint8_t reg, uint8_t *d
|
|||
uint8_t i2cBusReadRegister(const busDevice_t *bus, uint8_t reg);
|
||||
bool i2cBusReadRegisterBufferStart(const busDevice_t *busdev, uint8_t reg, uint8_t *data, uint8_t length);
|
||||
bool i2cBusBusy(const busDevice_t *busdev, bool *error);
|
||||
void i2cBusDeviceRegister(const busDevice_t *busdev);
|
||||
|
|
|
@ -33,6 +33,8 @@
|
|||
#include "drivers/io.h"
|
||||
#include "drivers/rcc.h"
|
||||
|
||||
static uint8_t spiRegisteredDeviceCount = 0;
|
||||
|
||||
spiDevice_t spiDevice[SPIDEV_COUNT];
|
||||
|
||||
SPIDevice spiDeviceByInstance(SPI_TypeDef *instance)
|
||||
|
@ -282,4 +284,16 @@ bool spiBusTransactionReadRegisterBuffer(const busDevice_t *bus, uint8_t reg, ui
|
|||
return spiBusReadRegisterBuffer(bus, reg, data, length);
|
||||
}
|
||||
#endif // USE_SPI_TRANSACTION
|
||||
|
||||
void spiBusDeviceRegister(const busDevice_t *bus)
|
||||
{
|
||||
UNUSED(bus);
|
||||
|
||||
spiRegisteredDeviceCount++;
|
||||
}
|
||||
|
||||
uint8_t spiGetRegisteredDeviceCount(void)
|
||||
{
|
||||
return spiRegisteredDeviceCount;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -177,3 +177,5 @@ bool spiBusTransactionTransfer(const busDevice_t *bus, const uint8_t *txData, ui
|
|||
|
||||
struct spiPinConfig_s;
|
||||
void spiPinConfigure(const struct spiPinConfig_s *pConfig);
|
||||
void spiBusDeviceRegister(const busDevice_t *bus);
|
||||
uint8_t spiGetRegisteredDeviceCount(void);
|
||||
|
|
|
@ -347,6 +347,8 @@ static bool ak8963Init(magDev_t *mag)
|
|||
|
||||
const busDevice_t *busdev = &mag->busdev;
|
||||
|
||||
busDeviceRegister(busdev);
|
||||
|
||||
ak8963WriteRegister(busdev, AK8963_MAG_REG_CNTL1, CNTL1_MODE_POWER_DOWN); // power down before entering fuse mode
|
||||
ak8963WriteRegister(busdev, AK8963_MAG_REG_CNTL1, CNTL1_MODE_FUSE_ROM); // Enter Fuse ROM access mode
|
||||
ak8963ReadRegisterBuffer(busdev, AK8963_MAG_REG_ASAX, asa, sizeof(asa)); // Read the x-, y-, and z-axis calibration values
|
||||
|
|
|
@ -79,6 +79,8 @@
|
|||
|
||||
static bool ak8975Init(magDev_t *mag)
|
||||
{
|
||||
busDeviceRegister(busdev);
|
||||
|
||||
uint8_t asa[3];
|
||||
uint8_t status;
|
||||
|
||||
|
@ -163,8 +165,9 @@ bool ak8975Detect(magDev_t *mag)
|
|||
|
||||
bool ack = busReadRegisterBuffer(busdev, AK8975_MAG_REG_WIA, &sig, 1);
|
||||
|
||||
if (!ack || sig != AK8975_DEVICE_ID) // 0x48 / 01001000 / 'H'
|
||||
if (!ack || sig != AK8975_DEVICE_ID) { // 0x48 / 01001000 / 'H'
|
||||
return false;
|
||||
}
|
||||
|
||||
mag->init = ak8975Init;
|
||||
mag->read = ak8975Read;
|
||||
|
|
|
@ -185,6 +185,8 @@ static void hmc5883lConfigureDataReadyInterruptHandling(magDev_t* mag)
|
|||
#ifdef USE_MAG_SPI_HMC5883
|
||||
static void hmc5883SpiInit(busDevice_t *busdev)
|
||||
{
|
||||
busDeviceRegister(busdev);
|
||||
|
||||
IOHi(busdev->busdev_u.spi.csnPin); // Disable
|
||||
|
||||
IOInit(busdev->busdev_u.spi.csnPin, OWNER_COMPASS_CS, 0);
|
||||
|
@ -222,7 +224,6 @@ static bool hmc5883lInit(magDev_t *mag)
|
|||
|
||||
busDevice_t *busdev = &mag->busdev;
|
||||
|
||||
|
||||
// leave test mode
|
||||
busWriteRegister(busdev, HMC58X3_REG_CONFA, HMC_CONFA_8_SAMLES | HMC_CONFA_DOR_15HZ | HMC_CONFA_NORMAL); // Configuration Register A -- 0 11 100 00 num samples: 8 ; output rate: 15Hz ; normal measurement mode
|
||||
busWriteRegister(busdev, HMC58X3_REG_CONFB, HMC_CONFB_GAIN_1_3GA); // Configuration Register B -- 001 00000 configuration gain 1.3Ga
|
||||
|
|
|
@ -124,6 +124,8 @@ static bool lis3mdlInit(magDev_t *mag)
|
|||
{
|
||||
busDevice_t *busdev = &mag->busdev;
|
||||
|
||||
busDeviceRegister(busdev);
|
||||
|
||||
busWriteRegister(busdev, LIS3MDL_REG_CTRL_REG2, LIS3MDL_FS_4GAUSS);
|
||||
busWriteRegister(busdev, LIS3MDL_REG_CTRL_REG1, LIS3MDL_TEMP_EN | LIS3MDL_OM_ULTRA_HI_PROF | LIS3MDL_DO_80);
|
||||
busWriteRegister(busdev, LIS3MDL_REG_CTRL_REG5, LIS3MDL_BDU);
|
||||
|
|
|
@ -79,6 +79,8 @@ static bool qmc5883lInit(magDev_t *magDev)
|
|||
bool ack = true;
|
||||
busDevice_t *busdev = &magDev->busdev;
|
||||
|
||||
busDeviceRegister(busdev);
|
||||
|
||||
ack = ack && busWriteRegister(busdev, 0x0B, 0x01);
|
||||
ack = ack && busWriteRegister(busdev, QMC5883L_REG_CONF1, QMC5883L_MODE_CONTINUOUS | QMC5883L_ODR_200HZ | QMC5883L_OSR_512 | QMC5883L_RNG_8G);
|
||||
|
||||
|
|
|
@ -168,6 +168,4 @@ ioTag_t timerioTagGetByUsage(timerUsageFlag_e usageFlag, uint8_t index)
|
|||
#endif
|
||||
return IO_TAG_NONE;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
|
|
|
@ -50,6 +50,7 @@
|
|||
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/bus_i2c.h"
|
||||
#include "drivers/bus_spi.h"
|
||||
#include "drivers/camera_control.h"
|
||||
#include "drivers/compass/compass.h"
|
||||
#include "drivers/display.h"
|
||||
|
@ -686,6 +687,18 @@ static bool mspCommonProcessOutCommand(int16_t cmdMSP, sbuf_t *dst, mspPostProce
|
|||
|
||||
sbufWriteU32(dst, configurationProblems);
|
||||
|
||||
// Added in MSP API 1.44
|
||||
#if defined(USE_SPI)
|
||||
sbufWriteU8(dst, spiGetRegisteredDeviceCount());
|
||||
#else
|
||||
sbufWriteU8(dst, 0);
|
||||
#endif
|
||||
#if defined(USE_I2C)
|
||||
sbufWriteU8(dst, i2cGetRegisteredDeviceCount());
|
||||
#else
|
||||
sbufWriteU8(dst, 0);
|
||||
#endif
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
|
|
|
@ -152,6 +152,7 @@ bool busReadRegisterBuffer(const busDevice_t*, uint8_t, uint8_t*, uint8_t) {retu
|
|||
bool busReadRegisterBufferStart(const busDevice_t*, uint8_t, uint8_t*, uint8_t) {return true;}
|
||||
bool busWriteRegister(const busDevice_t*, uint8_t, uint8_t) {return true;}
|
||||
bool busWriteRegisterStart(const busDevice_t*, uint8_t, uint8_t) {return true;}
|
||||
void busDeviceRegister(const busDevice_t*) {}
|
||||
|
||||
void spiBusSetDivisor() {
|
||||
}
|
||||
|
|
|
@ -148,6 +148,7 @@ bool busReadRegisterBuffer(const busDevice_t*, uint8_t, uint8_t*, uint8_t) {retu
|
|||
bool busReadRegisterBufferStart(const busDevice_t*, uint8_t, uint8_t*, uint8_t) {return true;}
|
||||
bool busWriteRegister(const busDevice_t*, uint8_t, uint8_t) {return true;}
|
||||
bool busWriteRegisterStart(const busDevice_t*, uint8_t, uint8_t) {return true;}
|
||||
void busDeviceRegister(const busDevice_t*) {}
|
||||
|
||||
void spiBusSetDivisor() {
|
||||
}
|
||||
|
|
|
@ -151,6 +151,7 @@ bool busRawReadRegisterBuffer(const busDevice_t*, uint8_t, uint8_t*, uint8_t) {r
|
|||
bool busRawReadRegisterBufferStart(const busDevice_t*, uint8_t, uint8_t*, uint8_t) {return true;}
|
||||
bool busRawWriteRegister(const busDevice_t*, uint8_t, uint8_t) {return true;}
|
||||
bool busRawWriteRegisterStart(const busDevice_t*, uint8_t, uint8_t) {return true;}
|
||||
void busDeviceRegister(const busDevice_t*) {}
|
||||
|
||||
void spiBusSetDivisor() {
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue