PX4 Firmware
PX4 Autopilot Software http://px4.io
CM8JL65.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2018-2019 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 #include "CM8JL65.hpp"
35 
36 static constexpr unsigned char crc_msb_vector[] = {
37  0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
38  0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
39  0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
40  0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
41  0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
42  0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
43  0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
44  0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
45  0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
46  0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
47  0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
48  0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
49  0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
50  0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
51  0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
52  0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
53  0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
54  0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
55  0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
56  0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
57  0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
58  0x00, 0xC1, 0x81, 0x40
59 };
60 
61 static constexpr unsigned char crc_lsb_vector[] = {
62  0x00, 0xC0, 0xC1, 0x01, 0xC3, 0x03, 0x02, 0xC2, 0xC6, 0x06, 0x07, 0xC7,
63  0x05, 0xC5, 0xC4, 0x04, 0xCC, 0x0C, 0x0D, 0xCD, 0x0F, 0xCF, 0xCE, 0x0E,
64  0x0A, 0xCA, 0xCB, 0x0B, 0xC9, 0x09, 0x08, 0xC8, 0xD8, 0x18, 0x19, 0xD9,
65  0x1B, 0xDB, 0xDA, 0x1A, 0x1E, 0xDE, 0xDF, 0x1F, 0xDD, 0x1D, 0x1C, 0xDC,
66  0x14, 0xD4, 0xD5, 0x15, 0xD7, 0x17, 0x16, 0xD6, 0xD2, 0x12, 0x13, 0xD3,
67  0x11, 0xD1, 0xD0, 0x10, 0xF0, 0x30, 0x31, 0xF1, 0x33, 0xF3, 0xF2, 0x32,
68  0x36, 0xF6, 0xF7, 0x37, 0xF5, 0x35, 0x34, 0xF4, 0x3C, 0xFC, 0xFD, 0x3D,
69  0xFF, 0x3F, 0x3E, 0xFE, 0xFA, 0x3A, 0x3B, 0xFB, 0x39, 0xF9, 0xF8, 0x38,
70  0x28, 0xE8, 0xE9, 0x29, 0xEB, 0x2B, 0x2A, 0xEA, 0xEE, 0x2E, 0x2F, 0xEF,
71  0x2D, 0xED, 0xEC, 0x2C, 0xE4, 0x24, 0x25, 0xE5, 0x27, 0xE7, 0xE6, 0x26,
72  0x22, 0xE2, 0xE3, 0x23, 0xE1, 0x21, 0x20, 0xE0, 0xA0, 0x60, 0x61, 0xA1,
73  0x63, 0xA3, 0xA2, 0x62, 0x66, 0xA6, 0xA7, 0x67, 0xA5, 0x65, 0x64, 0xA4,
74  0x6C, 0xAC, 0xAD, 0x6D, 0xAF, 0x6F, 0x6E, 0xAE, 0xAA, 0x6A, 0x6B, 0xAB,
75  0x69, 0xA9, 0xA8, 0x68, 0x78, 0xB8, 0xB9, 0x79, 0xBB, 0x7B, 0x7A, 0xBA,
76  0xBE, 0x7E, 0x7F, 0xBF, 0x7D, 0xBD, 0xBC, 0x7C, 0xB4, 0x74, 0x75, 0xB5,
77  0x77, 0xB7, 0xB6, 0x76, 0x72, 0xB2, 0xB3, 0x73, 0xB1, 0x71, 0x70, 0xB0,
78  0x50, 0x90, 0x91, 0x51, 0x93, 0x53, 0x52, 0x92, 0x96, 0x56, 0x57, 0x97,
79  0x55, 0x95, 0x94, 0x54, 0x9C, 0x5C, 0x5D, 0x9D, 0x5F, 0x9F, 0x9E, 0x5E,
80  0x5A, 0x9A, 0x9B, 0x5B, 0x99, 0x59, 0x58, 0x98, 0x88, 0x48, 0x49, 0x89,
81  0x4B, 0x8B, 0x8A, 0x4A, 0x4E, 0x8E, 0x8F, 0x4F, 0x8D, 0x4D, 0x4C, 0x8C,
82  0x44, 0x84, 0x85, 0x45, 0x87, 0x47, 0x46, 0x86, 0x82, 0x42, 0x43, 0x83,
83  0x41, 0x81, 0x80, 0x40
84 };
85 
86 CM8JL65::CM8JL65(const char *port, uint8_t rotation) :
87  ScheduledWorkItem(MODULE_NAME, px4::serial_port_to_wq(port)),
88  _px4_rangefinder(0 /* TODO: device ids */, ORB_PRIO_DEFAULT, rotation)
89 {
90  // Store the port name.
91  strncpy(_port, port, sizeof(_port) - 1);
92 
93  // Enforce null termination.
94  _port[sizeof(_port) - 1] = '\0';
95 
96  // Use conservative distance bounds, to make sure we don't fuse garbage data
97  _px4_rangefinder.set_min_distance(0.2f); // Datasheet: 0.17m
98  _px4_rangefinder.set_max_distance(7.9f); // Datasheet: 8.0m
99  _px4_rangefinder.set_fov(0.0488692f);
100 }
101 
103 {
104  // Ensure we are truly inactive.
105  stop();
106 
109 }
110 
111 uint16_t
112 CM8JL65::crc16_calc(const unsigned char *data_frame, uint8_t crc16_length)
113 {
114  // compute CRC16 IBM 8005
115  unsigned char crc_high_byte = 0xFF;
116  unsigned char crc_low_byte = 0xFF;
117  size_t index = 0;
118 
119  while (crc16_length--) {
120  index = crc_low_byte ^ *(data_frame++);
121  crc_low_byte = (unsigned char)(crc_high_byte ^ crc_msb_vector[index]);
122  crc_high_byte = crc_lsb_vector[index];
123  }
124 
125  uint16_t crc16 = (crc_high_byte << 8 | crc_low_byte);
126  crc16 = (crc16 >> 8) | (crc16 << 8); // Convert endian
127 
128  return crc16;
129 }
130 
131 int
133 {
135 
136  int bytes_processed = 0;
137  int distance_mm = -1;
138  int index = 0;
139 
140  bool crc_valid = false;
141 
142  // Read from the sensor UART buffer.
143  const hrt_abstime timestamp_sample = hrt_absolute_time();
144  int bytes_read = ::read(_file_descriptor, &_linebuf[0], sizeof(_linebuf));
145 
146  if (bytes_read > 0) {
147  index = bytes_read - 6 ;
148 
149  while (index >= 0 && !crc_valid) {
150  if (_linebuf[index] == START_FRAME_DIGIT1) {
151  bytes_processed = index;
152 
153  while (bytes_processed < bytes_read && !crc_valid) {
154  if (data_parser(_linebuf[bytes_processed], _frame_data, _parse_state, _crc16, distance_mm) == PX4_OK) {
155  crc_valid = true;
156  }
157 
158  bytes_processed++;
159  }
160 
162  }
163 
164  index--;
165  }
166 
167  } else {
168  PX4_INFO("read error: %d", bytes_read);
171  return PX4_ERROR;
172  }
173 
174  if (!crc_valid) {
175  return -EAGAIN;
176  }
177 
178  bytes_read = OK;
179 
180  const float current_distance = static_cast<float>(distance_mm) / 1000.0f;
181 
182  _px4_rangefinder.update(timestamp_sample, current_distance);
183 
185 
186  return PX4_OK;
187 }
188 
189 int
190 CM8JL65::data_parser(const uint8_t check_byte, uint8_t parserbuf[PARSER_BUF_LENGTH],
191  PARSE_STATE &state, uint16_t &crc16, int &distance)
192 {
193  switch (state) {
195  if (check_byte == START_FRAME_DIGIT1) {
196  state = PARSE_STATE::DIGIT_1;
197  }
198 
199  break;
200 
202  if (check_byte == START_FRAME_DIGIT1) {
203  state = PARSE_STATE::DIGIT_1;
204 
205  } else if (check_byte == START_FRAME_DIGIT2) {
206  state = PARSE_STATE::DIGIT_2;
207 
208  } else {
210  }
211 
212  break;
213 
215  state = PARSE_STATE::MSB_DATA;
216  parserbuf[DISTANCE_MSB_POS] = check_byte; // MSB Data
217  break;
218 
220  state = PARSE_STATE::LSB_DATA;
221  parserbuf[DISTANCE_LSB_POS] = check_byte; // LSB Data
222 
223  // Calculate CRC.
224  crc16 = crc16_calc(parserbuf, PARSER_BUF_LENGTH);
225  break;
226 
228  if (check_byte == (crc16 >> 8)) {
229  state = PARSE_STATE::CHECKSUM;
230 
231  } else {
233  }
234 
235  break;
236 
238  // Here, reset state to `NOT-STARTED` no matter crc ok or not
240 
241  if (check_byte == (crc16 & 0xFF)) {
242  // printf("Checksum verified \n");
243  distance = (parserbuf[DISTANCE_MSB_POS] << 8) | parserbuf[DISTANCE_LSB_POS];
244  return PX4_OK;
245  }
246 
247  break;
248  }
249 
250  return PX4_ERROR;
251 }
252 
253 int
255 {
256  start();
257 
258  return PX4_OK;
259 }
260 
261 int
262 CM8JL65::open_serial_port(const speed_t speed)
263 {
264  // File descriptor initialized?
265  if (_file_descriptor > 0) {
266  // PX4_INFO("serial port already open");
267  return PX4_OK;
268  }
269 
270  // Configure port flags for read/write, non-controlling, non-blocking.
271  int flags = (O_RDWR | O_NOCTTY | O_NONBLOCK);
272 
273  // Open the serial port.
274  _file_descriptor = ::open(_port, flags);
275 
276  if (_file_descriptor < 0) {
277  PX4_ERR("open failed (%i)", errno);
278  return PX4_ERROR;
279  }
280 
281  termios uart_config = {};
282 
283  // Store the current port configuration. attributes.
284  tcgetattr(_file_descriptor, &uart_config);
285 
286  // Clear ONLCR flag (which appends a CR for every LF).
287  uart_config.c_oflag &= ~ONLCR;
288 
289  // No parity, one stop bit.
290  uart_config.c_cflag &= ~(CSTOPB | PARENB);
291 
292  // Set the input baud rate in the uart_config struct.
293  int termios_state = cfsetispeed(&uart_config, speed);
294 
295  if (termios_state < 0) {
296  PX4_ERR("CFG: %d ISPD", termios_state);
297  ::close(_file_descriptor);
298  return PX4_ERROR;
299  }
300 
301  // Set the output baud rate in the uart_config struct.
302  termios_state = cfsetospeed(&uart_config, speed);
303 
304  if (termios_state < 0) {
305  PX4_ERR("CFG: %d OSPD", termios_state);
306  ::close(_file_descriptor);
307  return PX4_ERROR;
308  }
309 
310  // Apply the modified port attributes.
311  termios_state = tcsetattr(_file_descriptor, TCSANOW, &uart_config);
312 
313  if (termios_state < 0) {
314  PX4_ERR("baud %d ATTR", termios_state);
315  ::close(_file_descriptor);
316  return PX4_ERROR;
317  }
318 
319  PX4_INFO("successfully opened UART port %s", _port);
320  return PX4_OK;
321 }
322 
323 void
325 {
328 
330 }
331 
332 void
334 {
335  // Ensure the serial port is open.
337 
338  // Perform collection.
339  collect();
340 }
341 
342 void
344 {
345  // Schedule the driver at regular intervals.
346  ScheduleOnInterval(CM8JL65_MEASURE_INTERVAL);
347 
348  PX4_INFO("driver started");
349 }
350 
351 void
353 {
354  // Clear the work queue schedule.
355  ScheduleClear();
356 
357  // Ensure the serial port is closed.
358  ::close(_file_descriptor);
359 }
void set_max_distance(const float distance)
static constexpr unsigned char START_FRAME_DIGIT1
Definition: CM8JL65.hpp:61
static constexpr unsigned char crc_msb_vector[]
Definition: CM8JL65.cpp:36
static constexpr unsigned char START_FRAME_DIGIT2
Definition: CM8JL65.hpp:62
static enum @74 state
void set_fov(const float fov)
CM8JL65(const char *port, uint8_t rotation=distance_sensor_s::ROTATION_DOWNWARD_FACING)
Default Constructor.
Definition: CM8JL65.cpp:86
unsigned char _frame_data[PARSER_BUF_LENGTH]
Definition: CM8JL65.hpp:154
int init()
Method : init() This method initializes the general driver for a range finder sensor.
Definition: CM8JL65.cpp:254
static constexpr uint8_t DISTANCE_MSB_POS
Frame format definition 1B 1B 1B 1B 2B | 0xA5 | 0x5A | distance-MSB | distance-LSB | crc-16 |...
Definition: CM8JL65.hpp:71
perf_counter_t _sample_perf
Definition: CM8JL65.hpp:165
PARSE_STATE _parse_state
Definition: CM8JL65.hpp:162
int collect()
Reads data from serial UART and places it into a buffer.
Definition: CM8JL65.cpp:132
int _file_descriptor
Definition: CM8JL65.hpp:156
static constexpr unsigned char crc_lsb_vector[]
Definition: CM8JL65.cpp:61
virtual ~CM8JL65() override
Virtual destructor.
Definition: CM8JL65.cpp:102
static void read(bootloader_app_shared_t *pshared)
PX4Rangefinder _px4_rangefinder
Definition: CM8JL65.hpp:150
uint8_t _linebuf[25]
Definition: CM8JL65.hpp:158
void update(const hrt_abstime timestamp, const float distance, const int8_t quality=-1)
void perf_count(perf_counter_t handle)
Count a performance event.
void perf_free(perf_counter_t handle)
Free a counter.
void stop()
Stops the automatic measurement state machine.
Definition: CM8JL65.cpp:352
char _port[20]
Definition: CM8JL65.hpp:152
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
Definition: integration.cpp:8
void set_min_distance(const float distance)
static constexpr uint8_t PARSER_BUF_LENGTH
Definition: CM8JL65.hpp:73
uint16_t _crc16
Definition: CM8JL65.hpp:160
uint16_t crc16(const uint8_t *data_p, uint32_t length)
Calculate buffer CRC16.
Definition: sbf.cpp:368
void perf_end(perf_counter_t handle)
End a performance event.
perf_counter_t _comms_errors
Definition: CM8JL65.hpp:164
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
void start()
Initialise the automatic measurement state machine and start it.
Definition: CM8JL65.cpp:343
void print_info()
Diagnostics - print some basic information about the driver.
Definition: CM8JL65.cpp:324
int open_serial_port(const speed_t speed=B115200)
Opens and configures the UART serial communications port.
Definition: CM8JL65.cpp:262
void perf_print_counter(perf_counter_t handle)
Print one performance counter to stdout.
Definition: bst.cpp:62
void Run() override
Perform a reading cycle; collect from the previous measurement and start a new one.
Definition: CM8JL65.cpp:333
int data_parser(const uint8_t check_byte, uint8_t parserbuf[PARSER_BUF_LENGTH], PARSE_STATE &state, uint16_t &crc16, int &distance)
Definition: CM8JL65.cpp:190
#define OK
Definition: uavcan_main.cpp:71
uint16_t crc16_calc(const unsigned char *data_frame, uint8_t crc16_length)
Calculates the 16 byte crc value for the data frame.
Definition: CM8JL65.cpp:112
static constexpr uint8_t DISTANCE_LSB_POS
Definition: CM8JL65.hpp:72
void perf_begin(perf_counter_t handle)
Begin a performance event.
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).
static constexpr uint32_t CM8JL65_MEASURE_INTERVAL
Definition: CM8JL65.hpp:58