mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-14 03:50:02 +03:00
Dshot RPM Telemetry Refactoring (#13012)
This commit is contained in:
parent
0c9d7e6c50
commit
5769b3021e
22 changed files with 166 additions and 112 deletions
|
@ -1165,7 +1165,7 @@ static void loadMainState(timeUs_t currentTimeUs)
|
||||||
|
|
||||||
#ifdef USE_DSHOT_TELEMETRY
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
for (int i = 0; i < motorCount; i++) {
|
for (int i = 0; i < motorCount; i++) {
|
||||||
blackboxCurrent->erpm[i] = getDshotTelemetry(i);
|
blackboxCurrent->erpm[i] = getDshotErpm(i);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -18,8 +18,6 @@
|
||||||
* If not, see <http://www.gnu.org/licenses/>.
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <stdint.h>
|
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#include "debug.h"
|
#include "debug.h"
|
||||||
|
|
|
@ -6119,8 +6119,8 @@ static void cliDshotTelemetryInfo(const char *cmdName, char *cmdline)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
for (uint8_t i = 0; i < getMotorCount(); i++) {
|
for (uint8_t i = 0; i < getMotorCount(); i++) {
|
||||||
const uint16_t erpm = getDshotTelemetry(i);
|
const uint16_t erpm = getDshotErpm(i);
|
||||||
const uint16_t rpm = erpmToRpm(erpm);
|
const uint16_t rpm = lrintf(getDshotRpm(i));
|
||||||
|
|
||||||
cliPrintf("%5d %c%c%c%c%c %6d %6d %6d",
|
cliPrintf("%5d %c%c%c%c%c %6d %6d %6d",
|
||||||
i + 1,
|
i + 1,
|
||||||
|
|
|
@ -43,6 +43,8 @@ typedef uint32_t timeUs_t;
|
||||||
#define TIMEZONE_OFFSET_MINUTES_MIN -780 // -13 hours
|
#define TIMEZONE_OFFSET_MINUTES_MIN -780 // -13 hours
|
||||||
#define TIMEZONE_OFFSET_MINUTES_MAX 780 // +13 hours
|
#define TIMEZONE_OFFSET_MINUTES_MAX 780 // +13 hours
|
||||||
|
|
||||||
|
#define SECONDS_PER_MINUTE 60.0f
|
||||||
|
|
||||||
static inline timeDelta_t cmpTimeUs(timeUs_t a, timeUs_t b) { return (timeDelta_t)(a - b); }
|
static inline timeDelta_t cmpTimeUs(timeUs_t a, timeUs_t b) { return (timeDelta_t)(a - b); }
|
||||||
static inline int32_t cmpTimeCycles(uint32_t a, uint32_t b) { return (int32_t)(a - b); }
|
static inline int32_t cmpTimeCycles(uint32_t a, uint32_t b) { return (int32_t)(a - b); }
|
||||||
|
|
||||||
|
@ -101,4 +103,5 @@ bool rtcSetDateTime(dateTime_t *dt);
|
||||||
|
|
||||||
void rtcPersistWrite(int16_t offsetMinutes);
|
void rtcPersistWrite(int16_t offsetMinutes);
|
||||||
bool rtcPersistRead(rtcTime_t *t);
|
bool rtcPersistRead(rtcTime_t *t);
|
||||||
#endif
|
|
||||||
|
#endif // USE_RTC_TIME
|
||||||
|
|
|
@ -22,9 +22,9 @@
|
||||||
* Follows the extended dshot telemetry documentation found at https://github.com/bird-sanctuary/extended-dshot-telemetry
|
* Follows the extended dshot telemetry documentation found at https://github.com/bird-sanctuary/extended-dshot-telemetry
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include <float.h>
|
||||||
#include <stdint.h>
|
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
#include <stdbool.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
@ -34,6 +34,7 @@
|
||||||
#include "build/debug.h"
|
#include "build/debug.h"
|
||||||
#include "build/atomic.h"
|
#include "build/atomic.h"
|
||||||
|
|
||||||
|
#include "common/filter.h"
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
@ -46,9 +47,14 @@
|
||||||
|
|
||||||
#include "flight/mixer.h"
|
#include "flight/mixer.h"
|
||||||
|
|
||||||
|
#include "pg/rpm_filter.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
||||||
#include "dshot.h"
|
#include "dshot.h"
|
||||||
|
|
||||||
|
#define ERPM_PER_LSB 100.0f
|
||||||
|
|
||||||
void dshotInitEndpoints(const motorConfig_t *motorConfig, float outputLimit, float *outputLow, float *outputHigh, float *disarm, float *deadbandMotor3dHigh, float *deadbandMotor3dLow)
|
void dshotInitEndpoints(const motorConfig_t *motorConfig, float outputLimit, float *outputLow, float *outputHigh, float *disarm, float *deadbandMotor3dHigh, float *deadbandMotor3dLow)
|
||||||
{
|
{
|
||||||
float outputLimitOffset = DSHOT_RANGE * (1 - outputLimit);
|
float outputLimitOffset = DSHOT_RANGE * (1 - outputLimit);
|
||||||
|
@ -134,9 +140,30 @@ FAST_CODE uint16_t prepareDshotPacket(dshotProtocolControl_t *pcb)
|
||||||
|
|
||||||
#ifdef USE_DSHOT_TELEMETRY
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
|
|
||||||
|
|
||||||
FAST_DATA_ZERO_INIT dshotTelemetryState_t dshotTelemetryState;
|
FAST_DATA_ZERO_INIT dshotTelemetryState_t dshotTelemetryState;
|
||||||
|
|
||||||
|
FAST_DATA_ZERO_INIT static pt1Filter_t motorFreqLpf[MAX_SUPPORTED_MOTORS];
|
||||||
|
FAST_DATA_ZERO_INIT static float motorFrequencyHz[MAX_SUPPORTED_MOTORS];
|
||||||
|
FAST_DATA_ZERO_INIT static float minMotorFrequencyHz;
|
||||||
|
FAST_DATA_ZERO_INIT static float erpmToHz;
|
||||||
|
FAST_DATA_ZERO_INIT static float dshotRpmAverage;
|
||||||
|
FAST_DATA_ZERO_INIT static float dshotRpm[MAX_SUPPORTED_MOTORS];
|
||||||
|
|
||||||
|
void initDshotTelemetry(const timeUs_t looptimeUs)
|
||||||
|
{
|
||||||
|
// if bidirectional DShot is not available
|
||||||
|
if (!motorConfig()->dev.useDshotTelemetry) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// init LPFs for RPM data
|
||||||
|
for (int i = 0; i < getMotorCount(); i++) {
|
||||||
|
pt1FilterInit(&motorFreqLpf[i], pt1FilterGain(rpmFilterConfig()->rpm_filter_lpf_hz, looptimeUs * 1e-6f));
|
||||||
|
}
|
||||||
|
|
||||||
|
erpmToHz = ERPM_PER_LSB / SECONDS_PER_MINUTE / (motorConfig()->motorPoleCount / 2.0f);
|
||||||
|
}
|
||||||
|
|
||||||
static uint32_t dshot_decode_eRPM_telemetry_value(uint16_t value)
|
static uint32_t dshot_decode_eRPM_telemetry_value(uint16_t value)
|
||||||
{
|
{
|
||||||
// eRPM range
|
// eRPM range
|
||||||
|
@ -259,41 +286,78 @@ static void dshotUpdateTelemetryData(uint8_t motorIndex, dshotTelemetryType_t ty
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t getDshotTelemetry(uint8_t index)
|
FAST_CODE_NOINLINE void updateDshotTelemetry(void)
|
||||||
{
|
{
|
||||||
// Process telemetry in case it haven´t been processed yet
|
if (!motorConfig()->dev.useDshotTelemetry) {
|
||||||
if (dshotTelemetryState.rawValueState == DSHOT_RAW_VALUE_STATE_NOT_PROCESSED) {
|
return;
|
||||||
const unsigned motorCount = motorDeviceCount();
|
|
||||||
uint32_t erpmTotal = 0;
|
|
||||||
uint32_t rpmSamples = 0;
|
|
||||||
|
|
||||||
// Decode all telemetry data now to discharge interrupt from this task
|
|
||||||
for (uint8_t k = 0; k < motorCount; k++) {
|
|
||||||
dshotTelemetryType_t type;
|
|
||||||
uint32_t value;
|
|
||||||
|
|
||||||
dshot_decode_telemetry_value(k, &value, &type);
|
|
||||||
|
|
||||||
if (value != DSHOT_TELEMETRY_INVALID) {
|
|
||||||
dshotUpdateTelemetryData(k, type, value);
|
|
||||||
|
|
||||||
if (type == DSHOT_TELEMETRY_TYPE_eRPM) {
|
|
||||||
erpmTotal += value;
|
|
||||||
rpmSamples++;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Update average
|
|
||||||
if (rpmSamples > 0) {
|
|
||||||
dshotTelemetryState.averageErpm = (uint16_t)(erpmTotal / rpmSamples);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Set state to processed
|
|
||||||
dshotTelemetryState.rawValueState = DSHOT_RAW_VALUE_STATE_PROCESSED;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
return dshotTelemetryState.motorState[index].telemetryData[DSHOT_TELEMETRY_TYPE_eRPM];
|
// Only process telemetry in case it hasn´t been processed yet
|
||||||
|
if (dshotTelemetryState.rawValueState != DSHOT_RAW_VALUE_STATE_NOT_PROCESSED) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
const unsigned motorCount = motorDeviceCount();
|
||||||
|
uint32_t erpmTotal = 0;
|
||||||
|
uint32_t rpmSamples = 0;
|
||||||
|
|
||||||
|
// Decode all telemetry data now to discharge interrupt from this task
|
||||||
|
for (uint8_t k = 0; k < motorCount; k++) {
|
||||||
|
dshotTelemetryType_t type;
|
||||||
|
uint32_t value;
|
||||||
|
|
||||||
|
dshot_decode_telemetry_value(k, &value, &type);
|
||||||
|
|
||||||
|
if (value != DSHOT_TELEMETRY_INVALID) {
|
||||||
|
dshotUpdateTelemetryData(k, type, value);
|
||||||
|
|
||||||
|
if (type == DSHOT_TELEMETRY_TYPE_eRPM) {
|
||||||
|
dshotRpm[k] = erpmToRpm(value);
|
||||||
|
erpmTotal += value;
|
||||||
|
rpmSamples++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Update average
|
||||||
|
if (rpmSamples > 0) {
|
||||||
|
dshotRpmAverage = erpmToRpm(erpmTotal) / (float)rpmSamples;
|
||||||
|
}
|
||||||
|
|
||||||
|
// update filtered rotation speed of motors for features (e.g. "RPM filter")
|
||||||
|
minMotorFrequencyHz = FLT_MAX;
|
||||||
|
for (int motor = 0; motor < getMotorCount(); motor++) {
|
||||||
|
motorFrequencyHz[motor] = pt1FilterApply(&motorFreqLpf[motor], erpmToHz * getDshotErpm(motor));
|
||||||
|
minMotorFrequencyHz = MIN(minMotorFrequencyHz, motorFrequencyHz[motor]);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Set state to processed
|
||||||
|
dshotTelemetryState.rawValueState = DSHOT_RAW_VALUE_STATE_PROCESSED;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t getDshotErpm(uint8_t motorIndex)
|
||||||
|
{
|
||||||
|
return dshotTelemetryState.motorState[motorIndex].telemetryData[DSHOT_TELEMETRY_TYPE_eRPM];
|
||||||
|
}
|
||||||
|
|
||||||
|
float getDshotRpm(uint8_t motorIndex)
|
||||||
|
{
|
||||||
|
return dshotRpm[motorIndex];
|
||||||
|
}
|
||||||
|
|
||||||
|
float getDshotRpmAverage(void)
|
||||||
|
{
|
||||||
|
return dshotRpmAverage;
|
||||||
|
}
|
||||||
|
|
||||||
|
float getMotorFrequencyHz(uint8_t motorIndex)
|
||||||
|
{
|
||||||
|
return motorFrequencyHz[motorIndex];
|
||||||
|
}
|
||||||
|
|
||||||
|
float getMinMotorFrequencyHz(void)
|
||||||
|
{
|
||||||
|
return minMotorFrequencyHz;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool isDshotMotorTelemetryActive(uint8_t motorIndex)
|
bool isDshotMotorTelemetryActive(uint8_t motorIndex)
|
||||||
|
@ -320,21 +384,15 @@ void dshotCleanTelemetryData(void)
|
||||||
memset(&dshotTelemetryState, 0, sizeof(dshotTelemetryState));
|
memset(&dshotTelemetryState, 0, sizeof(dshotTelemetryState));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
uint32_t getDshotAverageRpm(void)
|
|
||||||
{
|
|
||||||
return erpmToRpm(dshotTelemetryState.averageErpm);
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif // USE_DSHOT_TELEMETRY
|
#endif // USE_DSHOT_TELEMETRY
|
||||||
|
|
||||||
#if defined(USE_ESC_SENSOR) || defined(USE_DSHOT_TELEMETRY)
|
#if defined(USE_ESC_SENSOR) || defined(USE_DSHOT_TELEMETRY)
|
||||||
|
|
||||||
// Used with serial esc telem as well as dshot telem
|
// Used with serial esc telem as well as dshot telem
|
||||||
uint32_t erpmToRpm(uint16_t erpm)
|
float erpmToRpm(uint32_t erpm)
|
||||||
{
|
{
|
||||||
// rpm = (erpm * 100) / (motorConfig()->motorPoleCount / 2)
|
// rpm = (erpm * ERPM_PER_LSB) / (motorConfig()->motorPoleCount / 2)
|
||||||
return (erpm * 200) / motorConfig()->motorPoleCount;
|
return erpm * erpmToHz * SECONDS_PER_MINUTE;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // USE_ESC_SENSOR || USE_DSHOT_TELEMETRY
|
#endif // USE_ESC_SENSOR || USE_DSHOT_TELEMETRY
|
||||||
|
|
|
@ -20,6 +20,9 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
#include "common/time.h"
|
#include "common/time.h"
|
||||||
|
|
||||||
#include "pg/motor.h"
|
#include "pg/motor.h"
|
||||||
|
@ -66,13 +69,14 @@ typedef enum dshotTelemetryType_e {
|
||||||
DSHOT_TELEMETRY_TYPE_DEBUG2 = 5,
|
DSHOT_TELEMETRY_TYPE_DEBUG2 = 5,
|
||||||
DSHOT_TELEMETRY_TYPE_DEBUG3 = 6,
|
DSHOT_TELEMETRY_TYPE_DEBUG3 = 6,
|
||||||
DSHOT_TELEMETRY_TYPE_STATE_EVENTS = 7,
|
DSHOT_TELEMETRY_TYPE_STATE_EVENTS = 7,
|
||||||
DSHOT_TELEMETRY_TYPE_COUNT = 8
|
DSHOT_TELEMETRY_TYPE_COUNT
|
||||||
} dshotTelemetryType_t;
|
} dshotTelemetryType_t;
|
||||||
|
|
||||||
typedef enum dshotRawValueState_e {
|
typedef enum dshotRawValueState_e {
|
||||||
DSHOT_RAW_VALUE_STATE_INVALID = 0,
|
DSHOT_RAW_VALUE_STATE_INVALID = 0,
|
||||||
DSHOT_RAW_VALUE_STATE_NOT_PROCESSED = 1,
|
DSHOT_RAW_VALUE_STATE_NOT_PROCESSED = 1,
|
||||||
DSHOT_RAW_VALUE_STATE_PROCESSED = 2
|
DSHOT_RAW_VALUE_STATE_PROCESSED = 2,
|
||||||
|
DSHOT_RAW_VALUE_STATE_COUNT
|
||||||
} dshotRawValueState_t;
|
} dshotRawValueState_t;
|
||||||
|
|
||||||
typedef struct dshotProtocolControl_s {
|
typedef struct dshotProtocolControl_s {
|
||||||
|
@ -103,7 +107,6 @@ typedef struct dshotTelemetryState_s {
|
||||||
uint32_t readCount;
|
uint32_t readCount;
|
||||||
dshotTelemetryMotorState_t motorState[MAX_SUPPORTED_MOTORS];
|
dshotTelemetryMotorState_t motorState[MAX_SUPPORTED_MOTORS];
|
||||||
uint32_t inputBuffer[MAX_GCR_EDGES];
|
uint32_t inputBuffer[MAX_GCR_EDGES];
|
||||||
uint16_t averageErpm;
|
|
||||||
dshotRawValueState_t rawValueState;
|
dshotRawValueState_t rawValueState;
|
||||||
} dshotTelemetryState_t;
|
} dshotTelemetryState_t;
|
||||||
|
|
||||||
|
@ -112,15 +115,23 @@ extern dshotTelemetryState_t dshotTelemetryState;
|
||||||
#ifdef USE_DSHOT_TELEMETRY_STATS
|
#ifdef USE_DSHOT_TELEMETRY_STATS
|
||||||
void updateDshotTelemetryQuality(dshotTelemetryQuality_t *qualityStats, bool packetValid, timeMs_t currentTimeMs);
|
void updateDshotTelemetryQuality(dshotTelemetryQuality_t *qualityStats, bool packetValid, timeMs_t currentTimeMs);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif // USE_DSHOT_TELEMETRY
|
||||||
|
|
||||||
|
void initDshotTelemetry(const timeUs_t looptimeUs);
|
||||||
|
void updateDshotTelemetry(void);
|
||||||
|
|
||||||
|
uint16_t getDshotErpm(uint8_t motorIndex);
|
||||||
|
float getDshotRpm(uint8_t motorIndex);
|
||||||
|
float getDshotRpmAverage(void);
|
||||||
|
float getMotorFrequencyHz(uint8_t motorIndex);
|
||||||
|
float getMinMotorFrequencyHz(void);
|
||||||
|
|
||||||
uint16_t getDshotTelemetry(uint8_t index);
|
|
||||||
uint32_t erpmToRpm(uint16_t erpm);
|
|
||||||
uint32_t getDshotAverageRpm(void);
|
|
||||||
bool isDshotMotorTelemetryActive(uint8_t motorIndex);
|
bool isDshotMotorTelemetryActive(uint8_t motorIndex);
|
||||||
bool isDshotTelemetryActive(void);
|
bool isDshotTelemetryActive(void);
|
||||||
|
void dshotCleanTelemetryData(void);
|
||||||
|
|
||||||
|
float erpmToRpm(uint32_t erpm);
|
||||||
|
|
||||||
int16_t getDshotTelemetryMotorInvalidPercent(uint8_t motorIndex);
|
int16_t getDshotTelemetryMotorInvalidPercent(uint8_t motorIndex);
|
||||||
|
|
||||||
void validateAndfixMotorOutputReordering(uint8_t *array, const unsigned size);
|
void validateAndfixMotorOutputReordering(uint8_t *array, const unsigned size);
|
||||||
void dshotCleanTelemetryData(void);
|
|
||||||
|
|
|
@ -1270,8 +1270,10 @@ FAST_CODE bool pidLoopReady(void)
|
||||||
|
|
||||||
FAST_CODE void taskFiltering(timeUs_t currentTimeUs)
|
FAST_CODE void taskFiltering(timeUs_t currentTimeUs)
|
||||||
{
|
{
|
||||||
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
|
updateDshotTelemetry(); // decode and update Dshot telemetry
|
||||||
|
#endif
|
||||||
gyroFiltering(currentTimeUs);
|
gyroFiltering(currentTimeUs);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Function for loop trigger
|
// Function for loop trigger
|
||||||
|
|
|
@ -54,6 +54,7 @@
|
||||||
#include "drivers/camera_control_impl.h"
|
#include "drivers/camera_control_impl.h"
|
||||||
#include "drivers/compass/compass.h"
|
#include "drivers/compass/compass.h"
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
|
#include "drivers/dshot.h"
|
||||||
#include "drivers/exti.h"
|
#include "drivers/exti.h"
|
||||||
#include "drivers/flash.h"
|
#include "drivers/flash.h"
|
||||||
#include "drivers/inverter.h"
|
#include "drivers/inverter.h"
|
||||||
|
@ -694,6 +695,11 @@ void init(void)
|
||||||
// Now reset the targetLooptime as it's possible for the validation to change the pid_process_denom
|
// Now reset the targetLooptime as it's possible for the validation to change the pid_process_denom
|
||||||
gyroSetTargetLooptime(pidConfig()->pid_process_denom);
|
gyroSetTargetLooptime(pidConfig()->pid_process_denom);
|
||||||
|
|
||||||
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
|
// Initialize the motor frequency filter now that we have a target looptime
|
||||||
|
initDshotTelemetry(gyro.targetLooptime);
|
||||||
|
#endif
|
||||||
|
|
||||||
// Finally initialize the gyro filtering
|
// Finally initialize the gyro filtering
|
||||||
gyroInitFilters();
|
gyroInitFilters();
|
||||||
|
|
||||||
|
|
|
@ -220,7 +220,7 @@ static void calculateThrottleAndCurrentMotorEndpoints(timeUs_t currentTimeUs)
|
||||||
if (mixerRuntime.dynIdleMinRps > 0.0f) {
|
if (mixerRuntime.dynIdleMinRps > 0.0f) {
|
||||||
const float maxIncrease = isAirmodeActivated()
|
const float maxIncrease = isAirmodeActivated()
|
||||||
? mixerRuntime.dynIdleMaxIncrease : mixerRuntime.dynIdleStartIncrease;
|
? mixerRuntime.dynIdleMaxIncrease : mixerRuntime.dynIdleStartIncrease;
|
||||||
float minRps = getMinMotorFrequency();
|
float minRps = getMinMotorFrequencyHz();
|
||||||
DEBUG_SET(DEBUG_DYN_IDLE, 3, lrintf(minRps * 10.0f));
|
DEBUG_SET(DEBUG_DYN_IDLE, 3, lrintf(minRps * 10.0f));
|
||||||
float rpsError = mixerRuntime.dynIdleMinRps - minRps;
|
float rpsError = mixerRuntime.dynIdleMinRps - minRps;
|
||||||
// PT1 type lowpass delay and smoothing for D
|
// PT1 type lowpass delay and smoothing for D
|
||||||
|
|
|
@ -19,7 +19,6 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
#include <float.h>
|
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
@ -45,8 +44,6 @@
|
||||||
#include "rpm_filter.h"
|
#include "rpm_filter.h"
|
||||||
|
|
||||||
#define RPM_FILTER_DURATION_S 0.001f // Maximum duration allowed to update all RPM notches once
|
#define RPM_FILTER_DURATION_S 0.001f // Maximum duration allowed to update all RPM notches once
|
||||||
#define SECONDS_PER_MINUTE 60.0f
|
|
||||||
#define ERPM_PER_LSB 100.0f
|
|
||||||
|
|
||||||
|
|
||||||
typedef struct rpmFilter_s {
|
typedef struct rpmFilter_s {
|
||||||
|
@ -66,11 +63,6 @@ typedef struct rpmFilter_s {
|
||||||
// Singleton
|
// Singleton
|
||||||
FAST_DATA_ZERO_INIT static rpmFilter_t rpmFilter;
|
FAST_DATA_ZERO_INIT static rpmFilter_t rpmFilter;
|
||||||
|
|
||||||
FAST_DATA_ZERO_INIT static pt1Filter_t motorFreqLpf[MAX_SUPPORTED_MOTORS];
|
|
||||||
FAST_DATA_ZERO_INIT static float motorFrequencyHz[MAX_SUPPORTED_MOTORS];
|
|
||||||
FAST_DATA_ZERO_INIT static float minMotorFrequencyHz;
|
|
||||||
FAST_DATA_ZERO_INIT static float erpmToHz;
|
|
||||||
|
|
||||||
// batch processing of RPM notches
|
// batch processing of RPM notches
|
||||||
FAST_DATA_ZERO_INIT static int notchUpdatesPerIteration;
|
FAST_DATA_ZERO_INIT static int notchUpdatesPerIteration;
|
||||||
FAST_DATA_ZERO_INIT static int motorIndex;
|
FAST_DATA_ZERO_INIT static int motorIndex;
|
||||||
|
@ -81,7 +73,6 @@ void rpmFilterInit(const rpmFilterConfig_t *config, const timeUs_t looptimeUs)
|
||||||
{
|
{
|
||||||
motorIndex = 0;
|
motorIndex = 0;
|
||||||
harmonicIndex = 0;
|
harmonicIndex = 0;
|
||||||
minMotorFrequencyHz = 0;
|
|
||||||
rpmFilter.numHarmonics = 0; // disable RPM Filtering
|
rpmFilter.numHarmonics = 0; // disable RPM Filtering
|
||||||
|
|
||||||
// if bidirectional DShot is not available
|
// if bidirectional DShot is not available
|
||||||
|
@ -89,13 +80,6 @@ void rpmFilterInit(const rpmFilterConfig_t *config, const timeUs_t looptimeUs)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// init LPFs for RPM data
|
|
||||||
for (int i = 0; i < getMotorCount(); i++) {
|
|
||||||
pt1FilterInit(&motorFreqLpf[i], pt1FilterGain(config->rpm_filter_lpf_hz, looptimeUs * 1e-6f));
|
|
||||||
}
|
|
||||||
|
|
||||||
erpmToHz = ERPM_PER_LSB / SECONDS_PER_MINUTE / (motorConfig()->motorPoleCount / 2.0f);
|
|
||||||
|
|
||||||
// if RPM Filtering is configured to be off
|
// if RPM Filtering is configured to be off
|
||||||
if (!config->rpm_filter_harmonics) {
|
if (!config->rpm_filter_harmonics) {
|
||||||
return;
|
return;
|
||||||
|
@ -132,14 +116,8 @@ FAST_CODE_NOINLINE void rpmFilterUpdate(void)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// update motor RPM data
|
for (int motor = 0; motor < getMotorCount() && motor < DEBUG16_VALUE_COUNT; motor++) {
|
||||||
minMotorFrequencyHz = FLT_MAX;
|
DEBUG_SET(DEBUG_RPM_FILTER, motor, lrintf(getMotorFrequencyHz(motor)));
|
||||||
for (int motor = 0; motor < getMotorCount(); motor++) {
|
|
||||||
motorFrequencyHz[motor] = pt1FilterApply(&motorFreqLpf[motor], erpmToHz * getDshotTelemetry(motor));
|
|
||||||
minMotorFrequencyHz = MIN(minMotorFrequencyHz, motorFrequencyHz[motor]);
|
|
||||||
if (motor < 4) {
|
|
||||||
DEBUG_SET(DEBUG_RPM_FILTER, motor, motorFrequencyHz[motor]);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!isRpmFilterEnabled()) {
|
if (!isRpmFilterEnabled()) {
|
||||||
|
@ -149,13 +127,13 @@ FAST_CODE_NOINLINE void rpmFilterUpdate(void)
|
||||||
// update RPM notches
|
// update RPM notches
|
||||||
for (int i = 0; i < notchUpdatesPerIteration; i++) {
|
for (int i = 0; i < notchUpdatesPerIteration; i++) {
|
||||||
|
|
||||||
// Only bother updating notches which can have an effect on filtered output
|
// Only bother updating notches which have an effect on filtered output
|
||||||
if (rpmFilter.weights[harmonicIndex] > 0.0f) {
|
if (rpmFilter.weights[harmonicIndex] > 0.0f) {
|
||||||
|
|
||||||
// select current notch on ROLL
|
// select current notch on ROLL
|
||||||
biquadFilter_t *template = &rpmFilter.notch[0][motorIndex][harmonicIndex];
|
biquadFilter_t *template = &rpmFilter.notch[0][motorIndex][harmonicIndex];
|
||||||
|
|
||||||
const float frequencyHz = constrainf((harmonicIndex + 1) * motorFrequencyHz[motorIndex], rpmFilter.minHz, rpmFilter.maxHz);
|
const float frequencyHz = constrainf((harmonicIndex + 1) * getMotorFrequencyHz(motorIndex), rpmFilter.minHz, rpmFilter.maxHz);
|
||||||
const float marginHz = frequencyHz - rpmFilter.minHz;
|
const float marginHz = frequencyHz - rpmFilter.minHz;
|
||||||
float weight = 1.0f;
|
float weight = 1.0f;
|
||||||
|
|
||||||
|
@ -213,9 +191,4 @@ bool isRpmFilterEnabled(void)
|
||||||
return rpmFilter.numHarmonics > 0;
|
return rpmFilter.numHarmonics > 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
float getMinMotorFrequency(void)
|
|
||||||
{
|
|
||||||
return minMotorFrequencyHz;
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif // USE_RPM_FILTER
|
#endif // USE_RPM_FILTER
|
||||||
|
|
|
@ -30,4 +30,3 @@ void rpmFilterInit(const rpmFilterConfig_t *config, const timeUs_t looptimeUs);
|
||||||
void rpmFilterUpdate(void);
|
void rpmFilterUpdate(void);
|
||||||
float rpmFilterApply(const int axis, float value);
|
float rpmFilterApply(const int axis, float value);
|
||||||
bool isRpmFilterEnabled(void);
|
bool isRpmFilterEnabled(void);
|
||||||
float getMinMotorFrequency(void);
|
|
||||||
|
|
|
@ -1123,7 +1123,7 @@ static bool mspProcessOutCommand(mspDescriptor_t srcDesc, int16_t cmdMSP, sbuf_t
|
||||||
|
|
||||||
// Added in API version 1.46
|
// Added in API version 1.46
|
||||||
// Write CPU temp
|
// Write CPU temp
|
||||||
#ifdef USE_ADC_INTERNAL
|
#ifdef USE_ADC_INTERNAL
|
||||||
sbufWriteU16(dst, getCoreTemperatureCelsius());
|
sbufWriteU16(dst, getCoreTemperatureCelsius());
|
||||||
#else
|
#else
|
||||||
sbufWriteU16(dst, 0);
|
sbufWriteU16(dst, 0);
|
||||||
|
@ -1236,7 +1236,7 @@ case MSP_NAME:
|
||||||
|
|
||||||
#ifdef USE_DSHOT_TELEMETRY
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
if (motorConfig()->dev.useDshotTelemetry) {
|
if (motorConfig()->dev.useDshotTelemetry) {
|
||||||
rpm = erpmToRpm(getDshotTelemetry(i));
|
rpm = lrintf(getDshotRpm(i));
|
||||||
rpmDataAvailable = true;
|
rpmDataAvailable = true;
|
||||||
invalidPct = 10000; // 100.00%
|
invalidPct = 10000; // 100.00%
|
||||||
|
|
||||||
|
@ -1272,7 +1272,7 @@ case MSP_NAME:
|
||||||
if (featureIsEnabled(FEATURE_ESC_SENSOR)) {
|
if (featureIsEnabled(FEATURE_ESC_SENSOR)) {
|
||||||
escSensorData_t *escData = getEscSensorData(i);
|
escSensorData_t *escData = getEscSensorData(i);
|
||||||
if (!rpmDataAvailable) { // We want DSHOT telemetry RPM data (if available) to have precedence
|
if (!rpmDataAvailable) { // We want DSHOT telemetry RPM data (if available) to have precedence
|
||||||
rpm = erpmToRpm(escData->rpm);
|
rpm = lrintf(erpmToRpm(escData->rpm));
|
||||||
rpmDataAvailable = true;
|
rpmDataAvailable = true;
|
||||||
}
|
}
|
||||||
escTemperature = escData->temperature;
|
escTemperature = escData->temperature;
|
||||||
|
@ -1495,7 +1495,7 @@ case MSP_NAME:
|
||||||
sbufWriteU8(dst, getMotorCount());
|
sbufWriteU8(dst, getMotorCount());
|
||||||
for (int i = 0; i < getMotorCount(); i++) {
|
for (int i = 0; i < getMotorCount(); i++) {
|
||||||
sbufWriteU8(dst, dshotTelemetryState.motorState[i].telemetryData[DSHOT_TELEMETRY_TYPE_TEMPERATURE]);
|
sbufWriteU8(dst, dshotTelemetryState.motorState[i].telemetryData[DSHOT_TELEMETRY_TYPE_TEMPERATURE]);
|
||||||
sbufWriteU16(dst, getDshotTelemetry(i) * 100 * 2 / motorConfig()->motorPoleCount);
|
sbufWriteU16(dst, lrintf(getDshotRpm(i)));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
|
|
|
@ -599,12 +599,12 @@ static int32_t getAverageEscRpm(void)
|
||||||
{
|
{
|
||||||
#ifdef USE_ESC_SENSOR
|
#ifdef USE_ESC_SENSOR
|
||||||
if (featureIsEnabled(FEATURE_ESC_SENSOR)) {
|
if (featureIsEnabled(FEATURE_ESC_SENSOR)) {
|
||||||
return erpmToRpm(osdEscDataCombined->rpm);
|
return lrintf(erpmToRpm(osdEscDataCombined->rpm));
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_DSHOT_TELEMETRY
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
if (motorConfig()->dev.useDshotTelemetry) {
|
if (motorConfig()->dev.useDshotTelemetry) {
|
||||||
return getDshotAverageRpm();
|
return lrintf(getDshotRpmAverage());
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
return 0;
|
return 0;
|
||||||
|
@ -854,7 +854,7 @@ static bool osdDisplayStat(int statistic, uint8_t displayRow)
|
||||||
osdDisplayStatisticLabel(midCol, displayRow, osdConfig()->stat_show_cell_value ? "END AVG CELL" : "END BATTERY", buff);
|
osdDisplayStatisticLabel(midCol, displayRow, osdConfig()->stat_show_cell_value ? "END AVG CELL" : "END BATTERY", buff);
|
||||||
return true;
|
return true;
|
||||||
|
|
||||||
case OSD_STAT_BATTERY:
|
case OSD_STAT_BATTERY:
|
||||||
{
|
{
|
||||||
const uint16_t statsVoltage = getStatsVoltage();
|
const uint16_t statsVoltage = getStatsVoltage();
|
||||||
osdPrintFloat(buff, SYM_NONE, statsVoltage / 100.0f, "", 2, true, SYM_VOLT);
|
osdPrintFloat(buff, SYM_NONE, statsVoltage / 100.0f, "", 2, true, SYM_VOLT);
|
||||||
|
@ -862,7 +862,7 @@ static bool osdDisplayStat(int statistic, uint8_t displayRow)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case OSD_STAT_MIN_RSSI:
|
case OSD_STAT_MIN_RSSI:
|
||||||
itoa(stats.min_rssi, buff, 10);
|
itoa(stats.min_rssi, buff, 10);
|
||||||
strcat(buff, "%");
|
strcat(buff, "%");
|
||||||
|
@ -884,7 +884,7 @@ static bool osdDisplayStat(int statistic, uint8_t displayRow)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case OSD_STAT_WATT_HOURS_DRAWN:
|
case OSD_STAT_WATT_HOURS_DRAWN:
|
||||||
if (batteryConfig()->currentMeterSource != CURRENT_METER_NONE) {
|
if (batteryConfig()->currentMeterSource != CURRENT_METER_NONE) {
|
||||||
osdPrintFloat(buff, SYM_NONE, getWhDrawn(), "", 2, true, SYM_NONE);
|
osdPrintFloat(buff, SYM_NONE, getWhDrawn(), "", 2, true, SYM_NONE);
|
||||||
|
|
|
@ -266,12 +266,12 @@ static int getEscRpm(int i)
|
||||||
{
|
{
|
||||||
#ifdef USE_DSHOT_TELEMETRY
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
if (motorConfig()->dev.useDshotTelemetry) {
|
if (motorConfig()->dev.useDshotTelemetry) {
|
||||||
return erpmToRpm(getDshotTelemetry(i));
|
return lrintf(getDshotRpm(i));
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_ESC_SENSOR
|
#ifdef USE_ESC_SENSOR
|
||||||
if (featureIsEnabled(FEATURE_ESC_SENSOR)) {
|
if (featureIsEnabled(FEATURE_ESC_SENSOR)) {
|
||||||
return erpmToRpm(getEscSensorData(i)->rpm);
|
return lrintf(erpmToRpm(getEscSensorData(i)->rpm));
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
return 0;
|
return 0;
|
||||||
|
|
|
@ -282,7 +282,7 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr)
|
||||||
const char motorNumber = '1' + i;
|
const char motorNumber = '1' + i;
|
||||||
// if everything is OK just display motor number else R, T or C
|
// if everything is OK just display motor number else R, T or C
|
||||||
char warnFlag = motorNumber;
|
char warnFlag = motorNumber;
|
||||||
if (ARMING_FLAG(ARMED) && osdConfig()->esc_rpm_alarm != ESC_RPM_ALARM_OFF && erpmToRpm(escData->rpm) <= (uint32_t)osdConfig()->esc_rpm_alarm) {
|
if (ARMING_FLAG(ARMED) && osdConfig()->esc_rpm_alarm != ESC_RPM_ALARM_OFF && (uint32_t)erpmToRpm(escData->rpm) <= (uint32_t)osdConfig()->esc_rpm_alarm) {
|
||||||
warnFlag = 'R';
|
warnFlag = 'R';
|
||||||
}
|
}
|
||||||
if (osdConfig()->esc_temp_alarm != ESC_TEMP_ALARM_OFF && escData->temperature >= osdConfig()->esc_temp_alarm) {
|
if (osdConfig()->esc_temp_alarm != ESC_TEMP_ALARM_OFF && escData->temperature >= osdConfig()->esc_temp_alarm) {
|
||||||
|
|
|
@ -18,6 +18,7 @@
|
||||||
* If not, see <http://www.gnu.org/licenses/>.
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include <math.h>
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
|
@ -271,7 +272,7 @@ static uint8_t decodeEscFrame(void)
|
||||||
frameStatus = ESC_SENSOR_FRAME_COMPLETE;
|
frameStatus = ESC_SENSOR_FRAME_COMPLETE;
|
||||||
|
|
||||||
if (escSensorMotor < 4) {
|
if (escSensorMotor < 4) {
|
||||||
DEBUG_SET(DEBUG_ESC_SENSOR_RPM, escSensorMotor, erpmToRpm(escSensorData[escSensorMotor].rpm) / 10); // output actual rpm/10 to fit in 16bit signed.
|
DEBUG_SET(DEBUG_ESC_SENSOR_RPM, escSensorMotor, lrintf(erpmToRpm(escSensorData[escSensorMotor].rpm) / 10.0f)); // output actual rpm/10 to fit in 16bit signed.
|
||||||
DEBUG_SET(DEBUG_ESC_SENSOR_TMP, escSensorMotor, escSensorData[escSensorMotor].temperature);
|
DEBUG_SET(DEBUG_ESC_SENSOR_TMP, escSensorMotor, escSensorData[escSensorMotor].temperature);
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
|
|
|
@ -711,8 +711,8 @@ void gyroSetTargetLooptime(uint8_t pidDenom)
|
||||||
{
|
{
|
||||||
activePidLoopDenom = pidDenom;
|
activePidLoopDenom = pidDenom;
|
||||||
if (gyro.sampleRateHz) {
|
if (gyro.sampleRateHz) {
|
||||||
gyro.sampleLooptime = 1e6 / gyro.sampleRateHz;
|
gyro.sampleLooptime = 1e6f / gyro.sampleRateHz;
|
||||||
gyro.targetLooptime = activePidLoopDenom * 1e6 / gyro.sampleRateHz;
|
gyro.targetLooptime = activePidLoopDenom * 1e6f / gyro.sampleRateHz;
|
||||||
} else {
|
} else {
|
||||||
gyro.sampleLooptime = 0;
|
gyro.sampleLooptime = 0;
|
||||||
gyro.targetLooptime = 0;
|
gyro.targetLooptime = 0;
|
||||||
|
|
|
@ -18,6 +18,7 @@
|
||||||
* If not, see <http://www.gnu.org/licenses/>.
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
|
|
|
@ -192,7 +192,7 @@ static void sendThrottleOrBatterySizeAsRpm(void)
|
||||||
#if defined(USE_ESC_SENSOR_TELEMETRY)
|
#if defined(USE_ESC_SENSOR_TELEMETRY)
|
||||||
escSensorData_t *escData = getEscSensorData(ESC_SENSOR_COMBINED);
|
escSensorData_t *escData = getEscSensorData(ESC_SENSOR_COMBINED);
|
||||||
if (escData) {
|
if (escData) {
|
||||||
data = escData->dataAge < ESC_DATA_INVALID ? (erpmToRpm(escData->rpm) / 10) : 0;
|
data = escData->dataAge < ESC_DATA_INVALID ? lrintf(erpmToRpm(escData->rpm) / 10.0f) : 0;
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
if (ARMING_FLAG(ARMED)) {
|
if (ARMING_FLAG(ARMED)) {
|
||||||
|
|
|
@ -658,7 +658,7 @@ void processSmartPortTelemetry(smartPortPayload_t *payload, volatile bool *clear
|
||||||
case FSSP_DATAID_RPM :
|
case FSSP_DATAID_RPM :
|
||||||
escData = getEscSensorData(ESC_SENSOR_COMBINED);
|
escData = getEscSensorData(ESC_SENSOR_COMBINED);
|
||||||
if (escData != NULL) {
|
if (escData != NULL) {
|
||||||
smartPortSendPackage(id, erpmToRpm(escData->rpm));
|
smartPortSendPackage(id, lrintf(erpmToRpm(escData->rpm)));
|
||||||
*clearToSend = false;
|
*clearToSend = false;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
@ -672,7 +672,7 @@ void processSmartPortTelemetry(smartPortPayload_t *payload, volatile bool *clear
|
||||||
case FSSP_DATAID_RPM8 :
|
case FSSP_DATAID_RPM8 :
|
||||||
escData = getEscSensorData(id - FSSP_DATAID_RPM1);
|
escData = getEscSensorData(id - FSSP_DATAID_RPM1);
|
||||||
if (escData != NULL) {
|
if (escData != NULL) {
|
||||||
smartPortSendPackage(id, erpmToRpm(escData->rpm));
|
smartPortSendPackage(id, lrintf(erpmToRpm(escData->rpm)));
|
||||||
*clearToSend = false;
|
*clearToSend = false;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
|
@ -18,6 +18,7 @@
|
||||||
* If not, see <http://www.gnu.org/licenses/>.
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include <math.h>
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
|
@ -196,7 +197,7 @@ uint16_t getMotorAveragePeriod(void)
|
||||||
#if defined(USE_DSHOT_TELEMETRY)
|
#if defined(USE_DSHOT_TELEMETRY)
|
||||||
// Calculate this way when no rpm from esc data
|
// Calculate this way when no rpm from esc data
|
||||||
if (useDshotTelemetry && rpm == 0) {
|
if (useDshotTelemetry && rpm == 0) {
|
||||||
rpm = getDshotAverageRpm();
|
rpm = lrintf(getDshotRpmAverage());
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -15,6 +15,7 @@
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
extern "C" {
|
extern "C" {
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue