Added display of (KISS) ESC version info for 'dshotprog <ESC index> 6'.
This commit is contained in:
parent
2b7e74c994
commit
1f25b44c03
|
@ -120,6 +120,7 @@ extern uint8_t __config_end;
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
#include "sensors/boardalignment.h"
|
#include "sensors/boardalignment.h"
|
||||||
#include "sensors/compass.h"
|
#include "sensors/compass.h"
|
||||||
|
#include "sensors/esc_sensor.h"
|
||||||
#include "sensors/gyro.h"
|
#include "sensors/gyro.h"
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
|
|
||||||
|
@ -877,12 +878,12 @@ static void cliSerialPassthrough(char *cmdline)
|
||||||
tok = strtok_r(NULL, " ", &saveptr);
|
tok = strtok_r(NULL, " ", &saveptr);
|
||||||
}
|
}
|
||||||
|
|
||||||
tfp_printf("Port %d ", id);
|
cliPrintf("Port %d ", id);
|
||||||
serialPort_t *passThroughPort;
|
serialPort_t *passThroughPort;
|
||||||
serialPortUsage_t *passThroughPortUsage = findSerialPortUsageByIdentifier(id);
|
serialPortUsage_t *passThroughPortUsage = findSerialPortUsageByIdentifier(id);
|
||||||
if (!passThroughPortUsage || passThroughPortUsage->serialPort == NULL) {
|
if (!passThroughPortUsage || passThroughPortUsage->serialPort == NULL) {
|
||||||
if (!baud) {
|
if (!baud) {
|
||||||
tfp_printf("closed, specify baud.\r\n");
|
cliPrint("closed, specify baud.\r\n");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (!mode)
|
if (!mode)
|
||||||
|
@ -892,17 +893,17 @@ static void cliSerialPassthrough(char *cmdline)
|
||||||
baud, mode,
|
baud, mode,
|
||||||
SERIAL_NOT_INVERTED);
|
SERIAL_NOT_INVERTED);
|
||||||
if (!passThroughPort) {
|
if (!passThroughPort) {
|
||||||
tfp_printf("could not be opened.\r\n");
|
cliPrint("could not be opened.\r\n");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
tfp_printf("opened, baud = %d.\r\n", baud);
|
cliPrintf("opened, baud = %d.\r\n", baud);
|
||||||
} else {
|
} else {
|
||||||
passThroughPort = passThroughPortUsage->serialPort;
|
passThroughPort = passThroughPortUsage->serialPort;
|
||||||
// If the user supplied a mode, override the port's mode, otherwise
|
// If the user supplied a mode, override the port's mode, otherwise
|
||||||
// leave the mode unchanged. serialPassthrough() handles one-way ports.
|
// leave the mode unchanged. serialPassthrough() handles one-way ports.
|
||||||
tfp_printf("already open.\r\n");
|
cliPrint("already open.\r\n");
|
||||||
if (mode && passThroughPort->mode != mode) {
|
if (mode && passThroughPort->mode != mode) {
|
||||||
tfp_printf("mode changed from %d to %d.\r\n",
|
cliPrintf("mode changed from %d to %d.\r\n",
|
||||||
passThroughPort->mode, mode);
|
passThroughPort->mode, mode);
|
||||||
serialSetMode(passThroughPort, mode);
|
serialSetMode(passThroughPort, mode);
|
||||||
}
|
}
|
||||||
|
@ -913,7 +914,7 @@ static void cliSerialPassthrough(char *cmdline)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
tfp_printf("forwarding, power cycle to exit.\r\n");
|
cliPrint("Forwarding, power cycle to exit.\r\n");
|
||||||
|
|
||||||
serialPassthrough(cliPort, passThroughPort, NULL, NULL);
|
serialPassthrough(cliPort, passThroughPort, NULL, NULL);
|
||||||
}
|
}
|
||||||
|
@ -2202,6 +2203,21 @@ static int parseOutputIndex(char *pch, bool allowAllEscs) {
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_DSHOT
|
#ifdef USE_DSHOT
|
||||||
|
|
||||||
|
#define ESC_INFO_EXPECTED_FRAME_SIZE 15
|
||||||
|
|
||||||
|
void printEscInfo(const uint8_t *escInfoBytes)
|
||||||
|
{
|
||||||
|
cliPrint("MCU Id: 0x");
|
||||||
|
for (int i = 0; i < 12; i++) {
|
||||||
|
cliPrintf("%02x", escInfoBytes[i]);
|
||||||
|
}
|
||||||
|
cliPrintLinef("\nFirmware version: %d.%02d%c", escInfoBytes[12] / 100, escInfoBytes[12] % 100, (const char)((escInfoBytes[13] & 0x1f) + 97));
|
||||||
|
|
||||||
|
uint8_t escType = (escInfoBytes[13] & 0xe0) >> 5;
|
||||||
|
cliPrintLinef("ESC type: %d", escType);
|
||||||
|
}
|
||||||
|
|
||||||
static void cliDshotProg(char *cmdline)
|
static void cliDshotProg(char *cmdline)
|
||||||
{
|
{
|
||||||
if (isEmpty(cmdline) || motorConfig()->dev.motorPwmProtocol < PWM_TYPE_DSHOT150) {
|
if (isEmpty(cmdline) || motorConfig()->dev.motorPwmProtocol < PWM_TYPE_DSHOT150) {
|
||||||
|
@ -2232,17 +2248,45 @@ static void cliDshotProg(char *cmdline)
|
||||||
for (unsigned i = 0; i < getMotorCount(); i++) {
|
for (unsigned i = 0; i < getMotorCount(); i++) {
|
||||||
pwmWriteDshotCommand(i, command);
|
pwmWriteDshotCommand(i, command);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
cliPrintf("Command %d written.\r\n", command);
|
||||||
} else {
|
} else {
|
||||||
|
uint8_t escInfoBuffer[ESC_INFO_EXPECTED_FRAME_SIZE];
|
||||||
|
if (command == DSHOT_CMD_ESC_INFO) {
|
||||||
|
delay(10); // Wait for potential ESC telemetry transmission to finish
|
||||||
|
|
||||||
|
startEscDataRead(ESC_INFO_EXPECTED_FRAME_SIZE, escInfoBuffer);
|
||||||
|
}
|
||||||
|
|
||||||
pwmWriteDshotCommand(escIndex, command);
|
pwmWriteDshotCommand(escIndex, command);
|
||||||
|
|
||||||
|
if (command == DSHOT_CMD_ESC_INFO) {
|
||||||
|
bool escInfoReceived = false;
|
||||||
|
for (int i = 0; i < 10; i++) {
|
||||||
|
delay(20);
|
||||||
|
|
||||||
|
if (checkEscDataReadFinished()) {
|
||||||
|
escInfoReceived = true;
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (escInfoReceived) {
|
||||||
|
printEscInfo(escInfoBuffer);
|
||||||
|
} else {
|
||||||
|
cliPrint("No ESC info received.");
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
cliPrintf("Command %d written.\r\n", command);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (command <= 5) {
|
if (command <= 5) {
|
||||||
delay(10); // wait for sound output to finish
|
delay(10); // wait for sound output to finish
|
||||||
}
|
}
|
||||||
|
|
||||||
tfp_printf("Command %d written.\r\n", command);
|
|
||||||
} else {
|
} else {
|
||||||
tfp_printf("Invalid command, range 1 to %d.\r\n", DSHOT_MIN_THROTTLE - 1);
|
cliPrintf("Invalid command, range 1 to %d.\r\n", DSHOT_MIN_THROTTLE - 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
|
|
@ -97,12 +97,14 @@ typedef enum {
|
||||||
} escSensorTriggerState_t;
|
} escSensorTriggerState_t;
|
||||||
|
|
||||||
#define ESC_SENSOR_BAUDRATE 115200
|
#define ESC_SENSOR_BAUDRATE 115200
|
||||||
#define ESC_SENSOR_BUFFSIZE 10
|
|
||||||
#define ESC_BOOTTIME 5000 // 5 seconds
|
#define ESC_BOOTTIME 5000 // 5 seconds
|
||||||
#define ESC_REQUEST_TIMEOUT 100 // 100 ms (data transfer takes only 900us)
|
#define ESC_REQUEST_TIMEOUT 100 // 100 ms (data transfer takes only 900us)
|
||||||
|
|
||||||
static volatile bool tlmFramePending = false;
|
#define TELEMETRY_FRAME_SIZE 10
|
||||||
static uint8_t tlm[ESC_SENSOR_BUFFSIZE] = { 0, };
|
static uint8_t telemetryBuffer[TELEMETRY_FRAME_SIZE] = { 0, };
|
||||||
|
|
||||||
|
static volatile uint8_t *buffer;
|
||||||
|
static volatile uint8_t tlmExpectedFrameSize = 0;
|
||||||
static uint8_t tlmFramePosition = 0;
|
static uint8_t tlmFramePosition = 0;
|
||||||
|
|
||||||
static serialPort_t *escSensorPort = NULL;
|
static serialPort_t *escSensorPort = NULL;
|
||||||
|
@ -119,6 +121,17 @@ static bool combinedDataNeedsUpdate = true;
|
||||||
static uint16_t totalTimeoutCount = 0;
|
static uint16_t totalTimeoutCount = 0;
|
||||||
static uint16_t totalCrcErrorCount = 0;
|
static uint16_t totalCrcErrorCount = 0;
|
||||||
|
|
||||||
|
void startEscDataRead(uint8_t frameLength, uint8_t *frameBuffer)
|
||||||
|
{
|
||||||
|
buffer = frameBuffer;
|
||||||
|
tlmExpectedFrameSize = frameLength;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool checkEscDataReadFinished(void)
|
||||||
|
{
|
||||||
|
return tlmExpectedFrameSize == 0;
|
||||||
|
}
|
||||||
|
|
||||||
bool isEscSensorActive(void)
|
bool isEscSensorActive(void)
|
||||||
{
|
{
|
||||||
return escSensorPort != NULL;
|
return escSensorPort != NULL;
|
||||||
|
@ -166,18 +179,16 @@ static void escSensorDataReceive(uint16_t c)
|
||||||
// KISS ESC sends some data during startup, ignore this for now (maybe future use)
|
// KISS ESC sends some data during startup, ignore this for now (maybe future use)
|
||||||
// startup data could be firmware version and serialnumber
|
// startup data could be firmware version and serialnumber
|
||||||
|
|
||||||
if (!tlmFramePending) {
|
if (!tlmExpectedFrameSize) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
tlm[tlmFramePosition] = (uint8_t)c;
|
buffer[tlmFramePosition++] = (uint8_t)c;
|
||||||
|
|
||||||
if (tlmFramePosition == ESC_SENSOR_BUFFSIZE - 1) {
|
if (tlmFramePosition == tlmExpectedFrameSize) {
|
||||||
tlmFramePosition = 0;
|
tlmFramePosition = 0;
|
||||||
|
|
||||||
tlmFramePending = false;
|
tlmExpectedFrameSize = 0;
|
||||||
} else {
|
|
||||||
tlmFramePosition++;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -221,21 +232,21 @@ static uint8_t get_crc8(uint8_t *Buf, uint8_t BufLen)
|
||||||
|
|
||||||
static uint8_t decodeEscFrame(void)
|
static uint8_t decodeEscFrame(void)
|
||||||
{
|
{
|
||||||
if (tlmFramePending) {
|
if (tlmExpectedFrameSize) {
|
||||||
return ESC_SENSOR_FRAME_PENDING;
|
return ESC_SENSOR_FRAME_PENDING;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Get CRC8 checksum
|
// Get CRC8 checksum
|
||||||
uint16_t chksum = get_crc8(tlm, ESC_SENSOR_BUFFSIZE - 1);
|
uint16_t chksum = get_crc8(telemetryBuffer, TELEMETRY_FRAME_SIZE - 1);
|
||||||
uint16_t tlmsum = tlm[ESC_SENSOR_BUFFSIZE - 1]; // last byte contains CRC value
|
uint16_t tlmsum = telemetryBuffer[TELEMETRY_FRAME_SIZE - 1]; // last byte contains CRC value
|
||||||
uint8_t frameStatus;
|
uint8_t frameStatus;
|
||||||
if (chksum == tlmsum) {
|
if (chksum == tlmsum) {
|
||||||
escSensorData[escSensorMotor].dataAge = 0;
|
escSensorData[escSensorMotor].dataAge = 0;
|
||||||
escSensorData[escSensorMotor].temperature = tlm[0];
|
escSensorData[escSensorMotor].temperature = telemetryBuffer[0];
|
||||||
escSensorData[escSensorMotor].voltage = tlm[1] << 8 | tlm[2];
|
escSensorData[escSensorMotor].voltage = telemetryBuffer[1] << 8 | telemetryBuffer[2];
|
||||||
escSensorData[escSensorMotor].current = tlm[3] << 8 | tlm[4];
|
escSensorData[escSensorMotor].current = telemetryBuffer[3] << 8 | telemetryBuffer[4];
|
||||||
escSensorData[escSensorMotor].consumption = tlm[5] << 8 | tlm[6];
|
escSensorData[escSensorMotor].consumption = telemetryBuffer[5] << 8 | telemetryBuffer[6];
|
||||||
escSensorData[escSensorMotor].rpm = tlm[7] << 8 | tlm[8];
|
escSensorData[escSensorMotor].rpm = telemetryBuffer[7] << 8 | telemetryBuffer[8];
|
||||||
|
|
||||||
combinedDataNeedsUpdate = true;
|
combinedDataNeedsUpdate = true;
|
||||||
|
|
||||||
|
@ -286,7 +297,8 @@ void escSensorProcess(timeUs_t currentTimeUs)
|
||||||
case ESC_SENSOR_TRIGGER_READY:
|
case ESC_SENSOR_TRIGGER_READY:
|
||||||
escTriggerTimestamp = currentTimeMs;
|
escTriggerTimestamp = currentTimeMs;
|
||||||
|
|
||||||
tlmFramePending = true;
|
buffer = telemetryBuffer;
|
||||||
|
tlmExpectedFrameSize = TELEMETRY_FRAME_SIZE;
|
||||||
motorDmaOutput_t * const motor = getMotorDmaOutput(escSensorMotor);
|
motorDmaOutput_t * const motor = getMotorDmaOutput(escSensorMotor);
|
||||||
motor->requestTelemetry = true;
|
motor->requestTelemetry = true;
|
||||||
escSensorTriggerState = ESC_SENSOR_TRIGGER_PENDING;
|
escSensorTriggerState = ESC_SENSOR_TRIGGER_PENDING;
|
||||||
|
|
|
@ -45,3 +45,6 @@ void escSensorProcess(timeUs_t currentTime);
|
||||||
|
|
||||||
escSensorData_t *getEscSensorData(uint8_t motorNumber);
|
escSensorData_t *getEscSensorData(uint8_t motorNumber);
|
||||||
|
|
||||||
|
void startEscDataRead(uint8_t frameLength, uint8_t *frameBuffer);
|
||||||
|
bool checkEscDataReadFinished(void);
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue