APM:Libraries
AP_RangeFinder_LightWareSerial.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 #include <AP_HAL/AP_HAL.h>
19 #include <ctype.h>
20 
21 extern const AP_HAL::HAL& hal;
22 
23 /*
24  The constructor also initialises the rangefinder. Note that this
25  constructor is not called until detect() returns true, so we
26  already know that we should setup the rangefinder
27 */
30  uint8_t serial_instance) :
32 {
33  uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
34  if (uart != nullptr) {
35  uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance));
36  }
37 }
38 
39 /*
40  detect if a Lightware rangefinder is connected. We'll detect by
41  trying to take a reading on Serial. If we get a result the sensor is
42  there.
43 */
45 {
46  return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
47 }
48 
49 // read - return last value measured by sensor
51 {
52  if (uart == nullptr) {
53  return false;
54  }
55 
56  // read any available lines from the lidar
57  float sum = 0;
58  uint16_t count = 0;
59  int16_t nbytes = uart->available();
60  while (nbytes-- > 0) {
61  char c = uart->read();
62  if (c == '\r') {
63  linebuf[linebuf_len] = 0;
64  sum += (float)atof(linebuf);
65  count++;
66  linebuf_len = 0;
67  } else if (isdigit(c) || c == '.') {
68  linebuf[linebuf_len++] = c;
69  if (linebuf_len == sizeof(linebuf)) {
70  // too long, discard the line
71  linebuf_len = 0;
72  }
73  }
74  }
75 
76  // we need to write a byte to prompt another reading
77  uart->write('d');
78 
79  if (count == 0) {
80  return false;
81  }
82  reading_cm = 100 * sum / count;
83  return true;
84 }
85 
86 /*
87  update the state of the sensor
88 */
90 {
92  // update range_valid state based on distance measured
94  update_status();
95  } else if (AP_HAL::millis() - last_reading_ms > 200) {
97  }
98 }
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
AP_RangeFinder_LightWareSerial(RangeFinder::RangeFinder_State &_state, AP_SerialManager &serial_manager, uint8_t serial_instance)
virtual void begin(uint32_t baud)=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 bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
uint32_t find_baudrate(enum SerialProtocol protocol, uint8_t instance) const
virtual size_t write(uint8_t)=0
uint32_t millis()
Definition: system.cpp:157
virtual int16_t read()=0
virtual uint32_t available()=0
void set_status(RangeFinder::RangeFinder_Status status)
RangeFinder::RangeFinder_State & state
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const