3 Commits

Author SHA1 Message Date
01e2da6334 loop1 test 2024-05-27 12:39:20 +03:00
5efa3d3ba5 time 2024-05-27 11:07:44 +03:00
e8e2cd60c2 rp 2024-05-27 10:53:44 +03:00
11 changed files with 280 additions and 844 deletions

4
.gitignore vendored
View File

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

View File

@ -1,5 +1,8 @@
{ {
"board": "STMicroelectronics:stm32:GenF4", "configuration": "flash=2097152_0,freq=133,opt=Small,rtti=Disabled,stackprotect=Disabled,exceptions=Disabled,dbgport=Disabled,dbglvl=None,usbstack=picosdk,ipbtstack=ipv4only,uploadmethod=default",
"board": "rp2040:rp2040:rpipico",
"port": "COM17", "port": "COM17",
"prebuild": "if exist bin rd /s /q bin" "output": "bin",
"prebuild": "if exist bin rd /s /q bin",
"sketch": "IR-protocol.ino"
} }

View File

@ -1,17 +1,44 @@
#include "IR_Decoder.h" #include "IR_Decoder.h"
#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 encForward_PIN 0 #define dec0_PIN 0
#define encBackward_PIN 5 #define dec1_PIN 1
#define dec2_PIN 2
#define dec3_PIN 3
#define dec4_PIN 4
#define dec5_PIN 5
#define dec6_PIN 6
#define dec7_PIN 7
#define dec8_PIN 8
#define dec9_PIN 9
#define dec10_PIN 10
#define dec11_PIN 11
#define dec12_PIN 12
#define dec13_PIN 13
#define dec14_PIN 14
#define dec15_PIN 15
#define LoopOut 12 #define LoopOut 16
#define ISR_Out 10 #define LoopOut1 17
#define TestOut 13 #define dec_ISR(n) \
void dec_##n##_ISR() { dec##n.isr(); }
#define dec_Ini(n) \
IR_Decoder dec##n(dec##n##_PIN, n); \
dec_ISR(n)
#define decPinMode(n) pinMode(dec##n##_PIN, INPUT_PULLUP);
#define decAttach(n) attachInterrupt(dec##n##_PIN, dec_##n##_ISR, CHANGE);
#define decSetup(n) /* decPinMode(n); */ decAttach(n);
#define decTick(n) dec##n.tick();
#define decStat(n) rx_flag |= statusSimple(dec##n);
void digitalToggle(uint8_t pin){
digitalWrite(pin, !digitalRead(pin));
}
//////////////// Ini ///////////////// //////////////// Ini /////////////////
@ -21,11 +48,11 @@
//////////////// Var ///////////////// //////////////// Var /////////////////
// IR_Encoder encForward(PA5, 42 /* , &decBackward */); // IR_Encoder encForward(PA5, 42 /* , &decBackward */);
IR_Encoder enc0(PIN_KT8_OUT, 42 /* , &decBackward */); IR_Encoder enc0(18, 42 /* , &decBackward */);
// IR_Encoder enc1(PA1, 127 /* , &decBackward */); IR_Encoder enc1(19, 127 /* , &decBackward */);
// IR_Encoder enc2(PA2, 137 /* , &decBackward */); IR_Encoder enc2(20, 137 /* , &decBackward */);
// IR_Encoder enc3(PA3, 777 /* , &decBackward */); IR_Encoder enc3(21, 777 /* , &decBackward */);
// IR_Encoder enc10(PA4, 555 /* , &decBackward */); // IR_Encoder enc10(PC15, 555 /* , &decBackward */);
// IR_Encoder enc11(PC14, 127 /* , &decBackward */); // IR_Encoder enc11(PC14, 127 /* , &decBackward */);
// IR_Encoder enc12(PC13, 137 /* , &decBackward */); // IR_Encoder enc12(PC13, 137 /* , &decBackward */);
// IR_Encoder enc13(PA12, 777 /* , &decBackward */); // IR_Encoder enc13(PA12, 777 /* , &decBackward */);
@ -37,84 +64,26 @@ IR_Encoder enc0(PIN_KT8_OUT, 42 /* , &decBackward */);
void EncoderISR() void EncoderISR()
{ {
IR_Encoder::isr(); IR_Encoder::isr();
// digitalToggle(LoopOut);
} }
void decBackwardISR() { //-------------------------------------------------------------------
decBackward.isr();
}
static uint8_t* portOut; dec_Ini(0);
ISR(TIMER2_COMPA_vect) { dec_Ini(1);
encForward.isr(); dec_Ini(2);
// encBackward.isr(); dec_Ini(3);
// encTree.isr(); dec_Ini(4);
//TODO: Сделать выбор порта dec_Ini(5);
*portOut = (*portOut & 0b11111110) | dec_Ini(6);
( dec_Ini(7);
encForward.ir_out_virtual << 0U dec_Ini(8);
// | encBackward.ir_out_virtual << 6U dec_Ini(9);
// | encTree.ir_out_virtual << 2U dec_Ini(10);
); dec_Ini(11);
} dec_Ini(12);
///////////////////////////////////////////////////////////////////// dec_Ini(13);
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 };
uint32_t loopTimer;
uint8_t sig = 255;
uint16_t targetAddr = IR_Broadcast;
Timer t1(750, millis, []() {
IR_Decoder dec2(dec2_PIN, 2);
void dec_2_ISR() { dec2.isr(); }
IR_Decoder dec3(dec3_PIN, 3);
void dec_3_ISR() { dec3.isr(); }
IR_Decoder dec4(dec4_PIN, 4);
void dec_4_ISR() { dec4.isr(); }
IR_Decoder dec5(dec5_PIN, 5);
void dec_5_ISR() { dec5.isr(); }
IR_Decoder dec6(dec6_PIN, 6);
void dec_6_ISR() { dec6.isr(); }
IR_Decoder dec7(dec7_PIN, 7);
void dec_7_ISR() { dec7.isr(); }
// IR_Decoder dec8(dec8_PIN, 8);
// void dec_8_ISR() { dec8.isr(); }
// IR_Decoder dec9(dec9_PIN, 9);
// void dec_9_ISR() { dec9.isr(); }
default:
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);
// void dec_11_ISR() { dec11.isr(); }
// IR_Decoder dec12(dec12_PIN, 12);
// void dec_12_ISR() { dec12.isr(); }
// IR_Decoder dec13(dec13_PIN, 13);
// void dec_13_ISR() { dec13.isr(); }
///////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////
uint8_t data0[] = {}; uint8_t data0[] = {};
@ -123,22 +92,16 @@ 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};
pinMode(8, OUTPUT); uint32_t loopTimer;
pinMode(9, OUTPUT); uint8_t sig = 0;
pinMode(11, OUTPUT); uint16_t targetAddr = IR_Broadcast;
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, []()
{ {
// Serial.println( digitalPinToBitMask(enc0.getPin()), BIN); // Serial.println( digitalPinToBitMask(enc0.getPin()), BIN);
// enc0.sendData(IR_Broadcast, data4, sizeof(data4)); enc0.sendData(IR_Broadcast, data4, sizeof(data4));
// enc1.sendData(IR_Broadcast, data3, sizeof(data3)); enc1.sendData(IR_Broadcast, data3, sizeof(data3));
// enc2.sendData(IR_Broadcast, data2, sizeof(data2)); enc2.sendData(IR_Broadcast, data2, sizeof(data2));
// enc3.sendData(IR_Broadcast, data1, sizeof(data1)); enc3.sendData(IR_Broadcast, data1, sizeof(data1));
// enc10.sendData(IR_Broadcast, data4, sizeof(data4)); // enc10.sendData(IR_Broadcast, data4, sizeof(data4));
// enc11.sendData(IR_Broadcast, data3, sizeof(data3)); // enc11.sendData(IR_Broadcast, data3, sizeof(data3));
// enc12.sendData(IR_Broadcast, data2, sizeof(data2)); // enc12.sendData(IR_Broadcast, data2, sizeof(data2));
@ -225,50 +188,117 @@ Timer t1(500, millis, []()
// encBackward.sendData(IR_Broadcast, data2); // encBackward.sendData(IR_Broadcast, data2);
// encTree.sendData(IR_Broadcast, rawData3); // encTree.sendData(IR_Broadcast, rawData3);
}); });
// Timer t2(50, millis, []() // Timer t2(50, millis, []()
// { digitalToggle(LED_BUILTIN); }); // { digitalToggle(LED_BUILTIN); });
Timer signalDetectTimer; Timer signalDetectTimer;
///////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////
HardwareTimer IR_Timer(TIM3); // HardwareTimer IR_Timer(TIM3);
// RPI_PICO_Timer IR_Timer(0);
struct repeating_timer timer;
bool TimerISRHandler(struct repeating_timer *t){
(void) t;
EncoderISR();
return true;
}
void setup() void setup()
{ {
IR_Timer.setOverflow(carrierFrec * 2, HERTZ_FORMAT); pinMode(LoopOut1, OUTPUT);
IR_Timer.attachInterrupt(1, EncoderISR); add_repeating_timer_us(6, TimerISRHandler, NULL, &timer);
NVIC_SetPriority(IRQn_Type::TIM3_IRQn, 0);
IR_Timer.resume(); // IR_Timer.setOverflow(carrierFrec * 2, HERTZ_FORMAT);
// IR_Timer.attachInterrupt(1, EncoderISR);
// NVIC_SetPriority(IRQn_Type::TIM3_IRQn, 0);
// IR_Timer.resume();
Serial.begin(SERIAL_SPEED); Serial.begin(SERIAL_SPEED);
Serial.println(F(INFO)); Serial.println(F(INFO));
pinMode(LoopOut, OUTPUT); pinMode(LoopOut, OUTPUT);
// pinMode(SignalDetectLed, OUTPUT);
pinMode(dec1_PIN, INPUT_PULLUP);
// pinMode(dec2_PIN, INPUT_PULLUP);
static IR_DecoderRaw *blind[]{
&dec0,
&dec1,
&dec2,
&dec3,
&dec4,
&dec5,
&dec6,
&dec7,
&dec8,
&dec9,
&dec10,
&dec11,
&dec12,
&dec13,
};
// enc0.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *));
// enc1.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *));
// enc2.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *));
// enc3.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *));
// enc10.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *));
decSetup(0);
// decSetup(1);
// decSetup(2);
// decSetup(3);
// decSetup(4);
// decSetup(5);
// decSetup(6);
// decSetup(7);
// decSetup(8);
// decSetup(9);
// decSetup(10);
decSetup(11);
decSetup(12);
decSetup(13);
}
void loop()
{
digitalToggle(LoopOut);
attachInterrupt(0, decForwardISR, CHANGE); // D2
attachInterrupt(1, decBackwardISR, CHANGE); // D3
} }
bool testLed = false;
uint32_t testLed_timer;
void loop() { void loop1()
// digitalToggle(LoopOut); {
Timer::tick(); Timer::tick();
IR_Decoder::tick();
decForward.tick(); bool rx_flag;
decBackward.tick(); decStat(0);
decStat(1);
status(decForward); decStat(2);
status(decBackward); decStat(3);
decStat(4);
decStat(5);
decStat(6);
decStat(7);
decStat(8);
decStat(9);
decStat(10);
decStat(11);
decStat(12);
decStat(13);
// status(decForward);
// status(decBackward);
// Serial.println(micros() - loopTimer); // Serial.println(micros() - loopTimer);
// loopTimer = micros(); // loopTimer = micros();
// delayMicroseconds(120*5); // delayMicroseconds(120*5);
if (Serial.available()) { if (Serial.available())
{
uint8_t in = Serial.parseInt(); uint8_t in = Serial.parseInt();
switch (in) switch (in)
{ {
@ -281,21 +311,25 @@ void loop() {
case 102: case 102:
targetAddr = 777; targetAddr = 777;
break; break;
default: default:
sig = in; sig = in;
break; break;
} }
Serial.println(in);
} }
digitalToggle(LoopOut1);
if(testLed && millis() - testLed_timer > 100){
testLed=false;
digitalWrite(12, LOW);
}
} }
Timer statusSimpleDelay; Timer statusSimpleDelay;
bool statusSimple(IR_Decoder &dec) bool statusSimple(IR_Decoder &dec)
{ {
@ -320,19 +354,13 @@ void detectSignal()
// { digitalWrite(SignalDetectLed, LOW); }); // { digitalWrite(SignalDetectLed, LOW); });
} }
// test
void status(IR_Decoder &dec)
//test {
void status(IR_Decoder& dec) { if (dec.gotData.available())
if (dec.gotData.available() && dec.gotData.getAddrFrom() != 42) { {
detectSignal();
digitalWrite(12, HIGH); Serial.println(micros());
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)
{ {
@ -578,5 +606,4 @@ void status(IR_Decoder& dec) {
// obj->resetAvailable(); // obj->resetAvailable();
Serial.write(str.c_str()); Serial.write(str.c_str());
} }
return false;
} }

View File

@ -1,50 +1,17 @@
#include "IR_Decoder.h" #include "IR_Decoder.h"
std::list<IR_Decoder *> &IR_Decoder::get_dec_list() // определение функции std::list<IR_Decoder*>& IR_Decoder::get_dec_list() // определение функции
{ {
static std::list<IR_Decoder *> dec_list; // статическая локальная переменная static std::list<IR_Decoder*> dec_list; // статическая локальная переменная
return dec_list; // возвращается ссылка на переменную return dec_list; // возвращается ссылка на переменную
} }
// IR_Decoder::IR_Decoder() {}; IR_Decoder::IR_Decoder(const uint8_t pin, uint16_t addr, IR_Encoder *encPair)
IR_Decoder::IR_Decoder(const uint8_t pin, uint16_t addr, IR_Encoder *encPair, bool autoHandle)
: IR_DecoderRaw(pin, addr, encPair) : IR_DecoderRaw(pin, addr, encPair)
{ {
get_dec_list().push_back(this); get_dec_list().push_back(this);
if(autoHandle){
enable();
}
}; };
void IR_Decoder::enable()
{
auto &dec_list = get_dec_list();
if (std::find(dec_list.begin(), dec_list.end(), this) == dec_list.end())
{
dec_list.push_back(this);
}
pinMode(pin, INPUT_PULLUP);
attachInterrupt(pin, (*this)(), CHANGE);
}
void IR_Decoder::disable()
{
detachInterrupt(pin);
pinMode(pin, INPUT);
auto &dec_list = get_dec_list();
auto it = std::find(dec_list.begin(), dec_list.end(), this);
if (it != dec_list.end())
{
dec_list.erase(it);
}
}
std::function<void()> IR_Decoder::operator()()
{
return std::bind(&IR_Decoder::isr, this);
}
IR_Decoder::~IR_Decoder() IR_Decoder::~IR_Decoder()
{ {
IR_Decoder::get_dec_list().remove(this); IR_Decoder::get_dec_list().remove(this);
@ -61,7 +28,6 @@ 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
@ -98,13 +64,9 @@ void IR_Decoder::_tick()
} }
gotRaw.set(&packInfo, id); gotRaw.set(&packInfo, id);
} }
if (isWaitingAcceptSend && millis() - acceptSendTimer > acceptDelay) if (isWaitingAcceptSend && millis() - acceptSendTimer > 75)
{ {
encoder->sendAccept(addrAcceptSendTo, acceptCustomByte); encoder->sendAccept(addrAcceptSendTo, acceptCustomByte);
isWaitingAcceptSend = false; isWaitingAcceptSend = false;
} }
} }
bool IR_Decoder::isReceive(uint8_t type) {
return (msgTypeReceive & 0b11111000) && ((msgTypeReceive & IR_MASK_MSG_TYPE) == type);
}

View File

@ -14,7 +14,7 @@ private:
bool isWaitingAcceptSend; bool isWaitingAcceptSend;
uint16_t addrAcceptSendTo; uint16_t addrAcceptSendTo;
uint16_t acceptDelay = IR_ResponseDelay; uint16_t acceptDelay = 75;
uint8_t acceptCustomByte; uint8_t acceptCustomByte;
public: public:
@ -24,16 +24,7 @@ public:
PacketTypes::Request gotRequest; PacketTypes::Request gotRequest;
PacketTypes::BasePack gotRaw; PacketTypes::BasePack gotRaw;
// IR_Decoder(); IR_Decoder(const uint8_t pin, uint16_t addr, IR_Encoder *encPair = nullptr);
IR_Decoder(const uint8_t pin, uint16_t addr = 0, IR_Encoder *encPair = nullptr, bool autoHandle = true);
std::function<void()> operator()();
void enable();
void disable();
bool isReceive(uint8_t type);
~IR_Decoder(); ~IR_Decoder();
static void tick(); static void tick();

View File

@ -4,6 +4,7 @@
IR_DecoderRaw::IR_DecoderRaw(const uint8_t pin, uint16_t addr, IR_Encoder *encPair) : encoder(encPair) IR_DecoderRaw::IR_DecoderRaw(const uint8_t pin, uint16_t addr, IR_Encoder *encPair) : encoder(encPair)
{ {
setPin(pin); setPin(pin);
pinMode(pin, INPUT_PULLUP);
id = addr; id = addr;
prevRise = prevFall = prevPrevFall = prevPrevRise = 0; prevRise = prevFall = prevPrevFall = prevPrevRise = 0;
if (encPair != nullptr) if (encPair != nullptr)
@ -47,7 +48,7 @@ volatile uint32_t time_;
void IR_DecoderRaw::isr() void IR_DecoderRaw::isr()
{ {
// Serial.print("ISR\n");
if(isPairSending){ if(isPairSending){
return; return;
} }
@ -58,8 +59,7 @@ void IR_DecoderRaw::isr()
interrupts(); interrupts();
if (time_ < oldTime) if (time_ < oldTime)
{ {
#ifdef IRDEBUG
#ifdef IRDEBUG
Serial.print("\n"); Serial.print("\n");
Serial.print("count: "); Serial.print("count: ");
Serial.println(wrongCounter++); Serial.println(wrongCounter++);
@ -75,7 +75,8 @@ void IR_DecoderRaw::isr()
oldTime = time_; oldTime = time_;
FrontStorage edge; FrontStorage edge;
edge.dir = port->IDR & mask; // edge.dir = port->IDR & mask;
edge.dir = digitalRead(pin);
edge.time = time_; edge.time = time_;
subBuffer.push(edge); subBuffer.push(edge);
@ -112,37 +113,16 @@ void IR_DecoderRaw::firstRX()
void IR_DecoderRaw::listenStart() void IR_DecoderRaw::listenStart()
{ {
if (isReciveRaw && ((micros() - prevRise) > IR_timeout * 2)) if (isRecive && ((micros() - prevRise) > IR_timeout * 2))
{ {
// Serial.print("\nlis>"); // Serial.print("\nlis>");
isReciveRaw = false; isRecive = 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();
@ -151,24 +131,12 @@ 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)
@ -230,7 +198,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 && !isReciveRaw) if (currentFront.time > prevRise && currentFront.time - prevRise > IR_timeout * 2 && !isRecive)
{ // первый { // первый
#ifdef IRDEBUG #ifdef IRDEBUG
errPulse(up, 50); errPulse(up, 50);
@ -242,7 +210,6 @@ void IR_DecoderRaw::tick()
isPreamb = true; isPreamb = true;
isRecive = true; isRecive = true;
isReciveRaw = true;
isWrongPack = false; isWrongPack = false;
} }
@ -475,8 +442,6 @@ void IR_DecoderRaw::writeToBuffer(bool bit)
if (isBufferOverflow || isPreamb || isWrongPack) if (isBufferOverflow || isPreamb || isWrongPack)
{ {
isRecive = false; isRecive = false;
isReciveRaw = false;
msgTypeReceive = 0;
return; return;
} }
@ -600,8 +565,6 @@ 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
@ -632,12 +595,6 @@ 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

@ -23,7 +23,6 @@
#define riseTimeMin (riseTime - riseTolerance) #define riseTimeMin (riseTime - riseTolerance)
#define aroundRise(t) (riseTimeMin < t && t < riseTimeMax) #define aroundRise(t) (riseTimeMin < t && t < riseTimeMax)
#define IR_timeout (riseTimeMax * (8 + syncBits + 1)) // us // таймаут в 8 data + 3 sync + 1 #define IR_timeout (riseTimeMax * (8 + syncBits + 1)) // us // таймаут в 8 data + 3 sync + 1
constexpr uint16_t IR_ResponseDelay = ((uint16_t)(((bitTime+riseTolerance) * (8 + syncBits + 1))*2.7735))/1000;
class IR_Encoder; class IR_Encoder;
class IR_DecoderRaw : virtual public IR_FOX class IR_DecoderRaw : virtual public IR_FOX
@ -31,10 +30,9 @@ class IR_DecoderRaw : virtual public IR_FOX
friend IR_Encoder; friend IR_Encoder;
protected: protected:
PackInfo packInfo; PackInfo packInfo;
uint8_t msgTypeReceive = 0; IR_Encoder *encoder; // Указатель на парный передатчик
IR_Encoder *encoder; // Указатель на парный передатчик bool availableRaw();
bool availableRaw();
public: public:
////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////
@ -49,7 +47,7 @@ public:
inline bool isOverflow() { return isBufferOverflow; }; // Буффер переполнился inline bool isOverflow() { return isBufferOverflow; }; // Буффер переполнился
bool isSubOverflow(); bool isSubOverflow();
volatile inline bool isReciving() { return isRecive; }; // Возвращает true, если происходит приём пакета inline bool isReciving() { return isBufferOverflow; }; // Возвращает true, если происходит приём пакета
////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////
private: private:
@ -66,8 +64,6 @@ private:
uint16_t riseSyncTime = bitTime; // Подстраиваемое время бита в мкс uint16_t riseSyncTime = bitTime; // Подстраиваемое время бита в мкс
volatile uint32_t lastEdgeTime = 0; // время последнего фронта
//////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////
volatile uint32_t currentSubBufferIndex; // Счетчик текущей позиции во вспомогательном буфере фронтов/спадов volatile uint32_t currentSubBufferIndex; // Счетчик текущей позиции во вспомогательном буфере фронтов/спадов
@ -103,9 +99,7 @@ private:
int16_t bufBitPos = 0; // Позиция для записи бита в буффер int16_t bufBitPos = 0; // Позиция для записи бита в буффер
private: private:
bool isReciveRaw; void listenStart(); // @brief Слушатель для работы isReciving()
void listenStart();
void checkTimeout(); //
/// @brief Проверка CRC. Проверяет len байт со значением crc, пришедшим в пакете /// @brief Проверка CRC. Проверяет len байт со значением crc, пришедшим в пакете
/// @param len Длина в байтах проверяемых данных /// @param len Длина в байтах проверяемых данных
@ -138,4 +132,4 @@ bool isReciveRaw;
inline void errPulse(uint8_t pin, uint8_t count); inline void errPulse(uint8_t pin, uint8_t count);
inline void infoPulse(uint8_t pin, uint8_t count); inline void infoPulse(uint8_t pin, uint8_t count);
#endif #endif
}; };

View File

@ -1,18 +1,20 @@
#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
#define TestOut 13 #define TestOut 13
IR_Encoder *IR_Encoder::head = nullptr; std::list<IR_Encoder*>& IR_Encoder::get_enc_list() // определение функции
IR_Encoder *IR_Encoder::last = nullptr; {
volatile bool IR_Encoder::carrierStopPending = false; static std::list<IR_Encoder*> dec_list; // статическая локальная переменная
return dec_list; // возвращается ссылка на переменную
}
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)
{ {
setPin(pin); setPin(pin);
pinMode(pin,OUTPUT);
id = addr; id = addr;
this->decPair = decPair; this->decPair = decPair;
signal = noSignal; signal = noSignal;
@ -20,7 +22,8 @@ IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair, bool
#if disablePairDec #if disablePairDec
if (decPair != nullptr) if (decPair != nullptr)
{ {
blindDecoders = new IR_DecoderRaw *[1]{decPair}; blindDecoders = new IR_DecoderRaw *[1]
{ decPair };
decodersCount = 1; decodersCount = 1;
} }
#endif #endif
@ -28,277 +31,8 @@ IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair, bool
{ {
decPair->encoder = this; decPair->encoder = this;
} }
get_enc_list().push_back(this);
if (autoHandle)
{
if (IR_Encoder::head == nullptr)
{
IR_Encoder::head = this;
}
if (last != nullptr)
{
last->next = this;
}
last = this;
pinMode(pin, OUTPUT);
}
}; };
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;}
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)()){
IR_Timer = timer;
if(IR_Timer == nullptr) return;
IR_Timer->pause();
IR_Timer->setOverflow(carrierFrec * 2, HERTZ_FORMAT);
IR_Timer->attachInterrupt(channel, (isrCallback == nullptr ? IR_Encoder::isr : isrCallback));
NVIC_SetPriority(IRQn, priority);
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;
}
}
}
void IR_Encoder::enable()
{
bool exist = false;
IR_Encoder *current = IR_Encoder::head;
while (current != nullptr)
{
exist = (current == this);
if (exist) break;
current = current->next;
}
if (!exist)
{
if (IR_Encoder::head == nullptr)
{
IR_Encoder::head = this;
last = this;
}
else
{
last->next = this;
last = this;
}
this->next = nullptr; // Указываем, что следующий за этим элементом — nullptr
}
pinMode(pin, OUTPUT);
}
void IR_Encoder::disable()
{
IR_Encoder *current = IR_Encoder::head;
IR_Encoder *prev = nullptr;
while (current != nullptr)
{
if (current == this) break;
prev = current;
current = current->next;
}
if (current != nullptr) // Элемент найден в списке
{
if (prev != nullptr)
{
prev->next = current->next; // Убираем текущий элемент из списка
}
else
{
IR_Encoder::head = current->next; // Удаляемый элемент был первым
}
if (current == last)
{
last = prev; // Если удаляется последний элемент, обновляем last
}
}
pinMode(pin, INPUT);
}
void IR_Encoder::setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count) void IR_Encoder::setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count)
{ {
@ -310,26 +44,26 @@ void IR_Encoder::setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count)
blindDecoders = decoders; blindDecoders = decoders;
} }
IR_Encoder::~IR_Encoder(){}; IR_Encoder::~IR_Encoder()
IR_SendResult IR_Encoder::sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept)
{ {
return sendData(addrTo, &dataByte, 1, needAccept); delete[] bitLow;
delete[] bitHigh;
get_enc_list().remove(this);
};
void IR_Encoder::sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept)
{
uint8_t *dataPtr = new uint8_t[1];
dataPtr[0] = dataByte;
sendData(addrTo, dataPtr, 1, needAccept);
delete[] dataPtr;
} }
IR_SendResult IR_Encoder::sendData(uint16_t addrTo, uint8_t *data, uint8_t len, bool needAccept){ void IR_Encoder::sendData(uint16_t addrTo, uint8_t *data, uint8_t len, bool needAccept)
return sendDataFULL(id, addrTo, data, len, 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)
{ {
Serial.println("IR Pack to big"); return;
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);
@ -342,8 +76,8 @@ void IR_Encoder::sendData(uint16_t addrFrom, uint16_t addrTo, uint8_t *data = nu
sendBuffer[0] = msgType; sendBuffer[0] = msgType;
// addr_self // addr_self
sendBuffer[1] = addrFrom >> 8 & 0xFF; sendBuffer[1] = id >> 8 & 0xFF;
sendBuffer[2] = addrFrom & 0xFF; sendBuffer[2] = id & 0xFF;
// addr_to // addr_to
sendBuffer[3] = addrTo >> 8 & 0xFF; sendBuffer[3] = addrTo >> 8 & 0xFF;
@ -358,19 +92,6 @@ void IR_Encoder::sendData(uint16_t addrFrom, uint16_t addrTo, uint8_t *data = nu
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) {
@ -380,14 +101,9 @@ void IR_Encoder::sendData(uint16_t addrFrom, uint16_t addrTo, uint8_t *data = nu
// отправка // отправка
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);
@ -408,13 +124,9 @@ IR_SendResult 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);
} }
IR_SendResult IR_Encoder::sendRequest(uint16_t addrTo) void 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);
@ -434,32 +146,28 @@ IR_SendResult 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);
} }
IR_SendResult IR_Encoder::sendBack(uint8_t data) void IR_Encoder::sendBack(uint8_t data)
{ {
return _sendBack(false, 0, &data, 1); _sendBack(false, 0, &data, 1);
} }
IR_SendResult IR_Encoder::sendBack(uint8_t *data, uint8_t len) void IR_Encoder::sendBack(uint8_t *data , uint8_t len)
{ {
return _sendBack(false, 0, data, len); _sendBack(false, 0, data, len);
} }
IR_SendResult IR_Encoder::sendBackTo(uint16_t addrTo, uint8_t *data, uint8_t len) void IR_Encoder::sendBackTo(uint16_t addrTo, uint8_t *data, uint8_t len)
{ {
return _sendBack(true, addrTo, data, len); _sendBack(true, addrTo, data, len);
} }
IR_SendResult IR_Encoder::_sendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint8_t len) void IR_Encoder::_sendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint8_t len)
{ {
if (len > bytePerPack) if (len > bytePerPack)
{ {
return IR_SendResult(false, 0); return;
} }
memset(sendBuffer, 0x00, dataByteSizeMax); memset(sendBuffer, 0x00, dataByteSizeMax);
uint8_t dataStart = msgBytes + addrBytes + (isAdressed ? addrBytes : 0); uint8_t dataStart = msgBytes + addrBytes + (isAdressed ? addrBytes : 0);
@ -491,10 +199,6 @@ IR_SendResult IR_Encoder::_sendBack(bool isAdressed, uint16_t addrTo, uint8_t *d
// отправка // отправка
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()
@ -504,10 +208,6 @@ void IR_Encoder::setDecoder_isSending()
for (uint8_t i = 0; i < decodersCount; i++) for (uint8_t i = 0; i < decodersCount; i++)
{ {
blindDecoders[i]->isPairSending ^= id; blindDecoders[i]->isPairSending ^= id;
// Serial.print("setDecoder_isSending() id = ");
// Serial.print(id);
// Serial.print(" isPairSending = ");
// Serial.println(blindDecoders[i]->isPairSending);
} }
} }
} }
@ -519,35 +219,7 @@ 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");
setDecoder_isSending(); setDecoder_isSending();
// noInterrupts(); // noInterrupts();
@ -566,16 +238,14 @@ void IR_Encoder::rawSend(uint8_t *ptr, uint8_t len)
state = HIGH; state = HIGH;
currentBitSequence = bitHigh; currentBitSequence = bitHigh;
isSending = true;
// interrupts(); // interrupts();
} }
void IR_Encoder::isr() void IR_Encoder::isr(){
{ // Serial.println(get_enc_list().size());
IR_Encoder *current = IR_Encoder::head; for(const auto &element : get_enc_list()){
while (current != nullptr) element->_isr();
{
current->_isr();
current = current->next;
} }
} }
@ -586,8 +256,10 @@ void IR_Encoder::_isr()
ir_out_virtual = !ir_out_virtual && state; ir_out_virtual = !ir_out_virtual && state;
port->ODR &= ~(mask); // port->ODR &= ~(mask);
port->ODR |= mask & (ir_out_virtual ? (uint16_t)0xFFFF : (uint16_t)0x0000); // port->ODR |= mask & (ir_out_virtual ? (uint16_t)0xFFFF : (uint16_t)0x0000);
digitalWrite(pin, ir_out_virtual);
if (toggleCounter) if (toggleCounter)
{ {
@ -603,10 +275,7 @@ void IR_Encoder::_isr()
// сброс счетчиков // сброс счетчиков
// ... // ...
isSending = false; isSending = false;
// Serial.println("STOP");
setDecoder_isSending(); setDecoder_isSending();
carrierStopPending = true;
// Serial.println();
return; return;
break; break;
@ -724,101 +393,9 @@ void IR_Encoder::addSync(bool *prev, bool *next)
} }
} }
uint8_t IR_Encoder::bitHigh[2] = { uint8_t* IR_Encoder::bitHigh = new uint8_t[2]{
(bitPauseTakts) * 2 - 1, (bitPauseTakts) * 2 - 1,
(bitActiveTakts) * 2 - 1}; (bitActiveTakts) * 2 - 1};
uint8_t IR_Encoder::bitLow[2] = { uint8_t* IR_Encoder::bitLow = new uint8_t[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]{
// (bitPauseTakts) * 2 - 0,
// (bitActiveTakts) * 2 - 0};
// uint8_t* IR_Encoder::bitLow = new uint8_t[2]{
// (bitPauseTakts/2 + bitActiveTakts) * 2 - 0,
// (bitPauseTakts) - 0};

View File

@ -3,107 +3,48 @@
// 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 : IR_FOX
{ {
friend IR_DecoderRaw; friend IR_DecoderRaw;
static IR_Encoder *head;
static IR_Encoder *last;
IR_Encoder *next;
public: public:
private: private:
// uint16_t id; /// @brief Адрес передатчика 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:
// uint16_t id; /// @brief Адрес передатчика
public: public:
/// @brief Класс передатчика /// @brief Класс передатчика
/// @param addr Адрес передатчика /// @param addr Адрес передатчика
/// @param pin Вывод передатчика /// @param pin Вывод передатчика
/// @param decPair Приёмник, для которого отключается приём в момент передачи передатчиком /// @param decPair Приёмник, для которого отключается приём в момент передачи передатчиком
IR_Encoder(uint8_t pin, uint16_t addr = 0, IR_DecoderRaw *decPair = nullptr, bool autoHandle = true); IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair = nullptr);
static void isr(); static void isr();
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();
/** 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 disable();
void setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count); void setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count);
void rawSend(uint8_t *ptr, uint8_t len); void rawSend(uint8_t *ptr, uint8_t len);
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 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); void sendAccept(uint16_t addrTo, uint8_t customByte = 0);
IR_SendResult sendRequest(uint16_t addrTo); void sendRequest(uint16_t addrTo);
IR_SendResult sendBack(uint8_t data); void sendBack(uint8_t data);
IR_SendResult sendBack(uint8_t *data = nullptr, uint8_t len = 0); void sendBack(uint8_t *data = nullptr, uint8_t len = 0);
IR_SendResult sendBackTo(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0); void sendBackTo(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0);
// Функция для тестирования времени отправки без фактической отправки
uint32_t testSendTime(uint16_t addrTo, uint8_t dataByte, bool needAccept = false) const;
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();
volatile bool ir_out_virtual; volatile bool ir_out_virtual;
void _isr();
private: private:
static volatile bool carrierStopPending; static std::list<IR_Encoder*>& get_enc_list();
static void carrierResume(); void _sendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint8_t len);
static void carrierPauseIfIdle(); void _isr();
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);
@ -141,8 +82,9 @@ private:
uint8_t low; uint8_t low;
uint8_t high; uint8_t high;
}; };
static uint8_t bitHigh[2]; static uint8_t *bitHigh;
static uint8_t bitLow[2]; static uint8_t *bitLow;
uint8_t *currentBitSequence = bitLow; uint8_t *currentBitSequence = bitLow;
volatile SignalPart signal; volatile SignalPart signal;
}; };

View File

@ -2,8 +2,9 @@
void IR_FOX::setPin(uint8_t pin){ void IR_FOX::setPin(uint8_t pin){
this->pin = pin; this->pin = pin;
port = digitalPinToPort(pin); // port = digitalPinToPort(pin);
mask = digitalPinToBitMask(pin); // mask = digitalPinToBitMask(pin);
// pinMode(pin, INPUT_PULLUP);
} }
void IR_FOX::checkAddressRuleApply(uint16_t address, uint16_t id, bool &flag) void IR_FOX::checkAddressRuleApply(uint16_t address, uint16_t id, bool &flag)

View File

@ -8,32 +8,19 @@
*/ */
// Адресация с 1 до 65 499 // Адресация с 1 до 65 499
#define IR_Broadcast 65000 // 65 500 ~ 65 535 - широковещательные пакеты (всем) #define IR_Broadcast 65000 // 65 500 ~ 65 535 - широковещательные пакеты (всем), возможно разделить на 35 типов
/* /*
*Адресное пространство: Адрес 0 запрещен и зарезервирован под NULL, либо тесты
Адрес 0 запрещен и зарезервирован под NULL, либо тесты IR_MSG_ACCEPT с адреса 0 воспринимается всеми устройствами
IR_MSG_ACCEPT с адреса 0 воспринимается всеми устройствами
*/
//**** Контрольные точки ******
#define IR_MAX_ADDR_CPU 63999
#define IR_MIN_ADDR_CPU 32000
// //***** Группы машинок ********
// #define IR_MAX_CAR_GROUP 31999
// #define IR_MIN_CAR_GROUP 30000
// //********** FREE ************* Адресное пространство:
// #define IR_MAX_FREE 31999
// #define IR_MIN_FREE 2000 Излучатели контрольных точек: 1000 ~ 1999
Излучатели без обратной связиЖ 2000 ~ 2999
Излучатели светофоров: 3000 ~ 3999
//********* Машинки ***********
#define IR_MAX_CAR 31999
#define IR_MIN_CAR 1
//***** Пульты управления *****
#define IR_MAX_CONTROLLER 64999
#define IR_MIN_CONTROLLER 64000
/*
/```````````````````````````````````````````````` data pack `````````````````````````````````````````````\                                   /```````````````````````````````````````````````` data pack `````````````````````````````````````````````\                                  
                                                                                                                                                                                                                   
@ -52,7 +39,7 @@ msg type:
                                        // | 01234567 |                                         // | 01234567 |
                                        //  ----------                                         //  ----------
                                        // | xxx..... | = тип сообщения                                         // | xxx..... | = тип сообщения
                                        // | ...xxxxx | = длина (максимум 31 бита) - не больше 24 байт на тело пакета                                         // | ...xxxxx | = длина (максимум 31 бита)
                                        //  ---------- */                                         //  ---------- */
#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 +103,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 (31) // колличество байтов в пакете #define bytePerPack 16 // колличество байтов в пакете
#ifndef freeFrec #ifndef freeFrec
#define freeFrec false #define freeFrec false
#endif #endif
#ifndef subBufferSize #ifndef subBufferSize
#define subBufferSize 250 // Буфер для складирования фронтов, пока их не обработают (передатчик) #define subBufferSize 50 // Буфер для складирования фронтов, пока их не обработают (передатчик)
#endif #endif
#define preambPulse 3 #define preambPulse 3
@ -155,11 +142,6 @@ typedef uint16_t crc_t;
#define bitTime (bitTakts * carrierPeriod) // Общая длительность бита #define bitTime (bitTakts * carrierPeriod) // Общая длительность бита
#define tolerance 300U #define tolerance 300U
constexpr uint16_t test_all_Time = bitTime;
constexpr uint16_t test_all_Takts = bitTakts * 2;
constexpr uint16_t test_hi = ((bitPauseTakts) * 2 - 0) + ((bitActiveTakts) * 2 - 0);
constexpr uint16_t test_low = ((bitPauseTakts / 2 + bitActiveTakts) * 2 - 0) + ((bitPauseTakts)-0);
class IR_FOX class IR_FOX
{ {
public: public:
@ -196,18 +178,16 @@ public:
uint16_t rTime = 0; uint16_t rTime = 0;
}; };
inline uint16_t getId() const { return id; } inline uint16_t getId() { return id; }
inline void setId(uint16_t id) { this->id = id; } inline void setId(uint16_t id) { this->id = id; }
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;
uint8_t pin; uint8_t pin;
GPIO_TypeDef *port; // GPIO_TypeDef *port;
uint16_t mask; uint16_t mask;
ErrorsStruct errors; ErrorsStruct errors;
uint8_t crc8(uint8_t *data, uint8_t start, uint8_t end, uint8_t poly); uint8_t crc8(uint8_t *data, uint8_t start, uint8_t end, uint8_t poly);