APM:Libraries
AP_RangeFinder_LeddarOne.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 
20 extern const AP_HAL::HAL& hal;
21 
22 /*
23  The constructor also initialises the rangefinder. Note that this
24  constructor is not called until detect() returns true, so we
25  already know that we should setup the rangefinder
26 */
29  uint8_t serial_instance) :
31 {
32  uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
33  if (uart != nullptr) {
34  uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance));
35  }
36 }
37 
38 /*
39  detect if a LeddarOne rangefinder is connected. We'll detect by
40  trying to take a reading on Serial. If we get a result the sensor is
41  there.
42 */
44 {
45  return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
46 }
47 
48 // read - return last value measured by sensor
49 bool AP_RangeFinder_LeddarOne::get_reading(uint16_t &reading_cm)
50 {
51  uint8_t number_detections;
52  LeddarOne_Status leddarone_status;
53 
54  if (uart == nullptr) {
55  return false;
56  }
57 
58  switch (modbus_status) {
60  uint8_t index = 0;
61  // clear read buffer
62  uint32_t nbytes = uart->available();
63  while (nbytes-- > 0) {
64  uart->read();
65  if (++index > LEDDARONE_SERIAL_PORT_MAX) {
66  // LEDDARONE_STATE_ERR_SERIAL_PORT
67  return false;
68  }
69  }
70  // clear buffer and buffer_len
71  memset(read_buffer, 0, sizeof(read_buffer));
72  read_len = 0;
74  }
75 
76  // fall through to next state LEDDARONE_MODBUS_STATE_PRE_SEND_REQUEST
77  // immediately
79 
81  // send a request message for Modbus function 4
86 
88  if (uart->available()) {
89  // change mod_bus status to read available buffer
92  } else {
94  // reset mod_bus status to read new buffer
95  // if read_len is zero, send request without initialize
97  }
98  }
99  break;
100 
102  // parse a response message, set number_detections, detections and sum_distance
103  leddarone_status = parse_response(number_detections);
104 
105  if (leddarone_status == LEDDARONE_STATE_OK) {
106  reading_cm = sum_distance / number_detections;
107 
108  // reset mod_bus status to read new buffer
110 
111  return true;
112  }
113  // if status is not reading buffer, reset mod_bus status to read new buffer
114  else if (leddarone_status != LEDDARONE_STATE_READING_BUFFER || AP_HAL::millis() - last_available_ms > 200) {
115  // if read_len is zero, send request without initialize
117  }
118  break;
119  }
120 
121  return false;
122 }
123 
124 /*
125  update the state of the sensor
126 */
128 {
130  // update range_valid state based on distance measured
132  update_status();
133  } else if (AP_HAL::millis() - last_reading_ms > 200) {
135  }
136 }
137 
138 /*
139  CRC16
140  CRC-16-IBM(x16+x15+x2+1)
141 */
142 bool AP_RangeFinder_LeddarOne::CRC16(uint8_t *aBuffer, uint8_t aLength, bool aCheck)
143 {
144  uint16_t crc = 0xFFFF;
145 
146  for (uint32_t i=0; i<aLength; i++) {
147  crc ^= aBuffer[i];
148  for (uint32_t j=0; j<8; j++) {
149  if (crc & 1) {
150  crc = (crc >> 1) ^ 0xA001;
151  } else {
152  crc >>= 1;
153  }
154  }
155  }
156 
157  uint8_t lCRCLo = LOWBYTE(crc);
158  uint8_t lCRCHi = HIGHBYTE(crc);
159 
160  if (aCheck) {
161  return (aBuffer[aLength] == lCRCLo) && (aBuffer[aLength+1] == lCRCHi);
162  } else {
163  aBuffer[aLength] = lCRCLo;
164  aBuffer[aLength+1] = lCRCHi;
165  return true;
166  }
167 }
168 
169  /*
170  parse a response message from Modbus
171  -----------------------------------------------
172  [ read buffer packet ]
173  -----------------------------------------------
174  0: slave address (LEDDARONE_DEFAULT_ADDRESS)
175  1: functions code
176  2: ?
177 3-4-5-6: timestamp
178  7-8: internal temperature
179  9: ?
180  10: number of detections
181  11-12: first distance
182  13-14: first amplitude
183  15-16: second distance
184  17-18: second amplitude
185  19-20: third distances
186  21-22: third amplitude
187  23: CRC Low
188  24: CRC High
189  -----------------------------------------------
190  */
192 {
193  uint8_t index;
194  uint8_t index_offset = LEDDARONE_DETECTION_DATA_INDEX_OFFSET;
195 
196  // read serial
197  uint32_t nbytes = uart->available();
198 
199  if (nbytes != 0) {
200  for (index=read_len; index<nbytes+read_len; index++) {
201  if (index >= LEDDARONE_READ_BUFFER_SIZE) {
203  }
204  read_buffer[index] = uart->read();
205  }
206 
207  read_len += nbytes;
208 
209  if (read_len < LEDDARONE_READ_BUFFER_SIZE) {
211  }
212  }
213 
214  // lead_len is not 25 byte or function code is not 0x04
217  }
218 
219  // CRC16
220  if (!CRC16(read_buffer, read_len-2, true)) {
222  }
223 
224  // number of detections (index:10)
226 
227  // if the number of detection is over or zero , it is false
228  if (number_detections > LEDDARONE_DETECTIONS_MAX || number_detections == 0) {
230  }
231 
232  memset(detections, 0, sizeof(detections));
233  sum_distance = 0;
234  for (index=0; index<number_detections; index++) {
235  // construct data word from two bytes and convert mm to cm
236  detections[index] = (static_cast<uint16_t>(read_buffer[index_offset])*256 + read_buffer[index_offset+1]) / 10;
237  sum_distance += detections[index];
238 
239  // add index offset (4) to read next detection data
240  index_offset += LEDDARONE_DETECTION_DATA_OFFSET;
241  }
242 
243  return LEDDARONE_STATE_OK;
244 }
bool get_reading(uint16_t &reading_cm)
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
#define LEDDARONE_READ_BUFFER_SIZE
#define FALLTHROUGH
Definition: AP_Common.h:50
#define LEDDARONE_DETECTION_DATA_INDEX_OFFSET
virtual void begin(uint32_t baud)=0
AP_RangeFinder_LeddarOne(RangeFinder::RangeFinder_State &_state, AP_SerialManager &serial_manager, uint8_t serial_instance)
#define LEDDARONE_DETECTION_DATA_OFFSET
#define HIGHBYTE(i)
Definition: AP_Common.h:72
uint16_t detections[LEDDARONE_DETECTIONS_MAX]
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 find_baudrate(enum SerialProtocol protocol, uint8_t instance) const
#define LEDDARONE_DETECTIONS_MAX
LeddarOne_ModbusStatus modbus_status
virtual size_t write(uint8_t)=0
uint32_t millis()
Definition: system.cpp:157
LeddarOne_Status parse_response(uint8_t &number_detections)
#define LEDDARONE_SERIAL_PORT_MAX
virtual int16_t read()=0
#define LOWBYTE(i)
Definition: AP_Common.h:71
virtual uint32_t available()=0
#define LEDDARONE_MODOBUS_FUNCTION_CODE
#define LEDDARONE_DETECTION_DATA_NUMBER_INDEX
void set_status(RangeFinder::RangeFinder_Status status)
uint8_t read_buffer[LEDDARONE_READ_BUFFER_SIZE]
RangeFinder::RangeFinder_State & state
bool CRC16(uint8_t *aBuffer, uint8_t aLength, bool aCheck)
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const