APM:Libraries
AP_RangeFinder_uLanding.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 #define ULANDING_HDR 254 // Header Byte from uLanding (0xFE)
22 #define ULANDING_HDR_V0 72 // Header Byte for beta V0 of uLanding (0x48)
23 
24 #define ULANDING_BAUD 115200
25 #define ULANDING_BUFSIZE_RX 128
26 #define ULANDING_BUFSIZE_TX 128
27 
28 extern const AP_HAL::HAL& hal;
29 
30 /*
31  The constructor also initialises the rangefinder. Note that this
32  constructor is not called until detect() returns true, so we
33  already know that we should setup the rangefinder
34 */
37  uint8_t serial_instance) :
39 {
40  uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
41  if (uart != nullptr) {
43  }
44 }
45 
46 /*
47  detect if a uLanding rangefinder is connected. We'll detect by
48  trying to take a reading on Serial. If we get a result the sensor is
49  there.
50 */
52 {
53  return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
54 }
55 
56 /*
57  detect uLanding Firmware Version
58 */
60 {
61  if (_version_known) {
62  // return true if we've already detected the uLanding version
63  return true;
64  } else if (uart == nullptr) {
65  return false;
66  }
67 
68  bool hdr_found = false;
69  uint8_t byte1 = 0;
70  uint8_t count = 0;
71 
72  // read any available data from uLanding
73  int16_t nbytes = uart->available();
74 
75  while (nbytes-- > 0) {
76  uint8_t c = uart->read();
77 
78  if (((c == ULANDING_HDR_V0) || (c == ULANDING_HDR)) && !hdr_found) {
79  byte1 = c;
80  hdr_found = true;
81  count++;
82  } else if (hdr_found) {
83  if (byte1 == ULANDING_HDR_V0) {
84  if (++count < 4) {
85  /* need to collect 4 bytes to check for recurring
86  * header byte in the old 3-byte data format
87  */
88  continue;
89  } else {
90  if (c == byte1) {
91  // if header byte is recurring, set uLanding Version
92  _version = 0;
94  _version_known = true;
95  return true;
96  } else {
97  /* if V0 header byte didn't occur again on 4th byte,
98  * start the search again for a header byte
99  */
100  count = 0;
101  byte1 = 0;
102  hdr_found = false;
103  }
104  }
105  } else {
106  if ((c & 0x80) || (c == ULANDING_HDR_V0)) {
107  /* Though unlikely, it is possible we could find ULANDING_HDR
108  * in a data byte from the old 3-byte format. In this case,
109  * either the next byte is another data byte (which by default
110  * is of the form 0x1xxxxxxx), or the next byte is the old
111  * header byte (ULANDING_HDR_V0). In this case, start the search
112  * again for a header byte.
113  */
114  count = 0;
115  byte1 = 0;
116  hdr_found = false;
117  } else {
118  /* if this second byte passes the above if statement, this byte
119  * is the version number
120  */
121  _version = c;
123  _version_known = true;
124  return true;
125  }
126  }
127  }
128  }
129 
130  /* return false if we've gone through all available data
131  * and haven't detected a uLanding firmware version
132  */
133  return false;
134 }
135 
136 
137 // read - return last value measured by sensor
138 bool AP_RangeFinder_uLanding::get_reading(uint16_t &reading_cm)
139 {
140  if (uart == nullptr) {
141  return false;
142  }
143 
144 
145  if (!detect_version()) {
146  // return false if uLanding version check failed
147  return false;
148  }
149 
150  // read any available lines from the uLanding
151  float sum = 0;
152  uint16_t count = 0;
153  bool hdr_found = false;
154 
155  int16_t nbytes = uart->available();
156 
157  while (nbytes-- > 0) {
158  uint8_t c = uart->read();
159 
160  if ((c == _header) && !hdr_found) {
161  // located header byte
162  _linebuf_len = 0;
163  hdr_found = true;
164  }
165  // decode index information
166  if (hdr_found) {
167  _linebuf[_linebuf_len++] = c;
168 
169  if ((_linebuf_len < (sizeof(_linebuf)/sizeof(_linebuf[0]))) ||
170  (_version == 0 && _linebuf_len < 3)) {
171  /* don't process _linebuf until we've collected six bytes of data
172  * (or 3 bytes for Version 0 firmware)
173  */
174  continue;
175  } else {
176  if (_version == 0) {
177  // parse data for Firmware Version #0
178  sum += (_linebuf[2]&0x7F)*128 + (_linebuf[1]&0x7F);
179  count++;
180  } else {
181  // evaluate checksum
182  if (((_linebuf[1] + _linebuf[2] + _linebuf[3] + _linebuf[4]) & 0xFF) == _linebuf[5]) {
183  // if checksum passed, parse data for Firmware Version #1
184  sum += _linebuf[3]*256 + _linebuf[2];
185  count++;
186  }
187  }
188 
189  hdr_found = false;
190  _linebuf_len = 0;
191  }
192  }
193  }
194 
195  if (count == 0) {
196  return false;
197  }
198 
199  reading_cm = sum / count;
200 
201  if (_version == 0) {
202  reading_cm *= 2.5f;
203  }
204 
205  return true;
206 }
207 
208 /*
209  update the state of the sensor
210 */
212 {
214  // update range_valid state based on distance measured
216  update_status();
217  } else if (AP_HAL::millis() - _last_reading_ms > 200) {
219  }
220 }
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
#define ULANDING_BUFSIZE_RX
#define ULANDING_BAUD
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
virtual void begin(uint32_t baud)=0
AP_RangeFinder_uLanding(RangeFinder::RangeFinder_State &_state, AP_SerialManager &serial_manager, uint8_t serial_instance)
#define ULANDING_HDR
#define ULANDING_HDR_V0
#define ULANDING_BUFSIZE_TX
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
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
bool get_reading(uint16_t &reading_cm)
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const