11 #define LSM9DS1M_OFFSET_X_REG_L_M 0x05 12 #define LSM9DS1M_OFFSET_X_REG_H_M 0x06 13 #define LSM9DS1M_OFFSET_Y_REG_L_M 0x07 14 #define LSM9DS1M_OFFSET_Y_REG_H_M 0x08 15 #define LSM9DS1M_OFFSET_Z_REG_L_M 0x09 16 #define LSM9DS1M_OFFSET_Z_REG_H_M 0x0A 18 #define LSM9DS1M_WHO_AM_I 0x0F 19 #define WHO_AM_I_MAG 0x3D 21 #define LSM9DS1M_CTRL_REG1_M 0x20 22 #define LSM9DS1M_TEMP_COMP (0x1 << 7) 23 #define LSM9DS1M_XY_ULTRA_HIGH (0x3 << 5) 24 #define LSM9DS1M_80HZ (0x7 << 2) 25 #define LSM9DS1M_FAST_ODR (0x1 << 1) 27 #define LSM9DS1M_CTRL_REG2_M 0x21 28 #define LSM9DS1M_FS_16G (0x3 << 5) 30 #define LSM9DS1M_CTRL_REG3_M 0x22 31 #define LSM9DS1M_SPI_ENABLE (0x01 << 2) 32 #define LSM9DS1M_CONTINUOUS_MODE 0x0 34 #define LSM9DS1M_CTRL_REG4_M 0x23 35 #define LSM9DS1M_Z_ULTRA_HIGH (0x3 << 2) 37 #define LSM9DS1M_CTRL_REG5_M 0x24 38 #define LSM9DS1M_BDU (0x0 << 6) 40 #define LSM9DS1M_STATUS_REG_M 0x27 42 #define LSM9DS1M_OUT_X_L_M 0x28 43 #define LSM9DS1M_OUT_X_H_M 0x29 44 #define LSM9DS1M_OUT_Y_L_M 0x2A 45 #define LSM9DS1M_OUT_Y_H_M 0x2B 46 #define LSM9DS1M_OUT_Z_L_M 0x2C 47 #define LSM9DS1M_OUT_Z_H_M 0x2D 48 #define LSM9DS1M_INT_CFG_M 0x30 49 #define LSM9DS1M_INT_SRC_M 0x31 50 #define LSM9DS1M_INT_THS_L_M 0x32 51 #define LSM9DS1M_INT_THS_H_M 0x33 64 , _dev(
std::move(dev))
77 if (!sensor || !sensor->
init()) {
90 hal.
console->
printf(
"LSM9DS1: Unable to get bus semaphore\n");
132 hal.
console->
printf(
"%02x:%02x ", (
unsigned)reg, (
unsigned)v);
149 if (regs.status & 0x80) {
153 raw_field =
Vector3f(regs.val[0], regs.val[1], regs.val[2]);
213 hal.
console->
printf(
"LSM9DS1: unexpected WHOAMI 0x%x\n", (
unsigned)value);
235 static const uint8_t FS_M_MASK = 0xc;
#define LSM9DS1M_TEMP_COMP
#define LSM9DS1M_XY_ULTRA_HIGH
Vector3< float > Vector3f
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
uint8_t _compass_instance
#define LSM9DS1M_STATUS_REG_M
#define LSM9DS1M_FAST_ODR
AP_HAL::UARTDriver * console
uint32_t get_bus_id(void) const
bool _block_read(uint8_t reg, uint8_t *buf, uint32_t size)
virtual AP_HAL::Semaphore * get_semaphore()=0
void rotate_field(Vector3f &mag, uint8_t instance)
void publish_filtered_field(const Vector3f &mag, uint8_t instance)
void correct_field(Vector3f &mag, uint8_t i)
#define HAL_SEMAPHORE_BLOCK_FOREVER
void _register_write(uint8_t reg, uint8_t val)
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
uint8_t _register_read(uint8_t reg)
#define LSM9DS1M_WHO_AM_I
void set_dev_id(uint8_t instance, uint32_t dev_id)
#define LSM9DS1M_OFFSET_X_REG_L_M
void set_device_type(uint8_t devtype)
virtual void printf(const char *,...) FMT_PRINTF(2
virtual bool take_nonblocking() WARN_IF_UNUSED=0
static AP_HAL::OwnPtr< AP_HAL::Device > dev
uint8_t register_compass(void) const
virtual bool set_speed(Speed speed)=0
bool is_zero(const T fVal1)
AP_Compass_LSM9DS1(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum Rotation rotation=ROTATION_NONE)
void _register_modify(uint8_t reg, uint8_t clearbits, uint8_t setbits)
#define LSM9DS1M_INT_THS_H_M
#define LSM9DS1M_CTRL_REG3_M
#define LSM9DS1M_CTRL_REG5_M
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum Rotation rotation=ROTATION_NONE)
#define LSM9DS1M_CTRL_REG4_M
void set_rotation(uint8_t instance, enum Rotation rotation)
AP_HAL::OwnPtr< AP_HAL::Device > _dev
#define LSM9DS1M_CTRL_REG1_M
#define LSM9DS1M_CONTINUOUS_MODE
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)
#define LSM9DS1M_CTRL_REG2_M
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
#define LSM9DS1M_Z_ULTRA_HIGH