Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 1 addition & 4 deletions src/main/drivers/compass/compass.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,6 @@ typedef struct magDev_s {
sensorMagInitFuncPtr init; // initialize function
sensorMagReadFuncPtr read; // read 3 axis data function
sensor_align_e magAlign;
uint8_t magSensorToUse;
int16_t magADCRaw[XYZ_AXIS_COUNT];
} magDev_t;

#ifndef MAG_I2C_INSTANCE
#define MAG_I2C_INSTANCE I2C_DEVICE
#endif
2 changes: 1 addition & 1 deletion src/main/drivers/compass/compass_ak8963.c
Original file line number Diff line number Diff line change
Expand Up @@ -164,7 +164,7 @@ static bool deviceDetect(magDev_t * mag)

bool ak8963Detect(magDev_t * mag)
{
mag->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_AK8963, 0, OWNER_COMPASS);
mag->busDev = busDeviceInit(BUSTYPE_I2C, DEVHW_AK8963, mag->magSensorToUse, OWNER_COMPASS);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If "BUSTYPE_I2C" instead of "BUSTYPE_ANY" is set here the AK8963 SPI compass will not be detected?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@MJ666 oops, sorry. Will fix ASAP

if (mag->busDev == NULL) {
return false;
}
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/compass/compass_ak8975.c
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,7 @@ static bool deviceDetect(magDev_t * mag)

bool ak8975Detect(magDev_t * mag)
{
mag->busDev = busDeviceInit(BUSTYPE_I2C, DEVHW_AK8975, 0, OWNER_COMPASS);
mag->busDev = busDeviceInit(BUSTYPE_I2C, DEVHW_AK8975, mag->magSensorToUse, OWNER_COMPASS);
if (mag->busDev == NULL) {
return false;
}
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/compass/compass_hmc5883l.c
Original file line number Diff line number Diff line change
Expand Up @@ -260,7 +260,7 @@ static bool deviceDetect(magDev_t * mag)

bool hmc5883lDetect(magDev_t * mag)
{
mag->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_HMC5883, 0, OWNER_COMPASS);
mag->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_HMC5883, mag->magSensorToUse, OWNER_COMPASS);
if (mag->busDev == NULL) {
return false;
}
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/compass/compass_ist8310.c
Original file line number Diff line number Diff line change
Expand Up @@ -162,7 +162,7 @@ static bool deviceDetect(magDev_t * mag)

bool ist8310Detect(magDev_t * mag)
{
mag->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_IST8310, 0, OWNER_COMPASS);
mag->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_IST8310, mag->magSensorToUse, OWNER_COMPASS);
if (mag->busDev == NULL) {
return false;
}
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/compass/compass_mag3110.c
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ static bool deviceDetect(magDev_t * mag)

bool mag3110detect(magDev_t * mag)
{
mag->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_MAG3110, 0, OWNER_COMPASS);
mag->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_MAG3110, mag->magSensorToUse, OWNER_COMPASS);
if (mag->busDev == NULL) {
return false;
}
Expand Down
3 changes: 2 additions & 1 deletion src/main/drivers/compass/compass_mpu9250.c
Original file line number Diff line number Diff line change
Expand Up @@ -284,7 +284,8 @@ static bool mpu9250CompassRead(magDev_t * mag)
bool mpu9250CompassDetect(magDev_t * mag)
{
// Compass on MPU9250 is only supported if MPU9250 is connected to SPI bus
mag->busDev = busDeviceOpen(BUSTYPE_SPI, DEVHW_MPU9250, 0);
// FIXME: We need to use gyro_to_use here, not mag_to_use
mag->busDev = busDeviceOpen(BUSTYPE_SPI, DEVHW_MPU9250, mag->magSensorToUse);
if (mag->busDev == NULL) {
return false;
}
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/compass/compass_qmc5883l.c
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,7 @@ static bool deviceDetect(magDev_t * mag)

bool qmc5883Detect(magDev_t * mag)
{
mag->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_QMC5883, 0, OWNER_COMPASS);
mag->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_QMC5883, mag->magSensorToUse, OWNER_COMPASS);
if (mag->busDev == NULL) {
return false;
}
Expand Down
4 changes: 4 additions & 0 deletions src/main/fc/settings.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -248,6 +248,10 @@ groups:
field: magCalibrationTimeLimit
min: 30
max: 120
- name: mag_to_use
condition: USE_DUAL_MAG
min: 0
max: 1

- name: PG_BAROMETER_CONFIG
type: barometerConfig_t
Expand Down
9 changes: 8 additions & 1 deletion src/main/sensors/compass.c
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@

mag_t mag; // mag access functions

PG_REGISTER_WITH_RESET_TEMPLATE(compassConfig_t, compassConfig, PG_COMPASS_CONFIG, 1);
PG_REGISTER_WITH_RESET_TEMPLATE(compassConfig_t, compassConfig, PG_COMPASS_CONFIG, 2);

#ifdef MAG
#define MAG_HARDWARE_DEFAULT MAG_AUTODETECT
Expand All @@ -71,6 +71,7 @@ PG_RESET_TEMPLATE(compassConfig_t, compassConfig,
.mag_align = ALIGN_DEFAULT,
.mag_hardware = MAG_HARDWARE_DEFAULT,
.mag_declination = 0,
.mag_to_use = 0,
.magCalibrationTimeLimit = 30
);

Expand Down Expand Up @@ -248,6 +249,12 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)

bool compassInit(void)
{
#ifdef USE_DUAL_MAG
mag.dev.magSensorToUse = compassConfig()->mag_to_use;
#else
mag.dev.magSensorToUse = 0;
#endif

if (!compassDetect(&mag.dev, compassConfig()->mag_hardware)) {
return false;
}
Expand Down
2 changes: 1 addition & 1 deletion src/main/sensors/compass.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ typedef struct compassConfig_s {
sensor_align_e mag_align; // mag alignment
uint8_t mag_hardware; // Which mag hardware to use on boards with more than one device
flightDynamicsTrims_t magZero;
uint8_t __dummy_1; // Maximum rotation rate MAG_HOLD mode can feed to yaw rate PID controller
uint8_t mag_to_use;
uint8_t magCalibrationTimeLimit; // Time for compass calibration (seconds)
} compassConfig_t;

Expand Down
11 changes: 11 additions & 0 deletions src/main/target/REVO/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,17 @@
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"

/* GYRO */
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE);

BUSDEV_REGISTER_I2C( busdev_ms5611, DEVHW_MS5611, BARO_I2C_BUS, 0x77, NONE, DEVFLAGS_USE_RAW_REGISTERS);

BUSDEV_REGISTER_I2C_TAG(busdev_hmc5883_int, DEVHW_HMC5883, MAG_I2C_BUS_INT, 0x1E, NONE, 0, DEVFLAGS_NONE);

BUSDEV_REGISTER_I2C_TAG(busdev_hmc5883, DEVHW_HMC5883, MAG_I2C_BUS_EXT, 0x1E, NONE, 1, DEVFLAGS_NONE);
BUSDEV_REGISTER_I2C_TAG(busdev_qmc5883, DEVHW_QMC5883, MAG_I2C_BUS_EXT, 0x0D, NONE, 1, DEVFLAGS_NONE);
BUSDEV_REGISTER_I2C_TAG(busdev_mag3110, DEVHW_MAG3110, MAG_I2C_BUS_EXT, 0x0E, NONE, 1, DEVFLAGS_NONE);

/* TIMERS */
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // S1_OUT
Expand Down
11 changes: 7 additions & 4 deletions src/main/target/REVO/target.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,9 @@
#define USBD_SERIALNUMBER_STRING "0x8020000"
#endif

// Use target-specific hardware descriptors (don't use common_hardware.h)
#define USE_TARGET_HARDWARE_DESCRIPTORS

#define LED0 PB5
#define LED1 PB4

Expand All @@ -34,7 +37,7 @@

// MPU6000 interrupts
#define USE_EXTI
#define MPU_INT_EXTI PC4
#define MPU6000_EXTI_PIN PC4
#define USE_MPU_DATA_READY_SIGNAL

#define MPU6000_CS_PIN PA4
Expand All @@ -49,16 +52,16 @@
#define GYRO_MPU6000_ALIGN CW270_DEG

#define MAG
#define MAG_I2C_BUS BUS_I2C2
#define USE_DUAL_MAG
#define MAG_I2C_BUS_EXT BUS_I2C2
#define MAG_I2C_BUS_INT BUS_I2C1
#define USE_MAG_MAG3110
#define USE_MAG_QMC5883
#define USE_MAG_HMC5883
#define MAG_HMC5883_ALIGN CW90_DEG

#define BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_BMP085
#define USE_BARO_BMP280
#define USE_BARO_MS5611

//#define USE_PITOT_MS4525
Expand Down