mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: fixed MindPX-v2 compass orientations
This commit is contained in:
parent
8ab35e8aca
commit
8e87c30a33
|
@ -576,10 +576,13 @@ void Compass::_detect_backends(void)
|
|||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(1, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
true, ROTATION_ROLL_180),
|
||||
AP_Compass_HMC5843::name, true);
|
||||
// internal i2c bus
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(0, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
both_i2c_external, both_i2c_external?ROTATION_ROLL_180:ROTATION_YAW_270),
|
||||
AP_Compass_HMC5843::name, both_i2c_external);
|
||||
|
||||
if (AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_MINDPXV2) {
|
||||
// internal i2c bus
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(0, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
both_i2c_external, both_i2c_external?ROTATION_ROLL_180:ROTATION_YAW_270),
|
||||
AP_Compass_HMC5843::name, both_i2c_external);
|
||||
}
|
||||
|
||||
//external i2c bus
|
||||
ADD_BACKEND(DRIVER_QMC5883, AP_Compass_QMC5883L::probe(*this, hal.i2c_mgr->get_device(1, HAL_COMPASS_QMC5883L_I2C_ADDR),
|
||||
|
@ -708,6 +711,14 @@ void Compass::_detect_backends(void)
|
|||
AP_Compass_AK8963::name, false);
|
||||
break;
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_MINDPXV2:
|
||||
ADD_BACKEND(DRIVER_HMC5883, AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(0, HAL_COMPASS_HMC5843_I2C_ADDR),
|
||||
false, ROTATION_YAW_90),
|
||||
AP_Compass_HMC5843::name, false);
|
||||
ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(*this, hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME), ROTATION_PITCH_180_YAW_270),
|
||||
AP_Compass_LSM303D::name, false);
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue