mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Compass: fixed orientation of PH2 in-tree compass drivers
This commit is contained in:
parent
4ba00720aa
commit
3d5c57c5dc
@ -514,14 +514,11 @@ void Compass::_detect_backends(void)
|
||||
AP_Compass_LSM303D::name, false);
|
||||
}
|
||||
if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_TEST_V3) {
|
||||
_add_backend(AP_Compass_HMC5843::probe(*this, hal.spi->get_device(HAL_COMPASS_HMC5843_NAME),
|
||||
false, ROTATION_PITCH_180),
|
||||
AP_Compass_HMC5843::name, false);
|
||||
_add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 0),
|
||||
_add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 0, ROTATION_PITCH_180),
|
||||
AP_Compass_AK8963::name, false);
|
||||
_add_backend(AP_Compass_LSM303D::probe(*this, hal.spi->get_device(HAL_INS_LSM9DS0_EXT_A_NAME)),
|
||||
_add_backend(AP_Compass_LSM303D::probe(*this, hal.spi->get_device(HAL_INS_LSM9DS0_EXT_A_NAME), ROTATION_YAW_270),
|
||||
AP_Compass_LSM303D::name, false);
|
||||
_add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 1),
|
||||
_add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 1, ROTATION_YAW_270),
|
||||
AP_Compass_AK8963::name, false);
|
||||
}
|
||||
if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXRACER) {
|
||||
|
@ -160,13 +160,14 @@ AP_Compass_LSM303D::AP_Compass_LSM303D(Compass &compass, AP_HAL::OwnPtr<AP_HAL::
|
||||
}
|
||||
|
||||
AP_Compass_Backend *AP_Compass_LSM303D::probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev)
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
enum Rotation rotation)
|
||||
{
|
||||
if (!dev) {
|
||||
return nullptr;
|
||||
}
|
||||
AP_Compass_LSM303D *sensor = new AP_Compass_LSM303D(compass, std::move(dev));
|
||||
if (!sensor || !sensor->init()) {
|
||||
if (!sensor || !sensor->init(rotation)) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
}
|
||||
@ -254,7 +255,7 @@ bool AP_Compass_LSM303D::_read_sample()
|
||||
return true;
|
||||
}
|
||||
|
||||
bool AP_Compass_LSM303D::init()
|
||||
bool AP_Compass_LSM303D::init(enum Rotation rotation)
|
||||
{
|
||||
if (LSM303D_DRDY_M_PIN >= 0) {
|
||||
_drdy_pin_m = hal.gpio->channel(LSM303D_DRDY_M_PIN);
|
||||
@ -272,6 +273,8 @@ bool AP_Compass_LSM303D::init()
|
||||
/* register the compass instance in the frontend */
|
||||
_compass_instance = register_compass();
|
||||
|
||||
set_rotation(_compass_instance, rotation);
|
||||
|
||||
_dev->set_device_type(DEVTYPE_LSM303D);
|
||||
set_dev_id(_compass_instance, _dev->get_bus_id());
|
||||
|
||||
|
@ -12,11 +12,11 @@ class AP_Compass_LSM303D : public AP_Compass_Backend
|
||||
{
|
||||
public:
|
||||
static AP_Compass_Backend *probe(Compass &compass,
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev);
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||
enum Rotation = ROTATION_NONE);
|
||||
|
||||
static constexpr const char *name = "LSM303D";
|
||||
|
||||
bool init() override;
|
||||
void read() override;
|
||||
|
||||
virtual ~AP_Compass_LSM303D() { }
|
||||
@ -24,6 +24,7 @@ public:
|
||||
private:
|
||||
AP_Compass_LSM303D(Compass &compass, AP_HAL::OwnPtr<AP_HAL::Device> dev);
|
||||
|
||||
bool init(enum Rotation rotation);
|
||||
uint8_t _register_read(uint8_t reg);
|
||||
void _register_write(uint8_t reg, uint8_t val);
|
||||
void _register_modify(uint8_t reg, uint8_t clearbits, uint8_t setbits);
|
||||
|
Loading…
Reference in New Issue
Block a user