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 169 additions and 221 deletions

1
.gitignore vendored
View File

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

View File

@ -1,7 +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",
"output": "bin",
"prebuild": "if exist bin rd /s /q bin", "prebuild": "if exist bin rd /s /q bin",
"sketch": "IR-protocol.ino", "sketch": "IR-protocol.ino"
"configuration": "clock=25MHz,pnum=MAKET_F401RETX,upload_method=dfuMethod,xserial=generic,usb=CDCgen,xusb=FS,opt=osstd,dbg=none,rtlib=nano"
} }

View File

@ -1,27 +1,28 @@
#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 PIN_KT1_IN #define dec0_PIN 0
#define dec1_PIN PIN_KT2_IN #define dec1_PIN 1
#define dec2_PIN PIN_KT3_IN #define dec2_PIN 2
#define dec3_PIN PIN_KT4_IN #define dec3_PIN 3
#define dec4_PIN PIN_KT5_IN #define dec4_PIN 4
#define dec5_PIN PIN_KT6_IN #define dec5_PIN 5
#define dec6_PIN PIN_KT7_IN #define dec6_PIN 6
#define dec7_PIN PIN_KT8_IN #define dec7_PIN 7
// #define dec8_PIN PB8 #define dec8_PIN 8
// #define dec9_PIN PB9 #define dec9_PIN 9
// #define dec10_PIN PB10 #define dec10_PIN 10
// #define dec11_PIN PB11 #define dec11_PIN 11
// #define dec12_PIN PB12 #define dec12_PIN 12
// #define dec13_PIN PB13 #define dec13_PIN 13
// #define dec14_PIN PB14 #define dec14_PIN 14
// #define dec15_PIN PB15 #define dec15_PIN 15
#define LoopOut PC13 #define LoopOut 16
#define LoopOut1 17
#define dec_ISR(n) \ #define dec_ISR(n) \
void dec_##n##_ISR() { dec##n.isr(); } void dec_##n##_ISR() { dec##n.isr(); }
@ -31,9 +32,13 @@
#define decPinMode(n) pinMode(dec##n##_PIN, INPUT_PULLUP); #define decPinMode(n) pinMode(dec##n##_PIN, INPUT_PULLUP);
#define decAttach(n) attachInterrupt(dec##n##_PIN, dec_##n##_ISR, CHANGE); #define decAttach(n) attachInterrupt(dec##n##_PIN, dec_##n##_ISR, CHANGE);
#define decSetup(n) decPinMode(n); decAttach(n); #define decSetup(n) /* decPinMode(n); */ decAttach(n);
#define decTick(n) dec##n.tick(); #define decTick(n) dec##n.tick();
#define decStat(n) rx_flag |= status/* Simple */(dec##n); #define decStat(n) rx_flag |= statusSimple(dec##n);
void digitalToggle(uint8_t pin){
digitalWrite(pin, !digitalRead(pin));
}
//////////////// Ini ///////////////// //////////////// Ini /////////////////
@ -43,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 */);
@ -59,6 +64,8 @@ IR_Encoder enc0(PIN_KT8_OUT, 42 /* , &decBackward */);
void EncoderISR() void EncoderISR()
{ {
IR_Encoder::isr(); IR_Encoder::isr();
// digitalToggle(LoopOut);
} }
//------------------------------------------------------------------- //-------------------------------------------------------------------
@ -71,12 +78,12 @@ dec_Ini(4);
dec_Ini(5); dec_Ini(5);
dec_Ini(6); dec_Ini(6);
dec_Ini(7); dec_Ini(7);
// dec_Ini(8); dec_Ini(8);
// dec_Ini(9); dec_Ini(9);
// dec_Ini(10); dec_Ini(10);
// dec_Ini(11); dec_Ini(11);
// dec_Ini(12); dec_Ini(12);
// dec_Ini(13); dec_Ini(13);
///////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////
uint8_t data0[] = {}; uint8_t data0[] = {};
@ -91,10 +98,10 @@ 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));
@ -186,16 +193,25 @@ Timer t1(500, millis, []()
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()
{ {
// MicrosTimer.setOve pinMode(LoopOut1, OUTPUT);
add_repeating_timer_us(6, TimerISRHandler, NULL, &timer);
IR_Timer.setOverflow(carrierFrec * 2, HERTZ_FORMAT); // IR_Timer.setOverflow(carrierFrec * 2, HERTZ_FORMAT);
IR_Timer.attachInterrupt(1, EncoderISR); // IR_Timer.attachInterrupt(1, EncoderISR);
NVIC_SetPriority(IRQn_Type::TIM3_IRQn, 0); // NVIC_SetPriority(IRQn_Type::TIM3_IRQn, 0);
IR_Timer.resume(); // IR_Timer.resume();
Serial.begin(SERIAL_SPEED); Serial.begin(SERIAL_SPEED);
Serial.println(F(INFO)); Serial.println(F(INFO));
@ -203,7 +219,7 @@ void setup()
pinMode(LoopOut, OUTPUT); pinMode(LoopOut, OUTPUT);
// pinMode(SignalDetectLed, OUTPUT); // pinMode(SignalDetectLed, OUTPUT);
pinMode(dec0_PIN, INPUT_PULLUP); pinMode(dec1_PIN, INPUT_PULLUP);
// pinMode(dec2_PIN, INPUT_PULLUP); // pinMode(dec2_PIN, INPUT_PULLUP);
static IR_DecoderRaw *blind[]{ static IR_DecoderRaw *blind[]{
@ -215,41 +231,47 @@ void setup()
&dec5, &dec5,
&dec6, &dec6,
&dec7, &dec7,
// &dec8, &dec8,
// &dec9, &dec9,
// &dec10, &dec10,
// &dec11, &dec11,
// &dec12, &dec12,
// &dec13, &dec13,
}; };
enc0.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *)); // enc0.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *));
// enc1.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *)); // enc1.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *));
// enc2.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *)); // enc2.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *));
// enc3.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *)); // enc3.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *));
// enc10.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *)); // enc10.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *));
decSetup(0); decSetup(0);
decSetup(1); // decSetup(1);
decSetup(2); // decSetup(2);
decSetup(3); // decSetup(3);
decSetup(4); // decSetup(4);
decSetup(5); // decSetup(5);
decSetup(6); // decSetup(6);
decSetup(7); // decSetup(7);
// decSetup(8); // decSetup(8);
// decSetup(9); // decSetup(9);
// decSetup(10); // decSetup(10);
// decSetup(11); decSetup(11);
// decSetup(12); decSetup(12);
// decSetup(13); decSetup(13);
} }
void loop() void loop()
{ {
digitalToggle(LoopOut); digitalToggle(LoopOut);
Timer::tick();
}
void loop1()
{
Timer::tick();
IR_Decoder::tick(); IR_Decoder::tick();
bool rx_flag; bool rx_flag;
@ -261,12 +283,12 @@ void loop()
decStat(5); decStat(5);
decStat(6); decStat(6);
decStat(7); decStat(7);
// decStat(8); decStat(8);
// decStat(9); decStat(9);
// decStat(10); decStat(10);
// decStat(11); decStat(11);
// decStat(12); decStat(12);
// decStat(13); decStat(13);
// status(decForward); // status(decForward);
// status(decBackward); // status(decBackward);
@ -294,8 +316,20 @@ void loop()
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)
{ {
@ -321,7 +355,7 @@ void detectSignal()
} }
// test // test
bool status(IR_Decoder &dec) void status(IR_Decoder &dec)
{ {
if (dec.gotData.available()) if (dec.gotData.available())
{ {
@ -572,5 +606,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,48 +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);
}
attachInterrupt(pin, (*this)(), CHANGE);
}
void IR_Decoder::disable()
{
detachInterrupt(pin);
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);

View File

@ -24,14 +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();
~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);

View File

@ -132,4 +132,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,15 +5,16 @@
#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, 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;
@ -21,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
@ -29,33 +31,9 @@ IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair, bool
{ {
decPair->encoder = this; decPair->encoder = this;
} }
pinMode(pin, OUTPUT); get_enc_list().push_back(this);
if (autoHandle)
{
get_enc_list().push_back(this);
}
}; };
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);
}
}
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);
}
}
void IR_Encoder::setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count) void IR_Encoder::setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count)
{ {
#if disablePairDec #if disablePairDec
@ -68,19 +46,20 @@ 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)
{ {
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)
{ {
@ -97,8 +76,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;
@ -174,7 +153,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);
} }
@ -263,11 +242,9 @@ 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();
} }
} }
@ -279,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)
{ {
@ -414,16 +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};
// 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,31 +4,27 @@
// 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:
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 = 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();
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);
@ -86,8 +82,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

@ -2,9 +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); // 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 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 `````````````````````````````````````````````\                                  
                                                                                                                                                                                                                   
@ -57,9 +44,9 @@ msg type:
#define IR_MSG_BACK 0U // | 000...... | = Задний сигнал машинки #define IR_MSG_BACK 0U // | 000...... | = Задний сигнал машинки
#define IR_MSG_ACCEPT 1U // | 001..... | = подтверждение #define IR_MSG_ACCEPT 1U // | 001..... | = подтверждение
#define IR_MSG_REQUEST 2U // | 010..... | = запрос #define IR_MSG_REQUEST 2U // | 010..... | = запрос
#define IR_MSG_ 3U // | 011..... | = ?? // #define IR_MSG_ 3U // | 011..... | = ??
#define IR_MSG_BACK_TO 4U // | 100..... | = Задний сигнал машинки c адресацией #define IR_MSG_BACK_TO 4U // | 100..... | = Задний сигнал машинки c адресацией
#define IR_MSG_ 5U // | 101..... | = ?? // #define IR_MSG_ 5U // | 101..... | = ??
#define IR_MSG_DATA_NOACCEPT 6U // | 110..... | = данные, не требующие подтверждения #define IR_MSG_DATA_NOACCEPT 6U // | 110..... | = данные, не требующие подтверждения
#define IR_MSG_DATA_ACCEPT 7U // | 111..... | = данные требующие подтверждения #define IR_MSG_DATA_ACCEPT 7U // | 111..... | = данные требующие подтверждения
; /*   // ---------- ; /*   // ----------
@ -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,16 +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;};
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);