32 Commits

Author SHA1 Message Date
277985f79a update ir adress space 2025-01-30 16:17:45 +03:00
444b84c313 hide test prints 2025-01-28 17:43:46 +03:00
2db1ef7805 test 2025-01-28 12:59:53 +03:00
1353ab6f75 constexpr IR_ResponseDelay 2025-01-28 12:59:42 +03:00
d1cb167aaf no define 2025-01-23 09:41:10 +03:00
30ad816c2a fix redifinded 2025-01-22 17:31:14 +03:00
ecfb3b5f98 downgrade 2025-01-17 19:11:05 +03:00
70a22463ef Merge pull request #5 from Show-maket/G431K-test
enable/disable update
2025-01-16 17:54:33 +03:00
71f58a4992 Revert "Update IR-protocol.ino"
This reverts commit 79bb804bb4.
2025-01-16 17:53:05 +03:00
b6b9d2c820 enable/disable fix 2025-01-16 17:51:21 +03:00
98a21f5e56 Update arduino.json 2025-01-16 17:02:51 +03:00
591727546e Update .gitignore 2025-01-16 17:02:42 +03:00
79bb804bb4 Update IR-protocol.ino 2025-01-16 16:58:38 +03:00
0471b8cc89 begin() 2025-01-16 16:58:33 +03:00
90c41cfe2b ambigious fix 2025-01-09 09:32:14 +03:00
1ecc33e9c4 hotfix 2024-12-25 17:13:28 +03:00
7ef8158a00 upd 2024-12-25 17:07:47 +03:00
341ff3a470 Update IR_DecoderRaw.cpp 2024-12-24 15:00:20 +03:00
e6dbdcee74 f401 MAKET 2024-12-23 17:36:35 +03:00
cf5a6641f4 Update arduino.json 2024-11-14 15:07:28 +03:00
da152c65ee address space config 2024-09-20 09:35:27 +03:00
8f77c60cba .gitignore 2024-09-09 10:40:47 +03:00
fd51a4935c small fix 2024-09-03 17:35:35 +03:00
aa862d8f2c default addr 2024-08-29 17:06:10 +03:00
7c9529d42f enable-disable func 2024-08-29 16:46:40 +03:00
d4dd0e95fd upd 2024-08-29 16:22:09 +03:00
04af094f4b opti 2024-08-29 14:25:09 +03:00
2f4ac3ddf8 no default construct 2024-08-29 14:14:46 +03:00
784365181e default constructor and operator() for test 2024-08-28 18:00:18 +03:00
c66d47e464 info 2024-07-08 17:14:49 +03:00
3057e78aeb pin 2024-05-27 11:11:52 +03:00
a958c1d3b2 pin 2024-05-27 11:02:45 +03:00
11 changed files with 304 additions and 228 deletions

4
.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,8 +1,5 @@
{ {
"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": "STMicroelectronics:stm32:GenF4",
"board": "rp2040:rp2040:rpipico",
"port": "COM17", "port": "COM17",
"output": "bin", "prebuild": "if exist bin rd /s /q bin"
"prebuild": "if exist bin rd /s /q bin",
"sketch": "IR-protocol.ino"
} }

View File

@ -1,44 +1,27 @@
#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"
/////////////// Pinout /////////////// /////////////// Pinout ///////////////
#define dec0_PIN 0 #define dec0_PIN PIN_KT1_IN
#define dec1_PIN 1 #define dec1_PIN PIN_KT2_IN
#define dec2_PIN 2 #define dec2_PIN PIN_KT3_IN
#define dec3_PIN 3 #define dec3_PIN PIN_KT4_IN
#define dec4_PIN 4 #define dec4_PIN PIN_KT5_IN
#define dec5_PIN 5 #define dec5_PIN PIN_KT6_IN
#define dec6_PIN 6 #define dec6_PIN PIN_KT7_IN
#define dec7_PIN 7 #define dec7_PIN PIN_KT8_IN
#define dec8_PIN 8 // #define dec8_PIN PB8
#define dec9_PIN 9 // #define dec9_PIN PB9
#define dec10_PIN 10 // #define dec10_PIN PB10
#define dec11_PIN 11 // #define dec11_PIN PB11
#define dec12_PIN 12 // #define dec12_PIN PB12
#define dec13_PIN 13 // #define dec13_PIN PB13
#define dec14_PIN 14 // #define dec14_PIN PB14
#define dec15_PIN 15 // #define dec15_PIN PB15
#define LoopOut 16 #define LoopOut PC13
#define LoopOut1 17
#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 /////////////////
@ -48,11 +31,11 @@ void digitalToggle(uint8_t pin){
//////////////// Var ///////////////// //////////////// Var /////////////////
// IR_Encoder encForward(PA5, 42 /* , &decBackward */); // IR_Encoder encForward(PA5, 42 /* , &decBackward */);
IR_Encoder enc0(18, 42 /* , &decBackward */); IR_Encoder enc0(PIN_KT8_OUT, 42 /* , &decBackward */);
IR_Encoder enc1(19, 127 /* , &decBackward */); // IR_Encoder enc1(PA1, 127 /* , &decBackward */);
IR_Encoder enc2(20, 137 /* , &decBackward */); // IR_Encoder enc2(PA2, 137 /* , &decBackward */);
IR_Encoder enc3(21, 777 /* , &decBackward */); // IR_Encoder enc3(PA3, 777 /* , &decBackward */);
// IR_Encoder enc10(PC15, 555 /* , &decBackward */); // IR_Encoder enc10(PA4, 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 */);
@ -64,26 +47,51 @@ IR_Encoder enc3(21, 777 /* , &decBackward */);
void EncoderISR() void EncoderISR()
{ {
IR_Encoder::isr(); IR_Encoder::isr();
// digitalToggle(LoopOut);
} }
//------------------------------------------------------------------- //-------------------------------------------------------------------
dec_Ini(0); IR_Decoder dec0(dec0_PIN, 0);
dec_Ini(1); void dec_0_ISR() { dec0.isr(); }
dec_Ini(2);
dec_Ini(3); IR_Decoder dec1(dec1_PIN, 1);
dec_Ini(4); void dec_1_ISR() { dec1.isr(); }
dec_Ini(5);
dec_Ini(6); IR_Decoder dec2(dec2_PIN, 2);
dec_Ini(7); void dec_2_ISR() { dec2.isr(); }
dec_Ini(8);
dec_Ini(9); IR_Decoder dec3(dec3_PIN, 3);
dec_Ini(10); void dec_3_ISR() { dec3.isr(); }
dec_Ini(11);
dec_Ini(12); IR_Decoder dec4(dec4_PIN, 4);
dec_Ini(13); 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(); }
// IR_Decoder dec10(dec10_PIN, 10);
// void dec_10_ISR() { dec10.isr(); }
// 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[] = {};
@ -95,13 +103,14 @@ uint8_t data4[] = {42, 127, 137, 255};
uint32_t loopTimer; uint32_t loopTimer;
uint8_t sig = 0; 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); // 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));
@ -188,114 +197,78 @@ 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()
{ {
pinMode(LoopOut1, OUTPUT); IR_Timer.setOverflow(carrierFrec * 2, HERTZ_FORMAT);
add_repeating_timer_us(6, TimerISRHandler, NULL, &timer); IR_Timer.attachInterrupt(1, EncoderISR);
NVIC_SetPriority(IRQn_Type::TIM3_IRQn, 0);
// IR_Timer.setOverflow(carrierFrec * 2, HERTZ_FORMAT); IR_Timer.resume();
// 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(dec0_PIN, INPUT_PULLUP);
pinMode(dec1_PIN, INPUT_PULLUP); pinMode(dec1_PIN, INPUT_PULLUP);
// pinMode(dec2_PIN, INPUT_PULLUP); pinMode(dec2_PIN, INPUT_PULLUP);
pinMode(dec3_PIN, INPUT_PULLUP);
pinMode(dec4_PIN, INPUT_PULLUP);
pinMode(dec5_PIN, INPUT_PULLUP);
pinMode(dec6_PIN, INPUT_PULLUP);
pinMode(dec7_PIN, INPUT_PULLUP);
// pinMode(dec8_PIN, INPUT_PULLUP);
// pinMode(dec9_PIN, INPUT_PULLUP);
// pinMode(dec10_PIN, INPUT_PULLUP);
// pinMode(dec11_PIN, INPUT_PULLUP);
// pinMode(dec12_PIN, INPUT_PULLUP);
// pinMode(dec13_PIN, INPUT_PULLUP);
static IR_DecoderRaw *blind[]{ attachInterrupt(dec0_PIN, dec_0_ISR, CHANGE);
&dec0, attachInterrupt(dec1_PIN, dec_1_ISR, CHANGE);
&dec1, attachInterrupt(dec2_PIN, dec_2_ISR, CHANGE);
&dec2, attachInterrupt(dec3_PIN, dec_3_ISR, CHANGE);
&dec3, attachInterrupt(dec4_PIN, dec_4_ISR, CHANGE);
&dec4, attachInterrupt(dec5_PIN, dec_5_ISR, CHANGE);
&dec5, attachInterrupt(dec6_PIN, dec_6_ISR, CHANGE);
&dec6, attachInterrupt(dec7_PIN, dec_7_ISR, CHANGE);
&dec7, // attachInterrupt(dec8_PIN, dec_8_ISR, CHANGE);
&dec8, // attachInterrupt(dec9_PIN, dec_9_ISR, CHANGE);
&dec9, // attachInterrupt(dec10_PIN, dec_10_ISR, CHANGE);
&dec10, // attachInterrupt(dec11_PIN, dec_11_ISR, CHANGE);
&dec11, // attachInterrupt(dec12_PIN, dec_12_ISR, CHANGE);
&dec12, // attachInterrupt(dec13_PIN, dec_13_ISR, CHANGE);
&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() void loop()
{ {
digitalToggle(LoopOut); digitalToggle(LoopOut);
}
void loop1()
{
Timer::tick(); Timer::tick();
IR_Decoder::tick(); IR_Decoder::tick();
bool rx_flag; bool rx_flag = false;
decStat(0); rx_flag |= status(dec0);
decStat(1); rx_flag |= status(dec1);
decStat(2); rx_flag |= status(dec2);
decStat(3); rx_flag |= status(dec3);
decStat(4); rx_flag |= status(dec4);
decStat(5); rx_flag |= status(dec5);
decStat(6); rx_flag |= status(dec6);
decStat(7); rx_flag |= status(dec7);
decStat(8); // rx_flag |= status(dec8);
decStat(9); // rx_flag |= status(dec9);
decStat(10); // rx_flag |= status(dec10);
decStat(11); // rx_flag |= status(dec11);
decStat(12); // rx_flag |= status(dec12);
decStat(13); // rx_flag |= status(dec13);
// status(decForward);
// status(decBackward);
// Serial.println(micros() - loopTimer);
// loopTimer = micros();
// delayMicroseconds(120*5);
if (Serial.available()) if (Serial.available())
{ {
@ -311,25 +284,14 @@ void loop1()
case 102: case 102:
targetAddr = 777; targetAddr = 777;
break; break;
default: default:
sig = in; sig = in;
break; break;
} }
Serial.println(in);
} }
digitalToggle(LoopOut1);
} }
Timer statusSimpleDelay; Timer statusSimpleDelay;
bool statusSimple(IR_Decoder &dec) bool statusSimple(IR_Decoder &dec)
{ {
@ -355,12 +317,12 @@ void detectSignal()
} }
// test // test
void status(IR_Decoder &dec) bool status(IR_Decoder &dec)
{ {
if (dec.gotData.available()) if (dec.gotData.available())
{ {
detectSignal(); detectSignal();
Serial.println(micros()); // Serial.println(micros());
String str; String str;
if (/* dec.gotData.getDataPrt()[1] */ 1) if (/* dec.gotData.getDataPrt()[1] */ 1)
{ {
@ -606,4 +568,5 @@ void status(IR_Decoder &dec)
// obj->resetAvailable(); // obj->resetAvailable();
Serial.write(str.c_str()); Serial.write(str.c_str());
} }
return false;
} }

View File

@ -1,17 +1,50 @@
#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(const uint8_t pin, uint16_t addr, IR_Encoder *encPair) // 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) : 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);
@ -64,7 +97,7 @@ void IR_Decoder::_tick()
} }
gotRaw.set(&packInfo, id); gotRaw.set(&packInfo, id);
} }
if (isWaitingAcceptSend && millis() - acceptSendTimer > 75) if (isWaitingAcceptSend && millis() - acceptSendTimer > acceptDelay)
{ {
encoder->sendAccept(addrAcceptSendTo, acceptCustomByte); encoder->sendAccept(addrAcceptSendTo, acceptCustomByte);
isWaitingAcceptSend = false; isWaitingAcceptSend = false;

View File

@ -14,7 +14,7 @@ private:
bool isWaitingAcceptSend; bool isWaitingAcceptSend;
uint16_t addrAcceptSendTo; uint16_t addrAcceptSendTo;
uint16_t acceptDelay = 75; uint16_t acceptDelay = IR_ResponseDelay;
uint8_t acceptCustomByte; uint8_t acceptCustomByte;
public: public:
@ -24,7 +24,14 @@ public:
PacketTypes::Request gotRequest; PacketTypes::Request gotRequest;
PacketTypes::BasePack gotRaw; PacketTypes::BasePack gotRaw;
IR_Decoder(const uint8_t pin, uint16_t addr, IR_Encoder *encPair = nullptr); // IR_Decoder();
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();
~IR_Decoder(); ~IR_Decoder();
static void tick(); static void tick();

View File

@ -4,7 +4,6 @@
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)
@ -48,7 +47,7 @@ volatile uint32_t time_;
void IR_DecoderRaw::isr() void IR_DecoderRaw::isr()
{ {
// Serial.print("ISR\n");
if(isPairSending){ if(isPairSending){
return; return;
} }
@ -59,7 +58,8 @@ 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,8 +75,7 @@ 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);

View File

@ -23,6 +23,7 @@
#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
@ -132,4 +133,4 @@ private:
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,16 +5,15 @@
#define ISR_Out 10 #define ISR_Out 10
#define TestOut 13 #define TestOut 13
std::list<IR_Encoder*>& IR_Encoder::get_enc_list() // определение функции std::list<IR_Encoder *> &IR_Encoder::get_enc_list() // определение функции
{ {
static std::list<IR_Encoder*> dec_list; // статическая локальная переменная static std::list<IR_Encoder *> dec_list; // статическая локальная переменная
return dec_list; // возвращается ссылка на переменную return dec_list; // возвращается ссылка на переменную
} }
IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair) IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair, bool autoHandle)
{ {
setPin(pin); setPin(pin);
pinMode(pin,OUTPUT);
id = addr; id = addr;
this->decPair = decPair; this->decPair = decPair;
signal = noSignal; signal = noSignal;
@ -22,8 +21,7 @@ IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair)
#if disablePairDec #if disablePairDec
if (decPair != nullptr) if (decPair != nullptr)
{ {
blindDecoders = new IR_DecoderRaw *[1] blindDecoders = new IR_DecoderRaw *[1]{decPair};
{ decPair };
decodersCount = 1; decodersCount = 1;
} }
#endif #endif
@ -31,9 +29,51 @@ IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair)
{ {
decPair->encoder = this; decPair->encoder = this;
} }
get_enc_list().push_back(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 Encoder_ISR(){
// IR_Encoder::isr();
// }
void IR_Encoder::begin(HardwareTimer timer, uint8_t channel, IRQn_Type IRQn){
//TODO: check std::bind isr func
// IR_Timer = timer;
// IR_Timer.setOverflow(carrierFrec * 2, HERTZ_FORMAT);
// IR_Timer.attachInterrupt(channel, 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
@ -46,20 +86,19 @@ void IR_Encoder::setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count)
IR_Encoder::~IR_Encoder() IR_Encoder::~IR_Encoder()
{ {
delete[] bitLow;
delete[] bitHigh;
get_enc_list().remove(this); get_enc_list().remove(this);
}; };
void IR_Encoder::sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept) void IR_Encoder::sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept)
{ {
uint8_t *dataPtr = new uint8_t[1]; sendData(addrTo, &dataByte, 1, needAccept);
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)
{ {
@ -76,8 +115,8 @@ void IR_Encoder::sendData(uint16_t addrTo, uint8_t *data, uint8_t len, bool need
sendBuffer[0] = msgType; sendBuffer[0] = msgType;
// addr_self // addr_self
sendBuffer[1] = id >> 8 & 0xFF; sendBuffer[1] = addrFrom >> 8 & 0xFF;
sendBuffer[2] = id & 0xFF; sendBuffer[2] = addrFrom & 0xFF;
// addr_to // addr_to
sendBuffer[3] = addrTo >> 8 & 0xFF; sendBuffer[3] = addrTo >> 8 & 0xFF;
@ -153,7 +192,7 @@ 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);
} }
@ -208,6 +247,10 @@ 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);
} }
} }
} }
@ -219,7 +262,7 @@ void IR_Encoder::rawSend(uint8_t *ptr, uint8_t len)
// TODO: Обработка повторной отправки // TODO: Обработка повторной отправки
return; return;
} }
// Serial.println("START");
setDecoder_isSending(); setDecoder_isSending();
// noInterrupts(); // noInterrupts();
@ -242,9 +285,11 @@ void IR_Encoder::rawSend(uint8_t *ptr, uint8_t len)
// interrupts(); // interrupts();
} }
void IR_Encoder::isr(){ void IR_Encoder::isr()
{
// Serial.println(get_enc_list().size()); // Serial.println(get_enc_list().size());
for(const auto &element : get_enc_list()){ for (const auto &element : get_enc_list())
{
element->_isr(); element->_isr();
} }
} }
@ -256,10 +301,8 @@ 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)
{ {
@ -275,7 +318,9 @@ void IR_Encoder::_isr()
// сброс счетчиков // сброс счетчиков
// ... // ...
isSending = false; isSending = false;
// Serial.println("STOP");
setDecoder_isSending(); setDecoder_isSending();
// Serial.println();
return; return;
break; break;
@ -393,9 +438,16 @@ void IR_Encoder::addSync(bool *prev, bool *next)
} }
} }
uint8_t* IR_Encoder::bitHigh = new uint8_t[2]{ uint8_t IR_Encoder::bitHigh[2] = {
(bitPauseTakts) * 2 - 1, (bitPauseTakts) * 2 - 1,
(bitActiveTakts) * 2 - 1}; (bitActiveTakts) * 2 - 1};
uint8_t* IR_Encoder::bitLow = new uint8_t[2]{ uint8_t IR_Encoder::bitLow[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,27 +4,34 @@
// TODO: Отложенная передача после завершения приема // TODO: Отложенная передача после завершения приема
class IR_DecoderRaw; class IR_DecoderRaw;
class IR_Encoder : IR_FOX class IR_Encoder : public 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 decPair Приёмник, для которого отключается приём в момент передачи передатчиком /// @param decPair Приёмник, для которого отключается приём в момент передачи передатчиком
IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair = nullptr); IR_Encoder(uint8_t pin, uint16_t addr = 0, IR_DecoderRaw *decPair = nullptr, bool autoHandle = true);
static void isr(); static void isr();
static void begin(HardwareTimer IR_Timer, uint8_t channel, IRQn_Type IRQn);
static HardwareTimer* get_IR_Timer();
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 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);
@ -82,8 +89,8 @@ private:
uint8_t low; uint8_t low;
uint8_t high; uint8_t high;
}; };
static uint8_t *bitHigh; static uint8_t bitHigh[2];
static uint8_t *bitLow; static uint8_t bitLow[2];
uint8_t *currentBitSequence = bitLow; uint8_t *currentBitSequence = bitLow;
volatile SignalPart signal; volatile SignalPart signal;
}; };

View File

@ -2,9 +2,8 @@
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,19 +8,32 @@
*/ */
// Адресация с 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, либо тесты *Адресное пространство:
IR_MSG_ACCEPT с адреса 0 воспринимается всеми устройствами Адрес 0 запрещен и зарезервирован под NULL, либо тесты
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
Излучатели контрольных точек: 1000 ~ 1999 // #define IR_MIN_FREE 2000
Излучатели без обратной связиЖ 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 `````````````````````````````````````````````\                                  
                                                                                                                                                                                                                   
@ -142,6 +155,11 @@ 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:
@ -178,16 +196,16 @@ public:
uint16_t rTime = 0; uint16_t rTime = 0;
}; };
inline uint16_t getId() { return id; } inline uint16_t getId() const { 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; };
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);