29 #define DEVICE_ID 0x10 31 #define OUTPUT_X_L_REG 0x3 32 #define OUTPUT_X_H_REG 0x4 33 #define OUTPUT_Y_L_REG 0x5 34 #define OUTPUT_Y_H_REG 0x6 35 #define OUTPUT_Z_L_REG 0x7 36 #define OUTPUT_Z_H_REG 0x8 39 #define CNTL1_VAL_SINGLE_MEASUREMENT_MODE 0x1 42 #define CNTL2_VAL_SRST 1 44 #define AVGCNTL_REG 0x41 45 #define AVGCNTL_VAL_XZ_0 (0) 46 #define AVGCNTL_VAL_XZ_2 (1) 47 #define AVGCNTL_VAL_XZ_4 (2) 48 #define AVGCNTL_VAL_XZ_8 (3) 49 #define AVGCNTL_VAL_XZ_16 (4) 50 #define AVGCNTL_VAL_Y_0 (0 << 3) 51 #define AVGCNTL_VAL_Y_2 (1 << 3) 52 #define AVGCNTL_VAL_Y_4 (2 << 3) 53 #define AVGCNTL_VAL_Y_8 (3 << 3) 54 #define AVGCNTL_VAL_Y_16 (4 << 3) 56 #define PDCNTL_REG 0x42 57 #define PDCNTL_VAL_PULSE_DURATION_NORMAL 0xC0 59 #define SAMPLING_PERIOD_USEC (10 * AP_USEC_PER_MSEC) 68 #define IST8310_RESOLUTION 0.3 88 if (!sensor || !sensor->
init()) {
109 uint8_t reset_count = 0;
125 for (; reset_count < 5; reset_count++) {
133 uint8_t cntl2 = 0xFF;
135 (cntl2 & 0x01) == 0) {
140 if (reset_count == 5) {
141 printf(
"IST8310: failed to reset device\n");
147 printf(
"IST8310: found device but could not set it up\n");
161 printf(
"%s found on bus %u id %u address 0x%02x\n",
name,
219 auto x =
static_cast<int16_t
>(
le16toh(buffer.rx));
220 auto y =
static_cast<int16_t
>(
le16toh(buffer.ry));
221 auto z =
static_cast<int16_t
>(
le16toh(buffer.rz));
int printf(const char *fmt,...)
static const int16_t IST8310_MIN_VAL_XY
void set_external(uint8_t instance, bool external)
virtual perf_counter_t perf_alloc(perf_counter_type t, const char *name)
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
AP_HAL::OwnPtr< AP_HAL::Device > _dev
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, bool force_external=false, enum Rotation rotation=ROTATION_NONE)
#define SAMPLING_PERIOD_USEC
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 PDCNTL_VAL_PULSE_DURATION_NORMAL
void publish_filtered_field(const Vector3f &mag, uint8_t instance)
AP_HAL::Util::perf_counter_t _perf_bad_data
void correct_field(Vector3f &mag, uint8_t i)
uint8_t get_bus_address(void) const
AP_HAL::Device::PeriodicHandle _periodic_handle
#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)
uint8_t bus_num(void) const
void fail(const char *why)
static const int16_t IST8310_MIN_VAL_Z
virtual void delay(uint16_t ms)=0
void set_device_type(uint8_t devtype)
virtual bool take_nonblocking() WARN_IF_UNUSED=0
static AP_HAL::OwnPtr< AP_HAL::Device > dev
#define AVGCNTL_VAL_XZ_16
uint8_t register_compass(void) const
static constexpr const char * name
virtual bool adjust_periodic_callback(PeriodicHandle h, uint32_t period_usec)=0
uint16_t __ap_bitwise le16_t
#define CNTL1_VAL_SINGLE_MEASUREMENT_MODE
#define IST8310_RESOLUTION
static const int16_t IST8310_MAX_VAL_XY
static const int16_t IST8310_MAX_VAL_Z
void set_rotation(uint8_t instance, enum Rotation rotation)
AP_Compass_IST8310(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, bool force_external, enum Rotation rotation)
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)
static uint16_t le16toh(le16_t value)
AP_HAL::Util::perf_counter_t _perf_xfer_err
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
AP_HAL::Scheduler * scheduler
virtual void perf_count(perf_counter_t h)