PX4 Firmware
PX4 Autopilot Software http://px4.io
telemetry.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 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 "telemetry.h"
35 
36 #include <px4_platform_common/log.h>
37 
38 #include <unistd.h>
39 #include <fcntl.h>
40 #include <termios.h>
41 #include <errno.h>
42 
43 using namespace time_literals;
44 
45 #define DSHOT_TELEMETRY_UART_BAUDRATE 115200
46 
48 {
49  deinit();
50 }
51 
52 int DShotTelemetry::init(const char *uart_device)
53 {
54  deinit();
55  _uart_fd = ::open(uart_device, O_RDONLY | O_NOCTTY);
56 
57  if (_uart_fd < 0) {
58  PX4_ERR("failed to open serial port: %s err: %d", uart_device, errno);
59  return -errno;
60  }
61 
62  _num_timeouts = 0;
63  _num_successful_responses = 0;
64  _current_motor_index_request = -1;
66 }
67 
69 {
70  if (_uart_fd >= 0) {
71  close(_uart_fd);
72  _uart_fd = -1;
73  }
74 }
75 
77 {
78  if (expectingData()) {
79  // Error: cannot override while we already expect data
80  return -EBUSY;
81  }
82 
83  _current_motor_index_request = buffer.motor_index;
84  _current_request_start = hrt_absolute_time();
85  _redirect_output = &buffer;
86  _redirect_output->buf_pos = 0;
87  return 0;
88 }
89 
91 {
92  if (_uart_fd < 0) {
93  return -1;
94  }
95 
96  if (_current_motor_index_request == -1) {
97  // nothing in progress, start a request
98  _current_motor_index_request = 0;
99  _current_request_start = 0;
100  _frame_position = 0;
101  return -1;
102  }
103 
104  // read from the uart. This must be non-blocking, so check first if there is data available
105  int bytes_available = 0;
106  int ret = ioctl(_uart_fd, FIONREAD, (unsigned long)&bytes_available);
107 
108  if (ret != 0 || bytes_available <= 0) {
109  // no data available. Check for a timeout
110  const hrt_abstime now = hrt_absolute_time();
111 
112  if (_current_request_start > 0 && now - _current_request_start > 30_ms) {
113  if (_redirect_output) {
114  // clear and go back to internal buffer
115  _redirect_output = nullptr;
116  _current_motor_index_request = -1;
117 
118  } else {
119  PX4_DEBUG("ESC telemetry timeout for motor %i (frame pos=%i)", _current_motor_index_request, _frame_position);
120  ++_num_timeouts;
121  }
122 
123  requestNextMotor();
124  return -2;
125  }
126 
127  return -1;
128  }
129 
130  const int buf_length = ESC_FRAME_SIZE;
131  uint8_t buf[buf_length];
132 
133  int num_read = read(_uart_fd, buf, buf_length);
134  ret = -1;
135 
136  for (int i = 0; i < num_read && ret == -1; ++i) {
137  if (_redirect_output) {
138  _redirect_output->buffer[_redirect_output->buf_pos++] = buf[i];
139 
140  if (_redirect_output->buf_pos == sizeof(_redirect_output->buffer)) {
141  // buffer full: return & go back to internal buffer
142  _redirect_output = nullptr;
143  ret = _current_motor_index_request;
144  _current_motor_index_request = -1;
145  requestNextMotor();
146  }
147 
148  } else {
149  bool successful_decoding;
150 
151  if (decodeByte(buf[i], successful_decoding)) {
152  if (successful_decoding) {
153  ret = _current_motor_index_request;
154  }
155 
156  requestNextMotor();
157  }
158  }
159  }
160 
161  return ret;
162 }
163 
164 bool DShotTelemetry::decodeByte(uint8_t byte, bool &successful_decoding)
165 {
166  _frame_buffer[_frame_position++] = byte;
167  successful_decoding = false;
168 
169  if (_frame_position == ESC_FRAME_SIZE) {
170  PX4_DEBUG("got ESC frame for motor %i", _current_motor_index_request);
171  uint8_t checksum = crc8(_frame_buffer, ESC_FRAME_SIZE - 1);
172  uint8_t checksum_data = _frame_buffer[ESC_FRAME_SIZE - 1];
173 
174  if (checksum == checksum_data) {
175  _latest_data.time = hrt_absolute_time();
176  _latest_data.temperature = _frame_buffer[0];
177  _latest_data.voltage = (_frame_buffer[1] << 8) | _frame_buffer[2];
178  _latest_data.current = (_frame_buffer[3] << 8) | _frame_buffer[4];
179  _latest_data.consumption = (_frame_buffer[5]) << 8 | _frame_buffer[6];
180  _latest_data.erpm = (_frame_buffer[7] << 8) | _frame_buffer[8];
181  PX4_DEBUG("Motor %i: temp=%i, V=%i, cur=%i, consumpt=%i, rpm=%i", _current_motor_index_request,
182  _latest_data.temperature, _latest_data.voltage, _latest_data.current, _latest_data.consumption,
183  _latest_data.erpm);
184  ++_num_successful_responses;
185  successful_decoding = true;
186  }
187 
188  return true;
189  }
190 
191  return false;
192 }
193 
195 {
196  PX4_INFO("Number of successful ESC frames: %i", _num_successful_responses);
197  PX4_INFO("Number of timeouts: %i", _num_timeouts);
198 }
199 
200 uint8_t DShotTelemetry::updateCrc8(uint8_t crc, uint8_t crc_seed)
201 {
202  uint8_t crc_u = crc ^ crc_seed;
203 
204  for (int i = 0; i < 8; ++i) {
205  crc_u = (crc_u & 0x80) ? 0x7 ^ (crc_u << 1) : (crc_u << 1);
206  }
207 
208  return crc_u;
209 }
210 
211 
212 uint8_t DShotTelemetry::crc8(const uint8_t *buf, uint8_t len)
213 {
214  uint8_t crc = 0;
215 
216  for (int i = 0; i < len; ++i) {
217  crc = updateCrc8(buf[i], crc);
218  }
219 
220  return crc;
221 }
222 
223 
225 {
226  _current_motor_index_request = (_current_motor_index_request + 1) % _num_motors;
227  _current_request_start = 0;
228  _frame_position = 0;
229 }
230 
232 {
233  if (_current_request_start != 0) {
234  // already in progress, do not send another request
235  return -1;
236  }
237 
238  _current_request_start = hrt_absolute_time();
239  return _current_motor_index_request;
240 }
241 
243 {
244  static constexpr int version_position = 12;
245  const uint8_t *data = buffer.buffer;
246 
247  if (buffer.buf_pos < version_position) {
248  PX4_ERR("Not enough data received");
249  return;
250  }
251 
252  enum class ESCVersionInfo {
253  BLHELI32,
254  KissV1,
255  KissV2,
256  };
257  ESCVersionInfo version;
258  int packet_length;
259 
260  if (data[version_position] == 254) {
261  version = ESCVersionInfo::BLHELI32;
262  packet_length = esc_info_size_blheli32;
263 
264  } else if (data[version_position] == 255) {
265  version = ESCVersionInfo::KissV2;
266  packet_length = esc_info_size_kiss_v2;
267 
268  } else {
269  version = ESCVersionInfo::KissV1;
270  packet_length = esc_info_size_kiss_v1;
271  }
272 
273  if (buffer.buf_pos != packet_length) {
274  PX4_ERR("Packet length mismatch (%i != %i)", buffer.buf_pos, packet_length);
275  return;
276  }
277 
278  if (DShotTelemetry::crc8(data, packet_length - 1) != data[packet_length - 1]) {
279  PX4_ERR("Checksum mismatch");
280  return;
281  }
282 
283  uint8_t esc_firmware_version = 0;
284  uint8_t esc_firmware_subversion = 0;
285  uint8_t esc_type = 0;
286 
287  switch (version) {
288  case ESCVersionInfo::KissV1:
289  esc_firmware_version = data[12];
290  esc_firmware_subversion = (data[13] & 0x1f) + 97;
291  esc_type = (data[13] & 0xe0) >> 5;
292  break;
293 
294  case ESCVersionInfo::KissV2:
295  case ESCVersionInfo::BLHELI32:
296  esc_firmware_version = data[13];
297  esc_firmware_subversion = data[14];
298  esc_type = data[15];
299  break;
300  }
301 
302  const char *esc_type_str = "";
303 
304  switch (version) {
305  case ESCVersionInfo::KissV1:
306  case ESCVersionInfo::KissV2:
307  switch (esc_type) {
308  case 1: esc_type_str = "KISS8A";
309  break;
310 
311  case 2: esc_type_str = "KISS16A";
312  break;
313 
314  case 3: esc_type_str = "KISS24A";
315  break;
316 
317  case 5: esc_type_str = "KISS Ultralite";
318  break;
319 
320  default: esc_type_str = "KISS (unknown)";
321  break;
322  }
323 
324  break;
325 
326  case ESCVersionInfo::BLHELI32: {
327  char *esc_type_mutable = (char *)(data + 31);
328  esc_type_mutable[32] = 0;
329  esc_type_str = esc_type_mutable;
330  }
331  break;
332  }
333 
334  PX4_INFO("ESC Type: %s", esc_type_str);
335 
336  PX4_INFO("MCU Serial Number: %02x%02x%02x-%02x%02x%02x-%02x%02x%02x-%02x%02x%02x",
337  data[0], data[1], data[2], data[3], data[4], data[5], data[6], data[7], data[8],
338  data[9], data[10], data[11]);
339 
340  switch (version) {
341  case ESCVersionInfo::KissV1:
342  case ESCVersionInfo::KissV2:
343  PX4_INFO("Firmware version: %d.%d%c", esc_firmware_version / 100, esc_firmware_version % 100,
344  (char)esc_firmware_subversion);
345  break;
346 
347  case ESCVersionInfo::BLHELI32:
348  PX4_INFO("Firmware version: %d.%d", esc_firmware_version, esc_firmware_subversion);
349  break;
350  }
351 
352  if (version == ESCVersionInfo::KissV2 || version == ESCVersionInfo::BLHELI32) {
353  PX4_INFO("Rotation Direction: %s", data[16] ? "reversed" : "normal");
354  PX4_INFO("3D Mode: %s", data[17] ? "on" : "off");
355  }
356 
357  if (version == ESCVersionInfo::BLHELI32) {
358  uint8_t setting = data[18];
359 
360  switch (setting) {
361  case 0:
362  PX4_INFO("Low voltage Limit: off");
363  break;
364 
365  case 255:
366  PX4_INFO("Low voltage Limit: unsupported");
367  break;
368 
369  default:
370  PX4_INFO("Low voltage Limit: %d.%01d V", setting / 10, setting % 10);
371  break;
372  }
373 
374  setting = data[19];
375 
376  switch (setting) {
377  case 0:
378  PX4_INFO("Current Limit: off");
379  break;
380 
381  case 255:
382  PX4_INFO("Current Limit: unsupported");
383  break;
384 
385  default:
386  PX4_INFO("Current Limit: %d A", setting);
387  break;
388  }
389 
390  for (int i = 0; i < 4; ++i) {
391  setting = data[i + 20];
392  PX4_INFO("LED %d: %s", i, setting ? (setting == 255 ? "unsupported" : "on") : "off");
393  }
394  }
395 
396 
397 }
398 
399 int DShotTelemetry::setBaudrate(unsigned baud)
400 {
401  int speed;
402 
403  switch (baud) {
404  case 9600: speed = B9600; break;
405 
406  case 19200: speed = B19200; break;
407 
408  case 38400: speed = B38400; break;
409 
410  case 57600: speed = B57600; break;
411 
412  case 115200: speed = B115200; break;
413 
414  case 230400: speed = B230400; break;
415 
416  default:
417  return -EINVAL;
418  }
419 
420  struct termios uart_config;
421 
422  int termios_state;
423 
424  /* fill the struct for the new configuration */
425  tcgetattr(_uart_fd, &uart_config);
426 
427  //
428  // Input flags - Turn off input processing
429  //
430  // convert break to null byte, no CR to NL translation,
431  // no NL to CR translation, don't mark parity errors or breaks
432  // no input parity check, don't strip high bit off,
433  // no XON/XOFF software flow control
434  //
435  uart_config.c_iflag &= ~(IGNBRK | BRKINT | ICRNL |
436  INLCR | PARMRK | INPCK | ISTRIP | IXON);
437  //
438  // Output flags - Turn off output processing
439  //
440  // no CR to NL translation, no NL to CR-NL translation,
441  // no NL to CR translation, no column 0 CR suppression,
442  // no Ctrl-D suppression, no fill characters, no case mapping,
443  // no local output processing
444  //
445  // config.c_oflag &= ~(OCRNL | ONLCR | ONLRET |
446  // ONOCR | ONOEOT| OFILL | OLCUC | OPOST);
447  uart_config.c_oflag = 0;
448 
449  //
450  // No line processing
451  //
452  // echo off, echo newline off, canonical mode off,
453  // extended input processing off, signal chars off
454  //
455  uart_config.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG);
456 
457  /* no parity, one stop bit, disable flow control */
458  uart_config.c_cflag &= ~(CSTOPB | PARENB | CRTSCTS);
459 
460  /* set baud rate */
461  if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) {
462  return -errno;
463  }
464 
465  if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) {
466  return -errno;
467  }
468 
469  if ((termios_state = tcsetattr(_uart_fd, TCSANOW, &uart_config)) < 0) {
470  return -errno;
471  }
472 
473  return 0;
474 }
475 
static uint8_t crc8(const uint8_t *buf, uint8_t len)
Definition: telemetry.cpp:212
static uint8_t updateCrc8(uint8_t crc, uint8_t crc_seed)
Definition: telemetry.cpp:200
bool decodeByte(uint8_t byte, bool &successful_decoding)
Decode a single byte from an ESC feedback frame.
Definition: telemetry.cpp:164
int getRequestMotorIndex()
Get the motor index for which telemetry should be requested.
Definition: telemetry.cpp:231
void printStatus() const
Definition: telemetry.cpp:194
#define DSHOT_TELEMETRY_UART_BAUDRATE
Definition: telemetry.cpp:45
uint8_t buffer[max_esc_info_size]
Definition: telemetry.h:56
static void read(bootloader_app_shared_t *pshared)
set Baudrate data1: ignored data2: baudrate return: 0 on success
int update()
Read telemetry from the UART (non-blocking) and handle timeouts.
Definition: telemetry.cpp:90
uint8_t * data
Definition: dataman.cpp:149
static uint8_t crc8(uint8_t *p, uint8_t len)
Definition: teraranger.cpp:180
int setBaudrate(unsigned baud)
set the Baudrate
Definition: telemetry.cpp:399
void requestNextMotor()
Definition: telemetry.cpp:224
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
int redirectOutput(OutputBuffer &buffer)
Redirect everything that is read into a different buffer.
Definition: telemetry.cpp:76
int init(const char *uart_device)
Definition: telemetry.cpp:52
static void decodeAndPrintEscInfoPacket(const OutputBuffer &buffer)
Definition: telemetry.cpp:242
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).