2 Commits

Author SHA1 Message Date
59d6e7aa23 test 2024-04-22 14:55:16 +03:00
b2dfee5495 public id 2024-04-22 14:55:07 +03:00
13 changed files with 716 additions and 802 deletions

2
.gitignore vendored
View File

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

View File

@ -1,5 +1,8 @@
{ {
"board": "STMicroelectronics:stm32:GenF4", "configuration": "pnum=BLUEPILL_F103C8,upload_method=swdMethod,xserial=none,usb=CDCgen,xusb=FS,opt=osstd,dbg=none,rtlib=nano",
"board": "STMicroelectronics:stm32:GenF1",
"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

@ -4,36 +4,28 @@
#include "MemoryCheck.h" #include "MemoryCheck.h"
/////////////// Pinout /////////////// /////////////// Pinout ///////////////
#define dec0_PIN PIN_KT1_IN #define encForward_PIN PA0
#define dec1_PIN PIN_KT2_IN #define encBackward_PIN PA1
#define dec2_PIN PIN_KT3_IN
#define dec3_PIN PIN_KT4_IN #define dec0_PIN PB0
#define dec4_PIN PIN_KT5_IN #define dec1_PIN PB1
#define dec5_PIN PIN_KT6_IN #define dec2_PIN PB2
#define dec6_PIN PIN_KT7_IN #define dec3_PIN PB3
#define dec7_PIN PIN_KT8_IN #define dec4_PIN PB4
// #define dec8_PIN PB8 #define dec5_PIN PB5
// #define dec9_PIN PB9 #define dec6_PIN PB6
// #define dec10_PIN PB10 #define dec7_PIN PB7
// #define dec11_PIN PB11 #define dec8_PIN PB8
// #define dec12_PIN PB12 #define dec9_PIN PB9
// #define dec13_PIN PB13 #define dec10_PIN PB10
// #define dec14_PIN PB14 #define dec11_PIN PB11
// #define dec15_PIN PB15 #define dec12_PIN PB12
#define dec13_PIN PB13
#define dec14_PIN PB14
#define dec15_PIN PB15
#define LoopOut PC13 #define LoopOut PC13
#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 |= status/* Simple */(dec##n);
//////////////// Ini ///////////////// //////////////// Ini /////////////////
@ -41,42 +33,32 @@
#define SERIAL_SPEED 115200 #define SERIAL_SPEED 115200
//////////////// Var ///////////////// //////////////// Var /////////////////
// IR_Encoder encForward(PA5, 42 /* , &decBackward */);
IR_Encoder enc0(PIN_KT8_OUT, 42 /* , &decBackward */); IR_Decoder dec0(dec1_PIN, 0);
// IR_Encoder enc1(PA1, 127 /* , &decBackward */); IR_Decoder dec1(dec2_PIN, 1);
// IR_Encoder enc2(PA2, 137 /* , &decBackward */);
// IR_Encoder enc3(PA3, 777 /* , &decBackward */);
// IR_Encoder enc10(PA4, 555 /* , &decBackward */);
// IR_Encoder enc11(PC14, 127 /* , &decBackward */);
// IR_Encoder enc12(PC13, 137 /* , &decBackward */);
// IR_Encoder enc13(PA12, 777 /* , &decBackward */);
IR_Encoder encForward(42 /* , &decBackward */);
// IR_Encoder encBackward(321, encBackward_PIN);
// IR_Encoder encTree(325, A2); // IR_Encoder encTree(325, A2);
//////////////////////// Функции прерываний //////////////////////// //////////////////////// Функции прерываний ////////////////////////
void EncoderISR() void EncoderISR()
{ {
IR_Encoder::isr(); encForward.isr();
// encBackward.isr();
// encTree.isr();
digitalWrite(PB5, encForward.ir_out_virtual);
} }
//------------------------------------------------------------------- //------------------------------------------------------------------
#define dec_ISR(n) \
void dec_##n##_ISR() { dec##n.isr(); }
dec_ISR(0);
dec_ISR(1);
dec_Ini(0);
dec_Ini(1);
dec_Ini(2);
dec_Ini(3);
dec_Ini(4);
dec_Ini(5);
dec_Ini(6);
dec_Ini(7);
// dec_Ini(8);
// dec_Ini(9);
// dec_Ini(10);
// dec_Ini(11);
// dec_Ini(12);
// dec_Ini(13);
///////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////
uint8_t data0[] = {}; uint8_t data0[] = {};
@ -90,94 +72,84 @@ uint8_t sig = 0;
uint16_t targetAddr = IR_Broadcast; uint16_t targetAddr = IR_Broadcast;
Timer t1(500, millis, []() Timer t1(500, millis, []()
{ {
// Serial.println( digitalPinToBitMask(enc0.getPin()), BIN);
// enc0.sendData(IR_Broadcast, data4, sizeof(data4));
// enc1.sendData(IR_Broadcast, data3, sizeof(data3));
// enc2.sendData(IR_Broadcast, data2, sizeof(data2));
// enc3.sendData(IR_Broadcast, data1, sizeof(data1));
// enc10.sendData(IR_Broadcast, data4, sizeof(data4));
// enc11.sendData(IR_Broadcast, data3, sizeof(data3));
// enc12.sendData(IR_Broadcast, data2, sizeof(data2));
// enc13.sendData(IR_Broadcast, data1, sizeof(data1));
// Serial.println(sig); // Serial.println(sig);
// switch (sig) switch (sig)
// { {
// case 0: case 0:
// encForward.sendData(targetAddr); encForward.sendData(targetAddr);
// break; break;
// case 1: case 1:
// encForward.sendData(targetAddr, data1, sizeof(data1)); encForward.sendData(targetAddr, data1, sizeof(data1));
// break; break;
// case 2: case 2:
// encForward.sendData(targetAddr, data2, sizeof(data2)); encForward.sendData(targetAddr, data2, sizeof(data2));
// break; break;
// case 3: case 3:
// encForward.sendData(targetAddr, data3, sizeof(data3)); encForward.sendData(targetAddr, data3, sizeof(data3));
// break; break;
// case 4: case 4:
// encForward.sendData(targetAddr, data4, sizeof(data4)); encForward.sendData(targetAddr, data4, sizeof(data4));
// break; break;
// case 10: case 10:
// encForward.sendData(targetAddr, data0, sizeof(data0), true); encForward.sendData(targetAddr, data0, sizeof(data0), true);
// break; break;
// case 11: case 11:
// encForward.sendData(targetAddr, data1, sizeof(data1), true); encForward.sendData(targetAddr, data1, sizeof(data1), true);
// break; break;
// case 12: case 12:
// encForward.sendData(targetAddr, data2, sizeof(data2), true); encForward.sendData(targetAddr, data2, sizeof(data2), true);
// break; break;
// case 13: case 13:
// encForward.sendData(targetAddr, data3, sizeof(data3), true); encForward.sendData(targetAddr, data3, sizeof(data3), true);
// break; break;
// case 14: case 14:
// encForward.sendData(targetAddr, data4, sizeof(data4), true); encForward.sendData(targetAddr, data4, sizeof(data4), true);
// break; break;
// case 20: case 20:
// encForward.sendBack(); encForward.sendBack();
// break; break;
// case 21: case 21:
// encForward.sendBack(data1, sizeof(data1)); encForward.sendBack(data1, sizeof(data1));
// break; break;
// case 22: case 22:
// encForward.sendBack(data2, sizeof(data2)); encForward.sendBack(data2, sizeof(data2));
// break; break;
// case 23: case 23:
// encForward.sendBack(data3, sizeof(data3)); encForward.sendBack(data3, sizeof(data3));
// break; break;
// case 24: case 24:
// encForward.sendBack(data4, sizeof(data4)); encForward.sendBack(data4, sizeof(data4));
// break; break;
// case 30: case 30:
// encForward.sendBackTo(targetAddr); encForward.sendBackTo(targetAddr);
// break; break;
// case 31: case 31:
// encForward.sendBackTo(targetAddr, data1, sizeof(data1)); encForward.sendBackTo(targetAddr, data1, sizeof(data1));
// break; break;
// case 32: case 32:
// encForward.sendBackTo(targetAddr, data2, sizeof(data2)); encForward.sendBackTo(targetAddr, data2, sizeof(data2));
// break; break;
// case 33: case 33:
// encForward.sendBackTo(targetAddr, data3, sizeof(data3)); encForward.sendBackTo(targetAddr, data3, sizeof(data3));
// break; break;
// case 34: case 34:
// encForward.sendBackTo(targetAddr, data4, sizeof(data4)); encForward.sendBackTo(targetAddr, data4, sizeof(data4));
// break; break;
// case 41: case 41:
// encForward.sendRequest(targetAddr); encForward.sendRequest(targetAddr);
// break; break;
// case 42: case 42:
// encForward.sendAccept(targetAddr); encForward.sendAccept(targetAddr);
// break; break;
// default: default:
// break; break;
// } }
// encBackward.sendData(IR_Broadcast, data2); // encBackward.sendData(IR_Broadcast, data2);
// encTree.sendData(IR_Broadcast, rawData3); // encTree.sendData(IR_Broadcast, rawData3);
}); });
@ -187,62 +159,38 @@ Timer t1(500, millis, []()
Timer signalDetectTimer; Timer signalDetectTimer;
///////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////
HardwareTimer IR_Timer(TIM3); HardwareTimer IR_Timer(TIM3);
HardwareTimer MicrosTimer(TIM1);
void MicrosTimerISR(){
}
void setup() void setup()
{ {
// MicrosTimer.setOve
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));
IR_Timer.setOverflow(carrierFrec*2, HERTZ_FORMAT);
IR_Timer.attachInterrupt(1, EncoderISR);
pinMode(LoopOut, OUTPUT); pinMode(LoopOut, OUTPUT);
// pinMode(SignalDetectLed, OUTPUT);
pinMode(dec0_PIN, INPUT_PULLUP); // IR_DecoderRaw* blindFromForward [] { &decForward, &decBackward };
// pinMode(dec2_PIN, INPUT_PULLUP); // encForward.setBlindDecoders(blindFromForward, sizeof(blindFromForward) / sizeof(IR_DecoderRaw*));
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 *)); pinMode(encForward_PIN, OUTPUT);
// enc1.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *)); pinMode(encBackward_PIN, OUTPUT);
// enc2.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *)); pinMode(LED_BUILTIN, OUTPUT);
// enc3.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *));
// enc10.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *)); #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);
decSetup(0); 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() void loop()
@ -250,30 +198,18 @@ void loop()
digitalToggle(LoopOut); digitalToggle(LoopOut);
Timer::tick(); Timer::tick();
IR_Decoder::tick();
decTick(0);
decTick(1);
bool rx_flag; bool rx_flag;
decStat(0); decStat(0);
decStat(1); decStat(1);
decStat(2);
decStat(3);
decStat(4);
decStat(5);
decStat(6);
decStat(7);
// decStat(8);
// decStat(9);
// decStat(10);
// decStat(11);
// decStat(12);
// decStat(13);
// status(decForward); if(rx_flag){
// status(decBackward); Serial.print("\n\n\n\n");
}
// Serial.println(micros() - loopTimer);
// loopTimer = micros();
// delayMicroseconds(120*5);
if (Serial.available()) if (Serial.available())
{ {
@ -296,22 +232,6 @@ void loop()
} }
} }
} }
Timer statusSimpleDelay;
bool statusSimple(IR_Decoder &dec)
{
bool ret;
if (ret = dec.gotData.available())
{
Serial.print("DEC: ");
Serial.print(dec.getId());
Serial.print(" err: ");
Serial.print(dec.gotData.getErrorCount());
Serial.print("\n");
statusSimpleDelay.delay(100, millis, []()
{ Serial.print("\n\n\n\n"); });
}
return ret;
}
void detectSignal() void detectSignal()
{ {
@ -321,7 +241,15 @@ void detectSignal()
} }
// test // test
bool status(IR_Decoder &dec)
bool statusSimple(IR_Decoder &dec){
if (dec.gotData.available())
{
Serial.print("DEC "); Serial.println(dec.id);
}
}
void status(IR_Decoder &dec)
{ {
if (dec.gotData.available()) if (dec.gotData.available())
{ {
@ -331,7 +259,7 @@ bool status(IR_Decoder &dec)
if (/* dec.gotData.getDataPrt()[1] */ 1) if (/* dec.gotData.getDataPrt()[1] */ 1)
{ {
str += ("Data on pin "); str += ("Data on pin ");
str += (dec.getPin()); str += (dec.isrPin);
str += "\n"; str += "\n";
uint8_t msg = dec.gotData.getMsgRAW(); uint8_t msg = dec.gotData.getMsgRAW();
@ -405,7 +333,7 @@ bool status(IR_Decoder &dec)
if (/* dec.gotData.getDataPrt()[1] */ 1) if (/* dec.gotData.getDataPrt()[1] */ 1)
{ {
str += ("BackData on pin "); str += ("BackData on pin ");
str += (dec.getPin()); str += (dec.isrPin);
str += "\n"; str += "\n";
uint8_t msg = dec.gotBackData.getMsgRAW(); uint8_t msg = dec.gotBackData.getMsgRAW();
@ -477,7 +405,7 @@ bool status(IR_Decoder &dec)
if (/* dec.gotData.getDataPrt()[1] */ 1) if (/* dec.gotData.getDataPrt()[1] */ 1)
{ {
str += ("Accept on pin "); str += ("Accept on pin ");
str += (dec.getPin()); str += (dec.isrPin);
str += "\n"; str += "\n";
uint8_t msg = dec.gotAccept.getMsgRAW(); uint8_t msg = dec.gotAccept.getMsgRAW();
@ -529,7 +457,7 @@ bool status(IR_Decoder &dec)
if (/* dec.gotData.getDataPrt()[1] */ 1) if (/* dec.gotData.getDataPrt()[1] */ 1)
{ {
str += ("Request on pin "); str += ("Request on pin ");
str += (dec.getPin()); str += (dec.isrPin);
str += "\n"; str += "\n";
uint8_t msg = dec.gotRequest.getMsgRAW(); uint8_t msg = dec.gotRequest.getMsgRAW();
@ -572,5 +500,4 @@ bool status(IR_Decoder &dec)
// obj->resetAvailable(); // obj->resetAvailable();
Serial.write(str.c_str()); Serial.write(str.c_str());
} }
return false;
} }

View File

@ -1,105 +0,0 @@
#include "IR_Decoder.h"
std::list<IR_Decoder *> &IR_Decoder::get_dec_list() // определение функции
{
static std::list<IR_Decoder *> dec_list; // статическая локальная переменная
return dec_list; // возвращается ссылка на переменную
}
// IR_Decoder::IR_Decoder() {};
IR_Decoder::IR_Decoder(const uint8_t pin, uint16_t addr, IR_Encoder *encPair, bool autoHandle)
: IR_DecoderRaw(pin, addr, encPair)
{
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::get_dec_list().remove(this);
}
void IR_Decoder::tick()
{
for (const auto &element : IR_Decoder::get_dec_list())
{
element->_tick();
}
}
void IR_Decoder::_tick()
{
IR_DecoderRaw::tick();
if (availableRaw())
{
#ifdef IRDEBUG_INFO
Serial.println("PARSING RAW DATA");
#endif
isWaitingAcceptSend = false;
switch (packInfo.buffer[0] >> 5 & IR_MASK_MSG_TYPE)
{
case IR_MSG_DATA_ACCEPT:
case IR_MSG_DATA_NOACCEPT:
gotData.set(&packInfo, id);
break;
case IR_MSG_BACK:
case IR_MSG_BACK_TO:
gotBackData.set(&packInfo, id);
break;
case IR_MSG_REQUEST:
gotRequest.set(&packInfo, id);
break;
case IR_MSG_ACCEPT:
gotAccept.set(&packInfo, id);
break;
default:
break;
}
if (gotData.isAvailable && (gotData.getMsgType() == IR_MSG_DATA_ACCEPT))
{
acceptSendTimer = millis();
addrAcceptSendTo = gotData.getAddrFrom();
acceptCustomByte = crc8(gotData.getDataPrt(), 0, gotData.getDataSize(), poly1);
if (addrAcceptSendTo && addrAcceptSendTo < IR_Broadcast)
isWaitingAcceptSend = true;
}
gotRaw.set(&packInfo, id);
}
if (isWaitingAcceptSend && millis() - acceptSendTimer > 75)
{
encoder->sendAccept(addrAcceptSendTo, acceptCustomByte);
isWaitingAcceptSend = false;
}
}

View File

@ -5,11 +5,6 @@
class IR_Decoder : public IR_DecoderRaw class IR_Decoder : public IR_DecoderRaw
{ {
private:
// static std::list<IR_Decoder *> dec_list;
static std::list<IR_Decoder*>& get_dec_list();
void _tick();
uint32_t acceptSendTimer; uint32_t acceptSendTimer;
bool isWaitingAcceptSend; bool isWaitingAcceptSend;
uint16_t addrAcceptSendTo; uint16_t addrAcceptSendTo;
@ -24,23 +19,59 @@ public:
PacketTypes::Request gotRequest; PacketTypes::Request gotRequest;
PacketTypes::BasePack gotRaw; PacketTypes::BasePack gotRaw;
// IR_Decoder(); IR_Decoder(const uint8_t isrPin, uint16_t addr, IR_Encoder *encPair = nullptr) : IR_DecoderRaw(isrPin, addr, encPair) {}
IR_Decoder(const uint8_t pin, uint16_t addr = 0, IR_Encoder *encPair = nullptr, bool autoHandle = true);
std::function<void()> operator()(); void tick()
{
IR_DecoderRaw::tick();
if (availableRaw())
{
#ifdef IRDEBUG_INFO
Serial.println("PARSING RAW DATA");
#endif
isWaitingAcceptSend = false;
switch (packInfo.buffer[0] >> 5 & IR_MASK_MSG_TYPE)
{
case IR_MSG_DATA_ACCEPT:
case IR_MSG_DATA_NOACCEPT:
gotData.set(&packInfo, id);
break;
case IR_MSG_BACK:
case IR_MSG_BACK_TO:
gotBackData.set(&packInfo, id);
break;
case IR_MSG_REQUEST:
gotRequest.set(&packInfo, id);
break;
case IR_MSG_ACCEPT:
gotAccept.set(&packInfo, id);
break;
void enable(); default:
void disable(); break;
}
if (gotData.isAvailable && (gotData.getMsgType() == IR_MSG_DATA_ACCEPT))
{
acceptSendTimer = millis();
addrAcceptSendTo = gotData.getAddrFrom();
acceptCustomByte = crc8(gotData.getDataPrt(), 0, gotData.getDataSize(), poly1);
if (addrAcceptSendTo && addrAcceptSendTo < IR_Broadcast)
isWaitingAcceptSend = true;
}
gotRaw.set(&packInfo, id);
}
if (isWaitingAcceptSend && millis() - acceptSendTimer > 75)
{
encoder->sendAccept(addrAcceptSendTo, acceptCustomByte);
isWaitingAcceptSend = false;
}
}
~IR_Decoder(); void setAcceptDelay(uint16_t acceptDelay)
static void tick();
inline void setAcceptDelay(uint16_t acceptDelay)
{ {
this->acceptDelay = acceptDelay; this->acceptDelay = acceptDelay;
} }
inline uint16_t getAcceptDelay() uint16_t getAcceptDelay()
{ {
return this->acceptDelay; return this->acceptDelay;
} }

View File

@ -1,9 +1,8 @@
#include "IR_DecoderRaw.h" #include "IR_DecoderRaw.h"
#include "IR_Encoder.h" #include "IR_Encoder.h"
IR_DecoderRaw::IR_DecoderRaw(const uint8_t pin, uint16_t addr, IR_Encoder *encPair) : encoder(encPair) IR_DecoderRaw::IR_DecoderRaw(const uint8_t isrPin, uint16_t addr, IR_Encoder *encPair) : isrPin(isrPin), encoder(encPair)
{ {
setPin(pin);
id = addr; id = addr;
prevRise = prevFall = prevPrevFall = prevPrevRise = 0; prevRise = prevFall = prevPrevFall = prevPrevRise = 0;
if (encPair != nullptr) if (encPair != nullptr)
@ -21,44 +20,17 @@ IR_DecoderRaw::IR_DecoderRaw(const uint8_t pin, uint16_t addr, IR_Encoder *encPa
#endif #endif
} }
bool IR_DecoderRaw::isSubOverflow()
{
noInterrupts();
volatile bool ret = isSubBufferOverflow;
interrupts();
return ret;
}
bool IR_DecoderRaw::availableRaw()
{
if (isAvailable)
{
isAvailable = false;
return true;
}
else
{
return false;
}
};
//////////////////////////////////// isr /////////////////////////////////////////// //////////////////////////////////// isr ///////////////////////////////////////////
volatile uint32_t time_; volatile uint32_t time_;
void IR_DecoderRaw::isr() void IR_DecoderRaw::isr()
{ {
// Serial.print("ISR\n");
if(isPairSending){
return;
}
noInterrupts(); noInterrupts();
// time_ = HAL_GetTick() * 1000 + ((SysTick->LOAD + 1 - SysTick->VAL) * 1000) / SysTick->LOAD + 1; // time_ = HAL_GetTick() * 1000 + ((SysTick->LOAD + 1 - SysTick->VAL) * 1000) / SysTick->LOAD + 1;
time_ = micros(); time_ = micros();
interrupts(); interrupts();
if (time_ < oldTime) if (time_ < oldTime)
{ {
#ifdef IRDEBUG #ifdef IRDEBUG
Serial.print("\n"); Serial.print("\n");
Serial.print("count: "); Serial.print("count: ");
@ -75,7 +47,7 @@ void IR_DecoderRaw::isr()
oldTime = time_; oldTime = time_;
FrontStorage edge; FrontStorage edge;
edge.dir = port->IDR & mask; edge.dir = digitalRead(isrPin);
edge.time = time_; edge.time = time_;
subBuffer.push(edge); subBuffer.push(edge);
@ -83,6 +55,7 @@ void IR_DecoderRaw::isr()
//////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////////
uint32_t wrCounter;
void IR_DecoderRaw::firstRX() void IR_DecoderRaw::firstRX()
{ {
@ -104,9 +77,9 @@ void IR_DecoderRaw::firstRX()
isPreamb = true; isPreamb = true;
riseSyncTime = bitTime /* 1100 */; riseSyncTime = bitTime /* 1100 */;
#ifdef IRDEBUG
wrCounter = 0; wrCounter = 0;
#endif
memset(dataBuffer, 0x00, dataByteSizeMax); memset(dataBuffer, 0x00, dataByteSizeMax);
} }
@ -119,7 +92,6 @@ void IR_DecoderRaw::listenStart()
firstRX(); firstRX();
} }
} }
void IR_DecoderRaw::tick() void IR_DecoderRaw::tick()
{ {
FrontStorage currentFront; FrontStorage currentFront;

View File

@ -14,6 +14,8 @@
#define up PA3 #define up PA3
#define down PA2 #define down PA2
#endif #endif
#define up PA3
#define down PA2
///////////////////////////////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////////////////////////////////
@ -32,22 +34,43 @@ class IR_DecoderRaw : virtual public IR_FOX
protected: protected:
PackInfo packInfo; PackInfo packInfo;
IR_Encoder *encoder; // Указатель на парный передатчик IR_Encoder *encoder; // Указатель на парный передатчик
bool availableRaw(); bool availableRaw()
{
if (isAvailable)
{
isAvailable = false;
return true;
}
else
{
return false;
}
};
public: public:
const uint8_t isrPin; // Пин прерывания
////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////
/// @brief Конструктор /// @brief Конструктор
/// @param pin Номер вывода прерывания/данных от приёмника (2 или 3 для atmega 328p) /// @param isrPin Номер вывода прерывания/данных от приёмника (2 или 3 для atmega 328p)
/// @param addr Адрес приёмника /// @param addr Адрес приёмника
/// @param encPair Указатель на передатчик, работающий в паре /// @param encPair Указатель на передатчик, работающий в паре
IR_DecoderRaw(const uint8_t pin, uint16_t addr, IR_Encoder *encPair = nullptr); IR_DecoderRaw(const uint8_t isrPin, uint16_t addr, IR_Encoder *encPair = nullptr);
void isr(); // Функция прерывания void isr(); // Функция прерывания
void tick(); // Обработка приёмника, необходима для работы void tick(); // Обработка приёмника, необходима для работы
void tickOld();
inline bool isOverflow() { return isBufferOverflow; }; // Буффер переполнился bool isOverflow() { return isBufferOverflow; }; // Буффер переполнился
bool isSubOverflow(); bool isSubOverflow()
inline bool isReciving() { return isBufferOverflow; }; // Возвращает true, если происходит приём пакета {
// noInterrupts();
volatile bool ret = isSubBufferOverflow;
// interrupts();
return ret;
};
bool isReciving() { return isBufferOverflow; }; // Возвращает true, если происходит приём пакета
////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////
private: private:
@ -127,8 +150,7 @@ private:
/// @return Результат /// @return Результат
uint16_t ceil_div(uint16_t val, uint16_t divider); uint16_t ceil_div(uint16_t val, uint16_t divider);
#ifdef IRDEBUG #if true //def IRDEBUG
uint32_t wrCounter;
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

@ -5,15 +5,8 @@
#define ISR_Out 10 #define ISR_Out 10
#define TestOut 13 #define TestOut 13
std::list<IR_Encoder *> &IR_Encoder::get_enc_list() // определение функции IR_Encoder::IR_Encoder(uint16_t addr, IR_DecoderRaw *decPair)
{ {
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)
{
setPin(pin);
id = addr; id = addr;
this->decPair = decPair; this->decPair = decPair;
signal = noSignal; signal = noSignal;
@ -21,7 +14,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
@ -29,48 +23,7 @@ IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair, bool
{ {
decPair->encoder = this; decPair->encoder = this;
} }
if (autoHandle)
{
get_enc_list().push_back(this);
}
}; };
HardwareTimer IR_Encoder::IR_Timer;
inline HardwareTimer* IR_Encoder::get_IR_Timer(){return &IR_Encoder::IR_Timer;}
void IR_Encoder::begin(HardwareTimer timer, uint8_t channel, IRQn_Type IRQn){
IR_Timer = timer;
IR_Timer.setOverflow(carrierFrec * 2, HERTZ_FORMAT);
IR_Timer.attachInterrupt(channel, IR_Encoder::isr);
NVIC_SetPriority(IRQn, 0);
IR_Timer.resume();
}
void IR_Encoder::enable()
{
auto &enc_list = get_enc_list();
if (std::find(enc_list.begin(), enc_list.end(), this) == enc_list.end())
{
enc_list.push_back(this);
}
pinMode(pin, OUTPUT);
}
void IR_Encoder::disable()
{
auto &enc_list = get_enc_list();
auto it = std::find(enc_list.begin(), enc_list.end(), this);
if (it != enc_list.end())
{
enc_list.erase(it);
}
pinMode(pin, INPUT);
}
void IR_Encoder::setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count) void IR_Encoder::setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count)
{ {
#if disablePairDec #if disablePairDec
@ -83,19 +36,19 @@ void IR_Encoder::setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count)
IR_Encoder::~IR_Encoder() IR_Encoder::~IR_Encoder()
{ {
get_enc_list().remove(this); delete[] bitLow;
delete[] bitHigh;
}; };
void IR_Encoder::sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept) void IR_Encoder::sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept)
{ {
sendData(addrTo, &dataByte, 1, needAccept); uint8_t *dataPtr = new uint8_t[1];
dataPtr[0] = dataByte;
sendData(addrTo, dataPtr, 1, needAccept);
delete[] dataPtr;
} }
void 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)
sendDataFULL(id, addrTo, data, len, needAccept);
}
void IR_Encoder::sendDataFULL(uint16_t addrFrom, uint16_t addrTo, uint8_t *data, uint8_t len, bool needAccept)
{ {
if (len > bytePerPack) if (len > bytePerPack)
{ {
@ -112,8 +65,8 @@ void IR_Encoder::sendDataFULL(uint16_t addrFrom, uint16_t addrTo, uint8_t *data,
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;
@ -188,7 +141,6 @@ void IR_Encoder::sendBack(uint8_t data)
{ {
_sendBack(false, 0, &data, 1); _sendBack(false, 0, &data, 1);
} }
void IR_Encoder::sendBack(uint8_t *data , uint8_t len) void IR_Encoder::sendBack(uint8_t *data , uint8_t len)
{ {
_sendBack(false, 0, data, len); _sendBack(false, 0, data, len);
@ -279,24 +231,12 @@ void IR_Encoder::rawSend(uint8_t *ptr, uint8_t len)
} }
void IR_Encoder::isr() void IR_Encoder::isr()
{
// Serial.println(get_enc_list().size());
for (const auto &element : get_enc_list())
{
element->_isr();
}
}
void IR_Encoder::_isr()
{ {
if (!isSending) if (!isSending)
return; return;
ir_out_virtual = !ir_out_virtual && state; ir_out_virtual = !ir_out_virtual && state;
port->ODR &= ~(mask);
port->ODR |= mask & (ir_out_virtual ? (uint16_t)0xFFFF : (uint16_t)0x0000);
if (toggleCounter) if (toggleCounter)
{ {
toggleCounter--; toggleCounter--;
@ -429,16 +369,37 @@ void IR_Encoder::addSync(bool *prev, bool *next)
} }
} }
uint8_t IR_Encoder::bitHigh[2] = { void IR_Encoder::send_HIGH(bool prevBite)
{
// if (/* prevBite */1) {
// meanderBlock(bitPauseTakts * 2, halfPeriod, LOW);
// meanderBlock(bitActiveTakts, halfPeriod, HIGH);
// } else { // более короткий HIGH после нуля
// meanderBlock(bitTakts - (bitActiveTakts - bitPauseTakts), halfPeriod, LOW);
// meanderBlock(bitActiveTakts - bitPauseTakts, halfPeriod, HIGH);
// }
}
void IR_Encoder::send_LOW()
{
// meanderBlock(bitPauseTakts, halfPeriod, LOW);
// meanderBlock(bitActiveTakts, halfPeriod, LOW);
// meanderBlock(bitPauseTakts, halfPeriod, HIGH);
}
void IR_Encoder::send_EMPTY(uint8_t count)
{
// for (size_t i = 0; i < count * 2; i++) {
// meanderBlock((bitPauseTakts * 2 + bitActiveTakts), halfPeriod, prevPreambBit);
// prevPreambBit = !prevPreambBit;
// }
// meanderBlock(bitPauseTakts * 2 + bitActiveTakts, halfPeriod, 0); //TODO: Отодвинуть преамбулу
}
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};
// 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

@ -4,34 +4,53 @@
// TODO: Отложенная передача после завершения приема // TODO: Отложенная передача после завершения приема
class IR_DecoderRaw; class IR_DecoderRaw;
class IR_Encoder : public IR_FOX class IR_Encoder : IR_FOX
{ {
friend IR_DecoderRaw; friend IR_DecoderRaw;
public: public:
static HardwareTimer IR_Timer;
private: private:
// uint16_t id; /// @brief Адрес передатчика uint16_t id; /// @brief Адрес передатчика
public: public:
/// @brief Класс передатчика /// @brief Класс передатчика
/// @param addr Адрес передатчика /// @param addr Адрес передатчика
/// @param pin Вывод передатчика /// @param pin Вывод передатчика
/// @param tune Подстройка несущей частоты
/// @param decPair Приёмник, для которого отключается приём в момент передачи передатчиком /// @param decPair Приёмник, для которого отключается приём в момент передачи передатчиком
IR_Encoder(uint8_t pin, uint16_t addr = 0, IR_DecoderRaw *decPair = nullptr, bool autoHandle = true); IR_Encoder(uint16_t addr, IR_DecoderRaw *decPair = nullptr);
static void isr();
static void begin(HardwareTimer IR_Timer, uint8_t channel, IRQn_Type IRQn);
static HardwareTimer* get_IR_Timer();
void enable(); // static void timerSetup()
void disable(); // {
// // // TIMER2 Ini
// // uint8_t oldSREG = SREG; // Save global interupts settings
// // cli();
// // // DDRB |= (1 << PORTB3); //OC2A (17)
// // TCCR2A = 0;
// // TCCR2B = 0;
// // // TCCR2A |= (1 << COM2A0); //Переключение состояния
// // TCCR2A |= (1 << WGM21); // Clear Timer On Compare (Сброс по совпадению)
// // TCCR2B |= (1 << CS20); // Предделитель 1
// // TIMSK2 |= (1 << OCIE2A); // Прерывание по совпадению
// // OCR2A = /* 465 */ ((F_CPU / (38000 * 2)) - 2); // 38кГц
// // SREG = oldSREG; // Return interrupt settings
// }
// static void timerOFFSetup()
// {
// TIMSK2 &= ~(1 << OCIE2A); // Прерывание по совпадению выкл
// }
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 sendDataFULL(uint16_t addrFrom, uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false);
void sendAccept(uint16_t addrTo, uint8_t customByte = 0); void sendAccept(uint16_t addrTo, uint8_t customByte = 0);
void sendRequest(uint16_t addrTo); void sendRequest(uint16_t addrTo);
@ -40,14 +59,13 @@ public:
void sendBack(uint8_t *data = nullptr, uint8_t len = 0); void sendBack(uint8_t *data = nullptr, uint8_t len = 0);
void 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);
void isr();
~IR_Encoder(); ~IR_Encoder();
volatile bool ir_out_virtual; volatile bool ir_out_virtual;
private: private:
static std::list<IR_Encoder*>& get_enc_list();
void _sendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint8_t len); void _sendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint8_t len);
void _isr();
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);
@ -89,8 +107,8 @@ 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

@ -1,33 +0,0 @@
#include "IR_config.h"
void IR_FOX::setPin(uint8_t pin){
this->pin = pin;
port = digitalPinToPort(pin);
mask = digitalPinToBitMask(pin);
}
void IR_FOX::checkAddressRuleApply(uint16_t address, uint16_t id, bool &flag)
{
flag = false;
flag |= id == 0;
flag |= address == id;
flag |= address >= IR_Broadcast;
}
uint8_t IR_FOX::crc8(uint8_t *data, uint8_t start, uint8_t end, uint8_t poly)
{ // TODO: сделать возможность межбайтовой проверки
uint8_t crc = 0xff;
size_t i, j;
for (i = start; i < end; i++)
{
crc ^= data[i];
for (j = 0; j < 8; j++)
{
if ((crc & 0x80) != 0)
crc = (uint8_t)((crc << 1) ^ poly);
else
crc <<= 1;
}
}
return crc;
};

View File

@ -1,39 +1,25 @@
#pragma once #pragma once
#include <Arduino.h> #include <Arduino.h>
#include <list>
// #define IRDEBUG_INFO #define IRDEBUG_INFO
/*////////////////////////////////////////////////////////////////////////////////////// /*//////////////////////////////////////////////////////////////////////////////////////
Для работы в паре положить декодер в энкодер Для работы в паре положить декодер в энкодер
*/ */// Адресация с 1 до 65 499
// Адресация с 1 до 65 499 #define IR_Broadcast 65000 // 65 500 ~ 65 535 - широковещательные пакеты (всем), возможно разделить на 35 типов
#define IR_Broadcast 65000 // 65 500 ~ 65 535 - широковещательные пакеты (всем)
/* /*
*Адресное пространство:
Адрес 0 запрещен и зарезервирован под NULL, либо тесты Адрес 0 запрещен и зарезервирован под NULL, либо тесты
IR_MSG_ACCEPT с адреса 0 воспринимается всеми устройствами IR_MSG_ACCEPT с адреса 0 воспринимается всеми устройствами
*/
//**** Контрольные точки ******
#define IR_MAX_ADDR_CPU 64999
#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 100
//***** Пульты управления *****
#define IR_MAX_CONTROLLER 99
#define IR_MIN_CONTROLLER 0
/*
/```````````````````````````````````````````````` data pack `````````````````````````````````````````````\                                   /```````````````````````````````````````````````` data pack `````````````````````````````````````````````\                                  
                                                                                                                                                                                                                   
@ -115,14 +101,14 @@ 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 16 // колличество байтов в пакете
#ifndef freeFrec #ifndef freeFrec
#define freeFrec false #define freeFrec false
#endif #endif
#ifndef subBufferSize #ifndef subBufferSize
#define subBufferSize 50 // Буфер для складирования фронтов, пока их не обработают (передатчик) #define subBufferSize 5 //Буфер для складирования фронтов, пока их не обработают (передатчик)
#endif #endif
#define preambPulse 3 #define preambPulse 3
@ -154,17 +140,9 @@ typedef uint16_t crc_t;
#define bitTakts (bitActiveTakts+bitPauseTakts) // Общая длительность бита в тактах #define bitTakts (bitActiveTakts+bitPauseTakts) // Общая длительность бита в тактах
#define bitTime (bitTakts*carrierPeriod) // Общая длительность бита #define bitTime (bitTakts*carrierPeriod) // Общая длительность бита
#define tolerance 300U #define tolerance 300U
class IR_FOX {
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
{
public: public:
struct PackOffsets struct PackOffsets {
{
uint8_t msgOffset; uint8_t msgOffset;
uint8_t addrFromOffset; uint8_t addrFromOffset;
uint8_t addrToOffset; uint8_t addrToOffset;
@ -172,23 +150,21 @@ public:
uint8_t crcOffset; uint8_t crcOffset;
}; };
struct ErrorsStruct struct ErrorsStruct {
{
uint8_t lowSignal = 0; uint8_t lowSignal = 0;
uint8_t highSignal = 0; uint8_t highSignal = 0;
uint8_t other = 0; uint8_t other = 0;
void reset() void reset() {
{
lowSignal = 0; lowSignal = 0;
highSignal = 0; highSignal = 0;
other = 0; other = 0;
} }
uint16_t all() { return lowSignal + highSignal + other; } uint16_t all() { return lowSignal + highSignal + other; }
}; };
struct PackInfo struct PackInfo {
{
uint8_t* buffer = nullptr; uint8_t* buffer = nullptr;
uint8_t packSize = 0; uint8_t packSize = 0;
uint16_t crc = 0; uint16_t crc = 0;
@ -196,17 +172,32 @@ public:
uint16_t rTime = 0; uint16_t rTime = 0;
}; };
inline uint16_t getId() const { return id; } static void checkAddressRuleApply(uint16_t address, uint16_t id, bool& flag) {
inline void setId(uint16_t id) { this->id = id; } flag = false;
static void checkAddressRuleApply(uint16_t address, uint16_t id, bool &flag); flag |= id == 0;
void setPin(uint8_t pin); flag |= address == id;
inline uint8_t getPin() { return pin; }; flag |= address >= IR_Broadcast;
}
uint16_t getId() { return id; }
void setId(uint16_t id) { this->id = id; }
protected:
uint16_t id; uint16_t id;
uint8_t pin; protected:
GPIO_TypeDef *port;
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) { //TODO: сделать возможность межбайтовой проверки
uint8_t crc = 0xff;
size_t i, j;
for (i = start; i < end; i++) {
crc ^= data[i];
for (j = 0; j < 8; j++) {
if ((crc & 0x80) != 0)
crc = (uint8_t)((crc << 1) ^ poly);
else
crc <<= 1;
}
}
return crc;
}
}; };

View File

@ -1,107 +0,0 @@
#include "PacketTypes.h"
namespace PacketTypes
{
bool BasePack::checkAddress() { return true; };
void BasePack::set(IR_FOX::PackInfo *packInfo, uint16_t id)
{
this->packInfo = packInfo;
this->id = id;
if (checkAddress())
{
isAvailable = true;
isRawAvailable = true;
#ifdef IRDEBUG_INFO
Serial.print(" OK ");
#endif
}
else
{
isRawAvailable = true;
#ifdef IRDEBUG_INFO
Serial.print(" NOT-OK ");
#endif
}
}
uint16_t BasePack::_getAddrFrom(BasePack *obj)
{
return (obj->packInfo->buffer[obj->addressFromOffset] << 8) | obj->packInfo->buffer[obj->addressFromOffset + 1];
};
uint16_t BasePack::_getAddrTo(BasePack *obj)
{
return (obj->packInfo->buffer[obj->addressToOffset] << 8) | obj->packInfo->buffer[obj->addressToOffset + 1];
};
uint8_t BasePack::_getDataSize(BasePack *obj)
{
return obj->packInfo->packSize - crcBytes - obj->DataOffset;
};
uint8_t *BasePack::_getDataPrt(BasePack *obj)
{
return obj->packInfo->buffer + obj->DataOffset;
};
uint8_t BasePack::_getDataRawSize(BasePack *obj)
{
return obj->packInfo->packSize;
};
bool BasePack::available()
{
if (isAvailable)
{
isAvailable = false;
isRawAvailable = false;
return true;
}
else
{
return false;
}
};
bool BasePack::availableRaw()
{
if (isRawAvailable)
{
isRawAvailable = false;
return true;
}
else
{
return false;
}
};
bool Data::checkAddress()
{
bool ret;
IR_FOX::checkAddressRuleApply(getAddrTo(), this->id, ret);
return ret;
}
bool DataBack::checkAddress()
{
bool ret;
if (getMsgType() == IR_MSG_BACK_TO)
{
DataOffset = 5;
IR_FOX::checkAddressRuleApply((packInfo->buffer[addressToOffset] << 8) | packInfo->buffer[addressToOffset + 1], this->id, ret);
}
else
{
DataOffset = 3;
ret = true;
}
return ret;
}
bool Accept::checkAddress() { return true; }
bool Request::checkAddress()
{
bool ret;
IR_FOX::checkAddressRuleApply(getAddrTo(), this->id, ret);
return ret;
}
}

View File

@ -21,28 +21,86 @@ namespace PacketTypes
IR_FOX::PackInfo *packInfo; IR_FOX::PackInfo *packInfo;
uint16_t id; uint16_t id;
virtual bool checkAddress(); virtual bool checkAddress() { return true; };
void set(IR_FOX::PackInfo *packInfo, uint16_t id); void set(IR_FOX::PackInfo *packInfo, uint16_t id)
{
this->packInfo = packInfo;
this->id = id;
static uint16_t _getAddrFrom(BasePack *obj); if (checkAddress())
static uint16_t _getAddrTo(BasePack *obj); {
static uint8_t _getDataSize(BasePack *obj); isAvailable = true;
static uint8_t *_getDataPrt(BasePack *obj); isRawAvailable = true;
static uint8_t _getDataRawSize(BasePack *obj); #ifdef IRDEBUG_INFO
Serial.print(" OK ");
#endif
}
else
{
isRawAvailable = true;
#ifdef IRDEBUG_INFO
Serial.print(" NOT-OK ");
#endif
}
}
static uint16_t _getAddrFrom(BasePack *obj)
{
return (obj->packInfo->buffer[obj->addressFromOffset] << 8) | obj->packInfo->buffer[obj->addressFromOffset + 1];
};
static uint16_t _getAddrTo(BasePack *obj)
{
return (obj->packInfo->buffer[obj->addressToOffset] << 8) | obj->packInfo->buffer[obj->addressToOffset + 1];
};
static uint8_t _getDataSize(BasePack *obj)
{
return obj->packInfo->packSize - crcBytes - obj->DataOffset;
};
static uint8_t *_getDataPrt(BasePack *obj)
{
return obj->packInfo->buffer + obj->DataOffset;
};
static uint8_t _getDataRawSize(BasePack *obj)
{
return obj->packInfo->packSize;
};
public: public:
bool available(); bool available()
bool availableRaw(); {
if (isAvailable)
inline uint8_t getMsgInfo() { return packInfo->buffer[0] & IR_MASK_MSG_INFO; }; {
inline uint8_t getMsgType() { return (packInfo->buffer[0] >> 5) & IR_MASK_MSG_TYPE; }; isAvailable = false;
inline uint8_t getMsgRAW() { return packInfo->buffer[0]; }; isRawAvailable = false;
inline uint16_t getErrorCount() { return packInfo->err.all(); }; return true;
inline uint8_t getErrorLowSignal() { return packInfo->err.lowSignal; }; }
inline uint8_t getErrorHighSignal() { return packInfo->err.highSignal; }; else
inline uint8_t getErrorOther() { return packInfo->err.other; }; {
inline uint16_t getTunerTime() { return packInfo->rTime; }; return false;
inline uint8_t *getDataRawPtr() { return packInfo->buffer; }; }
};
bool availableRaw()
{
if (isRawAvailable)
{
isRawAvailable = false;
return true;
}
else
{
return false;
}
};
uint8_t getMsgInfo() { return packInfo->buffer[0] & IR_MASK_MSG_INFO; };
uint8_t getMsgType() { return (packInfo->buffer[0] >> 5) & IR_MASK_MSG_TYPE; };
uint8_t getMsgRAW() { return packInfo->buffer[0]; };
uint16_t getErrorCount() { return packInfo->err.all(); };
uint8_t getErrorLowSignal() { return packInfo->err.lowSignal; };
uint8_t getErrorHighSignal() { return packInfo->err.highSignal; };
uint8_t getErrorOther() { return packInfo->err.other; };
uint16_t getTunerTime() { return packInfo->rTime; };
uint8_t *getDataRawPtr() { return packInfo->buffer; };
}; };
class Data : public BasePack class Data : public BasePack
@ -56,15 +114,20 @@ namespace PacketTypes
DataOffset = 5; DataOffset = 5;
} }
inline uint16_t getAddrFrom() { return _getAddrFrom(this); }; uint16_t getAddrFrom() { return _getAddrFrom(this); };
inline uint16_t getAddrTo() { return _getAddrTo(this); }; uint16_t getAddrTo() { return _getAddrTo(this); };
inline uint8_t getDataSize() { return _getDataSize(this); }; uint8_t getDataSize() { return _getDataSize(this); };
inline uint8_t *getDataPrt() { return _getDataPrt(this); }; uint8_t *getDataPrt() { return _getDataPrt(this); };
inline uint8_t getDataRawSize() { return _getDataRawSize(this); }; uint8_t getDataRawSize() { return _getDataRawSize(this); };
private: private:
bool checkAddress() override; bool checkAddress() override
{
bool ret;
IR_FOX::checkAddressRuleApply(getAddrTo(), this->id, ret);
return ret;
}
}; };
class DataBack : public BasePack class DataBack : public BasePack
@ -78,15 +141,29 @@ namespace PacketTypes
DataOffset = 3; DataOffset = 3;
} }
inline uint16_t getAddrFrom() { return _getAddrFrom(this); }; uint16_t getAddrFrom() { return _getAddrFrom(this); };
inline uint16_t getAddrTo() { return _getAddrTo(this); }; uint16_t getAddrTo() { return _getAddrTo(this); };
inline uint8_t getDataSize() { return _getDataSize(this); }; uint8_t getDataSize() { return _getDataSize(this); };
inline uint8_t *getDataPrt() { return _getDataPrt(this); }; uint8_t *getDataPrt() { return _getDataPrt(this); };
inline uint8_t getDataRawSize() { return _getDataRawSize(this); }; uint8_t getDataRawSize() { return _getDataRawSize(this); };
private: private:
bool checkAddress() override; bool checkAddress() override
{
bool ret;
if (getMsgType() == IR_MSG_BACK_TO)
{
DataOffset = 5;
IR_FOX::checkAddressRuleApply((packInfo->buffer[addressToOffset] << 8) | packInfo->buffer[addressToOffset + 1], this->id, ret);
}
else
{
DataOffset = 3;
ret = true;
}
return ret;
}
}; };
class Accept : public BasePack class Accept : public BasePack
@ -99,11 +176,11 @@ namespace PacketTypes
DataOffset = 3; DataOffset = 3;
} }
inline uint16_t getAddrFrom() { return _getAddrFrom(this); }; uint16_t getAddrFrom() { return _getAddrFrom(this); };
inline uint8_t getCustomByte() { return packInfo->buffer[DataOffset]; }; uint8_t getCustomByte() { return packInfo->buffer[DataOffset]; };
private: private:
bool checkAddress() override; bool checkAddress() override { return true; }
}; };
class Request : public BasePack class Request : public BasePack
@ -117,11 +194,168 @@ namespace PacketTypes
DataOffset = 3; DataOffset = 3;
} }
inline uint16_t getAddrFrom() { return _getAddrFrom(this); }; uint16_t getAddrFrom() { return _getAddrFrom(this); };
inline uint16_t getAddrTo() { return _getAddrTo(this); }; uint16_t getAddrTo() { return _getAddrTo(this); };
private: private:
bool checkAddress() override; bool checkAddress() override
{
bool ret;
IR_FOX::checkAddressRuleApply(getAddrTo(), this->id, ret);
return ret;
}
}; };
} }
// class IOffsets {
// protected:
// uint8_t msgOffset;
// uint8_t addressFromOffset;
// uint8_t addressToOffset;
// uint8_t DataOffset;
// };
// class IPackInfo {
// public:
// IR_FOX::PackInfo* packInfo;
// };
// class IBaseEmptyPack : virtual public IOffsets, virtual public IPackInfo {
// };
// class IR_Decoder;
// class IEmptyPack : virtual protected IBaseEmptyPack, virtual public IR_FOX {
// friend IR_Decoder;
// bool isAvailable;
// bool isRawAvailable;
// bool isNeedAccept;
// protected:
// uint16_t id;
// virtual bool checkAddress() {};
// virtual void set(IR_FOX::PackInfo* packInfo, uint16_t id, bool isNeedAccept = false) {
// IBaseEmptyPack::IPackInfo::packInfo = packInfo;
// this->id = id;
// this->isNeedAccept = isNeedAccept;
// if (isAvailable = checkAddress()) {
// isAvailable = true;
// isRawAvailable = true;
// Serial.print(" OK ");
// } else {
// isRawAvailable = true;
// Serial.print(" NOT-OK ");
// }
// }
// public:
// virtual bool available() { if (isAvailable) { isAvailable = false; isRawAvailable = false; return true; } else { return false; } };
// virtual bool availableRaw() { if (isRawAvailable) { isRawAvailable = false; return true; } else { return false; } };
// virtual uint8_t getMsgInfo() { return packInfo->buffer[0] & IR_MASK_MSG_INFO; };
// virtual uint8_t getMsgType() { return (packInfo->buffer[0] >> 5) & IR_MASK_MSG_TYPE; };
// virtual uint8_t getMsgRAW() { return packInfo->buffer[0]; };
// virtual uint16_t getErrorCount() { return packInfo->err.all(); };
// virtual uint8_t getErrorLowSignal() { return packInfo->err.lowSignal; };
// virtual uint8_t getErrorHighSignal() { return packInfo->err.highSignal; };
// virtual uint8_t getErrorOther() { return packInfo->err.other; };
// virtual uint16_t getTunerTime() { return packInfo->rTime; };
// };
// class IHasAddresFrom : virtual protected IBaseEmptyPack {
// public:
// virtual uint16_t getAddrFrom() { return (packInfo->buffer[addressFromOffset] << 8) | packInfo->buffer[addressFromOffset + 1]; };
// };
// class IHasAddresTo : virtual protected IBaseEmptyPack {
// public:
// virtual uint16_t getAddrTo() { return (packInfo->buffer[addressToOffset] << 8) | packInfo->buffer[addressToOffset + 1]; };
// };
// class IHasAddresData : virtual protected IBaseEmptyPack {
// public:
// virtual uint8_t getDataSize() { return packInfo->packSize - crcBytes - DataOffset; };
// virtual uint8_t* getDataPrt() { return packInfo->buffer + DataOffset; };
// virtual uint8_t getDataRawSize() { return packInfo->packSize; };
// virtual uint8_t* getDataRawPtr() { return packInfo->buffer; };
// };
// /////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
// class Data :
// virtual public IEmptyPack,
// virtual public IHasAddresFrom,
// virtual public IHasAddresTo,
// virtual public IHasAddresData {
// public:
// Data() {
// msgOffset = 0;
// addressFromOffset = 1;
// addressToOffset = 3;
// DataOffset = 5;
// }
// protected:
// bool checkAddress() override {
// bool ret;
// checkAddressRuleApply(getAddrTo(), this->id, ret);
// return ret;
// }
// };
// class DataBack :
// virtual public IEmptyPack,
// virtual public IHasAddresFrom,
// virtual public IHasAddresData {
// public:
// DataBack() {
// msgOffset = 0;
// addressFromOffset = 1;
// addressToOffset = 3;
// DataOffset = 3;
// }
// protected:
// bool checkAddress() override {
// bool ret;
// if (getMsgType() == IR_MSG_BACK_TO) {
// DataOffset = 5;
// checkAddressRuleApply((packInfo->buffer[addressToOffset] << 8) | packInfo->buffer[addressToOffset + 1], this->id, ret);
// } else {
// DataOffset = 3;
// ret = true;
// }
// return ret;
// }
// };
// class Request :
// virtual public IEmptyPack,
// virtual public IHasAddresFrom,
// virtual public IHasAddresTo {
// public:
// Request() {
// msgOffset = 0;
// addressFromOffset = 1;
// addressToOffset = 3;
// DataOffset = 3;
// }
// protected:
// bool checkAddress() override {
// bool ret;
// checkAddressRuleApply(getAddrTo(), this->id, ret);
// return ret;
// }
// };
// class Accept :
// virtual public IEmptyPack,
// virtual public IHasAddresFrom {
// public:
// Accept() {
// msgOffset = 0;
// addressFromOffset = 1;
// DataOffset = 1;
// }
// protected:
// };