mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: AK8963: refactor constructors
Declare a common constructor that others can call.
This commit is contained in:
parent
a5df93bf10
commit
868d0bf3c3
|
@ -93,13 +93,30 @@ AP_Compass_AK8963::AP_Compass_AK8963(Compass &compass, AP_AK8963_SerialBus *bus)
|
|||
|
||||
AP_Compass_Backend *AP_Compass_AK8963::detect_mpu9250(Compass &compass)
|
||||
{
|
||||
AP_Compass_AK8963 *sensor = new AP_Compass_AK8963(compass,
|
||||
new AP_AK8963_SerialBus_MPU9250());
|
||||
AP_AK8963_SerialBus *bus = new AP_AK8963_SerialBus_MPU9250();
|
||||
if (!bus)
|
||||
return nullptr;
|
||||
return _detect(compass, bus);
|
||||
}
|
||||
|
||||
AP_Compass_Backend *AP_Compass_AK8963::detect_i2c(Compass &compass,
|
||||
AP_HAL::I2CDriver *i2c,
|
||||
uint8_t addr)
|
||||
{
|
||||
AP_AK8963_SerialBus *bus = new AP_AK8963_SerialBus_I2C(i2c, addr);
|
||||
if (!bus)
|
||||
return nullptr;
|
||||
return _detect(compass, bus);
|
||||
}
|
||||
|
||||
AP_Compass_Backend *AP_Compass_AK8963::_detect(Compass &compass,
|
||||
AP_AK8963_SerialBus *bus)
|
||||
{
|
||||
AP_Compass_AK8963 *sensor = new AP_Compass_AK8963(compass, bus);
|
||||
if (sensor == nullptr) {
|
||||
delete bus;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
if (!sensor->init()) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
|
@ -108,24 +125,9 @@ AP_Compass_Backend *AP_Compass_AK8963::detect_mpu9250(Compass &compass)
|
|||
return sensor;
|
||||
}
|
||||
|
||||
|
||||
AP_Compass_Backend *AP_Compass_AK8963::detect_i2c(Compass &compass,
|
||||
AP_HAL::I2CDriver *i2c,
|
||||
uint8_t addr)
|
||||
AP_Compass_AK8963::~AP_Compass_AK8963()
|
||||
{
|
||||
AP_Compass_AK8963 *sensor =
|
||||
new AP_Compass_AK8963(compass, new AP_AK8963_SerialBus_I2C(i2c, addr));
|
||||
|
||||
if (sensor == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
if (!sensor->init()) {
|
||||
delete sensor;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
return sensor;
|
||||
delete _bus;
|
||||
}
|
||||
|
||||
/* stub to satisfy Compass API*/
|
||||
|
|
|
@ -17,6 +17,7 @@ public:
|
|||
uint8_t st2;
|
||||
};
|
||||
|
||||
virtual ~AP_AK8963_SerialBus() { }
|
||||
virtual void register_read(uint8_t address, uint8_t *value, uint8_t count) = 0;
|
||||
uint8_t register_read(uint8_t address) {
|
||||
uint8_t reg;
|
||||
|
@ -34,18 +35,21 @@ public:
|
|||
class AP_Compass_AK8963 : public AP_Compass_Backend
|
||||
{
|
||||
public:
|
||||
AP_Compass_AK8963(Compass &compass, AP_AK8963_SerialBus *bus);
|
||||
|
||||
static AP_Compass_Backend *detect_mpu9250(Compass &compass);
|
||||
static AP_Compass_Backend *detect_i2c(Compass &compass,
|
||||
AP_HAL::I2CDriver *i2c,
|
||||
uint8_t addr);
|
||||
|
||||
AP_Compass_AK8963(Compass &compass, AP_AK8963_SerialBus *bus);
|
||||
~AP_Compass_AK8963();
|
||||
|
||||
bool init(void);
|
||||
void read(void);
|
||||
void accumulate(void);
|
||||
|
||||
private:
|
||||
static AP_Compass_Backend *_detect(Compass &compass, AP_AK8963_SerialBus *bus);
|
||||
|
||||
void _make_factory_sensitivity_adjustment(Vector3f& field) const;
|
||||
Vector3f _get_filtered_field() const;
|
||||
void _reset_filter();
|
||||
|
@ -73,7 +77,7 @@ private:
|
|||
uint32_t _last_update_timestamp;
|
||||
uint32_t _last_accum_time;
|
||||
|
||||
AP_AK8963_SerialBus *_bus;
|
||||
AP_AK8963_SerialBus *_bus = nullptr;
|
||||
AP_HAL::Semaphore *_bus_sem;
|
||||
};
|
||||
|
||||
|
|
Loading…
Reference in New Issue