29 #define QMC5883L_REG_CONF1 0x09 30 #define QMC5883L_REG_CONF2 0x0A 33 #define QMC5883L_ODR_10HZ (0x00 << 2) 34 #define QMC5883L_ODR_50HZ (0x01 << 2) 35 #define QMC5883L_ODR_100HZ (0x02 << 2) 36 #define QMC5883L_ODR_200HZ (0x03 << 2) 39 #define QMC5883L_MODE_STANDBY 0x00 40 #define QMC5883L_MODE_CONTINUOUS 0x01 42 #define QMC5883L_RNG_2G (0x00 << 4) 43 #define QMC5883L_RNG_8G (0x01 << 4) 45 #define QMC5883L_OSR_512 (0x00 << 6) 46 #define QMC5883L_OSR_256 (0x01 << 6) 47 #define QMC5883L_OSR_128 (0x10 << 6) 48 #define QMC5883L_OSR_64 (0x11 << 6) 50 #define QMC5883L_RST 0x80 52 #define QMC5883L_REG_DATA_OUTPUT_X 0x00 53 #define QMC5883L_REG_STATUS 0x06 55 #define QMC5883L_REG_ID 0x0D 56 #define QMC5883_ID_VAL 0xFF 70 if (!sensor || !sensor->
init()) {
123 printf(
"%s found on bus %u id %u address 0x%02x\n",
name,
169 const float range_scale = 1000.0f / 3000.0f;
176 if (!(status & 0x04)) {
184 auto x = -
static_cast<int16_t
>(
le16toh(buffer.rx));
185 auto y =
static_cast<int16_t
>(
le16toh(buffer.ry));
186 auto z = -
static_cast<int16_t
>(
le16toh(buffer.rz));
251 printf(
"QMC5883L registers dump\n");
255 printf(
"%02x:%02x ", (
unsigned)reg, (
unsigned)v);
int printf(const char *fmt,...)
#define QMC5883L_REG_CONF1
void set_external(uint8_t instance, bool external)
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
#define QMC5883L_ODR_100HZ
static uint8_t buffer[SRXL_FRAMELEN_MAX]
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)
#define QMC5883L_REG_DATA_OUTPUT_X
void publish_filtered_field(const Vector3f &mag, uint8_t instance)
void correct_field(Vector3f &mag, uint8_t i)
uint8_t get_bus_address(void) const
bool field_ok(const Vector3f &field)
#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)
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, bool force_external, enum Rotation rotation=ROTATION_NONE)
uint8_t bus_num(void) const
void fail(const char *why)
void set_device_type(uint8_t devtype)
virtual bool take_nonblocking() WARN_IF_UNUSED=0
AP_Compass_QMC5883L(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, bool force_external, enum Rotation rotation)
static AP_HAL::OwnPtr< AP_HAL::Device > dev
uint8_t register_compass(void) const
uint16_t __ap_bitwise le16_t
AP_HAL::OwnPtr< AP_HAL::Device > _dev
void rotate(enum Rotation rotation)
#define QMC5883L_REG_STATUS
#define QMC5883L_MODE_CONTINUOUS
void set_rotation(uint8_t instance, enum Rotation rotation)
static constexpr const char * name
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
bool is_external(uint8_t instance)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
void publish_raw_field(const Vector3f &mag, uint8_t instance)
static uint16_t le16toh(le16_t value)
bool write_register(uint8_t reg, uint8_t val, bool checked=false)