PX4 Firmware
PX4 Autopilot Software http://px4.io
DShotTelemetry Class Reference

#include <telemetry.h>

Collaboration diagram for DShotTelemetry:

Classes

struct  EscData
 
struct  OutputBuffer
 

Public Member Functions

 ~DShotTelemetry ()
 
int init (const char *uart_device)
 
void deinit ()
 
void setNumMotors (int num_motors)
 
int numMotors () const
 
int update ()
 Read telemetry from the UART (non-blocking) and handle timeouts. More...
 
int redirectOutput (OutputBuffer &buffer)
 Redirect everything that is read into a different buffer. More...
 
bool redirectActive () const
 
int getRequestMotorIndex ()
 Get the motor index for which telemetry should be requested. More...
 
const EscDatalatestESCData () const
 
bool expectingData () const
 Check whether we are currently expecting to read new data from an ESC. More...
 
void printStatus () const
 

Static Public Member Functions

static void decodeAndPrintEscInfoPacket (const OutputBuffer &buffer)
 

Static Public Attributes

static constexpr int esc_info_size_blheli32 = 64
 
static constexpr int esc_info_size_kiss_v1 = 15
 
static constexpr int esc_info_size_kiss_v2 = 21
 
static constexpr int max_esc_info_size = esc_info_size_blheli32
 

Private Member Functions

int setBaudrate (unsigned baud)
 set the Baudrate More...
 
void requestNextMotor ()
 
bool decodeByte (uint8_t byte, bool &successful_decoding)
 Decode a single byte from an ESC feedback frame. More...
 

Static Private Member Functions

static uint8_t updateCrc8 (uint8_t crc, uint8_t crc_seed)
 
static uint8_t crc8 (const uint8_t *buf, uint8_t len)
 

Private Attributes

int _uart_fd {-1}
 
int _num_motors {0}
 
uint8_t _frame_buffer [ESC_FRAME_SIZE]
 
int _frame_position {0}
 
EscData _latest_data
 
int _current_motor_index_request {-1}
 
hrt_abstime _current_request_start {0}
 
OutputBuffer_redirect_output {nullptr}
 if set, all read bytes are stored here instead of the internal buffer More...
 
int _num_timeouts {0}
 
int _num_successful_responses {0}
 

Static Private Attributes

static constexpr int ESC_FRAME_SIZE = 10
 

Detailed Description

Definition at line 38 of file telemetry.h.

Constructor & Destructor Documentation

◆ ~DShotTelemetry()

DShotTelemetry::~DShotTelemetry ( )

Definition at line 47 of file telemetry.cpp.

Member Function Documentation

◆ crc8()

uint8_t DShotTelemetry::crc8 ( const uint8_t *  buf,
uint8_t  len 
)
staticprivate

Definition at line 212 of file telemetry.cpp.

Referenced by decodeAndPrintEscInfoPacket().

Here is the caller graph for this function:

◆ decodeAndPrintEscInfoPacket()

void DShotTelemetry::decodeAndPrintEscInfoPacket ( const OutputBuffer buffer)
static

Definition at line 242 of file telemetry.cpp.

References DShotTelemetry::OutputBuffer::buf_pos, DShotTelemetry::OutputBuffer::buffer, crc8(), and data.

Referenced by expectingData(), and DShotOutput::retrieveAndPrintESCInfoThreadSafe().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ decodeByte()

bool DShotTelemetry::decodeByte ( uint8_t  byte,
bool &  successful_decoding 
)
private

Decode a single byte from an ESC feedback frame.

Parameters
byte
successful_decodingset to true if checksum matches
Returns
true if received the expected amount of bytes and the next motor can be requested

Definition at line 164 of file telemetry.cpp.

References crc8(), and hrt_absolute_time().

Here is the call graph for this function:

◆ deinit()

void DShotTelemetry::deinit ( )

Definition at line 68 of file telemetry.cpp.

◆ expectingData()

bool DShotTelemetry::expectingData ( ) const
inline

Check whether we are currently expecting to read new data from an ESC.

Definition at line 99 of file telemetry.h.

References _current_request_start, decodeAndPrintEscInfoPacket(), and printStatus().

Referenced by DShotOutput::updateOutputs().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getRequestMotorIndex()

int DShotTelemetry::getRequestMotorIndex ( )

Get the motor index for which telemetry should be requested.

Returns
-1 if no request should be made, motor index otherwise

Definition at line 231 of file telemetry.cpp.

References hrt_absolute_time().

Referenced by redirectActive(), and DShotOutput::updateOutputs().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init()

int DShotTelemetry::init ( const char *  uart_device)

Definition at line 52 of file telemetry.cpp.

References DSHOT_TELEMETRY_UART_BAUDRATE, and setBaudrate.

Referenced by DShotOutput::initTelemetry().

Here is the caller graph for this function:

◆ latestESCData()

const EscData& DShotTelemetry::latestESCData ( ) const
inline

Definition at line 94 of file telemetry.h.

References _latest_data.

Referenced by DShotOutput::Run().

Here is the caller graph for this function:

◆ numMotors()

int DShotTelemetry::numMotors ( ) const
inline

Definition at line 68 of file telemetry.h.

References _num_motors, redirectOutput(), and update().

Referenced by DShotOutput::handleNewTelemetryData().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ printStatus()

void DShotTelemetry::printStatus ( ) const

Definition at line 194 of file telemetry.cpp.

Referenced by expectingData(), and DShotOutput::print_status().

Here is the caller graph for this function:

◆ redirectActive()

bool DShotTelemetry::redirectActive ( ) const
inline

Definition at line 86 of file telemetry.h.

References _redirect_output, and getRequestMotorIndex().

Here is the call graph for this function:

◆ redirectOutput()

int DShotTelemetry::redirectOutput ( OutputBuffer buffer)

Redirect everything that is read into a different buffer.

Future calls to will write to that instead of an internal buffer, until returns a value different from -1. No decoding is done. The caller must ensure the buffer exists until that point.

Parameters
buffer
Returns
0 on success <0 on error

Definition at line 76 of file telemetry.cpp.

References DShotTelemetry::OutputBuffer::buf_pos, hrt_absolute_time(), and DShotTelemetry::OutputBuffer::motor_index.

Referenced by numMotors(), and DShotOutput::requestESCInfo().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ requestNextMotor()

void DShotTelemetry::requestNextMotor ( )
private

Definition at line 224 of file telemetry.cpp.

◆ setBaudrate()

int DShotTelemetry::setBaudrate ( unsigned  baud)
private

set the Baudrate

Parameters
baud
Returns
0 on success, <0 on error

Definition at line 399 of file telemetry.cpp.

◆ setNumMotors()

void DShotTelemetry::setNumMotors ( int  num_motors)
inline

Definition at line 67 of file telemetry.h.

References _num_motors.

Referenced by DShotOutput::updateTelemetryNumMotors().

Here is the caller graph for this function:

◆ update()

int DShotTelemetry::update ( )

Read telemetry from the UART (non-blocking) and handle timeouts.

Returns
-1 if no update, -2 timeout, >= 0 for the motor index. Use () to get the data.

Definition at line 90 of file telemetry.cpp.

References hrt_absolute_time(), hrt_abstime, and read().

Referenced by numMotors(), and DShotOutput::Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ updateCrc8()

uint8_t DShotTelemetry::updateCrc8 ( uint8_t  crc,
uint8_t  crc_seed 
)
inlinestaticprivate

Definition at line 200 of file telemetry.cpp.

Member Data Documentation

◆ _current_motor_index_request

int DShotTelemetry::_current_motor_index_request {-1}
private

Definition at line 135 of file telemetry.h.

◆ _current_request_start

hrt_abstime DShotTelemetry::_current_request_start {0}
private

Definition at line 136 of file telemetry.h.

Referenced by expectingData().

◆ _frame_buffer

uint8_t DShotTelemetry::_frame_buffer[ESC_FRAME_SIZE]
private

Definition at line 130 of file telemetry.h.

◆ _frame_position

int DShotTelemetry::_frame_position {0}
private

Definition at line 131 of file telemetry.h.

◆ _latest_data

EscData DShotTelemetry::_latest_data
private

Definition at line 133 of file telemetry.h.

Referenced by latestESCData().

◆ _num_motors

int DShotTelemetry::_num_motors {0}
private

Definition at line 129 of file telemetry.h.

Referenced by numMotors(), and setNumMotors().

◆ _num_successful_responses

int DShotTelemetry::_num_successful_responses {0}
private

Definition at line 142 of file telemetry.h.

◆ _num_timeouts

int DShotTelemetry::_num_timeouts {0}
private

Definition at line 141 of file telemetry.h.

◆ _redirect_output

OutputBuffer* DShotTelemetry::_redirect_output {nullptr}
private

if set, all read bytes are stored here instead of the internal buffer

Definition at line 138 of file telemetry.h.

Referenced by redirectActive().

◆ _uart_fd

int DShotTelemetry::_uart_fd {-1}
private

Definition at line 128 of file telemetry.h.

◆ ESC_FRAME_SIZE

constexpr int DShotTelemetry::ESC_FRAME_SIZE = 10
staticprivate

Definition at line 106 of file telemetry.h.

◆ esc_info_size_blheli32

constexpr int DShotTelemetry::esc_info_size_blheli32 = 64
static

Definition at line 50 of file telemetry.h.

◆ esc_info_size_kiss_v1

constexpr int DShotTelemetry::esc_info_size_kiss_v1 = 15
static

Definition at line 51 of file telemetry.h.

◆ esc_info_size_kiss_v2

constexpr int DShotTelemetry::esc_info_size_kiss_v2 = 21
static

Definition at line 52 of file telemetry.h.

◆ max_esc_info_size

constexpr int DShotTelemetry::max_esc_info_size = esc_info_size_blheli32
static

Definition at line 53 of file telemetry.h.


The documentation for this class was generated from the following files: