diff --git a/INS_RC_ORIG_README.md b/INS_RC_ORIG_README.md new file mode 100644 index 00000000000..f9093b7456a --- /dev/null +++ b/INS_RC_ORIG_README.md @@ -0,0 +1,156 @@ +# INS_RC_ORIG + +Custom INS fork feature for preserving original RX channel values when `MSP RC Override` is active. + +This branch is intended for local INS builds and flight testing. It is not an upstream INAV feature at this stage. + +## Why this exists + +With standard `MSP RC Override`, the final RC channels seen by the flight controller are the overridden ones. That is fine for control, but it makes it hard for an external computer to also read the pilot's original stick input at the same time. + +`INS_RC_ORIG` solves that by mirroring selected **pre-override** RX channels into spare destination channels. + +Typical use case: + +- channels `1..4` are used for flight control and may be overridden by MSP +- spare channels such as `18`, `19`, `20`, `21` carry the original RX values +- an external controller can read both the overridden controls and the pilot's original inputs over MSP + +## What it does + +The feature adds four configurable copy rules. + +For each rule: + +1. INAV reads and processes normal RX input. +2. A snapshot of the original processed RX channels is stored. +3. `MSP RC Override` is applied normally. +4. The selected original channel is copied into the selected destination channel. + +The destination channel therefore always contains the **original value from before MSP override**. + +## Requirements + +- firmware must be built with `USE_MSP_RC_OVERRIDE` +- `MSP RC Override` must be configured in the normal way if you want channels to be overridden +- destination channels should be spare channels that are not already used for important functions + +## CLI settings + +Four source/destination pairs are available: + +- `rc_orig_src_1` and `rc_orig_dst_1` +- `rc_orig_src_2` and `rc_orig_dst_2` +- `rc_orig_src_3` and `rc_orig_dst_3` +- `rc_orig_src_4` and `rc_orig_dst_4` + +Rules are **1-based** channel numbers: + +- `0` disables the source or destination side of that rule +- valid channel range is `1..34` + +## Recommended setup + +For the common Raspberry Pi use case: + +- keep MSP override on channels `1..4` +- mirror original pilot input to high spare channels + +Example: + +```text +set msp_override_channels = 15 +set rc_orig_src_1 = 1 +set rc_orig_dst_1 = 18 +set rc_orig_src_2 = 2 +set rc_orig_dst_2 = 19 +set rc_orig_src_3 = 3 +set rc_orig_dst_3 = 20 +set rc_orig_src_4 = 4 +set rc_orig_dst_4 = 21 +save +``` + +Meaning: + +- channel `1` may be overridden by MSP +- channel `18` always carries the original value of channel `1` +- channel `2` may be overridden by MSP +- channel `19` always carries the original value of channel `2` +- channel `3` may be overridden by MSP +- channel `20` always carries the original value of channel `3` +- channel `4` may be overridden by MSP +- channel `21` always carries the original value of channel `4` + +## Example with only roll and pitch + +If you only need two original channels: + +```text +set rc_orig_src_1 = 1 +set rc_orig_dst_1 = 18 +set rc_orig_src_2 = 2 +set rc_orig_dst_2 = 19 +set rc_orig_src_3 = 0 +set rc_orig_dst_3 = 0 +set rc_orig_src_4 = 0 +set rc_orig_dst_4 = 0 +save +``` + +## MSP behavior + +`MSP_RC` is extended up to the highest configured destination channel so the mirrored channels are visible to external consumers. + +Example: + +- if your receiver normally exposes 16 channels +- and you mirror to channels `18` and `19` +- `MSP_RC` will return channels up to `19` + +This allows the external controller to read: + +- final overridden channels in their normal positions +- original mirrored channels in the configured destination positions + +## Important behavior notes + +- Destination channels are written **after** MSP override. +- Destination channels contain the original RX value, not the MSP value. +- If `src == dst`, that channel is effectively restored to the original pre-override value after MSP override. +- If a source channel is outside the active RX channel count, that rule is ignored. +- If a destination channel is used for arming, modes, RSSI, gimbal control, or anything else important, the copied value will overwrite that destination every cycle. + +## Recommended safety rules + +- Use only spare AUX channels as destinations. +- Do not map mirrored originals into channels that drive flight modes unless you explicitly want that behavior. +- Bench test with props removed before first flight. +- Verify channel behavior in Configurator and over MSP before airborne testing. + +## Quick verification checklist + +1. Build and flash firmware with `USE_MSP_RC_OVERRIDE`. +2. Set up your normal `MSP RC Override` mode and `msp_override_channels`. +3. Configure the `rc_orig_src_*` and `rc_orig_dst_*` rules. +4. Move the sticks with MSP override disabled and confirm destination channels mirror the source channels. +5. Enable MSP override and confirm: + - source control channels follow MSP override + - destination channels still follow the pilot's original RX input + +## Implementation summary + +Main changes for this feature live in: + +- [src/main/rx/rx.c](src/main/rx/rx.c) +- [src/main/rx/rx.h](src/main/rx/rx.h) +- [src/main/fc/settings.yaml](src/main/fc/settings.yaml) +- [src/main/fc/fc_msp.c](src/main/fc/fc_msp.c) + +## Status + +Current intent: + +- custom INS branch feature +- useful for local builds and Pi-assisted control experiments +- kept separate from upstream until the behavior is proven in real use diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 101c7223372..bf4bf6519d0 100755 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -213,6 +213,8 @@ main_sources(COMMON_SRC drivers/osd.h drivers/persistent.c drivers/persistent.h + drivers/dshot_bidir.c + drivers/dshot_bidir.h drivers/pitotmeter/pitotmeter_adc.c drivers/pitotmeter/pitotmeter_adc.h drivers/pitotmeter/pitotmeter_ms4525.c @@ -462,6 +464,8 @@ main_sources(COMMON_SRC sensors/esc_sensor.h sensors/irlock.c sensors/irlock.h + sensors/rpm_source.c + sensors/rpm_source.h sensors/sensors.c sensors/temperature.c sensors/temperature.h diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index e4c2afb3eec..072a168a8b4 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -81,6 +81,7 @@ #include "sensors/rangefinder.h" #include "sensors/sensors.h" #include "sensors/esc_sensor.h" +#include "sensors/rpm_source.h" #include "flight/wind_estimator.h" #include "sensors/temperature.h" @@ -1428,9 +1429,14 @@ static void loadSlowState(blackboxSlowState_t *slow) #endif #ifdef USE_ESC_SENSOR - escSensorData_t * escSensor = escSensorGetData(); - slow->escRPM = escSensor->rpm; - slow->escTemperature = escSensor->temperature; + uint32_t escRpm = 0; + slow->escRPM = rpmSourceGetAverageRpm(&escRpm) ? escRpm : 0; + slow->escTemperature = TEMPERATURE_INVALID_VALUE / 10; + + escSensorData_t *escSensor = escSensorGetData(); + if (escSensor && escSensor->dataAge <= ESC_DATA_MAX_AGE) { + slow->escTemperature = escSensor->temperature; + } #endif } diff --git a/src/main/build/debug.h b/src/main/build/debug.h index 0bb74bac1ac..1dc73209f55 100644 --- a/src/main/build/debug.h +++ b/src/main/build/debug.h @@ -79,6 +79,7 @@ typedef enum { DEBUG_GPS, DEBUG_LULU, DEBUG_SBUS2, + DEBUG_DSHOT_BIDIR, DEBUG_COUNT // also update debugModeNames in cli.c } debugType_e; diff --git a/src/main/drivers/dshot_bidir.c b/src/main/drivers/dshot_bidir.c new file mode 100644 index 00000000000..40fc4f2675a --- /dev/null +++ b/src/main/drivers/dshot_bidir.c @@ -0,0 +1,761 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include + +#include "platform.h" + +#ifdef USE_DSHOT_BIDIR + +#include "build/debug.h" + +#include "common/time.h" + +#include "drivers/dma.h" +#include "drivers/io.h" +#include "drivers/nvic.h" +#include "drivers/pwm_output.h" +#include "drivers/timer.h" + +#include "flight/mixer.h" +#include "sensors/rpm_source.h" + +#define DSHOT_BIDIR_MOTOR_LIMIT 4 +#define DSHOT_BIDIR_CAPTURE_BUFFER_LEN 32 +#define DSHOT_BIDIR_MIN_GCR_EDGES 7 +#define DSHOT_BIDIR_INVALID 0xFFFF +#define DSHOT_BIDIR_CAPTURE_DEADTIME_US 35 +#define DSHOT_BIDIR_TIMER_BIT_COUNT 16 +#define DSHOT_BIDIR_TIMER_BIT_LENGTH 20 +#define DSHOT_BIDIR_OUTPUT_PERIOD (DSHOT_BIDIR_TIMER_BIT_LENGTH - 1) +#define DSHOT_BIDIR_CAPTURE_FILTER 2 +#define DSHOT_BIDIR_BURST_LENGTH (18 * 4) +#define DSHOT_BIDIR_ERPM_PER_LSB 100.0f + +typedef enum { + DSHOT_BIDIR_STATE_READY = 0, + DSHOT_BIDIR_STATE_OUTPUT_PENDING, + DSHOT_BIDIR_STATE_CAPTURING, +} dshotBidirState_e; + +typedef struct { + TCH_t *tch; + DMA_t dma; + uint16_t dmaSource; + bool useInterruptCapture; + bool configured; + volatile uint8_t irqEdgeCount; + timerCallbacks_t irqCallbacks; + uint32_t captureBuffer[DSHOT_BIDIR_CAPTURE_BUFFER_LEN]; + DMA_InitTypeDef inputDmaInit; +} dshotBidirMotor_t; + +typedef struct { + TIM_TypeDef *timer; + TCH_t *burstTch; + DMA_t burstDma; + timerDMASafeType_t *dmaBurstBuffer; + DMA_InitTypeDef burstOutputDmaInit; + uint32_t captureWindowUs; + timeUs_t frameStartedUs; + volatile timeUs_t captureStartedUs; + volatile dshotBidirState_e state; + bool burstHandlerInstalled; +} dshotBidirContext_t; + +static dshotBidirContext_t dshotBidirCtx; +static dshotBidirMotor_t dshotBidirMotors[DSHOT_BIDIR_MOTOR_LIMIT]; +static const timerCallbacks_t dshotBidirCallbacksDisabled = { 0 }; +static uint32_t dshotBidirReadCount = 0; +static uint32_t dshotBidirInvalidPacketCount = 0; +static uint32_t dshotBidirNoEdgeCount = 0; +static uint32_t dshotBidirTimeoutCount = 0; +static uint8_t dshotBidirLastEdgeCount[DSHOT_BIDIR_MOTOR_LIMIT]; +static uint16_t dshotBidirLastRawValue[DSHOT_BIDIR_MOTOR_LIMIT]; +static uint32_t dshotBidirLastErpmValue[DSHOT_BIDIR_MOTOR_LIMIT]; +static uint32_t dshotBidirLastRpmValue[DSHOT_BIDIR_MOTOR_LIMIT]; + +static void dshotBidirUpdateDebug(uint32_t readDelta, uint32_t invalidDelta, uint32_t noEdgeDelta, uint32_t timeoutDelta) +{ + DEBUG_SET(DEBUG_DSHOT_BIDIR, 0, dshotBidirLastRpmValue[0]); + DEBUG_SET(DEBUG_DSHOT_BIDIR, 1, dshotBidirLastRpmValue[1]); + DEBUG_SET(DEBUG_DSHOT_BIDIR, 2, dshotBidirLastRpmValue[2]); + DEBUG_SET(DEBUG_DSHOT_BIDIR, 3, dshotBidirLastRpmValue[3]); + DEBUG_SET(DEBUG_DSHOT_BIDIR, 4, readDelta); + DEBUG_SET(DEBUG_DSHOT_BIDIR, 5, invalidDelta); + DEBUG_SET(DEBUG_DSHOT_BIDIR, 6, noEdgeDelta); + DEBUG_SET(DEBUG_DSHOT_BIDIR, 7, timeoutDelta); +} + +static uint16_t dshotBidirTimerDmaSource(uint8_t channelIndex) +{ + switch (channelIndex) { + case 0: + return TIM_DMA_CC1; + case 1: + return TIM_DMA_CC2; + case 2: + return TIM_DMA_CC3; + case 3: + return TIM_DMA_CC4; + default: + return 0; + } +} + +static uint16_t dshotBidirTimerChannel(uint8_t channelIndex) +{ + switch (channelIndex) { + case 0: + return TIM_Channel_1; + case 1: + return TIM_Channel_2; + case 2: + return TIM_Channel_3; + case 3: + return TIM_Channel_4; + default: + return TIM_Channel_1; + } +} + +static uint32_t dshotBidirDecodeTelemetryPacket(const uint32_t buffer[], uint32_t count) +{ + uint32_t value = 0; + uint32_t oldValue = buffer[0]; + int bits = 0; + int len; + + for (uint32_t i = 1; i <= count; i++) { + if (i < count) { + const int diff = buffer[i] - oldValue; + if (bits >= 21) { + break; + } + len = (diff + 8) / 16; + } else { + len = 21 - bits; + } + + if (len <= 0 || (bits + len) > 21) { + return DSHOT_BIDIR_INVALID; + } + + value <<= len; + value |= 1 << (len - 1); + oldValue = buffer[i]; + bits += len; + } + + if (bits != 21) { + return DSHOT_BIDIR_INVALID; + } + + static const uint32_t decodeTable[32] = { + 0, 0, 0, 0, 0, 0, 0, 0, 0, 9, 10, 11, 0, 13, 14, 15, + 0, 0, 2, 3, 0, 5, 6, 7, 0, 0, 8, 1, 0, 4, 12, 0 + }; + + uint32_t decodedValue = decodeTable[value & 0x1f]; + decodedValue |= decodeTable[(value >> 5) & 0x1f] << 4; + decodedValue |= decodeTable[(value >> 10) & 0x1f] << 8; + decodedValue |= decodeTable[(value >> 15) & 0x1f] << 12; + + uint32_t csum = decodedValue; + csum ^= csum >> 8; + csum ^= csum >> 4; + + if ((csum & 0xf) != 0xf) { + return DSHOT_BIDIR_INVALID; + } + + return decodedValue >> 4; +} + +static uint32_t dshotBidirDecodeErpmTelemetryValue(uint16_t value) +{ + if (value == 0x0fff) { + return 0; + } + + value = (value & 0x01ff) << ((value & 0xfe00) >> 9); + if (!value) { + return DSHOT_BIDIR_INVALID; + } + + return (1000000U * 60U / 100U + value / 2U) / value; +} + +static uint32_t dshotBidirComputeRpm(uint32_t erpm) +{ + const uint8_t polePairs = motorConfig()->motorPoleCount / 2; + + if (polePairs == 0) { + return 0; + } + + return lrintf((float)erpm * DSHOT_BIDIR_ERPM_PER_LSB / polePairs); +} + +static bool dshotBidirOutputInverted(const dshotBidirMotor_t *motor) +{ + return (motor->tch->timHw->output & TIMER_OUTPUT_INVERTED) == 0; +} + +static ioConfig_t dshotBidirGetIoConfig(const dshotBidirMotor_t *motor) +{ + return (motor->tch->timHw->output & TIMER_OUTPUT_INVERTED) ? IOCFG_AF_PP_PD : IOCFG_AF_PP_UP; +} + +static void dshotBidirConfigureOutputIo(const dshotBidirMotor_t *motor) +{ + const IO_t io = IOGetByTag(motor->tch->timHw->tag); + IOConfigGPIOAF(io, dshotBidirGetIoConfig(motor), motor->tch->timHw->alternateFunction); +} + +static void dshotBidirConfigureOutputChannel(const dshotBidirMotor_t *motor, uint16_t value) +{ + TIM_OCInitTypeDef outputInit; + + TIM_OCStructInit(&outputInit); + outputInit.TIM_OCMode = TIM_OCMode_PWM1; + outputInit.TIM_Pulse = value; + + if (motor->tch->timHw->output & TIMER_OUTPUT_N_CHANNEL) { + outputInit.TIM_OutputState = TIM_OutputState_Disable; + outputInit.TIM_OutputNState = TIM_OutputNState_Enable; + outputInit.TIM_OCNPolarity = dshotBidirOutputInverted(motor) ? TIM_OCPolarity_Low : TIM_OCPolarity_High; + outputInit.TIM_OCNIdleState = TIM_OCIdleState_Reset; + } else { + outputInit.TIM_OutputState = TIM_OutputState_Enable; + outputInit.TIM_OutputNState = TIM_OutputState_Disable; + outputInit.TIM_OCPolarity = dshotBidirOutputInverted(motor) ? TIM_OCPolarity_Low : TIM_OCPolarity_High; + outputInit.TIM_OCIdleState = TIM_OCIdleState_Set; + } + + switch (motor->tch->timHw->channelIndex) { + case 0: + TIM_OC1Init(motor->tch->timHw->tim, &outputInit); + TIM_OC1PreloadConfig(motor->tch->timHw->tim, TIM_OCPreload_Enable); + break; + case 1: + TIM_OC2Init(motor->tch->timHw->tim, &outputInit); + TIM_OC2PreloadConfig(motor->tch->timHw->tim, TIM_OCPreload_Enable); + break; + case 2: + TIM_OC3Init(motor->tch->timHw->tim, &outputInit); + TIM_OC3PreloadConfig(motor->tch->timHw->tim, TIM_OCPreload_Enable); + break; + case 3: + TIM_OC4Init(motor->tch->timHw->tim, &outputInit); + TIM_OC4PreloadConfig(motor->tch->timHw->tim, TIM_OCPreload_Enable); + break; + } +} + +static void dshotBidirInvalidateAll(void) +{ + for (uint8_t i = 0; i < DSHOT_BIDIR_MOTOR_LIMIT; i++) { + rpmSourceInvalidateDshotBidir(i); + } +} + +static void dshotBidirIrqCaptureCallback(TCH_t *tch, uint32_t value) +{ + if (dshotBidirCtx.state != DSHOT_BIDIR_STATE_CAPTURING) { + return; + } + + for (uint8_t i = 0; i < DSHOT_BIDIR_MOTOR_LIMIT; i++) { + dshotBidirMotor_t *motor = &dshotBidirMotors[i]; + if (!motor->configured || !motor->useInterruptCapture || motor->tch != tch) { + continue; + } + + const uint8_t edgeCount = motor->irqEdgeCount; + if (edgeCount < DSHOT_BIDIR_CAPTURE_BUFFER_LEN) { + motor->captureBuffer[edgeCount] = value; + motor->irqEdgeCount = edgeCount + 1; + } + return; + } +} + +static void dshotBidirConfigureInputCapture(TCH_t *tch) +{ + TIM_ICInitTypeDef icInit; + + TIM_ICStructInit(&icInit); + icInit.TIM_Channel = dshotBidirTimerChannel(tch->timHw->channelIndex); + icInit.TIM_ICPolarity = TIM_ICPolarity_BothEdge; + icInit.TIM_ICSelection = TIM_ICSelection_DirectTI; + icInit.TIM_ICPrescaler = TIM_ICPSC_DIV1; + icInit.TIM_ICFilter = DSHOT_BIDIR_CAPTURE_FILTER; + + TIM_ICInit(tch->timHw->tim, &icInit); +} + +static void dshotBidirRestoreOutputChannel(dshotBidirMotor_t *motor) +{ + if (!motor->configured) { + return; + } + + timerChCaptureDisable(motor->tch); + if (motor->useInterruptCapture) { + timerChConfigCallbacks(motor->tch, (timerCallbacks_t *)&dshotBidirCallbacksDisabled); + } + + dshotBidirConfigureOutputIo(motor); + dshotBidirConfigureOutputChannel(motor, 0); + timerPWMStart(motor->tch); +} + +static void dshotBidirRestoreBurstDma(void) +{ + if (!dshotBidirCtx.burstDma || !dshotBidirCtx.dmaBurstBuffer) { + return; + } + + DMA_Cmd(dshotBidirCtx.burstDma->ref, DISABLE); + TIM_DMACmd(dshotBidirCtx.timer, dshotBidirCtx.burstTch->timCtx->DMASource, DISABLE); + DMA_DeInit(dshotBidirCtx.burstDma->ref); + DMA_Init(dshotBidirCtx.burstDma->ref, &dshotBidirCtx.burstOutputDmaInit); + DMA_ITConfig(dshotBidirCtx.burstDma->ref, DMA_IT_TC, ENABLE); +} + +static void dshotBidirStartInputCapture(void) +{ + TIM_TypeDef *timer = dshotBidirCtx.timer; + + if (!timer) { + dshotBidirCtx.state = DSHOT_BIDIR_STATE_READY; + return; + } + + TIM_ARRPreloadConfig(timer, ENABLE); + timer->ARR = 0xFFFF; + TIM_SetCounter(timer, 0); + + for (uint8_t i = 0; i < DSHOT_BIDIR_MOTOR_LIMIT; i++) { + dshotBidirMotor_t *motor = &dshotBidirMotors[i]; + if (!motor->configured) { + continue; + } + + memset(motor->captureBuffer, 0, sizeof(motor->captureBuffer)); + motor->irqEdgeCount = 0; + dshotBidirConfigureInputCapture(motor->tch); + + if (motor->useInterruptCapture) { + timerChConfigCallbacks(motor->tch, &motor->irqCallbacks); + timerChCaptureEnable(motor->tch); + continue; + } + + DMA_Cmd(motor->dma->ref, DISABLE); + TIM_DMACmd(timer, motor->dmaSource, DISABLE); + DMA_DeInit(motor->dma->ref); + DMA_Init(motor->dma->ref, &motor->inputDmaInit); + DMA_ITConfig(motor->dma->ref, DMA_IT_TC, DISABLE); + DMA_Cmd(motor->dma->ref, ENABLE); + TIM_DMACmd(timer, motor->dmaSource, ENABLE); + } + + dshotBidirCtx.captureStartedUs = micros(); + dshotBidirCtx.state = DSHOT_BIDIR_STATE_CAPTURING; +} + +static void dshotBidirRestoreReadyState(void) +{ + if (dshotBidirCtx.timer) { + dshotBidirCtx.timer->ARR = DSHOT_BIDIR_OUTPUT_PERIOD; + TIM_SetCounter(dshotBidirCtx.timer, 0); + } + + dshotBidirRestoreBurstDma(); + + for (uint8_t i = 0; i < DSHOT_BIDIR_MOTOR_LIMIT; i++) { + dshotBidirRestoreOutputChannel(&dshotBidirMotors[i]); + } + + dshotBidirCtx.state = DSHOT_BIDIR_STATE_READY; +} + +static uint32_t dshotBidirGetCapturedEdgeCount(const dshotBidirMotor_t *motor) +{ + if (motor->useInterruptCapture) { + return motor->irqEdgeCount; + } + + return DSHOT_BIDIR_CAPTURE_BUFFER_LEN - DMA_GetCurrDataCounter(motor->dma->ref); +} + +static void dshotBidirStopInputCapture(void) +{ + for (uint8_t i = 0; i < DSHOT_BIDIR_MOTOR_LIMIT; i++) { + dshotBidirMotor_t *motor = &dshotBidirMotors[i]; + if (!motor->configured) { + continue; + } + + if (motor->useInterruptCapture) { + timerChCaptureDisable(motor->tch); + timerChConfigCallbacks(motor->tch, (timerCallbacks_t *)&dshotBidirCallbacksDisabled); + continue; + } + + DMA_Cmd(motor->dma->ref, DISABLE); + TIM_DMACmd(dshotBidirCtx.timer, motor->dmaSource, DISABLE); + } +} + +static void dshotBidirDecodeCapture(void) +{ + uint32_t readDelta = 0; + uint32_t invalidDelta = 0; + uint32_t noEdgeDelta = 0; + + for (uint8_t i = 0; i < DSHOT_BIDIR_MOTOR_LIMIT; i++) { + dshotBidirMotor_t *motor = &dshotBidirMotors[i]; + if (!motor->configured) { + rpmSourceInvalidateDshotBidir(i); + dshotBidirLastEdgeCount[i] = 0; + dshotBidirLastRawValue[i] = 0; + dshotBidirLastErpmValue[i] = 0; + dshotBidirLastRpmValue[i] = 0; + continue; + } + + const uint32_t edgeCount = dshotBidirGetCapturedEdgeCount(motor); + dshotBidirLastEdgeCount[i] = edgeCount; + if (edgeCount <= DSHOT_BIDIR_MIN_GCR_EDGES) { + dshotBidirNoEdgeCount++; + noEdgeDelta++; + rpmSourceInvalidateDshotBidir(i); + dshotBidirLastRawValue[i] = 0; + dshotBidirLastErpmValue[i] = 0; + dshotBidirLastRpmValue[i] = 0; + continue; + } + + dshotBidirReadCount++; + readDelta++; + const uint32_t rawValue = dshotBidirDecodeTelemetryPacket(motor->captureBuffer, edgeCount); + if (rawValue == DSHOT_BIDIR_INVALID) { + dshotBidirInvalidPacketCount++; + invalidDelta++; + rpmSourceInvalidateDshotBidir(i); + dshotBidirLastRawValue[i] = 0; + dshotBidirLastErpmValue[i] = 0; + dshotBidirLastRpmValue[i] = 0; + continue; + } + + const uint32_t erpm = dshotBidirDecodeErpmTelemetryValue((uint16_t)rawValue); + if (erpm == DSHOT_BIDIR_INVALID) { + dshotBidirInvalidPacketCount++; + invalidDelta++; + rpmSourceInvalidateDshotBidir(i); + dshotBidirLastRawValue[i] = (uint16_t)rawValue; + dshotBidirLastErpmValue[i] = 0; + dshotBidirLastRpmValue[i] = 0; + continue; + } + + const uint32_t rpm = dshotBidirComputeRpm(erpm); + dshotBidirLastRawValue[i] = (uint16_t)rawValue; + dshotBidirLastErpmValue[i] = erpm; + dshotBidirLastRpmValue[i] = rpm; + rpmSourceSetDshotBidirRpm(i, rpm); + } + + dshotBidirUpdateDebug(readDelta, invalidDelta, noEdgeDelta, 0); +} + +static void dshotBidirBurstDmaHandler(DMA_t descriptor) +{ + if (!DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) { + return; + } + + DMA_Cmd(descriptor->ref, DISABLE); + TIM_DMACmd(dshotBidirCtx.timer, dshotBidirCtx.burstTch->timCtx->DMASource, DISABLE); + DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF); + + if (dshotBidirCtx.state == DSHOT_BIDIR_STATE_OUTPUT_PENDING) { + dshotBidirStartInputCapture(); + } +} + +void dshotBidirInit(uint32_t dshotHz) +{ + memset(&dshotBidirCtx, 0, sizeof(dshotBidirCtx)); + memset(dshotBidirMotors, 0, sizeof(dshotBidirMotors)); + memset(dshotBidirLastEdgeCount, 0, sizeof(dshotBidirLastEdgeCount)); + memset(dshotBidirLastRawValue, 0, sizeof(dshotBidirLastRawValue)); + memset(dshotBidirLastErpmValue, 0, sizeof(dshotBidirLastErpmValue)); + memset(dshotBidirLastRpmValue, 0, sizeof(dshotBidirLastRpmValue)); + dshotBidirReadCount = 0; + dshotBidirInvalidPacketCount = 0; + dshotBidirNoEdgeCount = 0; + dshotBidirTimeoutCount = 0; + + dshotBidirCtx.captureWindowUs = DSHOT_BIDIR_CAPTURE_DEADTIME_US + + (1000000U * (DSHOT_BIDIR_TIMER_BIT_COUNT * DSHOT_BIDIR_TIMER_BIT_LENGTH)) / dshotHz; + dshotBidirCtx.state = DSHOT_BIDIR_STATE_READY; + dshotBidirUpdateDebug(0, 0, 0, 0); +} + +bool dshotBidirAttachMotor(uint8_t motorIndex, TCH_t *tch, void *dmaBurstBuffer) +{ + if (motorIndex >= DSHOT_BIDIR_MOTOR_LIMIT || !tch || tch->timHw->tim != TIM4) { + return false; + } + + dshotBidirMotor_t *motor = &dshotBidirMotors[motorIndex]; + + motor->tch = tch; + motor->dmaSource = dshotBidirTimerDmaSource(tch->timHw->channelIndex); + motor->dma = (tch->timHw->dmaTag != DMA_NONE) ? dmaGetByTag(tch->timHw->dmaTag) : NULL; + motor->useInterruptCapture = (motor->dma == NULL); + motor->irqCallbacks.callbackEdge = dshotBidirIrqCaptureCallback; + + if (!motor->useInterruptCapture) { + if (motor->dma != tch->timCtx->dmaBurstRef) { + if (dmaGetOwner(motor->dma) != OWNER_FREE) { + return false; + } + + dmaInit(motor->dma, OWNER_TIMER, motorIndex); + } + + DMA_StructInit(&motor->inputDmaInit); + motor->inputDmaInit.DMA_Channel = dmaGetChannelByTag(tch->timHw->dmaTag); + motor->inputDmaInit.DMA_PeripheralBaseAddr = (uint32_t)timerCCR(tch); + motor->inputDmaInit.DMA_Memory0BaseAddr = (uint32_t)motor->captureBuffer; + motor->inputDmaInit.DMA_DIR = DMA_DIR_PeripheralToMemory; + motor->inputDmaInit.DMA_BufferSize = DSHOT_BIDIR_CAPTURE_BUFFER_LEN; + motor->inputDmaInit.DMA_PeripheralInc = DMA_PeripheralInc_Disable; + motor->inputDmaInit.DMA_MemoryInc = DMA_MemoryInc_Enable; + motor->inputDmaInit.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word; + motor->inputDmaInit.DMA_MemoryDataSize = DMA_MemoryDataSize_Word; + motor->inputDmaInit.DMA_Mode = DMA_Mode_Normal; + motor->inputDmaInit.DMA_Priority = DMA_Priority_High; + } + + if (!dshotBidirCtx.timer) { + dshotBidirCtx.timer = tch->timHw->tim; + } + + if (!dshotBidirCtx.burstDma && tch->timCtx->dmaBurstRef && dmaBurstBuffer && motor->dma == tch->timCtx->dmaBurstRef) { + dshotBidirCtx.burstDma = tch->timCtx->dmaBurstRef; + dshotBidirCtx.burstTch = tch; + dshotBidirCtx.dmaBurstBuffer = (timerDMASafeType_t *)dmaBurstBuffer; + + DMA_StructInit(&dshotBidirCtx.burstOutputDmaInit); + dshotBidirCtx.burstOutputDmaInit.DMA_Channel = dmaGetChannelByTag(tch->timHw->dmaTag); + dshotBidirCtx.burstOutputDmaInit.DMA_PeripheralBaseAddr = (uint32_t)&tch->timHw->tim->DMAR; + dshotBidirCtx.burstOutputDmaInit.DMA_Memory0BaseAddr = (uint32_t)dmaBurstBuffer; + dshotBidirCtx.burstOutputDmaInit.DMA_DIR = DMA_DIR_MemoryToPeripheral; + dshotBidirCtx.burstOutputDmaInit.DMA_BufferSize = DSHOT_BIDIR_BURST_LENGTH; + dshotBidirCtx.burstOutputDmaInit.DMA_PeripheralInc = DMA_PeripheralInc_Disable; + dshotBidirCtx.burstOutputDmaInit.DMA_MemoryInc = DMA_MemoryInc_Enable; + dshotBidirCtx.burstOutputDmaInit.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word; + dshotBidirCtx.burstOutputDmaInit.DMA_MemoryDataSize = DMA_MemoryDataSize_Word; + dshotBidirCtx.burstOutputDmaInit.DMA_Mode = DMA_Mode_Normal; + dshotBidirCtx.burstOutputDmaInit.DMA_Priority = DMA_Priority_High; + + dmaSetHandler(dshotBidirCtx.burstDma, dshotBidirBurstDmaHandler, NVIC_PRIO_TIMER_DMA, 0); + dshotBidirCtx.burstHandlerInstalled = true; + } + + motor->configured = true; + dshotBidirConfigureOutputIo(motor); + dshotBidirConfigureOutputChannel(motor, 0); + timerPWMStart(motor->tch); + return dshotBidirCtx.burstHandlerInstalled; +} + +bool dshotBidirUpdate(void) +{ + const timeUs_t now = micros(); + + if (dshotBidirCtx.state == DSHOT_BIDIR_STATE_OUTPUT_PENDING) { + if (cmpTimeUs(now, dshotBidirCtx.frameStartedUs) < (timeDelta_t)dshotBidirCtx.captureWindowUs) { + return false; + } + + dshotBidirTimeoutCount++; + dshotBidirInvalidateAll(); + dshotBidirUpdateDebug(0, 0, 0, 1); + dshotBidirRestoreReadyState(); + return true; + } + + if (dshotBidirCtx.state != DSHOT_BIDIR_STATE_CAPTURING) { + return true; + } + + if (cmpTimeUs(now, dshotBidirCtx.captureStartedUs) < (timeDelta_t)dshotBidirCtx.captureWindowUs) { + return false; + } + + dshotBidirStopInputCapture(); + dshotBidirDecodeCapture(); + dshotBidirRestoreReadyState(); + return true; +} + +void dshotBidirOnFrameStarted(void) +{ + dshotBidirCtx.frameStartedUs = micros(); + dshotBidirCtx.state = DSHOT_BIDIR_STATE_OUTPUT_PENDING; +} + +uint32_t dshotBidirGetReadCount(void) +{ + return dshotBidirReadCount; +} + +uint32_t dshotBidirGetInvalidPacketCount(void) +{ + return dshotBidirInvalidPacketCount; +} + +uint32_t dshotBidirGetNoEdgeCount(void) +{ + return dshotBidirNoEdgeCount; +} + +uint32_t dshotBidirGetTimeoutCount(void) +{ + return dshotBidirTimeoutCount; +} + +uint8_t dshotBidirGetLastEdgeCount(uint8_t motorIndex) +{ + if (motorIndex >= DSHOT_BIDIR_MOTOR_LIMIT) { + return 0; + } + + return dshotBidirLastEdgeCount[motorIndex]; +} + +uint16_t dshotBidirGetLastRawValue(uint8_t motorIndex) +{ + if (motorIndex >= DSHOT_BIDIR_MOTOR_LIMIT) { + return 0; + } + + return dshotBidirLastRawValue[motorIndex]; +} + +uint32_t dshotBidirGetLastErpmValue(uint8_t motorIndex) +{ + if (motorIndex >= DSHOT_BIDIR_MOTOR_LIMIT) { + return 0; + } + + return dshotBidirLastErpmValue[motorIndex]; +} + +uint32_t dshotBidirGetLastRpmValue(uint8_t motorIndex) +{ + if (motorIndex >= DSHOT_BIDIR_MOTOR_LIMIT) { + return 0; + } + + return dshotBidirLastRpmValue[motorIndex]; +} + +#else + +void dshotBidirInit(uint32_t dshotHz) +{ + UNUSED(dshotHz); +} + +bool dshotBidirAttachMotor(uint8_t motorIndex, TCH_t *tch, void *dmaBurstBuffer) +{ + UNUSED(motorIndex); + UNUSED(tch); + UNUSED(dmaBurstBuffer); + return false; +} + +bool dshotBidirUpdate(void) +{ + return true; +} + +void dshotBidirOnFrameStarted(void) +{ +} + +uint32_t dshotBidirGetReadCount(void) +{ + return 0; +} + +uint32_t dshotBidirGetInvalidPacketCount(void) +{ + return 0; +} + +uint32_t dshotBidirGetNoEdgeCount(void) +{ + return 0; +} + +uint32_t dshotBidirGetTimeoutCount(void) +{ + return 0; +} + +uint8_t dshotBidirGetLastEdgeCount(uint8_t motorIndex) +{ + UNUSED(motorIndex); + return 0; +} + +uint16_t dshotBidirGetLastRawValue(uint8_t motorIndex) +{ + UNUSED(motorIndex); + return 0; +} + +uint32_t dshotBidirGetLastErpmValue(uint8_t motorIndex) +{ + UNUSED(motorIndex); + return 0; +} + +uint32_t dshotBidirGetLastRpmValue(uint8_t motorIndex) +{ + UNUSED(motorIndex); + return 0; +} + +#endif diff --git a/src/main/drivers/dshot_bidir.h b/src/main/drivers/dshot_bidir.h new file mode 100644 index 00000000000..f8cd59071a6 --- /dev/null +++ b/src/main/drivers/dshot_bidir.h @@ -0,0 +1,19 @@ +#pragma once + +#include +#include + +#include "drivers/timer.h" + +void dshotBidirInit(uint32_t dshotHz); +bool dshotBidirAttachMotor(uint8_t motorIndex, TCH_t *tch, void *dmaBurstBuffer); +bool dshotBidirUpdate(void); +void dshotBidirOnFrameStarted(void); +uint32_t dshotBidirGetReadCount(void); +uint32_t dshotBidirGetInvalidPacketCount(void); +uint32_t dshotBidirGetNoEdgeCount(void); +uint32_t dshotBidirGetTimeoutCount(void); +uint8_t dshotBidirGetLastEdgeCount(uint8_t motorIndex); +uint16_t dshotBidirGetLastRawValue(uint8_t motorIndex); +uint32_t dshotBidirGetLastErpmValue(uint8_t motorIndex); +uint32_t dshotBidirGetLastRpmValue(uint8_t motorIndex); diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 619f4b95db5..14b710f0fd4 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -31,6 +31,7 @@ #include "common/circular_queue.h" #include "drivers/io.h" +#include "drivers/dshot_bidir.h" #include "drivers/timer.h" #include "drivers/pwm_mapping.h" #include "drivers/pwm_output.h" @@ -114,6 +115,8 @@ static uint16_t beeperFrequency = 0; static uint8_t allocatedOutputPortCount = 0; static bool pwmMotorsEnabled = true; +static bool dshotBidirModeActive = false; +static uint8_t dshotBidirConfiguredMotorCount = 0; #ifdef USE_DSHOT static timeUs_t digitalMotorUpdateIntervalUs = 0; @@ -348,6 +351,12 @@ static uint16_t prepareDshotPacket(const uint16_t value, bool requestTelemetry) } csum &= 0xf; +#ifdef USE_DSHOT_BIDIR + if (dshotBidirModeActive) { + csum = (~csum) & 0xf; + } +#endif + // append checksum packet = (packet << 4) | csum; @@ -381,6 +390,15 @@ bool isMotorProtocolDigital(void) return isMotorProtocolDshot(); } +bool isDshotBidirModeActive(void) +{ +#ifdef USE_DSHOT_BIDIR + return dshotBidirModeActive && dshotBidirConfiguredMotorCount == getMotorCount(); +#else + return false; +#endif +} + void pwmRequestMotorTelemetry(int motorIndex) { if (!isMotorProtocolDigital()) { @@ -465,6 +483,12 @@ void pwmCompleteMotorUpdate(void) { return; } +#ifdef USE_DSHOT_BIDIR + if (dshotBidirModeActive && !dshotBidirUpdate()) { + return; + } +#endif + int motorCount = getMotorCount(); timeUs_t currentTimeUs = micros(); @@ -485,12 +509,18 @@ void pwmCompleteMotorUpdate(void) { #ifdef USE_DSHOT_DMAR for (int index = 0; index < motorCount; index++) { if (motors[index].pwmPort && motors[index].pwmPort->configured) { - uint16_t packet = prepareDshotPacket(motors[index].value, motors[index].requestTelemetry); + const bool requestTelemetry = dshotBidirModeActive || motors[index].requestTelemetry; + uint16_t packet = prepareDshotPacket(motors[index].value, requestTelemetry); loadDmaBufferDshotStride(&motors[index].pwmPort->dmaBurstBuffer[motors[index].pwmPort->tch->timHw->channelIndex], 4, packet); motors[index].requestTelemetry = false; } } +#ifdef USE_DSHOT_BIDIR + if (dshotBidirModeActive) { + dshotBidirOnFrameStarted(); + } +#endif for (int burstDmaTimerIndex = 0; burstDmaTimerIndex < burstDmaTimersCount; burstDmaTimerIndex++) { burstDmaTimer_t *burstDmaTimer = &burstDmaTimers[burstDmaTimerIndex]; pwmBurstDMAStart(burstDmaTimer, DSHOT_DMA_BUFFER_SIZE * 4); @@ -499,7 +529,8 @@ void pwmCompleteMotorUpdate(void) { // Generate DMA buffers for (int index = 0; index < motorCount; index++) { if (motors[index].pwmPort && motors[index].pwmPort->configured) { - uint16_t packet = prepareDshotPacket(motors[index].value, motors[index].requestTelemetry); + const bool requestTelemetry = dshotBidirModeActive || motors[index].requestTelemetry; + uint16_t packet = prepareDshotPacket(motors[index].value, requestTelemetry); loadDmaBufferDshot(motors[index].pwmPort->dmaBuffer, packet); timerPWMPrepareDMA(motors[index].pwmPort->tch, DSHOT_DMA_BUFFER_SIZE); motors[index].requestTelemetry = false; @@ -532,6 +563,23 @@ void pwmMotorPreconfigure(void) // Keep track of initial motor protocol initMotorProtocol = motorConfig()->motorPwmProtocol; +#ifdef USE_DSHOT_BIDIR + dshotBidirModeActive = motorConfig()->dshotBidirEnabled && + initMotorProtocol >= PWM_TYPE_DSHOT150 && + initMotorProtocol <= PWM_TYPE_DSHOT600 && + getMotorCount() > 0 && + getMotorCount() <= 4; + dshotBidirConfiguredMotorCount = 0; + + if (dshotBidirModeActive && initMotorProtocol == PWM_TYPE_DSHOT600) { + initMotorProtocol = PWM_TYPE_DSHOT300; + } + + if (dshotBidirModeActive) { + dshotBidirInit(getDshotHz(initMotorProtocol)); + } +#endif + #ifdef BRUSHED_MOTORS initMotorProtocol = PWM_TYPE_BRUSHED; // Override proto #endif @@ -592,6 +640,14 @@ uint32_t getEscUpdateFrequency(void) { bool pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, bool enableOutput) { +#ifdef USE_DSHOT_BIDIR + if (dshotBidirModeActive) { + if (motorIndex >= 4 || timerHardware->tim != TIM4) { + return false; + } + } +#endif + switch (initMotorProtocol) { case PWM_TYPE_BRUSHED: motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 0.0f, 0.0f, getEscUpdateFrequency(), enableOutput); @@ -622,6 +678,20 @@ bool pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, bo break; } +#ifdef USE_DSHOT_BIDIR + if (dshotBidirModeActive && motors[motorIndex].pwmPort != NULL) { + timerDMASafeType_t *dmaBurstBufferForMotor = NULL; + +#ifdef USE_DSHOT_DMAR + dmaBurstBufferForMotor = motors[motorIndex].pwmPort->dmaBurstBuffer; +#endif + + if (dshotBidirAttachMotor(motorIndex, motors[motorIndex].pwmPort->tch, dmaBurstBufferForMotor)) { + dshotBidirConfiguredMotorCount++; + } + } +#endif + return (motors[motorIndex].pwmPort != NULL); } diff --git a/src/main/drivers/pwm_output.h b/src/main/drivers/pwm_output.h index 1041ace04fa..a5224799dff 100644 --- a/src/main/drivers/pwm_output.h +++ b/src/main/drivers/pwm_output.h @@ -45,6 +45,7 @@ void pwmShutdownPulsesForAllMotors(uint8_t motorCount); void pwmCompleteMotorUpdate(void); bool isMotorProtocolDigital(void); bool isMotorProtocolDshot(void); +bool isDshotBidirModeActive(void); void pwmWriteServo(uint8_t index, uint16_t value); @@ -63,4 +64,4 @@ void beeperPwmInit(ioTag_t tag, uint16_t frequency); void sendDShotCommand(dshotCommands_e cmd); void initDShotCommands(void); -uint32_t getEscUpdateFrequency(void); \ No newline at end of file +uint32_t getEscUpdateFrequency(void); diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 6c60f08c6ed..983f96d50fd 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -55,6 +55,7 @@ bool cliMode = false; #include "drivers/buf_writer.h" #include "drivers/bus_i2c.h" #include "drivers/compass/compass.h" +#include "drivers/dshot_bidir.h" #include "drivers/flash.h" #include "drivers/io.h" #include "drivers/io_impl.h" @@ -82,6 +83,7 @@ bool cliMode = false; #include "flight/failsafe.h" #include "flight/imu.h" +#include "flight/mixer.h" #include "flight/mixer_profile.h" #include "flight/pid.h" #include "flight/servos.h" @@ -117,6 +119,7 @@ bool cliMode = false; #include "sensors/gyro.h" #include "sensors/pitotmeter.h" #include "sensors/rangefinder.h" +#include "sensors/rpm_source.h" #include "sensors/opflow.h" #include "sensors/sensors.h" #include "sensors/temperature.h" @@ -219,7 +222,8 @@ static const char *debugModeNames[DEBUG_COUNT] = { "HEADTRACKER", "GPS", "LULU", - "SBUS2" + "SBUS2", + "DSHOT_BIDIR" }; /* Sensor names (used in lookup tables for *_hardware settings and in status @@ -4126,6 +4130,35 @@ static void cliStatus(char *cmdline) } #endif +#ifdef USE_DSHOT_BIDIR + cliPrintLinef("DShot Bidir: requested=%s, configured=%s, active=%s, valid motors=%u, reads=%lu, invalid=%lu, noedge=%lu, timeouts=%lu, edges=%u/%u/%u/%u", + motorConfig()->dshotBidirEnabled ? "ON" : "OFF", + rpmSourceIsDshotBidirConfigured() ? "YES" : "NO", + rpmSourceIsDshotBidirActive() ? "YES" : "NO", + rpmSourceGetDshotBidirValidCount(), + dshotBidirGetReadCount(), + dshotBidirGetInvalidPacketCount(), + dshotBidirGetNoEdgeCount(), + dshotBidirGetTimeoutCount(), + dshotBidirGetLastEdgeCount(0), + dshotBidirGetLastEdgeCount(1), + dshotBidirGetLastEdgeCount(2), + dshotBidirGetLastEdgeCount(3)); + cliPrintLinef("DShot Bidir Data: raw=%u/%u/%u/%u, erpm=%lu/%lu/%lu/%lu, rpm=%lu/%lu/%lu/%lu", + dshotBidirGetLastRawValue(0), + dshotBidirGetLastRawValue(1), + dshotBidirGetLastRawValue(2), + dshotBidirGetLastRawValue(3), + dshotBidirGetLastErpmValue(0), + dshotBidirGetLastErpmValue(1), + dshotBidirGetLastErpmValue(2), + dshotBidirGetLastErpmValue(3), + dshotBidirGetLastRpmValue(0), + dshotBidirGetLastRpmValue(1), + dshotBidirGetLastRpmValue(2), + dshotBidirGetLastRpmValue(3)); +#endif + #ifdef USE_SDCARD cliSdInfo(NULL); #endif diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index a8ca6c0c199..29481e0b5e9 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -144,6 +144,7 @@ #include "sensors/initialisation.h" #include "sensors/pitotmeter.h" #include "sensors/rangefinder.h" +#include "sensors/rpm_source.h" #include "sensors/sensors.h" #include "sensors/esc_sensor.h" @@ -728,7 +729,8 @@ void init(void) #ifdef USE_RPM_FILTER disableRpmFilters(); - if (STATE(ESC_SENSOR_ENABLED) && (rpmFilterConfig()->gyro_filter_enabled || rpmFilterConfig()->dterm_filter_enabled)) { + rpmSourceResetDshotBidir(); + if (rpmSourceIsConfigured() && (rpmFilterConfig()->gyro_filter_enabled || rpmFilterConfig()->dterm_filter_enabled)) { rpmFiltersInit(); setTaskEnabled(TASK_RPM_FILTER, true); } diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 455d5f20897..61acf74ca99 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -131,6 +131,7 @@ #include "sensors/opflow.h" #include "sensors/temperature.h" #include "sensors/esc_sensor.h" +#include "sensors/rpm_source.h" #include "telemetry/telemetry.h" @@ -666,7 +667,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF break; case MSP_RC: - for (int i = 0; i < rxRuntimeConfig.channelCount; i++) { + for (int i = 0; i < rxGetChannelCount(); i++) { sbufWriteU16(dst, rxGetChannelValue(i)); } break; @@ -1732,8 +1733,9 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF uint8_t motorCount = getMotorCount(); for (uint8_t i = 0; i < motorCount; i++){ - const escSensorData_t *escState = getEscTelemetry(i); //Get ESC telemetry - sbufWriteU32(dst, escState->rpm); + uint32_t rpm = 0; + rpmSourceGetMotorRpm(i, &rpm); + sbufWriteU32(dst, rpm); } } break; @@ -1744,8 +1746,30 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU8(dst, motorCount); for (uint8_t i = 0; i < motorCount; i++){ - const escSensorData_t *escState = getEscTelemetry(i); //Get ESC telemetry - sbufWriteDataSafe(dst, escState, sizeof(escSensorData_t)); + escSensorData_t escState = { + .dataAge = ESC_DATA_INVALID, + .temperature = 0, + .voltage = 0, + .current = 0, + .rpm = 0, + }; + + if (STATE(ESC_SENSOR_ENABLED)) { + const escSensorData_t *serialEscState = getEscTelemetry(i); + if (serialEscState != NULL) { + escState = *serialEscState; + } + } + + if (escState.dataAge >= ESC_DATA_INVALID) { + uint32_t rpm = 0; + if (rpmSourceGetMotorRpm(i, &rpm)) { + escState.dataAge = 0; + escState.rpm = rpm; + } + } + + sbufWriteDataSafe(dst, &escState, sizeof(escSensorData_t)); } } break; diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 1e1932531e5..852c50b7b2c 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -794,6 +794,54 @@ groups: condition: USE_MSP_RC_OVERRIDE min: 0 max: UINT32_MAX + - name: rc_orig_src_1 + description: "Source RC channel copied before MSP override. Set to 0 to disable this copy rule." + field: rcOrigSrcChannels[0] + default_value: 0 + min: 0 + max: MAX_SUPPORTED_RC_CHANNEL_COUNT + - name: rc_orig_dst_1 + description: "Destination RC channel that receives the pre-override copy from rc_orig_src_1. Set to 0 to disable this copy rule." + field: rcOrigDstChannels[0] + default_value: 0 + min: 0 + max: MAX_SUPPORTED_RC_CHANNEL_COUNT + - name: rc_orig_src_2 + description: "Source RC channel copied before MSP override. Set to 0 to disable this copy rule." + field: rcOrigSrcChannels[1] + default_value: 0 + min: 0 + max: MAX_SUPPORTED_RC_CHANNEL_COUNT + - name: rc_orig_dst_2 + description: "Destination RC channel that receives the pre-override copy from rc_orig_src_2. Set to 0 to disable this copy rule." + field: rcOrigDstChannels[1] + default_value: 0 + min: 0 + max: MAX_SUPPORTED_RC_CHANNEL_COUNT + - name: rc_orig_src_3 + description: "Source RC channel copied before MSP override. Set to 0 to disable this copy rule." + field: rcOrigSrcChannels[2] + default_value: 0 + min: 0 + max: MAX_SUPPORTED_RC_CHANNEL_COUNT + - name: rc_orig_dst_3 + description: "Destination RC channel that receives the pre-override copy from rc_orig_src_3. Set to 0 to disable this copy rule." + field: rcOrigDstChannels[2] + default_value: 0 + min: 0 + max: MAX_SUPPORTED_RC_CHANNEL_COUNT + - name: rc_orig_src_4 + description: "Source RC channel copied before MSP override. Set to 0 to disable this copy rule." + field: rcOrigSrcChannels[3] + default_value: 0 + min: 0 + max: MAX_SUPPORTED_RC_CHANNEL_COUNT + - name: rc_orig_dst_4 + description: "Destination RC channel that receives the pre-override copy from rc_orig_src_4. Set to 0 to disable this copy rule." + field: rcOrigDstChannels[3] + default_value: 0 + min: 0 + max: MAX_SUPPORTED_RC_CHANNEL_COUNT - name: PG_BLACKBOX_CONFIG type: blackboxConfig_t @@ -857,6 +905,11 @@ groups: min: 4 max: 255 default_value: 14 + - name: dshot_bidir + field: dshotBidirEnabled + description: "Enable experimental true bidirectional DShot RPM telemetry. Current support is target-specific and intended for multirotors using the first four motor outputs." + default_value: OFF + type: bool - name: PG_FAILSAFE_CONFIG type: failsafeConfig_t @@ -1691,7 +1744,7 @@ groups: type: rpmFilterConfig_t members: - name: rpm_gyro_filter_enabled - description: "Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV" + description: "Enables gyro RPM filtere. Set to `ON` only when ESC telemetry or bidirectional DShot telemetry is working and rotation speed of the motors is correctly reported to INAV" default_value: OFF field: gyro_filter_enabled type: bool diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index a80992b772d..26238dd4140 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -86,13 +86,14 @@ PG_RESET_TEMPLATE(reversibleMotorsConfig_t, reversibleMotorsConfig, .neutral = SETTING_3D_NEUTRAL_DEFAULT ); -PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 11); +PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 12); PG_RESET_TEMPLATE(motorConfig_t, motorConfig, .motorPwmProtocol = SETTING_MOTOR_PWM_PROTOCOL_DEFAULT, .motorPwmRate = SETTING_MOTOR_PWM_RATE_DEFAULT, .mincommand = SETTING_MIN_COMMAND_DEFAULT, .motorPoleCount = SETTING_MOTOR_POLES_DEFAULT, // Most brushless motors that we use are 14 poles + .dshotBidirEnabled = SETTING_DSHOT_BIDIR_DEFAULT, ); PG_REGISTER_ARRAY_WITH_RESET_FN(timerOverride_t, HARDWARE_TIMER_DEFINITION_COUNT, timerOverrides, PG_TIMER_OVERRIDE_CONFIG, 0); @@ -737,4 +738,4 @@ uint16_t getMaxThrottle(void) { } return throttle; -} \ No newline at end of file +} diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index 12688bd2c09..34aac1e279d 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -86,6 +86,7 @@ typedef struct motorConfig_s { uint8_t motorPwmProtocol; uint16_t digitalIdleOffsetValue; uint8_t motorPoleCount; // Magnetic poles in the motors for calculating actual RPM from eRPM provided by ESC telemetry + uint8_t dshotBidirEnabled; } motorConfig_t; PG_DECLARE(motorConfig_t, motorConfig); diff --git a/src/main/flight/rpm_filter.c b/src/main/flight/rpm_filter.c index ffca6c8ea68..317d78f460f 100644 --- a/src/main/flight/rpm_filter.c +++ b/src/main/flight/rpm_filter.c @@ -36,7 +36,7 @@ #include "common/maths.h" #include "common/filter.h" #include "flight/mixer.h" -#include "sensors/esc_sensor.h" +#include "sensors/rpm_source.h" #include "fc/config.h" #include "fc/settings.h" @@ -188,8 +188,13 @@ void rpmFilterUpdateTask(timeUs_t currentTimeUs) */ for (uint8_t i = 0; i < motorCount; i++) { - const escSensorData_t *escState = getEscTelemetry(i); //Get ESC telemetry - const float baseFrequency = pt1FilterApply(&motorFrequencyFilter[i], escState->rpm * HZ_TO_RPM); //Filter motor frequency + uint32_t motorRpm; + + if (!rpmSourceGetMotorRpm(i, &motorRpm)) { + continue; + } + + const float baseFrequency = pt1FilterApply(&motorFrequencyFilter[i], motorRpm * HZ_TO_RPM); rpmGyroUpdateFn(&gyroRpmFilters, i, baseFrequency); } diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 6ad55632c17..44811ec553d 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -111,6 +111,7 @@ #include "sensors/pitotmeter.h" #include "sensors/temperature.h" #include "sensors/esc_sensor.h" +#include "sensors/rpm_source.h" #include "sensors/rangefinder.h" #include "programming/logic_condition.h" @@ -3923,9 +3924,9 @@ static bool osdDrawSingleElement(uint8_t item) #if defined(USE_ESC_SENSOR) case OSD_ESC_RPM: { - escSensorData_t * escSensor = escSensorGetData(); - if (escSensor && escSensor->dataAge <= ESC_DATA_MAX_AGE) { - osdFormatRpm(buff, escSensor->rpm); + uint32_t rpm = 0; + if (rpmSourceGetAverageRpm(&rpm)) { + osdFormatRpm(buff, rpm); } else { osdFormatRpm(buff, 0); @@ -4187,7 +4188,7 @@ uint8_t osdIncElementIndex(uint8_t elementIndex) } } - if (!STATE(ESC_SENSOR_ENABLED)) { + if (!rpmSourceIsConfigured()) { if (elementIndex == OSD_ESC_RPM) { elementIndex = OSD_AZIMUTH; } diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index a8adf663d57..caf5b366af1 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -69,6 +69,7 @@ #include "sensors/rangefinder.h" #include "sensors/acceleration.h" #include "sensors/esc_sensor.h" +#include "sensors/rpm_source.h" #include "sensors/temperature.h" #include "sensors/pitotmeter.h" #include "sensors/boardalignment.h" @@ -1347,19 +1348,21 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms { uint16_t protoRpm = 0; int16_t protoTemp = 0; + uint32_t averageRpm = 0; + + if (rpmSourceGetAverageRpm(&averageRpm)) { + protoRpm = (averageRpm > UINT16_MAX) ? UINT16_MAX : (uint16_t)averageRpm; + } #if defined(USE_ESC_SENSOR) if (STATE(ESC_SENSOR_ENABLED) && getMotorCount() > 0) { - uint32_t motorRpmAcc = 0; int32_t motorTempAcc = 0; for (int i = 0; i < getMotorCount(); i++) { const escSensorData_t * escSensor = getEscTelemetry(i); - motorRpmAcc += escSensor->rpm; motorTempAcc += escSensor->temperature; } - protoRpm = motorRpmAcc / getMotorCount(); protoTemp = motorTempAcc / getMotorCount(); } #endif diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index 0531904d063..65aff0bca8c 100755 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -93,12 +93,13 @@ static timeUs_t needRxSignalBefore = 0; static bool isRxSuspended = false; static rcChannel_t rcChannels[MAX_SUPPORTED_RC_CHANNEL_COUNT]; +static rcChannel_t rcOriginalChannels[MAX_SUPPORTED_RC_CHANNEL_COUNT]; rxLinkStatistics_t rxLinkStatistics; rxRuntimeConfig_t rxRuntimeConfig; static uint8_t rcSampleIndex = 0; -PG_REGISTER_WITH_RESET_TEMPLATE(rxConfig_t, rxConfig, PG_RX_CONFIG, 13); +PG_REGISTER_WITH_RESET_TEMPLATE(rxConfig_t, rxConfig, PG_RX_CONFIG, 14); #ifndef SERIALRX_PROVIDER #define SERIALRX_PROVIDER 0 @@ -132,6 +133,8 @@ PG_RESET_TEMPLATE(rxConfig_t, rxConfig, #if defined(USE_RX_MSP) && defined(USE_MSP_RC_OVERRIDE) .mspOverrideChannels = SETTING_MSP_OVERRIDE_CHANNELS_DEFAULT, #endif + .rcOrigSrcChannels = {0}, + .rcOrigDstChannels = {0}, .rssi_source = SETTING_RSSI_SOURCE_DEFAULT, #ifdef USE_SERIALRX_SRXL2 .srxl2_unit_id = SETTING_SRXL2_UNIT_ID_DEFAULT, @@ -173,6 +176,34 @@ static uint8_t nullFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig) return RX_FRAME_PENDING; } +static void storeOriginalRxChannels(void) +{ + for (unsigned channel = 0; channel < rxChannelCount; channel++) { + rcOriginalChannels[channel] = rcChannels[channel]; + } +} + +static void applyOriginalRxChannelCopies(void) +{ + for (unsigned rule = 0; rule < RX_ORIG_COPY_RULE_COUNT; rule++) { + const uint8_t srcChannel = rxConfig()->rcOrigSrcChannels[rule]; + const uint8_t dstChannel = rxConfig()->rcOrigDstChannels[rule]; + + if (srcChannel == 0 || dstChannel == 0) { + continue; + } + + const unsigned srcIndex = srcChannel - 1; + const unsigned dstIndex = dstChannel - 1; + + if (srcIndex >= rxChannelCount || dstIndex >= MAX_SUPPORTED_RC_CHANNEL_COUNT) { + continue; + } + + rcChannels[dstIndex] = rcOriginalChannels[srcIndex]; + } +} + bool isRxPulseValid(uint16_t pulseDuration) { return pulseDuration >= rxConfig()->rx_min_usec && @@ -271,10 +302,12 @@ void rxInit(void) rcChannels[i].raw = PWM_RANGE_MIDDLE; rcChannels[i].data = PWM_RANGE_MIDDLE; rcChannels[i].expiresAt = nowMs + MAX_INVALID_RX_PULSE_TIME; + rcOriginalChannels[i] = rcChannels[i]; } rcChannels[THROTTLE].raw = (feature(FEATURE_REVERSIBLE_MOTORS)) ? PWM_RANGE_MIDDLE : rxConfig()->rx_min_usec; rcChannels[THROTTLE].data = rcChannels[THROTTLE].raw; + rcOriginalChannels[THROTTLE] = rcChannels[THROTTLE]; // Initialize ARM switch to OFF position when arming via switch is defined for (int i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) { @@ -290,6 +323,7 @@ void rxInit(void) rcChannel_t *armChannel = &rcChannels[modeActivationConditions(i)->auxChannelIndex + NON_AUX_CHANNEL_COUNT]; armChannel->raw = value; armChannel->data = value; + rcOriginalChannels[modeActivationConditions(i)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = *armChannel; } } @@ -506,12 +540,16 @@ bool calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs) } } + storeOriginalRxChannels(); + #if defined(USE_RX_MSP) && defined(USE_MSP_RC_OVERRIDE) if (IS_RC_MODE_ACTIVE(BOXMSPRCOVERRIDE) && !mspOverrideIsInFailsafe()) { mspOverrideChannels(rcChannels); } #endif + applyOriginalRxChannelCopies(); + // Update failsafe if (rxFlightChannelsValid && rxSignalReceived) { failsafeOnValidDataReceived(); @@ -654,6 +692,21 @@ rssiSource_e getRSSISource(void) return activeRssiSource; } +uint8_t rxGetChannelCount(void) +{ + uint8_t channelCount = rxChannelCount; + + for (unsigned rule = 0; rule < RX_ORIG_COPY_RULE_COUNT; rule++) { + if (rxConfig()->rcOrigSrcChannels[rule] == 0 || rxConfig()->rcOrigDstChannels[rule] == 0) { + continue; + } + + channelCount = MAX(channelCount, rxConfig()->rcOrigDstChannels[rule]); + } + + return MIN(channelCount, MAX_SUPPORTED_RC_CHANNEL_COUNT); +} + int16_t rxGetChannelValue(unsigned channelNumber) { if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_RC_CHANNEL)) { diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index 3ed6add3e48..8f7bd02232a 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -85,6 +85,7 @@ typedef enum { } rxSerialReceiverType_e; #define MAX_SUPPORTED_RC_CHANNEL_COUNT 34 +#define RX_ORIG_COPY_RULE_COUNT 4 #define NON_AUX_CHANNEL_COUNT 4 #define MAX_AUX_CHANNEL_COUNT (MAX_SUPPORTED_RC_CHANNEL_COUNT - NON_AUX_CHANNEL_COUNT) @@ -127,6 +128,8 @@ typedef struct rxConfig_s { uint8_t autoSmooth; // auto smooth rx input (0 = off, 1 = on) uint8_t autoSmoothFactor; // auto smooth rx input factor (1 = no smoothing, 100 = lots of smoothing) uint32_t mspOverrideChannels; // Channels to override with MSP RC when BOXMSPRCOVERRIDE is active + uint8_t rcOrigSrcChannels[RX_ORIG_COPY_RULE_COUNT]; + uint8_t rcOrigDstChannels[RX_ORIG_COPY_RULE_COUNT]; uint8_t rssi_source; #ifdef USE_SERIALRX_SRXL2 uint8_t srxl2_unit_id; @@ -214,6 +217,7 @@ bool calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs); bool isRxPulseValid(uint16_t pulseDuration); uint8_t calculateChannelRemapping(const uint8_t *channelMap, uint8_t channelMapEntryCount, uint8_t channelToRemap); +uint8_t rxGetChannelCount(void); void parseRcChannels(const char *input); void setRSSIFromMSP_RC(uint8_t newMspRssi); diff --git a/src/main/sensors/rpm_source.c b/src/main/sensors/rpm_source.c new file mode 100644 index 00000000000..05b41addaa1 --- /dev/null +++ b/src/main/sensors/rpm_source.c @@ -0,0 +1,162 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include "platform.h" + +#include "sensors/rpm_source.h" + +#include "drivers/pwm_output.h" + +#include "fc/runtime_config.h" + +#include "flight/mixer.h" + +#ifdef USE_ESC_SENSOR +#include "sensors/esc_sensor.h" +#endif + +static uint32_t dshotBidirRpm[MAX_SUPPORTED_MOTORS]; +static uint8_t dshotBidirDataAge[MAX_SUPPORTED_MOTORS]; + +bool rpmSourceIsDshotBidirConfigured(void) +{ +#ifdef USE_DSHOT_BIDIR + return isDshotBidirModeActive(); +#else + return false; +#endif +} + +bool rpmSourceIsConfigured(void) +{ + if (rpmSourceIsDshotBidirConfigured()) { + return true; + } + +#ifdef USE_ESC_SENSOR + return STATE(ESC_SENSOR_ENABLED); +#else + return false; +#endif +} + +uint8_t rpmSourceGetDshotBidirValidCount(void) +{ + uint8_t validCount = 0; + + for (uint8_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) { + if (dshotBidirDataAge[i] < RPM_SOURCE_DATA_INVALID) { + validCount++; + } + } + + return validCount; +} + +bool rpmSourceIsDshotBidirActive(void) +{ + return rpmSourceGetDshotBidirValidCount() > 0; +} + +bool rpmSourceGetAverageRpm(uint32_t *rpm) +{ + if (!rpm) { + return false; + } + + uint32_t rpmAccumulator = 0; + uint8_t validMotorCount = 0; + + for (uint8_t i = 0; i < getMotorCount(); i++) { + uint32_t motorRpm; + + if (!rpmSourceGetMotorRpm(i, &motorRpm)) { + continue; + } + + rpmAccumulator += motorRpm; + validMotorCount++; + } + + if (!validMotorCount) { + return false; + } + + *rpm = rpmAccumulator / validMotorCount; + return true; +} + +bool rpmSourceGetMotorRpm(uint8_t motor, uint32_t *rpm) +{ + if (motor >= MAX_SUPPORTED_MOTORS || !rpm) { + return false; + } + + if (rpmSourceIsDshotBidirConfigured() && dshotBidirDataAge[motor] < RPM_SOURCE_DATA_INVALID) { + *rpm = dshotBidirRpm[motor]; + return true; + } + +#ifdef USE_ESC_SENSOR + if (STATE(ESC_SENSOR_ENABLED)) { + const escSensorData_t *escState = getEscTelemetry(motor); + + if (escState != NULL && escState->dataAge < ESC_DATA_INVALID) { + *rpm = escState->rpm; + return true; + } + } +#endif + + return false; +} + +void rpmSourceResetDshotBidir(void) +{ + for (uint8_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) { + dshotBidirRpm[i] = 0; + dshotBidirDataAge[i] = RPM_SOURCE_DATA_INVALID; + } +} + +void rpmSourceSetDshotBidirRpm(uint8_t motor, uint32_t rpm) +{ + if (motor >= MAX_SUPPORTED_MOTORS) { + return; + } + + dshotBidirRpm[motor] = rpm; + dshotBidirDataAge[motor] = 0; +} + +void rpmSourceInvalidateDshotBidir(uint8_t motor) +{ + if (motor >= MAX_SUPPORTED_MOTORS) { + return; + } + + if (dshotBidirDataAge[motor] < RPM_SOURCE_DATA_INVALID) { + dshotBidirDataAge[motor]++; + } +} diff --git a/src/main/sensors/rpm_source.h b/src/main/sensors/rpm_source.h new file mode 100644 index 00000000000..a6fa1b5e939 --- /dev/null +++ b/src/main/sensors/rpm_source.h @@ -0,0 +1,40 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#pragma once + +#include +#include + +#define RPM_SOURCE_DATA_INVALID 255 + +bool rpmSourceIsConfigured(void); +bool rpmSourceIsDshotBidirConfigured(void); +bool rpmSourceIsDshotBidirActive(void); +uint8_t rpmSourceGetDshotBidirValidCount(void); +bool rpmSourceGetAverageRpm(uint32_t *rpm); +bool rpmSourceGetMotorRpm(uint8_t motor, uint32_t *rpm); +void rpmSourceResetDshotBidir(void); +void rpmSourceSetDshotBidirRpm(uint8_t motor, uint32_t rpm); +void rpmSourceInvalidateDshotBidir(uint8_t motor); diff --git a/src/main/target/SPEEDYBEEF405V3/config.c b/src/main/target/SPEEDYBEEF405V3/config.c index c33c8839574..5940a52fb05 100644 --- a/src/main/target/SPEEDYBEEF405V3/config.c +++ b/src/main/target/SPEEDYBEEF405V3/config.c @@ -27,6 +27,10 @@ #include "platform.h" +#include "drivers/pwm_mapping.h" + +#include "flight/mixer.h" + #include "fc/fc_msp_box.h" #include "io/serial.h" @@ -39,3 +43,24 @@ void targetConfiguration(void) serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_MSP; // serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART5)].functionMask = FUNCTION_ESCSERIAL; } + +void validateAndFixTargetConfig(void) +{ + if (!motorConfig()->dshotBidirEnabled) { + return; + } + + if (motorConfig()->motorPwmProtocol < PWM_TYPE_DSHOT150 || motorConfig()->motorPwmProtocol > PWM_TYPE_DSHOT600) { + motorConfigMutable()->dshotBidirEnabled = false; + return; + } + + if (getMotorCount() == 0 || getMotorCount() > 4) { + motorConfigMutable()->dshotBidirEnabled = false; + return; + } + + if (motorConfig()->motorPwmProtocol == PWM_TYPE_DSHOT600) { + motorConfigMutable()->motorPwmProtocol = PWM_TYPE_DSHOT300; + } +} diff --git a/src/main/target/SPEEDYBEEF405V3/target.h b/src/main/target/SPEEDYBEEF405V3/target.h index 6653ea56c0c..d3135bf7e51 100644 --- a/src/main/target/SPEEDYBEEF405V3/target.h +++ b/src/main/target/SPEEDYBEEF405V3/target.h @@ -149,7 +149,9 @@ #define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD | FEATURE_BLACKBOX) #define USE_DSHOT #define USE_DSHOT_DMAR +#define USE_DSHOT_BIDIR // #define USE_ESC_SENSOR +#define USE_RPM_FILTER #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define DEFAULT_RX_TYPE RX_TYPE_SERIAL diff --git a/src/main/telemetry/jetiexbus.c b/src/main/telemetry/jetiexbus.c index 56073e54cc2..c5be4a45fdb 100644 --- a/src/main/telemetry/jetiexbus.c +++ b/src/main/telemetry/jetiexbus.c @@ -50,6 +50,7 @@ #include "sensors/battery.h" #include "sensors/sensors.h" #include "sensors/acceleration.h" +#include "sensors/rpm_source.h" #include "telemetry/jetiexbus.h" #include "telemetry/telemetry.h" @@ -293,7 +294,7 @@ void initJetiExBusTelemetry(void) enableGpsTelemetry(feature(FEATURE_GPS)); #ifdef USE_ESC_SENSOR - if (STATE(ESC_SENSOR_ENABLED) && getMotorCount() > 0) { + if (rpmSourceIsConfigured() && getMotorCount() > 0) { bitArraySet(&exSensorEnabled, EX_RPM); } #endif @@ -346,11 +347,6 @@ uint32_t calcGpsDDMMmmm(int32_t value, bool isLong) int32_t getSensorValue(uint8_t sensor) { - -#ifdef USE_ESC_SENSOR - escSensorData_t * escSensor; -#endif - switch (sensor) { case EX_VOLTAGE: return telemetryConfig()->report_cell_voltage ? getBatteryAverageCellVoltage() : getBatteryVoltage(); @@ -436,10 +432,11 @@ int32_t getSensorValue(uint8_t sensor) #ifdef USE_ESC_SENSOR case EX_RPM: - escSensor = escSensorGetData(); - if (escSensor && escSensor->dataAge <= ESC_DATA_MAX_AGE) { - return escSensor->rpm; - } else { + { + uint32_t rpm = 0; + if (rpmSourceGetAverageRpm(&rpm)) { + return rpm; + } return 0; } break; diff --git a/src/main/telemetry/sbus2.c b/src/main/telemetry/sbus2.c index 1e800f2f098..829b8ba72d5 100644 --- a/src/main/telemetry/sbus2.c +++ b/src/main/telemetry/sbus2.c @@ -39,6 +39,7 @@ #include "sensors/sensors.h" #include "sensors/temperature.h" #include "sensors/diagnostics.h" +#include "sensors/rpm_source.h" #include "io/gps.h" @@ -76,14 +77,12 @@ void handleSbus2Telemetry(timeUs_t currentTimeUs) float temperature = 0; uint32_t rpm = 0; + rpmSourceGetAverageRpm(&rpm); + #ifdef USE_ESC_SENSOR escSensorData_t * escSensor = escSensorGetData(); if (escSensor && escSensor->dataAge <= ESC_DATA_MAX_AGE) { - rpm = escSensor->rpm; temperature = escSensor->temperature; - } else { - rpm = 0; - temperature = 0; } #endif