15 Commits

Author SHA1 Message Date
2d839d3ff8 HardwareTimer auto set support 2025-03-06 17:05:37 +03:00
6ba8fdffe4 auto begin 2025-02-25 18:05:10 +03:00
aa0b478229 faster for each 2025-02-25 15:17:09 +03:00
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
79bb804bb4 Update IR-protocol.ino 2025-01-16 16:58:38 +03:00
0471b8cc89 begin() 2025-01-16 16:58:33 +03:00
8 changed files with 191 additions and 127 deletions

View File

@ -23,18 +23,6 @@
#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 /////////////////
#define INFO "IR_FOX TEST"
@ -63,20 +51,47 @@ void EncoderISR()
//-------------------------------------------------------------------
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);
IR_Decoder dec0(dec0_PIN, 0);
void dec_0_ISR() { dec0.isr(); }
IR_Decoder dec1(dec1_PIN, 1);
void dec_1_ISR() { dec1.isr(); }
IR_Decoder dec2(dec2_PIN, 2);
void dec_2_ISR() { dec2.isr(); }
IR_Decoder dec3(dec3_PIN, 3);
void dec_3_ISR() { dec3.isr(); }
IR_Decoder dec4(dec4_PIN, 4);
void dec_4_ISR() { dec4.isr(); }
IR_Decoder dec5(dec5_PIN, 5);
void dec_5_ISR() { dec5.isr(); }
IR_Decoder dec6(dec6_PIN, 6);
void dec_6_ISR() { dec6.isr(); }
IR_Decoder dec7(dec7_PIN, 7);
void dec_7_ISR() { dec7.isr(); }
// IR_Decoder dec8(dec8_PIN, 8);
// void dec_8_ISR() { dec8.isr(); }
// IR_Decoder dec9(dec9_PIN, 9);
// void dec_9_ISR() { dec9.isr(); }
// 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[] = {};
@ -88,6 +103,7 @@ uint8_t data4[] = {42, 127, 137, 255};
uint32_t loopTimer;
uint8_t sig = 0;
uint16_t targetAddr = IR_Broadcast;
Timer t1(500, millis, []()
{
// Serial.println( digitalPinToBitMask(enc0.getPin()), BIN);
@ -181,6 +197,7 @@ Timer t1(500, millis, []()
// encBackward.sendData(IR_Broadcast, data2);
// encTree.sendData(IR_Broadcast, rawData3);
});
// Timer t2(50, millis, []()
// { digitalToggle(LED_BUILTIN); });
@ -190,8 +207,6 @@ HardwareTimer IR_Timer(TIM3);
void setup()
{
// MicrosTimer.setOve
IR_Timer.setOverflow(carrierFrec * 2, HERTZ_FORMAT);
IR_Timer.attachInterrupt(1, EncoderISR);
NVIC_SetPriority(IRQn_Type::TIM3_IRQn, 0);
@ -201,79 +216,59 @@ void setup()
Serial.println(F(INFO));
pinMode(LoopOut, OUTPUT);
// pinMode(SignalDetectLed, OUTPUT);
pinMode(dec0_PIN, INPUT_PULLUP);
// pinMode(dec2_PIN, INPUT_PULLUP);
pinMode(dec1_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[]{
&dec0,
&dec1,
&dec2,
&dec3,
&dec4,
&dec5,
&dec6,
&dec7,
// &dec8,
// &dec9,
// &dec10,
// &dec11,
// &dec12,
// &dec13,
};
enc0.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *));
// enc1.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *));
// enc2.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *));
// enc3.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *));
// enc10.setBlindDecoders(blind, sizeof(blind) / sizeof(IR_DecoderRaw *));
decSetup(0);
decSetup(1);
decSetup(2);
decSetup(3);
decSetup(4);
decSetup(5);
decSetup(6);
decSetup(7);
// decSetup(8);
// decSetup(9);
// decSetup(10);
// decSetup(11);
// decSetup(12);
// decSetup(13);
attachInterrupt(dec0_PIN, dec_0_ISR, CHANGE);
attachInterrupt(dec1_PIN, dec_1_ISR, CHANGE);
attachInterrupt(dec2_PIN, dec_2_ISR, CHANGE);
attachInterrupt(dec3_PIN, dec_3_ISR, CHANGE);
attachInterrupt(dec4_PIN, dec_4_ISR, CHANGE);
attachInterrupt(dec5_PIN, dec_5_ISR, CHANGE);
attachInterrupt(dec6_PIN, dec_6_ISR, CHANGE);
attachInterrupt(dec7_PIN, dec_7_ISR, CHANGE);
// attachInterrupt(dec8_PIN, dec_8_ISR, CHANGE);
// attachInterrupt(dec9_PIN, dec_9_ISR, CHANGE);
// attachInterrupt(dec10_PIN, dec_10_ISR, CHANGE);
// attachInterrupt(dec11_PIN, dec_11_ISR, CHANGE);
// attachInterrupt(dec12_PIN, dec_12_ISR, CHANGE);
// attachInterrupt(dec13_PIN, dec_13_ISR, CHANGE);
}
void loop()
{
digitalToggle(LoopOut);
Timer::tick();
IR_Decoder::tick();
bool rx_flag;
decStat(0);
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);
// status(decBackward);
// Serial.println(micros() - loopTimer);
// loopTimer = micros();
// delayMicroseconds(120*5);
bool rx_flag = false;
rx_flag |= status(dec0);
rx_flag |= status(dec1);
rx_flag |= status(dec2);
rx_flag |= status(dec3);
rx_flag |= status(dec4);
rx_flag |= status(dec5);
rx_flag |= status(dec6);
rx_flag |= status(dec7);
// rx_flag |= status(dec8);
// rx_flag |= status(dec9);
// rx_flag |= status(dec10);
// rx_flag |= status(dec11);
// rx_flag |= status(dec12);
// rx_flag |= status(dec13);
if (Serial.available())
{
@ -289,13 +284,14 @@ void loop()
case 102:
targetAddr = 777;
break;
default:
sig = in;
break;
}
}
}
Timer statusSimpleDelay;
bool statusSimple(IR_Decoder &dec)
{
@ -326,7 +322,7 @@ bool status(IR_Decoder &dec)
if (dec.gotData.available())
{
detectSignal();
Serial.println(micros());
// Serial.println(micros());
String str;
if (/* dec.gotData.getDataPrt()[1] */ 1)
{

View File

@ -23,12 +23,14 @@ void IR_Decoder::enable()
{
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())
@ -95,7 +97,7 @@ void IR_Decoder::_tick()
}
gotRaw.set(&packInfo, id);
}
if (isWaitingAcceptSend && millis() - acceptSendTimer > 75)
if (isWaitingAcceptSend && millis() - acceptSendTimer > acceptDelay)
{
encoder->sendAccept(addrAcceptSendTo, acceptCustomByte);
isWaitingAcceptSend = false;

View File

@ -14,7 +14,7 @@ private:
bool isWaitingAcceptSend;
uint16_t addrAcceptSendTo;
uint16_t acceptDelay = 75;
uint16_t acceptDelay = IR_ResponseDelay;
uint8_t acceptCustomByte;
public:

View File

@ -23,6 +23,7 @@
#define riseTimeMin (riseTime - riseTolerance)
#define aroundRise(t) (riseTimeMin < t && t < riseTimeMax)
#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_DecoderRaw : virtual public IR_FOX

View File

@ -5,11 +5,8 @@
#define ISR_Out 10
#define TestOut 13
std::list<IR_Encoder *> &IR_Encoder::get_enc_list() // определение функции
{
static std::list<IR_Encoder *> dec_list; // статическая локальная переменная
return dec_list; // возвращается ссылка на переменную
}
IR_Encoder *IR_Encoder::head = nullptr;
IR_Encoder *IR_Encoder::last = nullptr;
IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair, bool autoHandle)
{
@ -29,31 +26,92 @@ IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair, bool
{
decPair->encoder = this;
}
pinMode(pin, OUTPUT);
if (autoHandle)
{
get_enc_list().push_back(this);
if (IR_Encoder::head == nullptr)
{
IR_Encoder::head = this;
}
if (last != nullptr)
{
last->next = this;
}
last = this;
}
};
HardwareTimer* IR_Encoder::IR_Timer = nullptr;
inline HardwareTimer* IR_Encoder::get_IR_Timer(){return IR_Encoder::IR_Timer;}
void IR_Encoder::begin(HardwareTimer* timer, uint8_t channel, IRQn_Type IRQn, uint8_t priority, void(*isrCallback)()){
IR_Timer = timer;
if(IR_Timer == nullptr) return;
IR_Timer->setOverflow(carrierFrec * 2, HERTZ_FORMAT);
IR_Timer->attachInterrupt(channel, (isrCallback == nullptr ? IR_Encoder::isr : isrCallback));
NVIC_SetPriority(IRQn, priority);
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())
bool exist = false;
IR_Encoder *current = IR_Encoder::head;
while (current != nullptr)
{
enc_list.push_back(this);
exist = (current == this);
if (exist) break;
current = current->next;
}
if (!exist)
{
if (IR_Encoder::head == nullptr)
{
IR_Encoder::head = this;
last = this;
}
else
{
last->next = this;
last = this;
}
this->next = nullptr; // Указываем, что следующий за этим элементом — nullptr
}
pinMode(pin, OUTPUT);
}
void IR_Encoder::disable()
{
auto &enc_list = get_enc_list();
auto it = std::find(enc_list.begin(), enc_list.end(), this);
if (it != enc_list.end())
IR_Encoder *current = IR_Encoder::head;
IR_Encoder *prev = nullptr;
while (current != nullptr)
{
enc_list.erase(it);
if (current == this) break;
prev = current;
current = current->next;
}
if (current != nullptr) // Элемент найден в списке
{
if (prev != nullptr)
{
prev->next = current->next; // Убираем текущий элемент из списка
}
else
{
IR_Encoder::head = current->next; // Удаляемый элемент был первым
}
if (current == last)
{
last = prev; // Если удаляется последний элемент, обновляем last
}
}
pinMode(pin, INPUT);
}
void IR_Encoder::setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count)
@ -66,10 +124,7 @@ void IR_Encoder::setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count)
blindDecoders = decoders;
}
IR_Encoder::~IR_Encoder()
{
get_enc_list().remove(this);
};
IR_Encoder::~IR_Encoder(){};
void IR_Encoder::sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept)
{
@ -229,6 +284,10 @@ void IR_Encoder::setDecoder_isSending()
for (uint8_t i = 0; i < decodersCount; i++)
{
blindDecoders[i]->isPairSending ^= id;
// Serial.print("setDecoder_isSending() id = ");
// Serial.print(id);
// Serial.print(" isPairSending = ");
// Serial.println(blindDecoders[i]->isPairSending);
}
}
}
@ -240,7 +299,7 @@ void IR_Encoder::rawSend(uint8_t *ptr, uint8_t len)
// TODO: Обработка повторной отправки
return;
}
// Serial.println("START");
setDecoder_isSending();
// noInterrupts();
@ -265,10 +324,11 @@ void IR_Encoder::rawSend(uint8_t *ptr, uint8_t len)
void IR_Encoder::isr()
{
// Serial.println(get_enc_list().size());
for (const auto &element : get_enc_list())
IR_Encoder *current = IR_Encoder::head;
while (current != nullptr)
{
element->_isr();
current->_isr();
current = current->next;
}
}
@ -296,7 +356,9 @@ void IR_Encoder::_isr()
// сброс счетчиков
// ...
isSending = false;
// Serial.println("STOP");
setDecoder_isSending();
// Serial.println();
return;
break;

View File

@ -7,8 +7,11 @@ class IR_DecoderRaw;
class IR_Encoder : public IR_FOX
{
friend IR_DecoderRaw;
static IR_Encoder *head;
static IR_Encoder *last;
IR_Encoder *next;
public:
static HardwareTimer* IR_Timer;
private:
// uint16_t id; /// @brief Адрес передатчика
public:
@ -18,6 +21,8 @@ public:
/// @param decPair Приёмник, для которого отключается приём в момент передачи передатчиком
IR_Encoder(uint8_t pin, uint16_t addr = 0, IR_DecoderRaw *decPair = nullptr, bool autoHandle = true);
static void isr();
static void begin(HardwareTimer* timer, uint8_t channel, IRQn_Type IRQn, uint8_t priority, void(*isrCallback)() = nullptr);
static HardwareTimer* get_IR_Timer();
void enable();
void disable();
@ -41,10 +46,9 @@ public:
~IR_Encoder();
volatile bool ir_out_virtual;
private:
static std::list<IR_Encoder*>& get_enc_list();
void _sendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint8_t len);
void _isr();
private:
void _sendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint8_t len);
void setDecoder_isSending();
void sendByte(uint8_t byte, bool *prev, bool LOW_FIRST);

View File

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

View File

@ -15,7 +15,7 @@
IR_MSG_ACCEPT с адреса 0 воспринимается всеми устройствами
*/
//**** Контрольные точки ******
#define IR_MAX_ADDR_CPU 64999
#define IR_MAX_ADDR_CPU 63999
#define IR_MIN_ADDR_CPU 32000
// //***** Группы машинок ********
@ -28,11 +28,11 @@
//********* Машинки ***********
#define IR_MAX_CAR 31999
#define IR_MIN_CAR 100
#define IR_MIN_CAR 1
//***** Пульты управления *****
#define IR_MAX_CONTROLLER 99
#define IR_MIN_CONTROLLER 0
#define IR_MAX_CONTROLLER 64999
#define IR_MIN_CONTROLLER 64000
/*
/```````````````````````````````````````````````` data pack `````````````````````````````````````````````\                                  
@ -57,9 +57,9 @@ msg type:
#define IR_MSG_BACK 0U // | 000...... | = Задний сигнал машинки
#define IR_MSG_ACCEPT 1U // | 001..... | = подтверждение
#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_ 5U // | 101..... | = ??
// #define IR_MSG_ 5U // | 101..... | = ??
#define IR_MSG_DATA_NOACCEPT 6U // | 110..... | = данные, не требующие подтверждения
#define IR_MSG_DATA_ACCEPT 7U // | 111..... | = данные требующие подтверждения
; /*   // ----------