AP_Compass: enable HMC5843 on SPI for PH2

This commit is contained in:
Andrew Tridgell 2016-11-04 17:57:52 +11:00
parent 88e24dd8bd
commit ac0ea12b42
3 changed files with 23 additions and 8 deletions

View File

@ -494,15 +494,30 @@ void Compass::_detect_backends(void)
#elif HAL_COMPASS_DEFAULT == HAL_COMPASS_PX4 || HAL_COMPASS_DEFAULT == HAL_COMPASS_VRBRAIN
if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_TEST_V1 ||
AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_TEST_V2 ||
AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_TEST_V3 ||
AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_TEST_V4) {
// use in-tree driver
// external i2c bus
_add_backend(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(1, HAL_COMPASS_HMC5843_I2C_ADDR), true),
AP_Compass_HMC5843::name, true);
// internal i2c bus
_add_backend(AP_Compass_HMC5843::probe(*this, hal.i2c_mgr->get_device(0, HAL_COMPASS_HMC5843_I2C_ADDR), false),
AP_Compass_HMC5843::name, false);
// try for SPI device too
_add_backend(AP_Compass_HMC5843::probe(*this, hal.spi->get_device(HAL_COMPASS_HMC5843_NAME), false),
AP_Compass_HMC5843::name, false);
}
if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_TEST_V2) {
_add_backend(AP_Compass_LSM303D::probe(*this, hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME)),
AP_Compass_LSM303D::name, false);
}
if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_TEST_V3) {
_add_backend(AP_Compass_LSM303D::probe(*this, hal.spi->get_device(HAL_INS_LSM9DS0_EXT_A_NAME)),
AP_Compass_LSM303D::name, false);
_add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 0),
AP_Compass_AK8963::name, false);
_add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 1),
AP_Compass_AK8963::name, false);
}
if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_TEST_V4) {
_add_backend(AP_Compass_AK8963::probe_mpu9250(*this, 0),
AP_Compass_AK8963::name, false);

View File

@ -102,7 +102,7 @@ AP_Compass_HMC5843::~AP_Compass_HMC5843()
}
AP_Compass_Backend *AP_Compass_HMC5843::probe(Compass &compass,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
AP_HAL::OwnPtr<AP_HAL::Device> dev,
bool force_external)
{
AP_HMC5843_BusDriver *bus = new AP_HMC5843_BusDriver_HALDevice(std::move(dev));
@ -475,8 +475,8 @@ bool AP_Compass_HMC5843::_calibrate()
return success;
}
/* AP_HAL::I2CDevice implementation of the HMC5843 */
AP_HMC5843_BusDriver_HALDevice::AP_HMC5843_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
/* AP_HAL::Device implementation of the HMC5843 */
AP_HMC5843_BusDriver_HALDevice::AP_HMC5843_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::Device> dev)
: _dev(std::move(dev))
{
}

View File

@ -2,7 +2,7 @@
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_HAL/Device.h>
#include <AP_Math/AP_Math.h>
#include "AP_Compass.h"
@ -17,7 +17,7 @@ class AP_Compass_HMC5843 : public AP_Compass_Backend
{
public:
static AP_Compass_Backend *probe(Compass &compass,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
AP_HAL::OwnPtr<AP_HAL::Device> dev,
bool force_external = false);
static AP_Compass_Backend *probe_mpu6000(Compass &compass);
@ -88,7 +88,7 @@ public:
class AP_HMC5843_BusDriver_HALDevice : public AP_HMC5843_BusDriver
{
public:
AP_HMC5843_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
AP_HMC5843_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::Device> dev);
bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;
bool register_read(uint8_t reg, uint8_t *val) override;
@ -99,7 +99,7 @@ public:
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
private:
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
AP_HAL::OwnPtr<AP_HAL::Device> _dev;
};
class AP_HMC5843_BusDriver_Auxiliary : public AP_HMC5843_BusDriver