Path: blob/master/libraries/AP_Compass/AP_Compass_HMC5843.h
9693 views
#pragma once12#include "AP_Compass_config.h"34#if AP_COMPASS_HMC5843_ENABLED56#ifndef HAL_COMPASS_HMC5843_I2C_ADDR7#define HAL_COMPASS_HMC5843_I2C_ADDR 0x1E8#endif910#include <AP_Common/AP_Common.h>11#include <AP_HAL/AP_HAL.h>12#include <AP_HAL/Device.h>1314#include "AP_Compass_Backend.h"15#include <AP_InertialSensor/AP_InertialSensor_config.h>1617class AuxiliaryBus;18class AuxiliaryBusSlave;19class AP_InertialSensor;20class AP_HMC5843_BusDriver;2122class AP_Compass_HMC5843 : public AP_Compass_Backend23{24public:25static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,26bool force_external,27enum Rotation rotation);2829#if AP_INERTIALSENSOR_ENABLED30static AP_Compass_Backend *probe_mpu6000(enum Rotation rotation);31#endif3233static constexpr const char *name = "HMC5843";3435virtual ~AP_Compass_HMC5843();3637void read() override;3839private:40AP_Compass_HMC5843(AP_HMC5843_BusDriver *bus,41bool force_external, enum Rotation rotation);4243bool init();44bool _check_whoami();45bool _calibrate();46bool _setup_sampling_mode();4748void _timer();4950/* Read a single sample */51bool _read_sample();5253// ask for a new sample54void _take_sample();5556AP_HMC5843_BusDriver *_bus;5758Vector3f _scaling;59float _gain_scale;6061int16_t _mag_x;62int16_t _mag_y;63int16_t _mag_z;6465enum Rotation _rotation;6667bool _initialised:1;68bool _force_external:1;69};7071class AP_HMC5843_BusDriver72{73public:74virtual ~AP_HMC5843_BusDriver() { }7576virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) = 0;77virtual bool register_read(uint8_t reg, uint8_t *val) = 0;78virtual bool register_write(uint8_t reg, uint8_t val) = 0;7980virtual AP_HAL::Semaphore *get_semaphore() = 0;8182virtual bool configure() { return true; }83virtual bool start_measurements() { return true; }8485virtual AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t, AP_HAL::Device::PeriodicCb) = 0;8687// set device type within a device class88virtual void set_device_type(uint8_t devtype) = 0;8990// return 24 bit bus identifier91virtual uint32_t get_bus_id(void) const = 0;9293virtual void set_retries(uint8_t retries) {}94};9596class AP_HMC5843_BusDriver_HALDevice : public AP_HMC5843_BusDriver97{98public:99AP_HMC5843_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::Device> dev);100101bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;102bool register_read(uint8_t reg, uint8_t *val) override;103bool register_write(uint8_t reg, uint8_t val) override;104105AP_HAL::Semaphore *get_semaphore() override;106107AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;108109// set device type within a device class110void set_device_type(uint8_t devtype) override {111_dev->set_device_type(devtype);112}113114// return 24 bit bus identifier115uint32_t get_bus_id(void) const override {116return _dev->get_bus_id();117}118119void set_retries(uint8_t retries) override {120return _dev->set_retries(retries);121}122123private:124AP_HAL::OwnPtr<AP_HAL::Device> _dev;125};126127#if AP_INERTIALSENSOR_ENABLED128class AP_HMC5843_BusDriver_Auxiliary : public AP_HMC5843_BusDriver129{130public:131AP_HMC5843_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,132uint8_t addr);133virtual ~AP_HMC5843_BusDriver_Auxiliary();134135bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;136bool register_read(uint8_t reg, uint8_t *val) override;137bool register_write(uint8_t reg, uint8_t val) override;138139AP_HAL::Semaphore *get_semaphore() override;140141bool configure() override;142bool start_measurements() override;143144AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;145146// set device type within a device class147void set_device_type(uint8_t devtype) override;148149// return 24 bit bus identifier150uint32_t get_bus_id(void) const override;151152private:153AuxiliaryBus *_bus;154AuxiliaryBusSlave *_slave;155bool _started;156};157#endif // AP_INERTIALSENSOR_ENABLED158159#endif // AP_COMPASS_HMC5843_ENABLED160161162