41 , _dev(
std::move(dev))
59 if (!sensor->
_init()) {
113 bool ret =
_dev->
transfer(
nullptr, 0, (uint8_t *) &val,
sizeof(val));
static AP_RangeFinder_Backend * detect(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
virtual Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb) override=0
virtual Semaphore * get_semaphore() override=0
#define HAL_SEMAPHORE_BLOCK_FOREVER
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
AP_RangeFinder_MaxsonarI2CXL(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
virtual void delay(uint16_t ms)=0
bool get_reading(uint16_t &reading_cm)
virtual bool take_nonblocking() WARN_IF_UNUSED=0
static uint16_t be16toh(be16_t value)
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
#define AP_RANGE_FINDER_MAXSONARI2CXL_COMMAND_TAKE_RANGE_READING
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
void set_status(RangeFinder::RangeFinder_Status status)
RangeFinder::RangeFinder_State & state
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
AP_HAL::Scheduler * scheduler
uint16_t __ap_bitwise be16_t