PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <telemetry.h>
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 EscData & | latestESCData () 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 |
Definition at line 38 of file telemetry.h.
DShotTelemetry::~DShotTelemetry | ( | ) |
Definition at line 47 of file telemetry.cpp.
|
staticprivate |
Definition at line 212 of file telemetry.cpp.
Referenced by decodeAndPrintEscInfoPacket().
|
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().
|
private |
Decode a single byte from an ESC feedback frame.
byte | |
successful_decoding | set to true if checksum matches |
Definition at line 164 of file telemetry.cpp.
References crc8(), and hrt_absolute_time().
void DShotTelemetry::deinit | ( | ) |
Definition at line 68 of file telemetry.cpp.
|
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().
int DShotTelemetry::getRequestMotorIndex | ( | ) |
Get the motor index for which telemetry should be requested.
Definition at line 231 of file telemetry.cpp.
References hrt_absolute_time().
Referenced by redirectActive(), and DShotOutput::updateOutputs().
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().
|
inline |
Definition at line 94 of file telemetry.h.
References _latest_data.
Referenced by DShotOutput::Run().
|
inline |
Definition at line 68 of file telemetry.h.
References _num_motors, redirectOutput(), and update().
Referenced by DShotOutput::handleNewTelemetryData().
void DShotTelemetry::printStatus | ( | ) | const |
Definition at line 194 of file telemetry.cpp.
Referenced by expectingData(), and DShotOutput::print_status().
|
inline |
Definition at line 86 of file telemetry.h.
References _redirect_output, and getRequestMotorIndex().
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.
buffer |
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().
|
private |
Definition at line 224 of file telemetry.cpp.
|
private |
set the Baudrate
baud |
Definition at line 399 of file telemetry.cpp.
|
inline |
Definition at line 67 of file telemetry.h.
References _num_motors.
Referenced by DShotOutput::updateTelemetryNumMotors().
int DShotTelemetry::update | ( | ) |
Read telemetry from the UART (non-blocking) and handle timeouts.
Definition at line 90 of file telemetry.cpp.
References hrt_absolute_time(), hrt_abstime, and read().
Referenced by numMotors(), and DShotOutput::Run().
|
inlinestaticprivate |
Definition at line 200 of file telemetry.cpp.
|
private |
Definition at line 135 of file telemetry.h.
|
private |
Definition at line 136 of file telemetry.h.
Referenced by expectingData().
|
private |
Definition at line 130 of file telemetry.h.
|
private |
Definition at line 131 of file telemetry.h.
|
private |
Definition at line 133 of file telemetry.h.
Referenced by latestESCData().
|
private |
Definition at line 129 of file telemetry.h.
Referenced by numMotors(), and setNumMotors().
|
private |
Definition at line 142 of file telemetry.h.
|
private |
Definition at line 141 of file telemetry.h.
|
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().
|
private |
Definition at line 128 of file telemetry.h.
|
staticprivate |
Definition at line 106 of file telemetry.h.
|
static |
Definition at line 50 of file telemetry.h.
|
static |
Definition at line 51 of file telemetry.h.
|
static |
Definition at line 52 of file telemetry.h.
|
static |
Definition at line 53 of file telemetry.h.