mirror of
https://github.com/Show-maket/IR-protocol.git
synced 2026-04-28 03:08:08 +00:00
Refactor IR decoder and encoder for improved pulse filtering and ISR handling. Removed unused filtered sub-buffer, updated pulse filter methods, and added support for buffered ISR storage in the encoder. Enhanced documentation for clarity on DMA TX backend and ISR modes.
This commit is contained in:
@ -74,7 +74,6 @@ bool IR_DecoderRaw::availableRaw()
|
||||
|
||||
void IR_DecoderRaw::pulseFilterResetStats()
|
||||
{
|
||||
pulseFilterDropFilteredOverflow = 0;
|
||||
pulseFilterDropHoldOverflow = 0;
|
||||
pulseFilterDropGlitchPairs = 0;
|
||||
}
|
||||
@ -344,7 +343,7 @@ bool IR_DecoderRaw::rxTimeoutPipelineBusy() const
|
||||
if (pulseFilterHoldCount != 0U)
|
||||
return true;
|
||||
noInterrupts();
|
||||
const bool busy = !subBuffer.isEmpty() || !filteredSubBuffer.isEmpty();
|
||||
const bool busy = !subBuffer.isEmpty();
|
||||
interrupts();
|
||||
return busy;
|
||||
}
|
||||
@ -403,10 +402,9 @@ void IR_DecoderRaw::tick()
|
||||
// Не в начале до pop: иначе после checkTimeout lastEdgeTime vs micros() расходятся
|
||||
// с метками ISR из очереди → ложные TIMEOUT (bits=0) каждый пакет.
|
||||
|
||||
FrontStorage currentFront;
|
||||
bool hasCurrentFront = false;
|
||||
FrontStorage rawFront;
|
||||
bool hasRawFront = false;
|
||||
bool processedFront = false;
|
||||
noInterrupts();
|
||||
FrontStorage *rawPtr = subBuffer.pop();
|
||||
if (rawPtr != nullptr)
|
||||
@ -419,26 +417,33 @@ void IR_DecoderRaw::tick()
|
||||
if (IR_INPUT_MIN_PULSE_US > 0U)
|
||||
{
|
||||
if (hasRawFront)
|
||||
pulseFilterFeedOneRaw(rawFront);
|
||||
else
|
||||
pulseFilterFlushTimeout(micros());
|
||||
|
||||
noInterrupts();
|
||||
FrontStorage *flt = filteredSubBuffer.pop();
|
||||
if (flt != nullptr)
|
||||
{
|
||||
currentFront = *flt;
|
||||
hasCurrentFront = true;
|
||||
pulseFilterPushRaw(rawFront);
|
||||
FrontStorage confirmedFront;
|
||||
while (pulseFilterTryTakeConfirmed(confirmedFront))
|
||||
{
|
||||
processDecodedFront(confirmedFront);
|
||||
processedFront = true;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
const uint32_t nowUs = micros();
|
||||
FrontStorage confirmedFront;
|
||||
while (pulseFilterTryFlushOne(nowUs, confirmedFront))
|
||||
{
|
||||
processDecodedFront(confirmedFront);
|
||||
processedFront = true;
|
||||
}
|
||||
}
|
||||
interrupts();
|
||||
}
|
||||
else if (hasRawFront)
|
||||
{
|
||||
currentFront = rawFront;
|
||||
hasCurrentFront = true;
|
||||
processDecodedFront(rawFront);
|
||||
processedFront = true;
|
||||
}
|
||||
|
||||
if (!hasCurrentFront)
|
||||
if (!processedFront)
|
||||
{
|
||||
isSubBufferOverflow = false;
|
||||
listenStart();
|
||||
@ -448,11 +453,22 @@ void IR_DecoderRaw::tick()
|
||||
#endif
|
||||
return;
|
||||
} // Если данных нет - ничего не делаем
|
||||
listenStart();
|
||||
checkTimeout();
|
||||
#if IR_RX_BRIEF_LOG
|
||||
rxBriefFlushDeferredIsrLogs();
|
||||
#endif
|
||||
#if defined(IR_EDGE_TRACE)
|
||||
while (edgeTraceFlushChunk(Serial, 48) > 0) {}
|
||||
#endif
|
||||
}
|
||||
|
||||
void IR_DecoderRaw::processDecodedFront(const FrontStorage ¤tFront)
|
||||
{
|
||||
if (preambleProcessEdge(currentFront))
|
||||
{
|
||||
lastEdgeTime = currentFront.time;
|
||||
goto END;
|
||||
return;
|
||||
}
|
||||
|
||||
lastEdgeTime = currentFront.time; // запоминаем любой фронт
|
||||
@ -478,7 +494,7 @@ void IR_DecoderRaw::tick()
|
||||
#if IR_GLITCH_REJECT_PHASE_NUDGE
|
||||
irGlitchPhaseNudge(currentFront.time, riseSyncTime, prevRise);
|
||||
#endif
|
||||
goto END;
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
#if IR_MICRO_GAP_RISE_REJECT
|
||||
@ -495,7 +511,7 @@ void IR_DecoderRaw::tick()
|
||||
#if IR_GLITCH_REJECT_PHASE_NUDGE
|
||||
irGlitchPhaseNudge(currentFront.time, riseSyncTime, prevRise);
|
||||
#endif
|
||||
goto END;
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
if (candRp <= riseTimeMax / 4U && !highCount && !lowCount)
|
||||
@ -504,7 +520,7 @@ void IR_DecoderRaw::tick()
|
||||
#if IR_RX_BRIEF_LOG
|
||||
rxBriefLog(RxBriefReason::Timing, irClampU16(candRp), 0, currentFront.time);
|
||||
#endif
|
||||
goto END;
|
||||
return;
|
||||
}
|
||||
|
||||
if (candRp > riseTimeMax / 4 || highCount || lowCount)
|
||||
@ -557,7 +573,7 @@ void IR_DecoderRaw::tick()
|
||||
}
|
||||
}
|
||||
#ifdef IRDEBUG
|
||||
// goto END; //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
|
||||
// return; //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
|
||||
#endif
|
||||
//----------------------------------------------------------------------------------
|
||||
#ifdef IRDEBUG
|
||||
@ -572,7 +588,7 @@ void IR_DecoderRaw::tick()
|
||||
rxBriefLog(RxBriefReason::Timing, irClampU16((uint32_t)risePeriod),
|
||||
irClampU16((uint32_t)highTime), currentFront.time);
|
||||
#endif
|
||||
goto END;
|
||||
return;
|
||||
}
|
||||
|
||||
// определить направление фронта
|
||||
@ -727,17 +743,6 @@ void IR_DecoderRaw::tick()
|
||||
else
|
||||
{ // Если ```\__ ↓
|
||||
}
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
||||
END:;
|
||||
listenStart();
|
||||
checkTimeout();
|
||||
#if IR_RX_BRIEF_LOG
|
||||
rxBriefFlushDeferredIsrLogs();
|
||||
#endif
|
||||
#if defined(IR_EDGE_TRACE)
|
||||
while (edgeTraceFlushChunk(Serial, 48) > 0) {}
|
||||
#endif
|
||||
}
|
||||
|
||||
void IR_DecoderRaw::writeToBuffer(bool bit, bool packTraceInvertFix)
|
||||
@ -1455,34 +1460,18 @@ void IR_DecoderRaw::pulseFilterShiftLeft(uint8_t n)
|
||||
pulseFilterHoldCount = newCount;
|
||||
}
|
||||
|
||||
bool IR_DecoderRaw::pulseFilterEmit(const FrontStorage &e)
|
||||
{
|
||||
if (filteredSubBuffer.isFull())
|
||||
{
|
||||
pulseFilterDropFilteredOverflow++;
|
||||
#if IR_RX_BRIEF_LOG
|
||||
rxBriefLog(RxBriefReason::FilterOverflow, irClampU16(pulseFilterDropFilteredOverflow), 0, e.time);
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
filteredSubBuffer.push(e);
|
||||
return true;
|
||||
}
|
||||
|
||||
void IR_DecoderRaw::pulseFilterReset()
|
||||
{
|
||||
pulseFilterHoldCount = 0;
|
||||
pulseFilterLastRawValid = false;
|
||||
pulseFilterLastRawTime = 0;
|
||||
while (filteredSubBuffer.pop() != nullptr) {}
|
||||
}
|
||||
|
||||
void IR_DecoderRaw::pulseFilterFeedOneRaw(const FrontStorage &e)
|
||||
void IR_DecoderRaw::pulseFilterPushRaw(const FrontStorage &e)
|
||||
{
|
||||
const uint32_t minUs = IR_INPUT_MIN_PULSE_US;
|
||||
if (minUs == 0U)
|
||||
{
|
||||
pulseFilterEmit(e);
|
||||
return;
|
||||
}
|
||||
|
||||
@ -1495,44 +1484,53 @@ void IR_DecoderRaw::pulseFilterFeedOneRaw(const FrontStorage &e)
|
||||
#if IR_RX_BRIEF_LOG
|
||||
rxBriefLog(RxBriefReason::HoldOverflow, irClampU16(pulseFilterDropHoldOverflow), 0, e.time);
|
||||
#endif
|
||||
pulseFilterEmit(pulseFilterHoldEdges[0]);
|
||||
pulseFilterShiftLeft(1);
|
||||
}
|
||||
|
||||
pulseFilterHoldEdges[pulseFilterHoldCount++] = e;
|
||||
const uint8_t holdback = irPulseFilterHoldbackEdges();
|
||||
}
|
||||
|
||||
bool IR_DecoderRaw::pulseFilterTryTakeConfirmed(FrontStorage &out, uint32_t logTime)
|
||||
{
|
||||
const uint32_t minUs = IR_INPUT_MIN_PULSE_US;
|
||||
if (minUs == 0U)
|
||||
return false;
|
||||
|
||||
const uint8_t holdback = irPulseFilterHoldbackEdges();
|
||||
if (logTime == 0U)
|
||||
logTime = pulseFilterLastRawTime;
|
||||
for (;;)
|
||||
{
|
||||
if (pulseFilterHoldCount < 2)
|
||||
return;
|
||||
return false;
|
||||
|
||||
const uint32_t dt = pulseFilterHoldEdges[1].time - pulseFilterHoldEdges[0].time;
|
||||
if (dt < minUs)
|
||||
{
|
||||
pulseFilterDropGlitchPairs++;
|
||||
#if IR_RX_BRIEF_LOG
|
||||
rxBriefLog(RxBriefReason::Glitch, irClampU16(pulseFilterDropGlitchPairs), 0, e.time);
|
||||
rxBriefLog(RxBriefReason::Glitch, irClampU16(pulseFilterDropGlitchPairs), 0, logTime);
|
||||
#endif
|
||||
pulseFilterShiftLeft(2);
|
||||
continue;
|
||||
}
|
||||
|
||||
if (pulseFilterHoldCount <= holdback)
|
||||
return;
|
||||
return false;
|
||||
|
||||
pulseFilterEmit(pulseFilterHoldEdges[0]);
|
||||
out = pulseFilterHoldEdges[0];
|
||||
pulseFilterShiftLeft(1);
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
void IR_DecoderRaw::pulseFilterFlushTimeout(uint32_t nowUs)
|
||||
bool IR_DecoderRaw::pulseFilterTryFlushOne(uint32_t nowUs, FrontStorage &out)
|
||||
{
|
||||
if (IR_INPUT_MIN_PULSE_US == 0U || !pulseFilterLastRawValid || pulseFilterHoldCount == 0)
|
||||
return;
|
||||
return false;
|
||||
const uint32_t waitUs = IR_INPUT_MIN_PULSE_US * (uint32_t)IR_INPUT_FILTER_TIMEOUT_MULT;
|
||||
if ((uint32_t)(nowUs - pulseFilterLastRawTime) < waitUs)
|
||||
return;
|
||||
return false;
|
||||
|
||||
while (pulseFilterHoldCount > 0)
|
||||
{
|
||||
@ -1549,9 +1547,11 @@ void IR_DecoderRaw::pulseFilterFlushTimeout(uint32_t nowUs)
|
||||
continue;
|
||||
}
|
||||
}
|
||||
pulseFilterEmit(pulseFilterHoldEdges[0]);
|
||||
out = pulseFilterHoldEdges[0];
|
||||
pulseFilterShiftLeft(1);
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
uint32_t IR_DecoderRaw::preambleJitterTolUs(uint32_t baselineUs) const
|
||||
|
||||
@ -52,7 +52,7 @@ public:
|
||||
inline bool isOverflow() { return isBufferOverflow; }; // Буффер переполнился
|
||||
bool isSubOverflow();
|
||||
volatile inline bool isReciving() { return isRecive; }; // Возвращает true, если происходит приём пакета
|
||||
uint32_t pulseFilterDroppedByFilteredOverflow() const { return pulseFilterDropFilteredOverflow; }
|
||||
uint32_t pulseFilterDroppedByFilteredOverflow() const { return 0; }
|
||||
uint32_t pulseFilterDroppedByHoldOverflow() const { return pulseFilterDropHoldOverflow; }
|
||||
uint32_t pulseFilterDroppedGlitchPairs() const { return pulseFilterDropGlitchPairs; }
|
||||
void pulseFilterResetStats();
|
||||
@ -122,8 +122,6 @@ private:
|
||||
// volatile FrontStorage subBuffer[subBufferSize]; // вспомогательный буфер для хранения необработанных фронтов/спадов
|
||||
|
||||
RingBuffer<FrontStorage, subBufferSize> subBuffer;
|
||||
/** Очередь фронтов после потокового анти-глитча; tick() читает из неё при включённом фильтре. */
|
||||
RingBuffer<FrontStorage, subBufferSize> filteredSubBuffer;
|
||||
IR_Encoder *pairMuteEncoders[IR_PAIR_MUTE_MAX_ENCODERS]{};
|
||||
uint8_t pairMuteEncoderCount = 0;
|
||||
static constexpr uint8_t kPulseFilterHoldCap = 6;
|
||||
@ -131,7 +129,6 @@ private:
|
||||
uint8_t pulseFilterHoldCount = 0;
|
||||
bool pulseFilterLastRawValid = false;
|
||||
uint32_t pulseFilterLastRawTime = 0;
|
||||
uint32_t pulseFilterDropFilteredOverflow = 0;
|
||||
uint32_t pulseFilterDropHoldOverflow = 0;
|
||||
uint32_t pulseFilterDropGlitchPairs = 0;
|
||||
static constexpr uint8_t kPreambleLockNeed = (uint8_t)IR_PREAMBLE_LOCK_RISE_PERIODS;
|
||||
@ -197,12 +194,12 @@ bool isReciveRaw = false;
|
||||
void checkTimeout(); //
|
||||
/** В очередях/hold фильтра ещё есть фронты — не оценивать таймаут по micros()-lastEdgeTime (ложный TIMEOUT). */
|
||||
bool rxTimeoutPipelineBusy() const;
|
||||
/** Один сырой фронт из subBuffer -> потоковый holdback-антиглитч. */
|
||||
void pulseFilterFeedOneRaw(const FrontStorage &e);
|
||||
void pulseFilterFlushTimeout(uint32_t nowUs);
|
||||
bool pulseFilterEmit(const FrontStorage &e);
|
||||
void pulseFilterPushRaw(const FrontStorage &e);
|
||||
bool pulseFilterTryTakeConfirmed(FrontStorage &out, uint32_t logTime = 0);
|
||||
bool pulseFilterTryFlushOne(uint32_t nowUs, FrontStorage &out);
|
||||
void pulseFilterShiftLeft(uint8_t n);
|
||||
void pulseFilterReset();
|
||||
void processDecodedFront(const FrontStorage ¤tFront);
|
||||
static uint32_t absDiffU32(uint32_t a, uint32_t b);
|
||||
bool registerPairMuteEncoder(IR_Encoder *enc);
|
||||
void refreshPairMuteState();
|
||||
|
||||
154
IR_Encoder.cpp
154
IR_Encoder.cpp
@ -1,7 +1,24 @@
|
||||
#include "IR_Encoder.h"
|
||||
#include "IR_DecoderRaw.h"
|
||||
#include "IrTxIsrBufferedStorage.h"
|
||||
#include <string.h>
|
||||
|
||||
#if defined(_MSC_VER)
|
||||
#define IRPROTO_PRAGMA_MESSAGE(text) __pragma(message(text))
|
||||
#else
|
||||
#define IRPROTO_PRAGMA_MESSAGE(text) _Pragma(#text)
|
||||
#endif
|
||||
|
||||
#if defined(ARDUINO_ARCH_STM32)
|
||||
#if defined(STM32G4xx)
|
||||
IRPROTO_PRAGMA_MESSAGE(message("[IR-protocol] TX backends: ISR + built-in DMA"))
|
||||
#elif defined(STM32F4xx)
|
||||
IRPROTO_PRAGMA_MESSAGE(message("[IR-protocol] TX backends: ISR only"))
|
||||
#else
|
||||
IRPROTO_PRAGMA_MESSAGE(message("[IR-protocol] TX backends: ISR"))
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#define LoopOut 12
|
||||
#define ISR_Out 10
|
||||
#define TestOut 13
|
||||
@ -14,6 +31,7 @@ IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair, bool
|
||||
{
|
||||
setPin(pin);
|
||||
id = addr;
|
||||
txIsrMode_ = txIsrLegacyMode_ ? TxIsrMode::Legacy : TxIsrMode::Buffered;
|
||||
this->decPair = decPair;
|
||||
if (decPair != nullptr)
|
||||
{
|
||||
@ -45,7 +63,7 @@ HardwareTimer* IR_Encoder::IR_Timer = nullptr;
|
||||
IR_Encoder::ExternalTxStartFn IR_Encoder::externalTxStartFn = nullptr;
|
||||
IR_Encoder::ExternalTxBusyFn IR_Encoder::externalTxBusyFn = nullptr;
|
||||
void *IR_Encoder::externalTxCtx = nullptr;
|
||||
bool IR_Encoder::txIsrLegacyMode_ = false;
|
||||
bool IR_Encoder::txIsrLegacyMode_ = true;
|
||||
uint16_t IR_Encoder::s_carrierMultiply = 2;
|
||||
|
||||
void IR_Encoder::setCarrierMultiply(uint16_t multiply)
|
||||
@ -146,6 +164,11 @@ bool IR_Encoder::scaleGateRunsToPhysical(IR_TxGateRun* runs, size_t* ioCount, si
|
||||
void IR_Encoder::setTxIsrLegacyMode(bool legacy)
|
||||
{
|
||||
txIsrLegacyMode_ = legacy;
|
||||
const TxIsrMode mode = legacy ? TxIsrMode::Legacy : TxIsrMode::Buffered;
|
||||
for (IR_Encoder *p = head; p != nullptr; p = p->next)
|
||||
{
|
||||
p->txIsrMode_ = mode;
|
||||
}
|
||||
}
|
||||
|
||||
bool IR_Encoder::txIsrLegacyMode()
|
||||
@ -153,6 +176,54 @@ bool IR_Encoder::txIsrLegacyMode()
|
||||
return txIsrLegacyMode_;
|
||||
}
|
||||
|
||||
void IR_Encoder::attachBufferedIsrStorage(IrTxIsrBufferedStorageBase& storage)
|
||||
{
|
||||
txBufferedCtx_ = &storage;
|
||||
}
|
||||
|
||||
void IR_Encoder::detachBufferedIsrStorage()
|
||||
{
|
||||
txBufferedCtx_ = nullptr;
|
||||
if (!isSending)
|
||||
{
|
||||
txActiveBufferedCtx_ = nullptr;
|
||||
txUseBufferedIsr_ = false;
|
||||
}
|
||||
}
|
||||
|
||||
bool IR_Encoder::hasBufferedIsrStorage() const
|
||||
{
|
||||
return txBufferedCtx_ != nullptr && txBufferedCtx_->isValid();
|
||||
}
|
||||
|
||||
void IR_Encoder::enableBufferedIsr(IrTxIsrBufferedStorageBase& storage)
|
||||
{
|
||||
attachBufferedIsrStorage(storage);
|
||||
txIsrMode_ = TxIsrMode::Buffered;
|
||||
}
|
||||
|
||||
void IR_Encoder::disableBufferedIsr()
|
||||
{
|
||||
txIsrMode_ = TxIsrMode::Legacy;
|
||||
if (!isSending)
|
||||
{
|
||||
txActiveBufferedCtx_ = nullptr;
|
||||
txUseBufferedIsr_ = false;
|
||||
}
|
||||
}
|
||||
|
||||
IR_Encoder::TxIsrMode IR_Encoder::txIsrMode() const
|
||||
{
|
||||
return txIsrMode_;
|
||||
}
|
||||
|
||||
bool IR_Encoder::shouldUseBufferedIsr() const
|
||||
{
|
||||
return txIsrMode_ == TxIsrMode::Buffered &&
|
||||
txBufferedCtx_ != nullptr &&
|
||||
txBufferedCtx_->isValid();
|
||||
}
|
||||
|
||||
bool IR_Encoder::txAdvanceBoundary(TxFsmState &st, const uint8_t *sendBufferLocal)
|
||||
{
|
||||
while (true)
|
||||
@ -336,6 +407,8 @@ void IR_Encoder::externalFinishSend()
|
||||
}
|
||||
|
||||
isSending = false;
|
||||
txUseBufferedIsr_ = false;
|
||||
txActiveBufferedCtx_ = nullptr;
|
||||
refreshBlindDecoderMuteState();
|
||||
}
|
||||
|
||||
@ -704,6 +777,8 @@ void IR_Encoder::rawSend(uint8_t *ptr, uint8_t len)
|
||||
}
|
||||
|
||||
sendLen = len;
|
||||
txUseBufferedIsr_ = false;
|
||||
txActiveBufferedCtx_ = nullptr;
|
||||
isSending = true;
|
||||
refreshBlindDecoderMuteState();
|
||||
|
||||
@ -727,7 +802,11 @@ void IR_Encoder::rawSend(uint8_t *ptr, uint8_t len)
|
||||
}
|
||||
sendLen = len;
|
||||
|
||||
if (txIsrLegacyMode_)
|
||||
const bool useBufferedIsr = shouldUseBufferedIsr();
|
||||
txUseBufferedIsr_ = useBufferedIsr;
|
||||
txActiveBufferedCtx_ = useBufferedIsr ? txBufferedCtx_ : nullptr;
|
||||
|
||||
if (!useBufferedIsr)
|
||||
{
|
||||
toggleCounter = preambToggle;
|
||||
dataBitCounter = bitPerByte - 1;
|
||||
@ -756,22 +835,36 @@ void IR_Encoder::rawSend(uint8_t *ptr, uint8_t len)
|
||||
return;
|
||||
}
|
||||
|
||||
size_t nRuns = buildGateRuns(sendBuffer, len, txGateRuns_, irproto::kIsrTxMaxGateRuns);
|
||||
if (nRuns == 0U)
|
||||
IrTxIsrBufferedStorageBase* buf = txActiveBufferedCtx_;
|
||||
if (buf == nullptr || !buf->isValid())
|
||||
{
|
||||
txUseBufferedIsr_ = false;
|
||||
txActiveBufferedCtx_ = nullptr;
|
||||
return;
|
||||
}
|
||||
if (!scaleGateRunsToPhysical(txGateRuns_, &nRuns, irproto::kIsrTxMaxGateRuns, carrierMultiply()))
|
||||
|
||||
buf->resetRuntimeState();
|
||||
|
||||
size_t nRuns = buildGateRuns(sendBuffer, len, buf->gateRuns, buf->maxGateRuns);
|
||||
if (nRuns == 0U)
|
||||
{
|
||||
txUseBufferedIsr_ = false;
|
||||
txActiveBufferedCtx_ = nullptr;
|
||||
return;
|
||||
}
|
||||
if (!scaleGateRunsToPhysical(buf->gateRuns, &nRuns, buf->maxGateRuns, carrierMultiply()))
|
||||
{
|
||||
txUseBufferedIsr_ = false;
|
||||
txActiveBufferedCtx_ = nullptr;
|
||||
return;
|
||||
}
|
||||
|
||||
uint32_t total = 0;
|
||||
for (size_t i = 0; i < nRuns; i++)
|
||||
{
|
||||
total += txGateRuns_[i].lenTicks;
|
||||
total += buf->gateRuns[i].lenTicks;
|
||||
}
|
||||
txBsrrTotalTicks_ = total;
|
||||
buf->totalTicks = total;
|
||||
|
||||
const uint32_t setW = (uint32_t)mask;
|
||||
const uint32_t resetW = ((uint32_t)mask) << 16U;
|
||||
@ -780,13 +873,8 @@ void IR_Encoder::rawSend(uint8_t *ptr, uint8_t len)
|
||||
const uint16_t cap = maxPowerNumerator();
|
||||
txPowerSnap_ = (powerNumerator_ > cap) ? cap : powerNumerator_;
|
||||
}
|
||||
txBsrrWave_.configure(setW, resetW, txGateRuns_, nRuns, txMultiplySnap_, txPowerSnap_);
|
||||
|
||||
txBsrrHalfLen_ = (uint16_t)(irproto::kIsrTxBsrrWordCount / 2U);
|
||||
txBsrrWave_.fill(txBsrrWords_, irproto::kIsrTxBsrrWordCount);
|
||||
|
||||
txBsrrReadIdx_ = 0;
|
||||
txBsrrTicksSent_ = 0;
|
||||
buf->wave.configure(setW, resetW, buf->gateRuns, nRuns, txMultiplySnap_, txPowerSnap_);
|
||||
buf->wave.fill(buf->bsrrWords, buf->wordCount);
|
||||
|
||||
isSending = true;
|
||||
refreshBlindDecoderMuteState();
|
||||
@ -815,7 +903,7 @@ void IR_Encoder::_isr()
|
||||
if (port == nullptr)
|
||||
return;
|
||||
|
||||
if (txIsrLegacyMode_)
|
||||
if (!txUseBufferedIsr_)
|
||||
{
|
||||
const uint32_t setW = (uint32_t)mask;
|
||||
const uint32_t resetW = ((uint32_t)mask) << 16U;
|
||||
@ -850,33 +938,49 @@ void IR_Encoder::_isr()
|
||||
{
|
||||
port->BSRR = resetW;
|
||||
isSending = false;
|
||||
txUseBufferedIsr_ = false;
|
||||
txActiveBufferedCtx_ = nullptr;
|
||||
refreshBlindDecoderMuteState();
|
||||
carrierStopPending = true;
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
port->BSRR = txBsrrWords_[txBsrrReadIdx_];
|
||||
txBsrrReadIdx_++;
|
||||
txBsrrTicksSent_++;
|
||||
|
||||
if (txBsrrTicksSent_ >= txBsrrTotalTicks_)
|
||||
IrTxIsrBufferedStorageBase* buf = txActiveBufferedCtx_;
|
||||
if (buf == nullptr || !buf->isValid())
|
||||
{
|
||||
port->BSRR = ((uint32_t)mask) << 16U;
|
||||
isSending = false;
|
||||
txUseBufferedIsr_ = false;
|
||||
txActiveBufferedCtx_ = nullptr;
|
||||
refreshBlindDecoderMuteState();
|
||||
carrierStopPending = true;
|
||||
return;
|
||||
}
|
||||
|
||||
if (txBsrrReadIdx_ == txBsrrHalfLen_)
|
||||
port->BSRR = buf->bsrrWords[buf->readIdx];
|
||||
buf->readIdx++;
|
||||
buf->ticksSent++;
|
||||
|
||||
if (buf->ticksSent >= buf->totalTicks)
|
||||
{
|
||||
txBsrrWave_.fill(&txBsrrWords_[0], txBsrrHalfLen_);
|
||||
port->BSRR = ((uint32_t)mask) << 16U;
|
||||
isSending = false;
|
||||
txUseBufferedIsr_ = false;
|
||||
txActiveBufferedCtx_ = nullptr;
|
||||
refreshBlindDecoderMuteState();
|
||||
carrierStopPending = true;
|
||||
return;
|
||||
}
|
||||
else if (txBsrrReadIdx_ >= irproto::kIsrTxBsrrWordCount)
|
||||
|
||||
if (buf->readIdx == buf->halfLen)
|
||||
{
|
||||
txBsrrReadIdx_ = 0;
|
||||
txBsrrWave_.fill(&txBsrrWords_[txBsrrHalfLen_], txBsrrHalfLen_);
|
||||
buf->wave.fill(&buf->bsrrWords[0], buf->halfLen);
|
||||
}
|
||||
else if (buf->readIdx >= buf->wordCount)
|
||||
{
|
||||
buf->readIdx = 0;
|
||||
buf->wave.fill(&buf->bsrrWords[buf->halfLen], buf->halfLen);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
31
IR_Encoder.h
31
IR_Encoder.h
@ -1,6 +1,6 @@
|
||||
#pragma once
|
||||
#include "IR_config.h"
|
||||
#include "IrTxBsrrWave.h"
|
||||
#include "IrTxGateTypes.h"
|
||||
|
||||
// TODO: Отложенная передача после завершения приема
|
||||
|
||||
@ -14,6 +14,7 @@ struct IR_SendResult {
|
||||
};
|
||||
|
||||
class IR_DecoderRaw;
|
||||
class IrTxIsrBufferedStorageBase;
|
||||
class IR_Encoder : public IR_FOX
|
||||
{
|
||||
friend IR_DecoderRaw;
|
||||
@ -24,6 +25,10 @@ public:
|
||||
static HardwareTimer* IR_Timer;
|
||||
|
||||
using IR_TxGateRun = IrTxGateRun;
|
||||
enum class TxIsrMode : uint8_t {
|
||||
Legacy = 0,
|
||||
Buffered = 1
|
||||
};
|
||||
|
||||
using ExternalTxBusyFn = bool (*)(void *ctx);
|
||||
using ExternalTxStartFn = bool (*)(void *ctx, IR_Encoder *enc, const uint8_t *packet, uint8_t len);
|
||||
@ -69,10 +74,19 @@ public:
|
||||
/**
|
||||
* Режим внутреннего TX без DMA: false — BSRR + кольцо (buildGateRuns + scaleGateRunsToPhysical);
|
||||
* true — FSM «налету» + скважность несущей как у буферного пути (подшаги multiply/2 на шаг FSM).
|
||||
* Выставить до begin/rawSend (глобально на все IR_Encoder). Игнорируется при externalTxStartFn.
|
||||
* По умолчанию включён legacy=true для обратной совместимости. Вызов меняет default и обновляет
|
||||
* все зарегистрированные encoder-объекты. Buffered ISR реально используется только если у encoder
|
||||
* привязан storage через attachBufferedIsrStorage()/enableBufferedIsr().
|
||||
* Выставить до begin/rawSend. Игнорируется при externalTxStartFn.
|
||||
*/
|
||||
static void setTxIsrLegacyMode(bool legacy);
|
||||
static bool txIsrLegacyMode();
|
||||
void attachBufferedIsrStorage(IrTxIsrBufferedStorageBase& storage);
|
||||
void detachBufferedIsrStorage();
|
||||
bool hasBufferedIsrStorage() const;
|
||||
void enableBufferedIsr(IrTxIsrBufferedStorageBase& storage);
|
||||
void disableBufferedIsr();
|
||||
TxIsrMode txIsrMode() const;
|
||||
|
||||
/** Optional: register external TX backend (e.g. DMA driver). */
|
||||
static void setExternalTxBackend(ExternalTxStartFn startFn, ExternalTxBusyFn busyFn, void *ctx);
|
||||
@ -175,14 +189,7 @@ private:
|
||||
static bool txEmitTick(TxFsmState &st, const uint8_t *sendBufferLocal, bool &gateOut);
|
||||
void loadTxFsmFromMembers(TxFsmState &st) const;
|
||||
void storeTxFsmToMembers(const TxFsmState &st);
|
||||
|
||||
IrTxBsrrWave txBsrrWave_{};
|
||||
IR_TxGateRun txGateRuns_[irproto::kIsrTxMaxGateRuns]{};
|
||||
uint32_t txBsrrWords_[irproto::kIsrTxBsrrWordCount]{};
|
||||
uint16_t txBsrrReadIdx_ = 0;
|
||||
uint16_t txBsrrHalfLen_ = 0;
|
||||
uint32_t txBsrrTotalTicks_ = 0;
|
||||
uint32_t txBsrrTicksSent_ = 0;
|
||||
bool shouldUseBufferedIsr() const;
|
||||
|
||||
/** Снимок на старт TX (буферный и legacy путь). */
|
||||
uint16_t txPowerSnap_ = 1;
|
||||
@ -194,6 +201,10 @@ private:
|
||||
uint16_t legacySlotInPeriod_ = 0;
|
||||
|
||||
volatile uint16_t powerNumerator_ = 1;
|
||||
IrTxIsrBufferedStorageBase* txBufferedCtx_ = nullptr;
|
||||
IrTxIsrBufferedStorageBase* txActiveBufferedCtx_ = nullptr;
|
||||
TxIsrMode txIsrMode_ = TxIsrMode::Legacy;
|
||||
bool txUseBufferedIsr_ = false;
|
||||
|
||||
IR_DecoderRaw *decPair = nullptr;
|
||||
IR_DecoderRaw *singleBlindDecoder = nullptr;
|
||||
|
||||
@ -5,6 +5,14 @@
|
||||
|
||||
#if defined(ARDUINO_ARCH_STM32) && defined(STM32G4xx)
|
||||
|
||||
#if defined(_MSC_VER)
|
||||
#define IRPROTO_DMA_PRAGMA_MESSAGE(text) __pragma(message(text))
|
||||
#else
|
||||
#define IRPROTO_DMA_PRAGMA_MESSAGE(text) _Pragma(#text)
|
||||
#endif
|
||||
|
||||
IRPROTO_DMA_PRAGMA_MESSAGE(message("[IR-protocol] TX path available: built-in DMA"))
|
||||
|
||||
#include <Arduino.h>
|
||||
#include <HardwareTimer.h>
|
||||
|
||||
|
||||
64
IrTxIsrBufferedStorage.h
Normal file
64
IrTxIsrBufferedStorage.h
Normal file
@ -0,0 +1,64 @@
|
||||
#pragma once
|
||||
|
||||
#include "IR_config.h"
|
||||
#include "IrTxBsrrWave.h"
|
||||
|
||||
class IrTxIsrBufferedStorageBase {
|
||||
public:
|
||||
IrTxGateRun* gateRuns = nullptr;
|
||||
size_t maxGateRuns = 0;
|
||||
uint32_t* bsrrWords = nullptr;
|
||||
uint16_t wordCount = 0;
|
||||
|
||||
IrTxBsrrWave wave{};
|
||||
uint16_t readIdx = 0;
|
||||
uint16_t halfLen = 0;
|
||||
uint32_t totalTicks = 0;
|
||||
uint32_t ticksSent = 0;
|
||||
|
||||
bool isValid() const {
|
||||
return gateRuns != nullptr &&
|
||||
maxGateRuns != 0U &&
|
||||
bsrrWords != nullptr &&
|
||||
wordCount >= 2U &&
|
||||
(wordCount & 1U) == 0U;
|
||||
}
|
||||
|
||||
void resetRuntimeState() {
|
||||
readIdx = 0;
|
||||
halfLen = static_cast<uint16_t>(wordCount / 2U);
|
||||
totalTicks = 0;
|
||||
ticksSent = 0;
|
||||
}
|
||||
};
|
||||
|
||||
class IrTxIsrBufferedStorageView : public IrTxIsrBufferedStorageBase {
|
||||
public:
|
||||
IrTxIsrBufferedStorageView(IrTxGateRun* runs, size_t runCount, uint32_t* words, uint16_t wordsCount) {
|
||||
gateRuns = runs;
|
||||
maxGateRuns = runCount;
|
||||
bsrrWords = words;
|
||||
wordCount = wordsCount;
|
||||
resetRuntimeState();
|
||||
}
|
||||
};
|
||||
|
||||
template<size_t MaxGateRuns = irproto::kIsrTxMaxGateRuns, uint16_t WordCount = irproto::kIsrTxBsrrWordCount>
|
||||
class IrTxIsrBufferedStorage : public IrTxIsrBufferedStorageBase {
|
||||
static_assert(MaxGateRuns > 0U, "IrTxIsrBufferedStorage: MaxGateRuns > 0");
|
||||
static_assert(WordCount >= 2U, "IrTxIsrBufferedStorage: WordCount >= 2");
|
||||
static_assert((WordCount & 1U) == 0U, "IrTxIsrBufferedStorage: WordCount must be even");
|
||||
|
||||
public:
|
||||
IrTxIsrBufferedStorage() {
|
||||
gateRuns = gateRunsStorage_;
|
||||
maxGateRuns = MaxGateRuns;
|
||||
bsrrWords = bsrrWordsStorage_;
|
||||
wordCount = WordCount;
|
||||
resetRuntimeState();
|
||||
}
|
||||
|
||||
private:
|
||||
IrTxGateRun gateRunsStorage_[MaxGateRuns]{};
|
||||
uint32_t bsrrWordsStorage_[WordCount]{};
|
||||
};
|
||||
@ -1,5 +1,7 @@
|
||||
# Контракт бэкенда DMA-TX ИК (`IrDmaTxStm32`)
|
||||
|
||||
См. также: [IR_TX_MODES.md](IR_TX_MODES.md) — общая схема выбора `legacy ISR`, `buffered ISR` и `external backend`.
|
||||
|
||||
Платформа: **STM32G4**, Arduino STM32. Передача: **DMA memory → GPIO BSRR**, запрос от **TIM UPDATE** (частота `carrierFrec×2` из `IR_Encoder::beginClockOnly`).
|
||||
|
||||
### Число потоков (шаблон)
|
||||
|
||||
@ -55,7 +55,7 @@ IRRX t=1234988 rsn=MUTE_END cnt=42
|
||||
## Когда смотреть подробный debug
|
||||
|
||||
- `listenStart` / `checkTimeout` — в конце обработки фронта (`END:`) и во ветке «нет фронта» в `tick()`; не в начале до `pop`, иначе после таймаута `lastEdgeTime` расходится с метками ISR из очереди → ложные `TIMEOUT` (`bits=0`).
|
||||
- Пока в `subBuffer` / `filteredSubBuffer` или в hold фильтра есть необработанные фронты, таймаут по `micros() - lastEdgeTime` **не оценивается** (`rxTimeoutPipelineBusy`): иначе при хвосте очереди «тихая пауза» считается слишком длинной и снова ложный `TIMEOUT`.
|
||||
- Пока в `subBuffer` или в hold фильтра есть необработанные фронты, таймаут по `micros() - lastEdgeTime` **не оценивается** (`rxTimeoutPipelineBusy`): иначе при хвосте очереди «тихая пауза» считается слишком длинной и снова ложный `TIMEOUT`.
|
||||
- Если нужен полный поток битов и sync: включать `IRDEBUG_SERIAL_PACK`
|
||||
- Если нужно понять, какие именно фронты пришли в ISR: включать `IR_EDGE_TRACE`
|
||||
- `IR_RX_BRIEF_LOG` нужен как короткий always-on-ish индикатор сути проблемы, без длинного дампа
|
||||
|
||||
Reference in New Issue
Block a user