AP_Compass: added IST8310 on FMUv3 I2C

This commit is contained in:
Andrew Tridgell 2017-09-15 19:03:43 -07:00
parent cb270a9acf
commit 678bd084b7
3 changed files with 23 additions and 2 deletions

View File

@ -620,6 +620,13 @@ void Compass::_detect_backends(void)
ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(*this, hal.i2c_mgr->get_device(0, HAL_COMPASS_AK09916_I2C_ADDR), ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(*this, hal.i2c_mgr->get_device(0, HAL_COMPASS_AK09916_I2C_ADDR),
both_i2c_external, both_i2c_external?ROTATION_YAW_270:ROTATION_NONE), both_i2c_external, both_i2c_external?ROTATION_YAW_270:ROTATION_NONE),
AP_Compass_AK09916::name, both_i2c_external); AP_Compass_AK09916::name, both_i2c_external);
// IST8310 on external and internal bus
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(*this, hal.i2c_mgr->get_device(1, HAL_COMPASS_IST8310_I2C_ADDR),
true, ROTATION_PITCH_180), AP_Compass_IST8310::name, true);
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(*this, hal.i2c_mgr->get_device(0, HAL_COMPASS_IST8310_I2C_ADDR),
both_i2c_external, ROTATION_PITCH_180), AP_Compass_IST8310::name, both_i2c_external);
#endif // HAL_MINIMIZE_FEATURES #endif // HAL_MINIMIZE_FEATURES
} }
break; break;
@ -627,7 +634,7 @@ void Compass::_detect_backends(void)
case AP_BoardConfig::PX4_BOARD_AEROFC: case AP_BoardConfig::PX4_BOARD_AEROFC:
#ifdef HAL_COMPASS_IST8310_I2C_BUS #ifdef HAL_COMPASS_IST8310_I2C_BUS
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_IST8310_I2C_BUS, HAL_COMPASS_IST8310_I2C_ADDR), ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_IST8310_I2C_BUS, HAL_COMPASS_IST8310_I2C_ADDR),
ROTATION_PITCH_180_YAW_90), AP_Compass_IST8310::name, true); true, ROTATION_PITCH_180_YAW_90), AP_Compass_IST8310::name, true);
#endif #endif
break; break;
default: default:

View File

@ -77,13 +77,14 @@ extern const AP_HAL::HAL &hal;
AP_Compass_Backend *AP_Compass_IST8310::probe(Compass &compass, AP_Compass_Backend *AP_Compass_IST8310::probe(Compass &compass,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
bool force_external,
enum Rotation rotation) enum Rotation rotation)
{ {
if (!dev) { if (!dev) {
return nullptr; return nullptr;
} }
AP_Compass_IST8310 *sensor = new AP_Compass_IST8310(compass, std::move(dev), rotation); AP_Compass_IST8310 *sensor = new AP_Compass_IST8310(compass, std::move(dev), force_external, rotation);
if (!sensor || !sensor->init()) { if (!sensor || !sensor->init()) {
delete sensor; delete sensor;
return nullptr; return nullptr;
@ -94,10 +95,12 @@ AP_Compass_Backend *AP_Compass_IST8310::probe(Compass &compass,
AP_Compass_IST8310::AP_Compass_IST8310(Compass &compass, AP_Compass_IST8310::AP_Compass_IST8310(Compass &compass,
AP_HAL::OwnPtr<AP_HAL::Device> dev, AP_HAL::OwnPtr<AP_HAL::Device> dev,
bool force_external,
enum Rotation rotation) enum Rotation rotation)
: AP_Compass_Backend(compass) : AP_Compass_Backend(compass)
, _dev(std::move(dev)) , _dev(std::move(dev))
, _rotation(rotation) , _rotation(rotation)
, _force_external(force_external)
{ {
} }
@ -163,6 +166,10 @@ bool AP_Compass_IST8310::init()
_dev->set_device_type(DEVTYPE_IST8310); _dev->set_device_type(DEVTYPE_IST8310);
set_dev_id(_instance, _dev->get_bus_id()); set_dev_id(_instance, _dev->get_bus_id());
if (_force_external) {
set_external(_instance, true);
}
_periodic_handle = _dev->register_periodic_callback(SAMPLING_PERIOD_USEC, _periodic_handle = _dev->register_periodic_callback(SAMPLING_PERIOD_USEC,
FUNCTOR_BIND_MEMBER(&AP_Compass_IST8310::timer, void)); FUNCTOR_BIND_MEMBER(&AP_Compass_IST8310::timer, void));

View File

@ -24,11 +24,16 @@
#include "AP_Compass.h" #include "AP_Compass.h"
#include "AP_Compass_Backend.h" #include "AP_Compass_Backend.h"
#ifndef HAL_COMPASS_IST8310_I2C_ADDR
#define HAL_COMPASS_IST8310_I2C_ADDR 0x0E
#endif
class AP_Compass_IST8310 : public AP_Compass_Backend class AP_Compass_IST8310 : public AP_Compass_Backend
{ {
public: public:
static AP_Compass_Backend *probe(Compass &compass, static AP_Compass_Backend *probe(Compass &compass,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
bool force_external = false,
enum Rotation rotation = ROTATION_NONE); enum Rotation rotation = ROTATION_NONE);
void read() override; void read() override;
@ -38,6 +43,7 @@ public:
private: private:
AP_Compass_IST8310(Compass &compass, AP_Compass_IST8310(Compass &compass,
AP_HAL::OwnPtr<AP_HAL::Device> dev, AP_HAL::OwnPtr<AP_HAL::Device> dev,
bool force_external,
enum Rotation rotation); enum Rotation rotation);
void timer(); void timer();
@ -55,4 +61,5 @@ private:
enum Rotation _rotation; enum Rotation _rotation;
uint8_t _instance; uint8_t _instance;
bool _ignore_next_sample; bool _ignore_next_sample;
bool _force_external;
}; };