APM:Libraries
AP_RangeFinder_Benewake.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>
21 
22 extern const AP_HAL::HAL& hal;
23 
24 #define BENEWAKE_FRAME_HEADER 0x59
25 #define BENEWAKE_FRAME_LENGTH 9
26 
27 // format of serial packets received from benewake lidar
28 //
29 // Data Bit Definition Description
30 // ------------------------------------------------
31 // byte 0 Frame header 0x59
32 // byte 1 Frame header 0x59
33 // byte 2 DIST_L Distance (in cm) low 8 bits
34 // byte 3 DIST_H Distance (in cm) high 8 bits
35 // byte 4 STRENGTH_L Strength low 8 bits
36 // byte 5 STRENGTH_H Strength high 8 bits
37 // byte 6 (TF02) SIG Reliability in 8 levels, 7 & 8 means reliable
38 // byte 6 (TFmini) Distance Mode 0x02 for short distance (mm), 0x07 for long distance (cm)
39 // byte 7 (TF02 only) TIME Exposure time in two levels 0x03 and 0x06
40 // byte 8 Checksum Checksum byte, sum of bytes 0 to bytes 7
41 
42 /*
43  The constructor also initialises the rangefinder. Note that this
44  constructor is not called until detect() returns true, so we
45  already know that we should setup the rangefinder
46 */
49  uint8_t serial_instance,
50  benewake_model_type model) :
51  AP_RangeFinder_Backend(_state),
52  model_type(model)
53 {
54  uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
55  if (uart != nullptr) {
56  uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance));
57  }
58 }
59 
60 /*
61  detect if a Benewake rangefinder is connected. We'll detect by
62  trying to take a reading on Serial. If we get a result the sensor is
63  there.
64 */
66 {
67  return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
68 }
69 
70 // distance returned in reading_cm, signal_ok is set to true if sensor reports a strong signal
71 bool AP_RangeFinder_Benewake::get_reading(uint16_t &reading_cm, bool &signal_ok)
72 {
73  if (uart == nullptr) {
74  return false;
75  }
76 
77  float sum_cm = 0;
78  uint16_t count = 0;
79  bool dist_reliable = false;
80 
81  // read any available lines from the lidar
82  int16_t nbytes = uart->available();
83  while (nbytes-- > 0) {
84  char c = uart->read();
85  // if buffer is empty and this byte is 0x59, add to buffer
86  if (linebuf_len == 0) {
87  if (c == BENEWAKE_FRAME_HEADER) {
88  linebuf[linebuf_len++] = c;
89  }
90  } else if (linebuf_len == 1) {
91  // if buffer has 1 element and this byte is 0x59, add it to buffer
92  // if not clear the buffer
93  if (c == BENEWAKE_FRAME_HEADER) {
94  linebuf[linebuf_len++] = c;
95  } else {
96  linebuf_len = 0;
97  dist_reliable = false;
98  }
99  } else {
100  // add character to buffer
101  linebuf[linebuf_len++] = c;
102  // if buffer now has 9 items try to decode it
104  // calculate checksum
105  uint16_t checksum = 0;
106  for (uint8_t i=0; i<BENEWAKE_FRAME_LENGTH-1; i++) {
107  checksum += linebuf[i];
108  }
109  // if checksum matches extract contents
110  if ((uint8_t)(checksum & 0xFF) == linebuf[BENEWAKE_FRAME_LENGTH-1]) {
111  // tell caller we are receiving packets
112  signal_ok = true;
113  // calculate distance and add to sum
114  uint16_t dist = ((uint16_t)linebuf[3] << 8) | linebuf[2];
115  if (dist != 0xFFFF) {
116  // TFmini has short distance mode (mm)
117  if ((model_type == BENEWAKE_TFmini)) {
118  if (linebuf[6] == 0x02) {
119  dist *= 0.1f;
120  }
121  // no signal byte from TFmini
122  dist_reliable = true;
123  } else {
124  // TF02 provides signal reliability (good = 7 or 8)
125  dist_reliable = (linebuf[6] >= 7);
126  }
127  if (dist_reliable) {
128  sum_cm += dist;
129  count++;
130  }
131  }
132  }
133  // clear buffer
134  linebuf_len = 0;
135  dist_reliable = false;
136  }
137  }
138  }
139 
140  if (count == 0) {
141  return false;
142  }
143  reading_cm = sum_cm / count;
144  return true;
145 }
146 
147 /*
148  update the state of the sensor
149 */
151 {
152  bool signal_ok;
153  if (get_reading(state.distance_cm, signal_ok)) {
154  // update range_valid state based on distance measured
156  if (signal_ok) {
157  update_status();
158  } else {
159  // if signal is weak set status to out-of-range
161  }
162  } else if (AP_HAL::millis() - last_reading_ms > 200) {
164  }
165 }
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_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
AP_RangeFinder_Benewake(RangeFinder::RangeFinder_State &_state, AP_SerialManager &serial_manager, uint8_t serial_instance, benewake_model_type model)
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
virtual void begin(uint32_t baud)=0
#define BENEWAKE_FRAME_HEADER
benewake_model_type model_type
uint32_t find_baudrate(enum SerialProtocol protocol, uint8_t instance) const
bool get_reading(uint16_t &reading_cm, bool &signal_ok)
uint32_t millis()
Definition: system.cpp:157
#define BENEWAKE_FRAME_LENGTH
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