19 Commits

Author SHA1 Message Date
0620d98e35 Merge branch 'main' into STM32 2026-03-11 17:06:06 +03:00
4caed06218 Merge pull request #7 from Show-maket/STM32DMA
upd
2026-03-11 16:59:08 +03:00
fc1a3bacef upd 2026-03-11 16:57:55 +03:00
8a0d7f8dba carrierPauseIfIdle/carrierResume 2026-02-06 16:06:23 +03:00
d1c84ba18a no grammar fix 2025-10-17 17:28:01 +03:00
e9c568aed2 grammar fix 2025-10-17 17:25:09 +03:00
7bf71d1d52 calculateSendTime (need to fix) 2025-09-05 18:24:19 +03:00
38f3ecac3a isBusy 2025-08-25 13:01:58 +03:00
dec8467280 max pack 2025-08-22 15:33:19 +03:00
bc9563fbb5 isReceive type 2025-05-23 11:43:51 +03:00
021e1e290d fix isRX flag 2025-05-22 12:08:22 +03:00
89d14919c9 fix isRecive 2025-03-12 16:15:35 +03:00
403b8e6850 isRecive fix 2025-03-12 15:38:33 +03:00
d0c3138c52 Merge pull request #6 from Show-maket/STM32-opti-test
Stm32 opti test
2025-03-06 17:07:13 +03:00
37522f974f upd 2024-12-25 16:56:18 +03:00
6375c4eed5 for debug test 2024-09-04 10:12:39 +03:00
c4000d6b75 test 2024-08-14 17:43:12 +03:00
fc02c79135 upd 2024-04-22 14:56:12 +03:00
d068a576f7 Merge pull request #3 from Show-maket/dev
v2.0
2024-03-18 16:24:38 +03:00
9 changed files with 574 additions and 125 deletions

2
.gitignore vendored
View File

@ -1,5 +1,3 @@
.vscode/* .vscode/*
bin/* bin/*
!.vscode/launch.json
log/* log/*
/.vscode

View File

@ -2,26 +2,16 @@
#include "IR_Encoder.h" #include "IR_Encoder.h"
#include "TimerStatic.h" #include "TimerStatic.h"
#include "MemoryCheck.h" #include "MemoryCheck.h"
#include "CarCmdList.h"
/////////////// Pinout /////////////// /////////////// Pinout ///////////////
#define dec0_PIN PIN_KT1_IN #define encForward_PIN 0
#define dec1_PIN PIN_KT2_IN #define encBackward_PIN 5
#define dec2_PIN PIN_KT3_IN
#define dec3_PIN PIN_KT4_IN
#define dec4_PIN PIN_KT5_IN
#define dec5_PIN PIN_KT6_IN
#define dec6_PIN PIN_KT7_IN
#define dec7_PIN PIN_KT8_IN
// #define dec8_PIN PB8
// #define dec9_PIN PB9
// #define dec10_PIN PB10
// #define dec11_PIN PB11
// #define dec12_PIN PB12
// #define dec13_PIN PB13
// #define dec14_PIN PB14
// #define dec15_PIN PB15
#define LoopOut PC13 #define LoopOut 12
#define ISR_Out 10
#define TestOut 13
//////////////// Ini ///////////////// //////////////// Ini /////////////////
@ -49,13 +39,35 @@ void EncoderISR()
IR_Encoder::isr(); IR_Encoder::isr();
} }
//------------------------------------------------------------------- void decBackwardISR() {
decBackward.isr();
}
IR_Decoder dec0(dec0_PIN, 0); static uint8_t* portOut;
void dec_0_ISR() { dec0.isr(); } ISR(TIMER2_COMPA_vect) {
encForward.isr();
// encBackward.isr();
// encTree.isr();
//TODO: Сделать выбор порта
*portOut = (*portOut & 0b11111110) |
(
encForward.ir_out_virtual << 0U
// | encBackward.ir_out_virtual << 6U
// | encTree.ir_out_virtual << 2U
);
}
/////////////////////////////////////////////////////////////////////
uint8_t data0 [] = { };
uint8_t data1 [] = { 42 };
uint8_t data2 [] = { 42 , 127 };
uint8_t data3 [] = { 42 , 127, 137 };
uint8_t data4 [] = { 42 , 127, 137, 255 };
IR_Decoder dec1(dec1_PIN, 1); uint32_t loopTimer;
void dec_1_ISR() { dec1.isr(); } uint8_t sig = 255;
uint16_t targetAddr = IR_Broadcast;
Timer t1(750, millis, []() {
IR_Decoder dec2(dec2_PIN, 2); IR_Decoder dec2(dec2_PIN, 2);
void dec_2_ISR() { dec2.isr(); } void dec_2_ISR() { dec2.isr(); }
@ -81,8 +93,19 @@ void dec_7_ISR() { dec7.isr(); }
// IR_Decoder dec9(dec9_PIN, 9); // IR_Decoder dec9(dec9_PIN, 9);
// void dec_9_ISR() { dec9.isr(); } // void dec_9_ISR() { dec9.isr(); }
// IR_Decoder dec10(dec10_PIN, 10); default:
// void dec_10_ISR() { dec10.isr(); } break;
}
// encBackward.sendData(IR_Broadcast, data2);
// encTree.sendData(IR_Broadcast, rawData3);
});
Timer t2(500, millis, []() {
digitalToggle(13);
});
/////////////////////////////////////////////////////////////////////
void setup() {
IR_Encoder::timerSetup();
portOut = &PORTB;
// IR_Decoder dec11(dec11_PIN, 11); // IR_Decoder dec11(dec11_PIN, 11);
// void dec_11_ISR() { dec11.isr(); } // void dec_11_ISR() { dec11.isr(); }
@ -100,9 +123,14 @@ uint8_t data2[] = {42, 127};
uint8_t data3[] = {42, 127, 137}; uint8_t data3[] = {42, 127, 137};
uint8_t data4[] = {42, 127, 137, 255}; uint8_t data4[] = {42, 127, 137, 255};
uint32_t loopTimer; pinMode(8, OUTPUT);
uint8_t sig = 0; pinMode(9, OUTPUT);
uint16_t targetAddr = IR_Broadcast; pinMode(11, OUTPUT);
pinMode(13, OUTPUT);
pinMode(encForward_PIN, OUTPUT);
pinMode(encBackward_PIN, OUTPUT);
pinMode(13, OUTPUT);
pinMode(12, OUTPUT);
Timer t1(500, millis, []() Timer t1(500, millis, []()
{ {
@ -217,61 +245,30 @@ void setup()
pinMode(LoopOut, OUTPUT); pinMode(LoopOut, OUTPUT);
pinMode(dec0_PIN, INPUT_PULLUP); attachInterrupt(0, decForwardISR, CHANGE); // D2
pinMode(dec1_PIN, INPUT_PULLUP); attachInterrupt(1, decBackwardISR, CHANGE); // D3
pinMode(dec2_PIN, INPUT_PULLUP);
pinMode(dec3_PIN, INPUT_PULLUP);
pinMode(dec4_PIN, INPUT_PULLUP);
pinMode(dec5_PIN, INPUT_PULLUP);
pinMode(dec6_PIN, INPUT_PULLUP);
pinMode(dec7_PIN, INPUT_PULLUP);
// pinMode(dec8_PIN, INPUT_PULLUP);
// pinMode(dec9_PIN, INPUT_PULLUP);
// pinMode(dec10_PIN, INPUT_PULLUP);
// pinMode(dec11_PIN, INPUT_PULLUP);
// pinMode(dec12_PIN, INPUT_PULLUP);
// pinMode(dec13_PIN, INPUT_PULLUP);
attachInterrupt(dec0_PIN, dec_0_ISR, CHANGE);
attachInterrupt(dec1_PIN, dec_1_ISR, CHANGE);
attachInterrupt(dec2_PIN, dec_2_ISR, CHANGE);
attachInterrupt(dec3_PIN, dec_3_ISR, CHANGE);
attachInterrupt(dec4_PIN, dec_4_ISR, CHANGE);
attachInterrupt(dec5_PIN, dec_5_ISR, CHANGE);
attachInterrupt(dec6_PIN, dec_6_ISR, CHANGE);
attachInterrupt(dec7_PIN, dec_7_ISR, CHANGE);
// attachInterrupt(dec8_PIN, dec_8_ISR, CHANGE);
// attachInterrupt(dec9_PIN, dec_9_ISR, CHANGE);
// attachInterrupt(dec10_PIN, dec_10_ISR, CHANGE);
// attachInterrupt(dec11_PIN, dec_11_ISR, CHANGE);
// attachInterrupt(dec12_PIN, dec_12_ISR, CHANGE);
// attachInterrupt(dec13_PIN, dec_13_ISR, CHANGE);
} }
void loop()
{ bool testLed = false;
digitalToggle(LoopOut); uint32_t testLed_timer;
void loop() {
// digitalToggle(LoopOut);
Timer::tick(); Timer::tick();
IR_Decoder::tick();
bool rx_flag = false; decForward.tick();
rx_flag |= status(dec0); decBackward.tick();
rx_flag |= status(dec1);
rx_flag |= status(dec2);
rx_flag |= status(dec3);
rx_flag |= status(dec4);
rx_flag |= status(dec5);
rx_flag |= status(dec6);
rx_flag |= status(dec7);
// rx_flag |= status(dec8);
// rx_flag |= status(dec9);
// rx_flag |= status(dec10);
// rx_flag |= status(dec11);
// rx_flag |= status(dec12);
// rx_flag |= status(dec13);
if (Serial.available()) status(decForward);
{ status(decBackward);
// Serial.println(micros() - loopTimer);
// loopTimer = micros();
// delayMicroseconds(120*5);
if (Serial.available()) {
uint8_t in = Serial.parseInt(); uint8_t in = Serial.parseInt();
switch (in) switch (in)
{ {
@ -289,6 +286,13 @@ void loop()
break; break;
} }
} }
if(testLed && millis() - testLed_timer > 100){
testLed=false;
digitalWrite(12, LOW);
}
} }
@ -316,13 +320,19 @@ void detectSignal()
// { digitalWrite(SignalDetectLed, LOW); }); // { digitalWrite(SignalDetectLed, LOW); });
} }
// test
bool status(IR_Decoder &dec)
{ //test
if (dec.gotData.available()) void status(IR_Decoder& dec) {
{ if (dec.gotData.available() && dec.gotData.getAddrFrom() != 42) {
detectSignal();
// Serial.println(micros()); digitalWrite(12, HIGH);
testLed = true;
testLed_timer = millis();
encForward.sendData(IR_Broadcast, CarCmd::stop); //<<<<<<<<<<<<<<<<<<<<<<<<<<< CMD IS HERE
String str; String str;
if (/* dec.gotData.getDataPrt()[1] */ 1) if (/* dec.gotData.getDataPrt()[1] */ 1)
{ {

View File

@ -61,6 +61,7 @@ void IR_Decoder::tick()
void IR_Decoder::_tick() void IR_Decoder::_tick()
{ {
IR_DecoderRaw::tick(); IR_DecoderRaw::tick();
if (availableRaw()) if (availableRaw())
{ {
#ifdef IRDEBUG_INFO #ifdef IRDEBUG_INFO
@ -103,3 +104,7 @@ void IR_Decoder::_tick()
isWaitingAcceptSend = false; isWaitingAcceptSend = false;
} }
} }
bool IR_Decoder::isReceive(uint8_t type) {
return (msgTypeReceive & 0b11111000) && ((msgTypeReceive & IR_MASK_MSG_TYPE) == type);
}

View File

@ -32,6 +32,8 @@ public:
void enable(); void enable();
void disable(); void disable();
bool isReceive(uint8_t type);
~IR_Decoder(); ~IR_Decoder();
static void tick(); static void tick();

View File

@ -112,16 +112,37 @@ void IR_DecoderRaw::firstRX()
void IR_DecoderRaw::listenStart() void IR_DecoderRaw::listenStart()
{ {
if (isRecive && ((micros() - prevRise) > IR_timeout * 2)) if (isReciveRaw && ((micros() - prevRise) > IR_timeout * 2))
{ {
// Serial.print("\nlis>"); // Serial.print("\nlis>");
isRecive = false; isReciveRaw = false;
firstRX(); firstRX();
} }
} }
// ---- быстрая проверка конца пакета ---------------------------------
inline void IR_DecoderRaw::checkTimeout()
{
if (!isRecive) return; // уже не принимаем нечего проверять
if (micros() - lastEdgeTime > IR_timeout * 2U)
{
isRecive = false; // приём завершён
msgTypeReceive = 0;
// firstRX(); // подготовка к новому пакету
lastEdgeTime = micros(); // защита от повторного срабатывания
}
}
// ====================================================================
void IR_DecoderRaw::tick() void IR_DecoderRaw::tick()
{ {
// FrontStorage *currentFrontPtr;
// noInterrupts();
// currentFrontPtr = subBuffer.pop();
// interrupts();
FrontStorage currentFront; FrontStorage currentFront;
noInterrupts(); noInterrupts();
listenStart(); listenStart();
@ -130,12 +151,24 @@ void IR_DecoderRaw::tick()
if (currentFrontPtr == nullptr) if (currentFrontPtr == nullptr)
{ {
isSubBufferOverflow = false; isSubBufferOverflow = false;
checkTimeout(); // <--- новое место проверки
interrupts(); interrupts();
return; return;
} // Если данных нет - ничего не делаем } // Если данных нет - ничего не делаем
currentFront = *currentFrontPtr; currentFront = *currentFrontPtr;
interrupts(); interrupts();
// ---------- буфер пуст: фронтов нет, проверяем тайм-аут ----------
// if (currentFrontPtr == nullptr)
// {
// isSubBufferOverflow = false;
// return;
// }
// // ---------- есть фронт: продолжаем обработку ----------
// FrontStorage currentFront = *currentFrontPtr;
lastEdgeTime = currentFront.time; // запоминаем любой фронт
//////////////////////////////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////////////////////////////////
if (currentFront.dir) if (currentFront.dir)
@ -197,7 +230,7 @@ void IR_DecoderRaw::tick()
digitalWrite(errOut, currentFront.dir); digitalWrite(errOut, currentFront.dir);
#endif #endif
if (currentFront.time > prevRise && currentFront.time - prevRise > IR_timeout * 2 && !isRecive) if (currentFront.time > prevRise && currentFront.time - prevRise > IR_timeout * 2 && !isReciveRaw)
{ // первый { // первый
#ifdef IRDEBUG #ifdef IRDEBUG
errPulse(up, 50); errPulse(up, 50);
@ -209,6 +242,7 @@ void IR_DecoderRaw::tick()
isPreamb = true; isPreamb = true;
isRecive = true; isRecive = true;
isReciveRaw = true;
isWrongPack = false; isWrongPack = false;
} }
@ -441,6 +475,8 @@ void IR_DecoderRaw::writeToBuffer(bool bit)
if (isBufferOverflow || isPreamb || isWrongPack) if (isBufferOverflow || isPreamb || isWrongPack)
{ {
isRecive = false; isRecive = false;
isReciveRaw = false;
msgTypeReceive = 0;
return; return;
} }
@ -564,6 +600,8 @@ void IR_DecoderRaw::writeToBuffer(bool bit)
packInfo.rTime = riseSyncTime; packInfo.rTime = riseSyncTime;
isRecive = false; isRecive = false;
isReciveRaw = false;
msgTypeReceive = 0;
isAvailable = crcCheck(packSize - crcBytes, crcValue); isAvailable = crcCheck(packSize - crcBytes, crcValue);
#ifdef BRUTEFORCE_CHECK #ifdef BRUTEFORCE_CHECK
@ -594,6 +632,12 @@ void IR_DecoderRaw::writeToBuffer(bool bit)
OUT_BRUTEFORCE:; OUT_BRUTEFORCE:;
#endif #endif
} }
if (packSize && (i_dataBuffer == 8)) {
msgTypeReceive = (dataBuffer[0]>>5) | 0b11111000;
// SerialUSB.println(msgTypeReceive & IR_MASK_MSG_TYPE);
}
} }
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////

View File

@ -31,9 +31,10 @@ class IR_DecoderRaw : virtual public IR_FOX
friend IR_Encoder; friend IR_Encoder;
protected: protected:
PackInfo packInfo; PackInfo packInfo;
IR_Encoder *encoder; // Указатель на парный передатчик uint8_t msgTypeReceive = 0;
bool availableRaw(); IR_Encoder *encoder; // Указатель на парный передатчик
bool availableRaw();
public: public:
////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////
@ -48,7 +49,7 @@ public:
inline bool isOverflow() { return isBufferOverflow; }; // Буффер переполнился inline bool isOverflow() { return isBufferOverflow; }; // Буффер переполнился
bool isSubOverflow(); bool isSubOverflow();
inline bool isReciving() { return isBufferOverflow; }; // Возвращает true, если происходит приём пакета volatile inline bool isReciving() { return isRecive; }; // Возвращает true, если происходит приём пакета
////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////
private: private:
@ -65,6 +66,8 @@ private:
uint16_t riseSyncTime = bitTime; // Подстраиваемое время бита в мкс uint16_t riseSyncTime = bitTime; // Подстраиваемое время бита в мкс
volatile uint32_t lastEdgeTime = 0; // время последнего фронта
//////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////
volatile uint32_t currentSubBufferIndex; // Счетчик текущей позиции во вспомогательном буфере фронтов/спадов volatile uint32_t currentSubBufferIndex; // Счетчик текущей позиции во вспомогательном буфере фронтов/спадов
@ -100,7 +103,9 @@ private:
int16_t bufBitPos = 0; // Позиция для записи бита в буффер int16_t bufBitPos = 0; // Позиция для записи бита в буффер
private: private:
void listenStart(); // @brief Слушатель для работы isReciving() bool isReciveRaw;
void listenStart();
void checkTimeout(); //
/// @brief Проверка CRC. Проверяет len байт со значением crc, пришедшим в пакете /// @brief Проверка CRC. Проверяет len байт со значением crc, пришедшим в пакете
/// @param len Длина в байтах проверяемых данных /// @param len Длина в байтах проверяемых данных

View File

@ -1,5 +1,6 @@
#include "IR_Encoder.h" #include "IR_Encoder.h"
#include "IR_DecoderRaw.h" #include "IR_DecoderRaw.h"
#include <string.h>
#define LoopOut 12 #define LoopOut 12
#define ISR_Out 10 #define ISR_Out 10
@ -7,6 +8,7 @@
IR_Encoder *IR_Encoder::head = nullptr; IR_Encoder *IR_Encoder::head = nullptr;
IR_Encoder *IR_Encoder::last = nullptr; IR_Encoder *IR_Encoder::last = nullptr;
volatile bool IR_Encoder::carrierStopPending = false;
IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair, bool autoHandle) IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair, bool autoHandle)
{ {
@ -38,20 +40,204 @@ IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair, bool
last->next = this; last->next = this;
} }
last = this; last = this;
pinMode(pin, OUTPUT);
} }
}; };
HardwareTimer* IR_Encoder::IR_Timer = nullptr; 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;
inline HardwareTimer* IR_Encoder::get_IR_Timer(){return IR_Encoder::IR_Timer;} inline HardwareTimer* IR_Encoder::get_IR_Timer(){return IR_Encoder::IR_Timer;}
void IR_Encoder::carrierResume() {
if (IR_Timer != nullptr)
IR_Timer->resume();
}
void IR_Encoder::carrierPauseIfIdle() {
for (IR_Encoder *p = head; p != nullptr; p = p->next)
if (p->isSending)
return;
if (IR_Timer != nullptr)
IR_Timer->pause();
}
void IR_Encoder::tick() {
if (!carrierStopPending)
return;
carrierStopPending = false;
carrierPauseIfIdle();
}
void IR_Encoder::begin(HardwareTimer* timer, uint8_t channel, IRQn_Type IRQn, uint8_t priority, void(*isrCallback)()){ void IR_Encoder::begin(HardwareTimer* timer, uint8_t channel, IRQn_Type IRQn, uint8_t priority, void(*isrCallback)()){
IR_Timer = timer; IR_Timer = timer;
if(IR_Timer == nullptr) return; if(IR_Timer == nullptr) return;
IR_Timer->pause();
IR_Timer->setOverflow(carrierFrec * 2, HERTZ_FORMAT); IR_Timer->setOverflow(carrierFrec * 2, HERTZ_FORMAT);
IR_Timer->attachInterrupt(channel, (isrCallback == nullptr ? IR_Encoder::isr : isrCallback)); IR_Timer->attachInterrupt(channel, (isrCallback == nullptr ? IR_Encoder::isr : isrCallback));
NVIC_SetPriority(IRQn, priority); NVIC_SetPriority(IRQn, priority);
IR_Timer->resume(); IR_Timer->pause();
}
void IR_Encoder::beginClockOnly(HardwareTimer *timer)
{
IR_Timer = timer;
if (IR_Timer == nullptr)
return;
IR_Timer->pause();
IR_Timer->setOverflow(carrierFrec * 2, HERTZ_FORMAT);
IR_Timer->pause();
}
void IR_Encoder::setExternalTxBackend(ExternalTxStartFn startFn, ExternalTxBusyFn busyFn, void *ctx)
{
externalTxStartFn = startFn;
externalTxBusyFn = busyFn;
externalTxCtx = ctx;
}
void IR_Encoder::externalFinishSend()
{
if (!isSending)
return;
// Force output low.
if (port != nullptr) {
port->BSRR = ((uint32_t)mask) << 16;
}
isSending = false;
setDecoder_isSending();
}
size_t IR_Encoder::buildGateRuns(const uint8_t *packet, uint8_t len, IR_TxGateRun *outRuns, size_t maxRuns)
{
if (packet == nullptr || outRuns == nullptr || maxRuns == 0)
{
return 0;
}
if (len == 0 || len > dataByteSizeMax)
{
return 0;
}
// Copy into fixed-size buffer to match original encoder behavior (safe reads past sendLen).
uint8_t sendBufferLocal[dataByteSizeMax] = {0};
memcpy(sendBufferLocal, packet, len);
uint8_t sendLenLocal = len;
uint8_t toggleCounterLocal = preambToggle;
uint8_t dataBitCounterLocal = bitPerByte - 1;
uint8_t dataByteCounterLocal = 0;
uint8_t preambFrontCounterLocal = preambPulse * 2 - 1;
uint8_t dataSequenceCounterLocal = bitPerByte * 2;
uint8_t syncSequenceCounterLocal = syncBits * 2;
bool syncLastBitLocal = false;
SignalPart signalLocal = preamb;
bool stateLocal = HIGH;
uint8_t *currentBitSequenceLocal = bitHigh;
size_t runCount = 0;
while (true)
{
const bool gate = stateLocal;
const uint16_t runLenTicks = (uint16_t)toggleCounterLocal + 1U;
if (runCount > 0 && outRuns[runCount - 1].gate == gate)
{
outRuns[runCount - 1].lenTicks = (uint16_t)(outRuns[runCount - 1].lenTicks + runLenTicks);
}
else
{
if (runCount >= maxRuns)
{
return 0;
}
outRuns[runCount].gate = gate;
outRuns[runCount].lenTicks = runLenTicks;
runCount++;
}
// Advance state to the next run boundary (equivalent to ISR iteration when toggleCounter == 0).
while (true)
{
switch (signalLocal)
{
case noSignal:
return runCount;
case preamb:
if (preambFrontCounterLocal)
{
preambFrontCounterLocal--;
toggleCounterLocal = preambToggle;
break;
}
// End of preamble.
signalLocal = data;
stateLocal = !LOW;
continue;
case data:
if (dataSequenceCounterLocal)
{
if (!(dataSequenceCounterLocal & 1U))
{
currentBitSequenceLocal = ((sendBufferLocal[dataByteCounterLocal] >> dataBitCounterLocal) & 1U) ? bitHigh : bitLow;
dataBitCounterLocal--;
}
toggleCounterLocal = currentBitSequenceLocal[!stateLocal];
dataSequenceCounterLocal--;
break;
}
// End of data byte.
syncLastBitLocal = ((sendBufferLocal[dataByteCounterLocal]) & 1U);
dataByteCounterLocal++;
dataBitCounterLocal = bitPerByte - 1;
dataSequenceCounterLocal = bitPerByte * 2;
signalLocal = sync;
continue;
case sync:
if (syncSequenceCounterLocal)
{
if (!(syncSequenceCounterLocal & 1U))
{
if (syncSequenceCounterLocal == 2)
{
currentBitSequenceLocal = ((sendBufferLocal[dataByteCounterLocal]) & 0b10000000) ? bitLow : bitHigh;
}
else
{
currentBitSequenceLocal = syncLastBitLocal ? bitLow : bitHigh;
syncLastBitLocal = !syncLastBitLocal;
}
}
toggleCounterLocal = currentBitSequenceLocal[!stateLocal];
syncSequenceCounterLocal--;
break;
}
// End of sync.
signalLocal = data;
syncSequenceCounterLocal = syncBits * 2;
if (dataByteCounterLocal >= sendLenLocal)
{
signalLocal = noSignal;
}
continue;
default:
return 0;
}
stateLocal = !stateLocal;
break;
}
}
} }
@ -126,20 +312,24 @@ void IR_Encoder::setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count)
IR_Encoder::~IR_Encoder(){}; IR_Encoder::~IR_Encoder(){};
void IR_Encoder::sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept) IR_SendResult IR_Encoder::sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept)
{ {
sendData(addrTo, &dataByte, 1, needAccept); return sendData(addrTo, &dataByte, 1, needAccept);
} }
void IR_Encoder::sendData(uint16_t addrTo, uint8_t *data, uint8_t len, bool needAccept){ IR_SendResult IR_Encoder::sendData(uint16_t addrTo, uint8_t *data, uint8_t len, bool needAccept){
sendDataFULL(id, addrTo, data, len, needAccept); return sendDataFULL(id, addrTo, data, len, needAccept);
} }
void IR_Encoder::sendDataFULL(uint16_t addrFrom, uint16_t addrTo, uint8_t *data, uint8_t len, bool needAccept) void IR_Encoder::sendData(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false){
sendData(id, addrTo, data, len, needAccept);
}
void IR_Encoder::sendData(uint16_t addrFrom, uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false)
{ {
if (len > bytePerPack) if (len > bytePerPack)
{ {
return; Serial.println("IR Pack to big");
return IR_SendResult(false, 0);
} }
constexpr uint8_t dataStart = msgBytes + addrBytes + addrBytes; constexpr uint8_t dataStart = msgBytes + addrBytes + addrBytes;
memset(sendBuffer, 0x00, dataByteSizeMax); memset(sendBuffer, 0x00, dataByteSizeMax);
@ -168,6 +358,19 @@ void IR_Encoder::sendDataFULL(uint16_t addrFrom, uint16_t addrTo, uint8_t *data,
sendBuffer[packSize - crcBytes] = crc8(sendBuffer, 0, packSize - crcBytes, poly1) & 0xFF; sendBuffer[packSize - crcBytes] = crc8(sendBuffer, 0, packSize - crcBytes, poly1) & 0xFF;
sendBuffer[packSize - crcBytes + 1] = crc8(sendBuffer, 0, packSize - crcBytes + 1, poly2) & 0xFF; sendBuffer[packSize - crcBytes + 1] = crc8(sendBuffer, 0, packSize - crcBytes + 1, poly2) & 0xFF;
//* вывод итогового буфера
// Serial.print("IR SEND [len=");
// Serial.print(packSize);
// Serial.print("] : ");
// for (uint8_t i = 0; i < packSize; i++)
// {
// if (sendBuffer[i] < 0x10)
// Serial.print('0');
// Serial.print(sendBuffer[i], HEX);
// Serial.print(' ');
// }
// Serial.println();
// if (decPair != nullptr) { // if (decPair != nullptr) {
// decPair->isWaitingAccept = ((msgType >> 5) & IR_MASK_MSG_TYPE == IR_MSG_DATA_ACCEPT); // decPair->isWaitingAccept = ((msgType >> 5) & IR_MASK_MSG_TYPE == IR_MSG_DATA_ACCEPT);
// if (decPair->isWaitingAccept) { // if (decPair->isWaitingAccept) {
@ -177,9 +380,14 @@ void IR_Encoder::sendDataFULL(uint16_t addrFrom, uint16_t addrTo, uint8_t *data,
// отправка // отправка
rawSend(sendBuffer, packSize); rawSend(sendBuffer, packSize);
// Возвращаем результат отправки
uint32_t sendTime = calculateSendTime(packSize);
return IR_SendResult(true, sendTime);
} }
void IR_Encoder::sendAccept(uint16_t addrTo, uint8_t customByte)
IR_SendResult IR_Encoder::sendAccept(uint16_t addrTo, uint8_t customByte)
{ {
constexpr uint8_t packsize = msgBytes + addrBytes + 1U + crcBytes; constexpr uint8_t packsize = msgBytes + addrBytes + 1U + crcBytes;
memset(sendBuffer, 0x00, dataByteSizeMax); memset(sendBuffer, 0x00, dataByteSizeMax);
@ -200,9 +408,13 @@ void IR_Encoder::sendAccept(uint16_t addrTo, uint8_t customByte)
sendBuffer[5] = crc8(sendBuffer, 0, 5, poly2) & 0xFF; sendBuffer[5] = crc8(sendBuffer, 0, 5, poly2) & 0xFF;
rawSend(sendBuffer, packsize); rawSend(sendBuffer, packsize);
// Возвращаем результат отправки
uint32_t sendTime = calculateSendTime(packsize);
return IR_SendResult(true, sendTime);
} }
void IR_Encoder::sendRequest(uint16_t addrTo) IR_SendResult IR_Encoder::sendRequest(uint16_t addrTo)
{ {
constexpr uint8_t packsize = msgBytes + addrBytes + addrBytes + crcBytes; constexpr uint8_t packsize = msgBytes + addrBytes + addrBytes + crcBytes;
memset(sendBuffer, 0x00, dataByteSizeMax); memset(sendBuffer, 0x00, dataByteSizeMax);
@ -222,28 +434,32 @@ void IR_Encoder::sendRequest(uint16_t addrTo)
sendBuffer[6] = crc8(sendBuffer, 0, 6, poly2) & 0xFF; sendBuffer[6] = crc8(sendBuffer, 0, 6, poly2) & 0xFF;
rawSend(sendBuffer, packsize); rawSend(sendBuffer, packsize);
// Возвращаем результат отправки
uint32_t sendTime = calculateSendTime(packsize);
return IR_SendResult(true, sendTime);
} }
void IR_Encoder::sendBack(uint8_t data) IR_SendResult IR_Encoder::sendBack(uint8_t data)
{ {
_sendBack(false, 0, &data, 1); return _sendBack(false, 0, &data, 1);
} }
void IR_Encoder::sendBack(uint8_t *data, uint8_t len) IR_SendResult IR_Encoder::sendBack(uint8_t *data, uint8_t len)
{ {
_sendBack(false, 0, data, len); return _sendBack(false, 0, data, len);
} }
void IR_Encoder::sendBackTo(uint16_t addrTo, uint8_t *data, uint8_t len) IR_SendResult IR_Encoder::sendBackTo(uint16_t addrTo, uint8_t *data, uint8_t len)
{ {
_sendBack(true, addrTo, data, len); return _sendBack(true, addrTo, data, len);
} }
void IR_Encoder::_sendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint8_t len) IR_SendResult IR_Encoder::_sendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint8_t len)
{ {
if (len > bytePerPack) if (len > bytePerPack)
{ {
return; return IR_SendResult(false, 0);
} }
memset(sendBuffer, 0x00, dataByteSizeMax); memset(sendBuffer, 0x00, dataByteSizeMax);
uint8_t dataStart = msgBytes + addrBytes + (isAdressed ? addrBytes : 0); uint8_t dataStart = msgBytes + addrBytes + (isAdressed ? addrBytes : 0);
@ -275,6 +491,10 @@ void IR_Encoder::_sendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint
// отправка // отправка
rawSend(sendBuffer, packSize); rawSend(sendBuffer, packSize);
// Возвращаем результат отправки
uint32_t sendTime = calculateSendTime(packSize);
return IR_SendResult(true, sendTime);
} }
void IR_Encoder::setDecoder_isSending() void IR_Encoder::setDecoder_isSending()
@ -299,6 +519,34 @@ void IR_Encoder::rawSend(uint8_t *ptr, uint8_t len)
// TODO: Обработка повторной отправки // TODO: Обработка повторной отправки
return; return;
} }
// Проверка на переполнение буфера
if (len > dataByteSizeMax)
{
return;
}
if (externalTxStartFn != nullptr)
{
if (externalTxBusyFn != nullptr && externalTxBusyFn(externalTxCtx))
{
return;
}
// Mark as sending and delegate actual signal output to external backend.
setDecoder_isSending();
sendLen = len;
isSending = true;
const bool ok = externalTxStartFn(externalTxCtx, this, ptr, len);
if (!ok)
{
isSending = false;
setDecoder_isSending();
}
return;
}
IR_Encoder::carrierResume();
// Serial.println("START"); // Serial.println("START");
setDecoder_isSending(); setDecoder_isSending();
@ -318,7 +566,6 @@ void IR_Encoder::rawSend(uint8_t *ptr, uint8_t len)
state = HIGH; state = HIGH;
currentBitSequence = bitHigh; currentBitSequence = bitHigh;
isSending = true;
// interrupts(); // interrupts();
} }
@ -358,6 +605,7 @@ void IR_Encoder::_isr()
isSending = false; isSending = false;
// Serial.println("STOP"); // Serial.println("STOP");
setDecoder_isSending(); setDecoder_isSending();
carrierStopPending = true;
// Serial.println(); // Serial.println();
return; return;
break; break;
@ -483,6 +731,91 @@ uint8_t IR_Encoder::bitLow[2] = {
(bitPauseTakts / 2 + bitActiveTakts) * 2 - 1, (bitPauseTakts / 2 + bitActiveTakts) * 2 - 1,
(bitPauseTakts)-1}; (bitPauseTakts)-1};
uint32_t IR_Encoder::calculateSendTime(uint8_t packSize) const
{
// Расчет времени отправки пакета в миллисекундах
// Время преамбулы: preambPulse * 2 фронта * bitTakts тактов
uint32_t preambTime = preambPulse * 2 * bitTakts;
// Время данных: количество бит * bitTakts тактов
uint32_t dataTime = packSize * 8 * bitTakts;
// Время синхронизации: syncBits * 2 фронта * bitTakts тактов
uint32_t syncTime = syncBits * 2 * bitTakts;
// Общее время в тактах
uint32_t totalTakts = preambTime + dataTime + syncTime;
// Конвертируем в миллисекунды
// carrierPeriod - период несущей в микросекундах
// totalTakts * carrierPeriod / 1000 = время в миллисекундах
uint32_t sendTimeMs = (totalTakts * carrierPeriod) / 1000;
return sendTimeMs;
}
// Функции для тестирования времени отправки без фактической отправки
uint32_t IR_Encoder::testSendTime(uint16_t addrTo, uint8_t dataByte, bool needAccept) const
{
return testSendTime(addrTo, &dataByte, 1, needAccept);
}
uint32_t IR_Encoder::testSendTime(uint16_t addrTo, uint8_t *data, uint8_t len, bool needAccept) const
{
return testSendTimeFULL(id, addrTo, data, len, needAccept);
}
uint32_t IR_Encoder::testSendTimeFULL(uint16_t addrFrom, uint16_t addrTo, uint8_t *data, uint8_t len, bool needAccept) const
{
if (len > bytePerPack)
{
return 0; // Возвращаем 0 для недопустимого размера
}
uint8_t packSize = msgBytes + addrBytes + addrBytes + len + crcBytes;
return calculateSendTime(packSize);
}
uint32_t IR_Encoder::testSendAccept(uint16_t addrTo, uint8_t customByte) const
{
constexpr uint8_t packsize = msgBytes + addrBytes + 1U + crcBytes;
return calculateSendTime(packsize);
}
uint32_t IR_Encoder::testSendRequest(uint16_t addrTo) const
{
constexpr uint8_t packsize = msgBytes + addrBytes + addrBytes + crcBytes;
return calculateSendTime(packsize);
}
uint32_t IR_Encoder::testSendBack(uint8_t data) const
{
return testSendBack(false, 0, &data, 1);
}
uint32_t IR_Encoder::testSendBack(uint8_t *data, uint8_t len) const
{
return testSendBack(false, 0, data, len);
}
uint32_t IR_Encoder::testSendBackTo(uint16_t addrTo, uint8_t *data, uint8_t len) const
{
return testSendBack(true, addrTo, data, len);
}
uint32_t IR_Encoder::testSendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint8_t len) const
{
if (len > bytePerPack)
{
return 0; // Возвращаем 0 для недопустимого размера
}
uint8_t packSize = msgBytes + addrBytes + (isAdressed ? addrBytes : 0) + min(uint8_t(1), len) + crcBytes;
return calculateSendTime(packSize);
}
// uint8_t* IR_Encoder::bitHigh = new uint8_t[2]{ // uint8_t* IR_Encoder::bitHigh = new uint8_t[2]{
// (bitPauseTakts) * 2 - 0, // (bitPauseTakts) * 2 - 0,
// (bitActiveTakts) * 2 - 0}; // (bitActiveTakts) * 2 - 0};

View File

@ -3,6 +3,15 @@
// TODO: Отложенная передача после завершения приема // TODO: Отложенная передача после завершения приема
// Структура для возврата результата отправки
struct IR_SendResult {
bool success; // Флаг успешности отправки
uint32_t sendTimeMs; // Время отправки пакета в миллисекундах
IR_SendResult(bool success = false, uint32_t sendTimeMs = 0)
: success(success), sendTimeMs(sendTimeMs) {}
};
class IR_DecoderRaw; class IR_DecoderRaw;
class IR_Encoder : public IR_FOX class IR_Encoder : public IR_FOX
{ {
@ -11,7 +20,16 @@ class IR_Encoder : public IR_FOX
static IR_Encoder *last; static IR_Encoder *last;
IR_Encoder *next; IR_Encoder *next;
public: public:
static HardwareTimer* IR_Timer; private:
// uint16_t id; /// @brief Адрес передатчика
struct IR_TxGateRun {
uint16_t lenTicks; // number of timer ticks at carrierFrec*2
bool gate; // true: carrier enabled (output toggles), false: silent (output forced low)
};
using ExternalTxBusyFn = bool (*)(void *ctx);
using ExternalTxStartFn = bool (*)(void *ctx, IR_Encoder *enc, const uint8_t *packet, uint8_t len);
private: private:
// uint16_t id; /// @brief Адрес передатчика // uint16_t id; /// @brief Адрес передатчика
public: public:
@ -22,7 +40,20 @@ public:
IR_Encoder(uint8_t pin, uint16_t addr = 0, IR_DecoderRaw *decPair = nullptr, bool autoHandle = true); IR_Encoder(uint8_t pin, uint16_t addr = 0, IR_DecoderRaw *decPair = nullptr, bool autoHandle = true);
static void isr(); static void isr();
static void begin(HardwareTimer* timer, uint8_t channel, IRQn_Type IRQn, uint8_t priority, void(*isrCallback)() = nullptr); static void begin(HardwareTimer* timer, uint8_t channel, IRQn_Type IRQn, uint8_t priority, void(*isrCallback)() = nullptr);
/** Configure timer frequency for TX clock (carrierFrec*2) without attaching ISR. */
static void beginClockOnly(HardwareTimer *timer);
static HardwareTimer* get_IR_Timer(); static HardwareTimer* get_IR_Timer();
/** Call from main loop/tick: if ISR requested carrier stop, pause timer here (not in ISR). */
static void tick();
/** Optional: register external TX backend (e.g. DMA driver). */
static void setExternalTxBackend(ExternalTxStartFn startFn, ExternalTxBusyFn busyFn, void *ctx);
/** Called by external TX backend on actual end of transmission. */
void externalFinishSend();
/** Build RLE runs of carrier gate for a packet (no HW access). */
static size_t buildGateRuns(const uint8_t *packet, uint8_t len, IR_TxGateRun *outRuns, size_t maxRuns);
void enable(); void enable();
void disable(); void disable();
@ -32,15 +63,26 @@ public:
void sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept = false); void sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept = false);
void sendData(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false); void sendData(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false);
void sendDataFULL(uint16_t addrFrom, uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false); void sendData(uint16_t addrFrom, uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false);
IR_SendResult sendAccept(uint16_t addrTo, uint8_t customByte = 0);
IR_SendResult sendRequest(uint16_t addrTo);
void sendAccept(uint16_t addrTo, uint8_t customByte = 0); IR_SendResult sendBack(uint8_t data);
void sendRequest(uint16_t addrTo); IR_SendResult sendBack(uint8_t *data = nullptr, uint8_t len = 0);
IR_SendResult sendBackTo(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0);
void sendBack(uint8_t data); // Функция для тестирования времени отправки без фактической отправки
void sendBack(uint8_t *data = nullptr, uint8_t len = 0); uint32_t testSendTime(uint16_t addrTo, uint8_t dataByte, bool needAccept = false) const;
void sendBackTo(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0); uint32_t testSendTime(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false) const;
uint32_t testSendTimeFULL(uint16_t addrFrom, uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false) const;
uint32_t testSendAccept(uint16_t addrTo, uint8_t customByte = 0) const;
uint32_t testSendRequest(uint16_t addrTo) const;
uint32_t testSendBack(uint8_t data) const;
uint32_t testSendBack(uint8_t *data = nullptr, uint8_t len = 0) const;
uint32_t testSendBackTo(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0) const;
inline bool isBusy() const { return isSending;}
~IR_Encoder(); ~IR_Encoder();
@ -48,11 +90,20 @@ public:
void _isr(); void _isr();
private: private:
void _sendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint8_t len); static volatile bool carrierStopPending;
static void carrierResume();
static void carrierPauseIfIdle();
static ExternalTxStartFn externalTxStartFn;
static ExternalTxBusyFn externalTxBusyFn;
static void *externalTxCtx;
IR_SendResult _sendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint8_t len);
void setDecoder_isSending(); void setDecoder_isSending();
void sendByte(uint8_t byte, bool *prev, bool LOW_FIRST); void sendByte(uint8_t byte, bool *prev, bool LOW_FIRST);
void addSync(bool *prev, bool *next); void addSync(bool *prev, bool *next);
uint32_t calculateSendTime(uint8_t packSize) const;
uint32_t testSendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint8_t len) const;
void send_HIGH(bool = 1); void send_HIGH(bool = 1);
void send_LOW(); void send_LOW();
void send_EMPTY(uint8_t count); void send_EMPTY(uint8_t count);
@ -95,4 +146,3 @@ private:
uint8_t *currentBitSequence = bitLow; uint8_t *currentBitSequence = bitLow;
volatile SignalPart signal; volatile SignalPart signal;
}; };

View File

@ -52,7 +52,7 @@ msg type:
                                        // | 01234567 |                                         // | 01234567 |
                                        //  ----------                                         //  ----------
                                        // | xxx..... | = тип сообщения                                         // | xxx..... | = тип сообщения
                                        // | ...xxxxx | = длина (максимум 31 бита)                                         // | ...xxxxx | = длина (максимум 31 бита) - не больше 24 байт на тело пакета
                                        //  ---------- */                                         //  ---------- */
#define IR_MSG_BACK 0U // | 000...... | = Задний сигнал машинки #define IR_MSG_BACK 0U // | 000...... | = Задний сигнал машинки
#define IR_MSG_ACCEPT 1U // | 001..... | = подтверждение #define IR_MSG_ACCEPT 1U // | 001..... | = подтверждение
@ -116,13 +116,13 @@ msg type:
typedef uint16_t crc_t; typedef uint16_t crc_t;
// #define BRUTEFORCE_CHECK // Перепроверяет пакет на 1 битные ошибки //TODO: зависает // #define BRUTEFORCE_CHECK // Перепроверяет пакет на 1 битные ошибки //TODO: зависает
#define bytePerPack 16 // колличество байтов в пакете #define bytePerPack (31) // колличество байтов в пакете
#ifndef freeFrec #ifndef freeFrec
#define freeFrec false #define freeFrec false
#endif #endif
#ifndef subBufferSize #ifndef subBufferSize
#define subBufferSize 50 // Буфер для складирования фронтов, пока их не обработают (передатчик) #define subBufferSize 250 // Буфер для складирования фронтов, пока их не обработают (передатчик)
#endif #endif
#define preambPulse 3 #define preambPulse 3
@ -201,6 +201,8 @@ public:
static void checkAddressRuleApply(uint16_t address, uint16_t id, bool &flag); static void checkAddressRuleApply(uint16_t address, uint16_t id, bool &flag);
void setPin(uint8_t pin); void setPin(uint8_t pin);
inline uint8_t getPin() { return pin; }; inline uint8_t getPin() { return pin; };
inline GPIO_TypeDef *getPort() const { return port; }
inline uint16_t getPinMask() const { return mask; }
protected: protected:
uint16_t id; uint16_t id;