Path: blob/master/libraries/AP_Compass/AP_Compass_LSM303D.h
9580 views
#pragma once12#include "AP_Compass_config.h"34#if AP_COMPASS_LSM303D_ENABLED56#include <AP_Common/AP_Common.h>7#include <AP_HAL/AP_HAL.h>8#include <AP_HAL/Device.h>9#include <AP_Math/AP_Math.h>1011#include "AP_Compass.h"12#include "AP_Compass_Backend.h"1314class AP_Compass_LSM303D : public AP_Compass_Backend15{16public:17static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,18enum Rotation rotation);1920static constexpr const char *name = "LSM303D";2122void read() override;2324virtual ~AP_Compass_LSM303D() { }2526private:27AP_Compass_LSM303D(AP_HAL::OwnPtr<AP_HAL::Device> dev);2829bool init(enum Rotation rotation);30uint8_t _register_read(uint8_t reg);31void _register_write(uint8_t reg, uint8_t val);32void _register_modify(uint8_t reg, uint8_t clearbits, uint8_t setbits);33bool _block_read(uint8_t reg, uint8_t *buf, uint32_t size);3435bool _read_sample();3637bool _data_ready();38bool _hardware_init();39void _update();40void _disable_i2c();41bool _mag_set_range(uint8_t max_ga);42bool _mag_set_samplerate(uint16_t frequency);4344AP_HAL::DigitalSource *_drdy_pin_m;45AP_HAL::OwnPtr<AP_HAL::Device> _dev;4647float _mag_range_scale;48int16_t _mag_x;49int16_t _mag_y;50int16_t _mag_z;5152bool _initialised;5354uint8_t _mag_range_ga;55uint8_t _mag_samplerate;56uint8_t _reg7_expected;57};5859#endif // AP_COMPASS_LSM303D_ENABLED606162