APM:Libraries
AP_RangeFinder_MaxsonarI2CXL.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  * AP_RangeFinder_MaxsonarI2CXL.cpp - Arduino Library for MaxBotix I2C XL sonar
18  * Code by Randy Mackay. DIYDrones.com
19  *
20  * datasheet: http://www.maxbotix.com/documents/I2CXL-MaxSonar-EZ_Datasheet.pdf
21  *
22  * Sensor should be connected to the I2C port
23  */
25 
26 #include <utility>
27 
28 #include <AP_HAL/AP_HAL.h>
30 
31 extern const AP_HAL::HAL& hal;
32 
33 /*
34  The constructor also initializes the rangefinder. Note that this
35  constructor is not called until detect() returns true, so we
36  already know that we should setup the rangefinder
37 */
40  : AP_RangeFinder_Backend(_state)
41  , _dev(std::move(dev))
42 {
43 }
44 
45 /*
46  detect if a Maxbotix rangefinder is connected. We'll detect by
47  trying to take a reading on I2C. If we get a result the sensor is
48  there.
49 */
52 {
54  = new AP_RangeFinder_MaxsonarI2CXL(_state, std::move(dev));
55  if (!sensor) {
56  return nullptr;
57  }
58 
59  if (!sensor->_init()) {
60  delete sensor;
61  return nullptr;
62  }
63 
64  return sensor;
65 }
66 
67 /*
68  initialise sensor
69  */
71 {
73  return false;
74  }
75 
76  if (!start_reading()) {
77  _dev->get_semaphore()->give();
78  return false;
79  }
80 
81  // give time for the sensor to process the request
82  hal.scheduler->delay(100);
83 
84  uint16_t reading_cm;
85  if (!get_reading(reading_cm)) {
86  _dev->get_semaphore()->give();
87  return false;
88  }
89 
90  _dev->get_semaphore()->give();
91 
94 
95  return true;
96 }
97 
98 // start_reading() - ask sensor to make a range reading
100 {
102 
103  // send command to take reading
104  return _dev->transfer(&cmd, sizeof(cmd), nullptr, 0);
105 }
106 
107 // read - return last value measured by sensor
109 {
110  be16_t val;
111 
112  // take range reading and read back results
113  bool ret = _dev->transfer(nullptr, 0, (uint8_t *) &val, sizeof(val));
114 
115  if (ret) {
116  // combine results into distance
117  reading_cm = be16toh(val);
118 
119  // trigger a new reading
120  start_reading();
121  }
122 
123  return ret;
124 }
125 
126 /*
127  timer called at 10Hz
128 */
130 {
131  uint16_t d;
132  if (get_reading(d)) {
134  distance = d;
135  new_distance = true;
136  _sem->give();
137  }
138  }
139 }
140 
141 /*
142  update the state of the sensor
143 */
145 {
146  if (_sem->take_nonblocking()) {
147  if (new_distance) {
149  new_distance = false;
150  update_status();
151  } else {
153  }
154  _sem->give();
155  }
156 }
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
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
AP_HAL::Semaphore * _sem
AP_RangeFinder_MaxsonarI2CXL(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
virtual void delay(uint16_t ms)=0
virtual bool take_nonblocking() WARN_IF_UNUSED=0
static uint16_t be16toh(be16_t value)
Definition: sparse-endian.h:83
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
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
virtual bool give()=0
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
void set_status(RangeFinder::RangeFinder_Status status)
RangeFinder::RangeFinder_State & state
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
uint16_t __ap_bitwise be16_t
Definition: sparse-endian.h:36