27 #define TR_MEASURE 0x00 28 #define TR_WHOAMI 0x01 29 #define TR_WHOAMI_VALUE 0xA1 56 if (!sensor->
init()) {
90 uint16_t _distance_cm;
128 _distance_cm = ((uint16_t(d[0]) << 8) | d[1]) / 10;
139 uint16_t _distance_cm;
141 accum.sum += _distance_cm;
157 if (
accum.count > 0) {
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
virtual Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb) override=0
struct AP_RangeFinder_TeraRangerI2C::@177 accum
virtual void set_retries(uint8_t retries)
virtual Semaphore * get_semaphore() override=0
AP_RangeFinder_TeraRangerI2C(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > i2c_dev)
uint8_t crc_crc8(const uint8_t *p, uint8_t len)
#define HAL_SEMAPHORE_BLOCK_FOREVER
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
virtual void delay(uint16_t ms)=0
static AP_HAL::OwnPtr< AP_HAL::Device > dev
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override=0
bool collect(uint16_t &distance_cm)
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
void set_status(RangeFinder::RangeFinder_Status status)
RangeFinder::RangeFinder_State & state
AP_HAL::Scheduler * scheduler
static AP_RangeFinder_Backend * detect(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > i2c_dev)