APM:Libraries
AP_RangeFinder_TeraRangerI2C.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  driver for TeraRanger I2C rangefinders
17  */
19 
20 #include <utility>
21 #include <AP_HAL/AP_HAL.h>
22 #include <AP_Math/crc.h>
23 
24 extern const AP_HAL::HAL& hal;
25 
26 // registers
27 #define TR_MEASURE 0x00
28 #define TR_WHOAMI 0x01
29 #define TR_WHOAMI_VALUE 0xA1
30 
31 /*
32  The constructor also initializes the rangefinder. Note that this
33  constructor is not called until detect() returns true, so we
34  already know that we should setup the rangefinder
35 */
38  : AP_RangeFinder_Backend(_state)
39  , dev(std::move(i2c_dev))
40 {
41 }
42 
43 /*
44  detect if a TeraRanger rangefinder is connected. We'll detect by
45  trying to take a reading on I2C. If we get a result the sensor is
46  there.
47 */
50 {
51  AP_RangeFinder_TeraRangerI2C *sensor = new AP_RangeFinder_TeraRangerI2C(_state, std::move(i2c_dev));
52  if (!sensor) {
53  return nullptr;
54  }
55 
56  if (!sensor->init()) {
57  delete sensor;
58  return nullptr;
59  }
60 
61  return sensor;
62 }
63 
64 /*
65  initialise sensor
66  */
68 {
70  return false;
71  }
72 
73  dev->set_retries(10);
74 
75  // check WHOAMI
76  uint8_t whoami;
77  if (!dev->read_registers(TR_WHOAMI, &whoami, 1) ||
78  whoami != TR_WHOAMI_VALUE) {
79  return false;
80  }
81 
82  if (!measure()) {
83  dev->get_semaphore()->give();
84  return false;
85  }
86 
87  // give time for the sensor to process the request
88  hal.scheduler->delay(70);
89 
90  uint16_t _distance_cm;
91  if (!collect(_distance_cm)) {
92  dev->get_semaphore()->give();
93  return false;
94  }
95 
96  dev->get_semaphore()->give();
97 
98  dev->set_retries(1);
99 
102 
103  return true;
104 }
105 
106 // measure() - ask sensor to make a range reading
108 {
109  uint8_t cmd = TR_MEASURE;
110  return dev->transfer(&cmd, 1, nullptr, 0);
111 }
112 
113 // collect - return last value measured by sensor
114 bool AP_RangeFinder_TeraRangerI2C::collect(uint16_t &_distance_cm)
115 {
116  uint8_t d[3];
117 
118  // take range reading and read back results
119  if (!dev->transfer(nullptr, 0, d, sizeof(d))) {
120  return false;
121  }
122 
123  if (d[2] != crc_crc8(d, 2)) {
124  // bad CRC
125  return false;
126  }
127 
128  _distance_cm = ((uint16_t(d[0]) << 8) | d[1]) / 10;
129 
130  return true;
131 }
132 
133 /*
134  timer called at 20Hz
135 */
137 {
138  // take a reading
139  uint16_t _distance_cm;
140  if (collect(_distance_cm) && _sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
141  accum.sum += _distance_cm;
142  accum.count++;
143  _sem->give();
144  }
145 
146  // and immediately ask for a new reading
147  measure();
148 }
149 
150 
151 /*
152  update the state of the sensor
153 */
155 {
157  if (accum.count > 0) {
158  state.distance_cm = accum.sum / accum.count;
159  accum.sum = 0;
160  accum.count = 0;
161  update_status();
162  } else {
164  }
165  _sem->give();
166  }
167 }
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
virtual Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb) override=0
struct AP_RangeFinder_TeraRangerI2C::@177 accum
I2C device type.
Definition: i2c.h:100
virtual void set_retries(uint8_t retries)
Definition: Device.h:260
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)
Definition: crc.cpp:50
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
AP_HAL::Semaphore * _sem
#define TR_MEASURE
virtual void delay(uint16_t ms)=0
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
virtual bool give()=0
#define TR_WHOAMI_VALUE
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
void set_status(RangeFinder::RangeFinder_Status status)
RangeFinder::RangeFinder_State & state
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
static AP_RangeFinder_Backend * detect(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > i2c_dev)