31 bool _block_read(uint8_t reg, uint8_t *buf, uint32_t size);
AP_HAL::OwnPtr< AP_HAL::Device > _dev
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum Rotation=ROTATION_NONE)
uint8_t _compass_instance
void _register_write(uint8_t reg, uint8_t val)
uint8_t _register_read(uint8_t reg)
virtual ~AP_Compass_LSM303D()
AP_Compass_LSM303D(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev)
void _register_modify(uint8_t reg, uint8_t clearbits, uint8_t setbits)
bool _mag_set_samplerate(uint16_t frequency)
bool _block_read(uint8_t reg, uint8_t *buf, uint32_t size)
static AP_HAL::OwnPtr< AP_HAL::Device > dev
bool init(enum Rotation rotation)
Common definitions and utility routines for the ArduPilot libraries.
static constexpr const char * name
AP_HAL::DigitalSource * _drdy_pin_m
bool _mag_set_range(uint8_t max_ga)