Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Compass/AP_Compass_HMC5843.h
Views: 1798
#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;6465uint8_t _compass_instance;6667enum Rotation _rotation;6869bool _initialised:1;70bool _force_external:1;71};7273class AP_HMC5843_BusDriver74{75public:76virtual ~AP_HMC5843_BusDriver() { }7778virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) = 0;79virtual bool register_read(uint8_t reg, uint8_t *val) = 0;80virtual bool register_write(uint8_t reg, uint8_t val) = 0;8182virtual AP_HAL::Semaphore *get_semaphore() = 0;8384virtual bool configure() { return true; }85virtual bool start_measurements() { return true; }8687virtual AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t, AP_HAL::Device::PeriodicCb) = 0;8889// set device type within a device class90virtual void set_device_type(uint8_t devtype) = 0;9192// return 24 bit bus identifier93virtual uint32_t get_bus_id(void) const = 0;9495virtual void set_retries(uint8_t retries) {}96};9798class AP_HMC5843_BusDriver_HALDevice : public AP_HMC5843_BusDriver99{100public:101AP_HMC5843_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::Device> dev);102103bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;104bool register_read(uint8_t reg, uint8_t *val) override;105bool register_write(uint8_t reg, uint8_t val) override;106107AP_HAL::Semaphore *get_semaphore() override;108109AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;110111// set device type within a device class112void set_device_type(uint8_t devtype) override {113_dev->set_device_type(devtype);114}115116// return 24 bit bus identifier117uint32_t get_bus_id(void) const override {118return _dev->get_bus_id();119}120121void set_retries(uint8_t retries) override {122return _dev->set_retries(retries);123}124125private:126AP_HAL::OwnPtr<AP_HAL::Device> _dev;127};128129#if AP_INERTIALSENSOR_ENABLED130class AP_HMC5843_BusDriver_Auxiliary : public AP_HMC5843_BusDriver131{132public:133AP_HMC5843_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,134uint8_t addr);135virtual ~AP_HMC5843_BusDriver_Auxiliary();136137bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;138bool register_read(uint8_t reg, uint8_t *val) override;139bool register_write(uint8_t reg, uint8_t val) override;140141AP_HAL::Semaphore *get_semaphore() override;142143bool configure() override;144bool start_measurements() override;145146AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;147148// set device type within a device class149void set_device_type(uint8_t devtype) override;150151// return 24 bit bus identifier152uint32_t get_bus_id(void) const override;153154private:155AuxiliaryBus *_bus;156AuxiliaryBusSlave *_slave;157bool _started;158};159#endif // AP_INERTIALSENSOR_ENABLED160161#endif // AP_COMPASS_HMC5843_ENABLED162163164