APM:Libraries
AP_RangeFinder_LightWareI2C.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  */
16 
17 #include <utility>
18 
19 #include <AP_HAL/AP_HAL.h>
21 
22 extern const AP_HAL::HAL& hal;
23 
24 /*
25  The constructor also initializes the rangefinder. Note that this
26  constructor is not called until detect() returns true, so we
27  already know that we should setup the rangefinder
28 */
30  : AP_RangeFinder_Backend(_state)
31  , _dev(std::move(dev)) {}
32 
33 /*
34  detect if a Lightware rangefinder is connected. We'll detect by
35  trying to take a reading on I2C. If we get a result the sensor is
36  there.
37 */
39 {
41  = new AP_RangeFinder_LightWareI2C(_state, std::move(dev));
42 
43  if (!sensor) {
44  delete sensor;
45  return nullptr;
46  }
47 
49  uint16_t reading_cm;
50  if (!sensor->get_reading(reading_cm)) {
51  sensor->_dev->get_semaphore()->give();
52  delete sensor;
53  return nullptr;
54  }
55  sensor->_dev->get_semaphore()->give();
56  }
57 
58  sensor->init();
59 
60  return sensor;
61 }
62 
64 {
65  // call timer() at 20Hz
68 }
69 
70 // read - return last value measured by sensor
71 bool AP_RangeFinder_LightWareI2C::get_reading(uint16_t &reading_cm)
72 {
73  be16_t val;
74 
75  if (state.address == 0) {
76  return false;
77  }
78 
79  // read the high and low byte distance registers
80  bool ret = _dev->read((uint8_t *) &val, sizeof(val));
81  if (ret) {
82  // combine results into distance
83  reading_cm = be16toh(val);
84  }
85 
86  return ret;
87 }
88 
89 /*
90  update the state of the sensor
91 */
93 {
94  // nothing to do - its all done in the timer()
95 }
96 
98 {
100  // update range_valid state based on distance measured
101  update_status();
102  } else {
104  }
105 }
virtual Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb) override=0
bool get_reading(uint16_t &reading_cm)
AP_RangeFinder_LightWareI2C(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
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
static uint16_t be16toh(be16_t value)
Definition: sparse-endian.h:83
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
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
static AP_RangeFinder_Backend * detect(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
bool read(uint8_t *recv, uint32_t recv_len)
Definition: Device.h:156
void set_status(RangeFinder::RangeFinder_Status status)
RangeFinder::RangeFinder_State & state
uint16_t __ap_bitwise be16_t
Definition: sparse-endian.h:36