mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_Compass: allow override of QMC5883L orientation
This commit is contained in:
parent
397ba488db
commit
2ded88e611
@ -586,14 +586,15 @@ void Compass::_probe_external_i2c_compasses(void)
|
|||||||
//external i2c bus
|
//external i2c bus
|
||||||
FOREACH_I2C_EXTERNAL(i) {
|
FOREACH_I2C_EXTERNAL(i) {
|
||||||
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(*this, GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(*this, GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
||||||
true,ROTATION_ROLL_180),
|
true, HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL),
|
||||||
AP_Compass_QMC5883L::name, true);
|
AP_Compass_QMC5883L::name, true);
|
||||||
}
|
}
|
||||||
|
|
||||||
//internal i2c bus
|
//internal i2c bus
|
||||||
FOREACH_I2C_INTERNAL(i) {
|
FOREACH_I2C_INTERNAL(i) {
|
||||||
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(*this, GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(*this, GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
||||||
both_i2c_external, both_i2c_external?ROTATION_ROLL_180:ROTATION_ROLL_180_YAW_270),
|
both_i2c_external,
|
||||||
|
both_i2c_external?HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL:HAL_COMPASS_QMC5883L_ORIENTATION_INTERNAL),
|
||||||
AP_Compass_QMC5883L::name,both_i2c_external);
|
AP_Compass_QMC5883L::name,both_i2c_external);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -933,10 +934,10 @@ void Compass::_detect_backends(void)
|
|||||||
true, ROTATION_PITCH_180_YAW_90), AP_Compass_IST8310::name, true);
|
true, ROTATION_PITCH_180_YAW_90), AP_Compass_IST8310::name, true);
|
||||||
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QMC5883L
|
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QMC5883L
|
||||||
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(*this, GET_I2C_DEVICE(1, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(*this, GET_I2C_DEVICE(1, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
||||||
true,ROTATION_ROLL_180),
|
true, HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL),
|
||||||
AP_Compass_QMC5883L::name, true);
|
AP_Compass_QMC5883L::name, true);
|
||||||
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(*this, GET_I2C_DEVICE(0, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(*this, GET_I2C_DEVICE(0, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
||||||
false,ROTATION_PITCH_180_YAW_270),
|
false, HAL_COMPASS_QMC5883L_ORIENTATION_INTERNAL),
|
||||||
AP_Compass_QMC5883L::name, false);
|
AP_Compass_QMC5883L::name, false);
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE
|
||||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR)),
|
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, GET_I2C_DEVICE(HAL_COMPASS_HMC5843_I2C_BUS, HAL_COMPASS_HMC5843_I2C_ADDR)),
|
||||||
|
@ -28,6 +28,17 @@
|
|||||||
#define HAL_COMPASS_QMC5883L_I2C_ADDR 0x0D
|
#define HAL_COMPASS_QMC5883L_I2C_ADDR 0x0D
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/*
|
||||||
|
setup default orientations
|
||||||
|
*/
|
||||||
|
#ifndef HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL
|
||||||
|
#define HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL ROTATION_ROLL_180
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef HAL_COMPASS_QMC5883L_ORIENTATION_INTERNAL
|
||||||
|
#define HAL_COMPASS_QMC5883L_ORIENTATION_INTERNAL ROTATION_ROLL_180_YAW_270
|
||||||
|
#endif
|
||||||
|
|
||||||
class AP_Compass_QMC5883L : public AP_Compass_Backend
|
class AP_Compass_QMC5883L : public AP_Compass_Backend
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
Loading…
Reference in New Issue
Block a user