36 #include <px4_platform_common/log.h> 45 #define DSHOT_TELEMETRY_UART_BAUDRATE 115200 55 _uart_fd = ::open(uart_device, O_RDONLY | O_NOCTTY);
58 PX4_ERR(
"failed to open serial port: %s err: %d", uart_device, errno);
63 _num_successful_responses = 0;
64 _current_motor_index_request = -1;
78 if (expectingData()) {
85 _redirect_output = &buffer;
96 if (_current_motor_index_request == -1) {
98 _current_motor_index_request = 0;
99 _current_request_start = 0;
105 int bytes_available = 0;
106 int ret = ioctl(_uart_fd, FIONREAD, (
unsigned long)&bytes_available);
108 if (ret != 0 || bytes_available <= 0) {
112 if (_current_request_start > 0 && now - _current_request_start > 30_ms) {
113 if (_redirect_output) {
115 _redirect_output =
nullptr;
116 _current_motor_index_request = -1;
119 PX4_DEBUG(
"ESC telemetry timeout for motor %i (frame pos=%i)", _current_motor_index_request, _frame_position);
130 const int buf_length = ESC_FRAME_SIZE;
131 uint8_t buf[buf_length];
133 int num_read =
read(_uart_fd, buf, buf_length);
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];
140 if (_redirect_output->buf_pos ==
sizeof(_redirect_output->buffer)) {
142 _redirect_output =
nullptr;
143 ret = _current_motor_index_request;
144 _current_motor_index_request = -1;
149 bool successful_decoding;
151 if (decodeByte(buf[i], successful_decoding)) {
152 if (successful_decoding) {
153 ret = _current_motor_index_request;
166 _frame_buffer[_frame_position++] = byte;
167 successful_decoding =
false;
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];
174 if (checksum == checksum_data) {
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,
184 ++_num_successful_responses;
185 successful_decoding =
true;
196 PX4_INFO(
"Number of successful ESC frames: %i", _num_successful_responses);
197 PX4_INFO(
"Number of timeouts: %i", _num_timeouts);
202 uint8_t crc_u = crc ^ crc_seed;
204 for (
int i = 0; i < 8; ++i) {
205 crc_u = (crc_u & 0x80) ? 0x7 ^ (crc_u << 1) : (crc_u << 1);
216 for (
int i = 0; i < len; ++i) {
217 crc = updateCrc8(buf[i], crc);
226 _current_motor_index_request = (_current_motor_index_request + 1) % _num_motors;
227 _current_request_start = 0;
233 if (_current_request_start != 0) {
239 return _current_motor_index_request;
244 static constexpr
int version_position = 12;
247 if (buffer.
buf_pos < version_position) {
248 PX4_ERR(
"Not enough data received");
252 enum class ESCVersionInfo {
257 ESCVersionInfo version;
260 if (data[version_position] == 254) {
261 version = ESCVersionInfo::BLHELI32;
262 packet_length = esc_info_size_blheli32;
264 }
else if (data[version_position] == 255) {
265 version = ESCVersionInfo::KissV2;
266 packet_length = esc_info_size_kiss_v2;
269 version = ESCVersionInfo::KissV1;
270 packet_length = esc_info_size_kiss_v1;
273 if (buffer.
buf_pos != packet_length) {
274 PX4_ERR(
"Packet length mismatch (%i != %i)", buffer.
buf_pos, packet_length);
279 PX4_ERR(
"Checksum mismatch");
283 uint8_t esc_firmware_version = 0;
284 uint8_t esc_firmware_subversion = 0;
285 uint8_t esc_type = 0;
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;
294 case ESCVersionInfo::KissV2:
295 case ESCVersionInfo::BLHELI32:
296 esc_firmware_version = data[13];
297 esc_firmware_subversion = data[14];
302 const char *esc_type_str =
"";
305 case ESCVersionInfo::KissV1:
306 case ESCVersionInfo::KissV2:
308 case 1: esc_type_str =
"KISS8A";
311 case 2: esc_type_str =
"KISS16A";
314 case 3: esc_type_str =
"KISS24A";
317 case 5: esc_type_str =
"KISS Ultralite";
320 default: esc_type_str =
"KISS (unknown)";
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;
334 PX4_INFO(
"ESC Type: %s", esc_type_str);
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]);
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);
347 case ESCVersionInfo::BLHELI32:
348 PX4_INFO(
"Firmware version: %d.%d", esc_firmware_version, esc_firmware_subversion);
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");
357 if (version == ESCVersionInfo::BLHELI32) {
358 uint8_t setting = data[18];
362 PX4_INFO(
"Low voltage Limit: off");
366 PX4_INFO(
"Low voltage Limit: unsupported");
370 PX4_INFO(
"Low voltage Limit: %d.%01d V", setting / 10, setting % 10);
378 PX4_INFO(
"Current Limit: off");
382 PX4_INFO(
"Current Limit: unsupported");
386 PX4_INFO(
"Current Limit: %d A", setting);
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");
404 case 9600: speed = B9600;
break;
406 case 19200: speed = B19200;
break;
408 case 38400: speed = B38400;
break;
410 case 57600: speed = B57600;
break;
412 case 115200: speed = B115200;
break;
414 case 230400: speed = B230400;
break;
420 struct termios uart_config;
425 tcgetattr(_uart_fd, &uart_config);
435 uart_config.c_iflag &= ~(IGNBRK | BRKINT | ICRNL |
436 INLCR | PARMRK | INPCK | ISTRIP | IXON);
447 uart_config.c_oflag = 0;
455 uart_config.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG);
458 uart_config.c_cflag &= ~(CSTOPB | PARENB | CRTSCTS);
461 if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) {
465 if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) {
469 if ((termios_state = tcsetattr(_uart_fd, TCSANOW, &uart_config)) < 0) {
static uint8_t crc8(const uint8_t *buf, uint8_t len)
static uint8_t updateCrc8(uint8_t crc, uint8_t crc_seed)
bool decodeByte(uint8_t byte, bool &successful_decoding)
Decode a single byte from an ESC feedback frame.
int getRequestMotorIndex()
Get the motor index for which telemetry should be requested.
#define DSHOT_TELEMETRY_UART_BAUDRATE
uint8_t buffer[max_esc_info_size]
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.
static uint8_t crc8(uint8_t *p, uint8_t len)
int setBaudrate(unsigned baud)
set the Baudrate
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
int redirectOutput(OutputBuffer &buffer)
Redirect everything that is read into a different buffer.
int init(const char *uart_device)
static void decodeAndPrintEscInfoPacket(const OutputBuffer &buffer)
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).