27 #define ADDR_CTRL_REG1 0x20 28 #define ADDR_CTRL_REG2 0x21 29 #define ADDR_CTRL_REG3 0x22 30 #define ADDR_CTRL_REG4 0x23 31 #define ADDR_CTRL_REG5 0x24 33 #define ADDR_STATUS_REG 0x27 34 #define ADDR_OUT_X_L 0x28 35 #define ADDR_OUT_X_H 0x29 36 #define ADDR_OUT_Y_L 0x2a 37 #define ADDR_OUT_Y_H 0x2b 38 #define ADDR_OUT_Z_L 0x2c 39 #define ADDR_OUT_Z_H 0x2d 40 #define ADDR_OUT_T_L 0x2e 41 #define ADDR_OUT_T_H 0x2f 43 #define MODE_REG_CONTINOUS_MODE (0 << 0) 44 #define MODE_REG_SINGLE_MODE (1 << 0) 46 #define ADDR_WHO_AM_I 0x0f 47 #define ID_WHO_AM_I 0x3d 60 if (!sensor || !sensor->
init()) {
144 const float range_scale = 1000.0f / 6842.0f;
150 goto check_registers;
152 if (!(status & 0x08)) {
154 goto check_registers;
158 goto check_registers;
161 field(data.magx * range_scale, data.magy * range_scale, data.magz * range_scale);
194 static uint32_t lastt;
195 static uint32_t total;
198 float dt = (now - lastt) * 1.0e-6;
200 printf(
"%u samples\n", total);
int printf(const char *fmt,...)
void set_external(uint8_t instance, bool external)
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
uint32_t get_bus_id(void) const
virtual AP_HAL::Semaphore * get_semaphore()=0
void rotate_field(Vector3f &mag, uint8_t instance)
virtual void set_retries(uint8_t retries)
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, bool force_external=false, enum Rotation rotation=ROTATION_NONE)
void publish_filtered_field(const Vector3f &mag, uint8_t instance)
void correct_field(Vector3f &mag, uint8_t i)
#define HAL_SEMAPHORE_BLOCK_FOREVER
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
void set_dev_id(uint8_t instance, uint32_t dev_id)
bool setup_checked_registers(uint8_t num_regs, uint8_t frequency=10)
void fail(const char *why)
void set_device_type(uint8_t devtype)
virtual bool take_nonblocking() WARN_IF_UNUSED=0
AP_Compass_LIS3MDL(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, bool force_external, enum Rotation rotation)
static AP_HAL::OwnPtr< AP_HAL::Device > dev
AP_HAL::OwnPtr< AP_HAL::Device > dev
uint8_t register_compass(void) const
enum BusType bus_type(void) const
void set_read_flag(uint8_t flag)
void set_rotation(uint8_t instance, enum Rotation rotation)
bool check_next_register(void)
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
void publish_raw_field(const Vector3f &mag, uint8_t instance)
bool write_register(uint8_t reg, uint8_t val, bool checked=false)