APM:Libraries
AP_RangeFinder_MaxsonarI2CXL.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "RangeFinder.h"
4 #include "RangeFinder_Backend.h"
5 #include <AP_HAL/I2CDevice.h>
6 
7 #define AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR 0x70
8 
9 #define AP_RANGEFINDER_MAXSONARI2CXL 4
10 #define AP_RANGE_FINDER_MAXSONARI2CXL_SCALER 1.0
11 #define AP_RANGE_FINDER_MAXSONARI2CXL_MIN_DISTANCE 20
12 #define AP_RANGE_FINDER_MAXSONARI2CXL_MAX_DISTANCE 765
13 
14 #define AP_RANGE_FINDER_MAXSONARI2CXL_COMMAND_TAKE_RANGE_READING 0x51
15 
17 {
18 public:
19  // static detection function
22 
23  // update state
24  void update(void);
25 
26 protected:
27 
28  MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
29  return MAV_DISTANCE_SENSOR_ULTRASOUND;
30  }
31 
32 private:
33  // constructor
36 
37  bool _init(void);
38  void _timer(void);
39 
40  uint16_t distance;
42 
43  // start a reading
44  bool start_reading(void);
45  bool get_reading(uint16_t &reading_cm);
47 };
MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override
static AP_RangeFinder_Backend * detect(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
AP_RangeFinder_MaxsonarI2CXL(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev