mirror of
https://github.com/Show-maket/IR-protocol.git
synced 2025-06-28 05:09:40 +00:00
Compare commits
10 Commits
2db1ef7805
...
STM32
Author | SHA1 | Date | |
---|---|---|---|
bc9563fbb5 | |||
021e1e290d | |||
89d14919c9 | |||
403b8e6850 | |||
d0c3138c52 | |||
2d839d3ff8 | |||
6ba8fdffe4 | |||
aa0b478229 | |||
277985f79a | |||
444b84c313 |
4
.vscode/arduino.json
vendored
4
.vscode/arduino.json
vendored
@ -1,7 +1,5 @@
|
|||||||
{
|
{
|
||||||
"board": "STMicroelectronics:stm32:GenF4",
|
"board": "STMicroelectronics:stm32:GenF4",
|
||||||
"port": "COM17",
|
"port": "COM17",
|
||||||
"prebuild": "if exist bin rd /s /q bin",
|
"prebuild": "if exist bin rd /s /q bin"
|
||||||
"configuration": "clock=25MHz,pnum=MAKET_F401RETX,upload_method=swdMethod,xserial=generic,usb=CDCgen,xusb=FS,opt=osstd,dbg=none,rtlib=nano",
|
|
||||||
"sketch": "IR-protocol.ino"
|
|
||||||
}
|
}
|
@ -61,6 +61,7 @@ void IR_Decoder::tick()
|
|||||||
void IR_Decoder::_tick()
|
void IR_Decoder::_tick()
|
||||||
{
|
{
|
||||||
IR_DecoderRaw::tick();
|
IR_DecoderRaw::tick();
|
||||||
|
|
||||||
if (availableRaw())
|
if (availableRaw())
|
||||||
{
|
{
|
||||||
#ifdef IRDEBUG_INFO
|
#ifdef IRDEBUG_INFO
|
||||||
@ -102,4 +103,8 @@ void IR_Decoder::_tick()
|
|||||||
encoder->sendAccept(addrAcceptSendTo, acceptCustomByte);
|
encoder->sendAccept(addrAcceptSendTo, acceptCustomByte);
|
||||||
isWaitingAcceptSend = false;
|
isWaitingAcceptSend = false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool IR_Decoder::isReceive(uint8_t type) {
|
||||||
|
return (msgTypeReceive & 0b11111000) && ((msgTypeReceive & IR_MASK_MSG_TYPE) == type);
|
||||||
|
}
|
||||||
|
@ -31,6 +31,8 @@ public:
|
|||||||
|
|
||||||
void enable();
|
void enable();
|
||||||
void disable();
|
void disable();
|
||||||
|
|
||||||
|
bool isReceive(uint8_t type);
|
||||||
|
|
||||||
~IR_Decoder();
|
~IR_Decoder();
|
||||||
|
|
||||||
|
@ -112,16 +112,37 @@ void IR_DecoderRaw::firstRX()
|
|||||||
|
|
||||||
void IR_DecoderRaw::listenStart()
|
void IR_DecoderRaw::listenStart()
|
||||||
{
|
{
|
||||||
if (isRecive && ((micros() - prevRise) > IR_timeout * 2))
|
if (isReciveRaw && ((micros() - prevRise) > IR_timeout * 2))
|
||||||
{
|
{
|
||||||
// Serial.print("\nlis>");
|
// Serial.print("\nlis>");
|
||||||
isRecive = false;
|
isReciveRaw = false;
|
||||||
firstRX();
|
firstRX();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// ---- быстрая проверка конца пакета ---------------------------------
|
||||||
|
inline void IR_DecoderRaw::checkTimeout()
|
||||||
|
{
|
||||||
|
if (!isRecive) return; // уже не принимаем – нечего проверять
|
||||||
|
|
||||||
|
if (micros() - lastEdgeTime > IR_timeout * 2U)
|
||||||
|
{
|
||||||
|
isRecive = false; // приём завершён
|
||||||
|
msgTypeReceive = 0;
|
||||||
|
// firstRX(); // подготовка к новому пакету
|
||||||
|
lastEdgeTime = micros(); // защита от повторного срабатывания
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// ====================================================================
|
||||||
|
|
||||||
void IR_DecoderRaw::tick()
|
void IR_DecoderRaw::tick()
|
||||||
{
|
{
|
||||||
|
// FrontStorage *currentFrontPtr;
|
||||||
|
// noInterrupts();
|
||||||
|
// currentFrontPtr = subBuffer.pop();
|
||||||
|
// interrupts();
|
||||||
|
|
||||||
FrontStorage currentFront;
|
FrontStorage currentFront;
|
||||||
noInterrupts();
|
noInterrupts();
|
||||||
listenStart();
|
listenStart();
|
||||||
@ -130,12 +151,24 @@ void IR_DecoderRaw::tick()
|
|||||||
if (currentFrontPtr == nullptr)
|
if (currentFrontPtr == nullptr)
|
||||||
{
|
{
|
||||||
isSubBufferOverflow = false;
|
isSubBufferOverflow = false;
|
||||||
|
checkTimeout(); // <--- новое место проверки
|
||||||
interrupts();
|
interrupts();
|
||||||
return;
|
return;
|
||||||
} // Если данных нет - ничего не делаем
|
} // Если данных нет - ничего не делаем
|
||||||
currentFront = *currentFrontPtr;
|
currentFront = *currentFrontPtr;
|
||||||
interrupts();
|
interrupts();
|
||||||
|
|
||||||
|
// ---------- буфер пуст: фронтов нет, проверяем тайм-аут ----------
|
||||||
|
// if (currentFrontPtr == nullptr)
|
||||||
|
// {
|
||||||
|
// isSubBufferOverflow = false;
|
||||||
|
// return;
|
||||||
|
// }
|
||||||
|
|
||||||
|
// // ---------- есть фронт: продолжаем обработку ----------
|
||||||
|
// FrontStorage currentFront = *currentFrontPtr;
|
||||||
|
lastEdgeTime = currentFront.time; // запоминаем любой фронт
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
||||||
|
|
||||||
if (currentFront.dir)
|
if (currentFront.dir)
|
||||||
@ -197,7 +230,7 @@ void IR_DecoderRaw::tick()
|
|||||||
digitalWrite(errOut, currentFront.dir);
|
digitalWrite(errOut, currentFront.dir);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (currentFront.time > prevRise && currentFront.time - prevRise > IR_timeout * 2 && !isRecive)
|
if (currentFront.time > prevRise && currentFront.time - prevRise > IR_timeout * 2 && !isReciveRaw)
|
||||||
{ // первый
|
{ // первый
|
||||||
#ifdef IRDEBUG
|
#ifdef IRDEBUG
|
||||||
errPulse(up, 50);
|
errPulse(up, 50);
|
||||||
@ -209,6 +242,7 @@ void IR_DecoderRaw::tick()
|
|||||||
isPreamb = true;
|
isPreamb = true;
|
||||||
|
|
||||||
isRecive = true;
|
isRecive = true;
|
||||||
|
isReciveRaw = true;
|
||||||
isWrongPack = false;
|
isWrongPack = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -441,6 +475,8 @@ void IR_DecoderRaw::writeToBuffer(bool bit)
|
|||||||
if (isBufferOverflow || isPreamb || isWrongPack)
|
if (isBufferOverflow || isPreamb || isWrongPack)
|
||||||
{
|
{
|
||||||
isRecive = false;
|
isRecive = false;
|
||||||
|
isReciveRaw = false;
|
||||||
|
msgTypeReceive = 0;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -564,6 +600,8 @@ void IR_DecoderRaw::writeToBuffer(bool bit)
|
|||||||
packInfo.rTime = riseSyncTime;
|
packInfo.rTime = riseSyncTime;
|
||||||
|
|
||||||
isRecive = false;
|
isRecive = false;
|
||||||
|
isReciveRaw = false;
|
||||||
|
msgTypeReceive = 0;
|
||||||
isAvailable = crcCheck(packSize - crcBytes, crcValue);
|
isAvailable = crcCheck(packSize - crcBytes, crcValue);
|
||||||
|
|
||||||
#ifdef BRUTEFORCE_CHECK
|
#ifdef BRUTEFORCE_CHECK
|
||||||
@ -594,6 +632,12 @@ void IR_DecoderRaw::writeToBuffer(bool bit)
|
|||||||
OUT_BRUTEFORCE:;
|
OUT_BRUTEFORCE:;
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (packSize && (i_dataBuffer == 8)) {
|
||||||
|
msgTypeReceive = (dataBuffer[0]>>5) | 0b11111000;
|
||||||
|
// SerialUSB.println(msgTypeReceive & IR_MASK_MSG_TYPE);
|
||||||
|
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
||||||
|
@ -31,9 +31,10 @@ class IR_DecoderRaw : virtual public IR_FOX
|
|||||||
friend IR_Encoder;
|
friend IR_Encoder;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
PackInfo packInfo;
|
PackInfo packInfo;
|
||||||
IR_Encoder *encoder; // Указатель на парный передатчик
|
uint8_t msgTypeReceive = 0;
|
||||||
bool availableRaw();
|
IR_Encoder *encoder; // Указатель на парный передатчик
|
||||||
|
bool availableRaw();
|
||||||
|
|
||||||
public:
|
public:
|
||||||
//////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////
|
||||||
@ -48,7 +49,7 @@ public:
|
|||||||
|
|
||||||
inline bool isOverflow() { return isBufferOverflow; }; // Буффер переполнился
|
inline bool isOverflow() { return isBufferOverflow; }; // Буффер переполнился
|
||||||
bool isSubOverflow();
|
bool isSubOverflow();
|
||||||
inline bool isReciving() { return isBufferOverflow; }; // Возвращает true, если происходит приём пакета
|
volatile inline bool isReciving() { return isRecive; }; // Возвращает true, если происходит приём пакета
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////
|
||||||
private:
|
private:
|
||||||
@ -65,6 +66,8 @@ private:
|
|||||||
|
|
||||||
uint16_t riseSyncTime = bitTime; // Подстраиваемое время бита в мкс
|
uint16_t riseSyncTime = bitTime; // Подстраиваемое время бита в мкс
|
||||||
|
|
||||||
|
volatile uint32_t lastEdgeTime = 0; // время последнего фронта
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////
|
||||||
volatile uint32_t currentSubBufferIndex; // Счетчик текущей позиции во вспомогательном буфере фронтов/спадов
|
volatile uint32_t currentSubBufferIndex; // Счетчик текущей позиции во вспомогательном буфере фронтов/спадов
|
||||||
|
|
||||||
@ -100,7 +103,9 @@ private:
|
|||||||
int16_t bufBitPos = 0; // Позиция для записи бита в буффер
|
int16_t bufBitPos = 0; // Позиция для записи бита в буффер
|
||||||
|
|
||||||
private:
|
private:
|
||||||
void listenStart(); // @brief Слушатель для работы isReciving()
|
bool isReciveRaw;
|
||||||
|
void listenStart();
|
||||||
|
void checkTimeout(); //
|
||||||
|
|
||||||
/// @brief Проверка CRC. Проверяет len байт со значением crc, пришедшим в пакете
|
/// @brief Проверка CRC. Проверяет len байт со значением crc, пришедшим в пакете
|
||||||
/// @param len Длина в байтах проверяемых данных
|
/// @param len Длина в байтах проверяемых данных
|
||||||
|
108
IR_Encoder.cpp
108
IR_Encoder.cpp
@ -5,11 +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::head = nullptr;
|
||||||
{
|
IR_Encoder *IR_Encoder::last = nullptr;
|
||||||
static std::list<IR_Encoder *> dec_list; // статическая локальная переменная
|
|
||||||
return dec_list; // возвращается ссылка на переменную
|
|
||||||
}
|
|
||||||
|
|
||||||
IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair, bool autoHandle)
|
IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair, bool autoHandle)
|
||||||
{
|
{
|
||||||
@ -32,45 +29,88 @@ IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair, bool
|
|||||||
|
|
||||||
if (autoHandle)
|
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;
|
||||||
|
|
||||||
HardwareTimer IR_Encoder::IR_Timer;
|
inline HardwareTimer* IR_Encoder::get_IR_Timer(){return 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, uint8_t priority, void(*isrCallback)()){
|
||||||
// void Encoder_ISR(){
|
IR_Timer = timer;
|
||||||
// IR_Encoder::isr();
|
if(IR_Timer == nullptr) return;
|
||||||
// }
|
IR_Timer->setOverflow(carrierFrec * 2, HERTZ_FORMAT);
|
||||||
void IR_Encoder::begin(HardwareTimer timer, uint8_t channel, IRQn_Type IRQn){
|
IR_Timer->attachInterrupt(channel, (isrCallback == nullptr ? IR_Encoder::isr : isrCallback));
|
||||||
//TODO: check std::bind isr func
|
NVIC_SetPriority(IRQn, priority);
|
||||||
// IR_Timer = timer;
|
IR_Timer->resume();
|
||||||
// IR_Timer.setOverflow(carrierFrec * 2, HERTZ_FORMAT);
|
|
||||||
// IR_Timer.attachInterrupt(channel, Encoder_ISR);
|
|
||||||
// NVIC_SetPriority(IRQn, 0);
|
|
||||||
// IR_Timer.resume();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void IR_Encoder::enable()
|
void IR_Encoder::enable()
|
||||||
{
|
{
|
||||||
auto &enc_list = get_enc_list();
|
bool exist = false;
|
||||||
if (std::find(enc_list.begin(), enc_list.end(), this) == enc_list.end())
|
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);
|
pinMode(pin, OUTPUT);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void IR_Encoder::disable()
|
void IR_Encoder::disable()
|
||||||
{
|
{
|
||||||
auto &enc_list = get_enc_list();
|
IR_Encoder *current = IR_Encoder::head;
|
||||||
auto it = std::find(enc_list.begin(), enc_list.end(), this);
|
IR_Encoder *prev = nullptr;
|
||||||
if (it != enc_list.end())
|
|
||||||
|
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);
|
pinMode(pin, INPUT);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -84,10 +124,7 @@ void IR_Encoder::setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count)
|
|||||||
blindDecoders = decoders;
|
blindDecoders = decoders;
|
||||||
}
|
}
|
||||||
|
|
||||||
IR_Encoder::~IR_Encoder()
|
IR_Encoder::~IR_Encoder(){};
|
||||||
{
|
|
||||||
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)
|
||||||
{
|
{
|
||||||
@ -287,10 +324,11 @@ void IR_Encoder::rawSend(uint8_t *ptr, uint8_t len)
|
|||||||
|
|
||||||
void IR_Encoder::isr()
|
void IR_Encoder::isr()
|
||||||
{
|
{
|
||||||
// Serial.println(get_enc_list().size());
|
IR_Encoder *current = IR_Encoder::head;
|
||||||
for (const auto &element : get_enc_list())
|
while (current != nullptr)
|
||||||
{
|
{
|
||||||
element->_isr();
|
current->_isr();
|
||||||
|
current = current->next;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -318,9 +356,9 @@ void IR_Encoder::_isr()
|
|||||||
// сброс счетчиков
|
// сброс счетчиков
|
||||||
// ...
|
// ...
|
||||||
isSending = false;
|
isSending = false;
|
||||||
Serial.println("STOP");
|
// Serial.println("STOP");
|
||||||
setDecoder_isSending();
|
setDecoder_isSending();
|
||||||
Serial.println();
|
// Serial.println();
|
||||||
return;
|
return;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
13
IR_Encoder.h
13
IR_Encoder.h
@ -7,9 +7,11 @@ class IR_DecoderRaw;
|
|||||||
class IR_Encoder : public IR_FOX
|
class IR_Encoder : public IR_FOX
|
||||||
{
|
{
|
||||||
friend IR_DecoderRaw;
|
friend IR_DecoderRaw;
|
||||||
|
static IR_Encoder *head;
|
||||||
|
static IR_Encoder *last;
|
||||||
|
IR_Encoder *next;
|
||||||
public:
|
public:
|
||||||
static HardwareTimer IR_Timer;
|
static HardwareTimer* IR_Timer;
|
||||||
private:
|
private:
|
||||||
// uint16_t id; /// @brief Адрес передатчика
|
// uint16_t id; /// @brief Адрес передатчика
|
||||||
public:
|
public:
|
||||||
@ -19,7 +21,7 @@ public:
|
|||||||
/// @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 = 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 void begin(HardwareTimer* timer, uint8_t channel, IRQn_Type IRQn, uint8_t priority, void(*isrCallback)() = nullptr);
|
||||||
static HardwareTimer* get_IR_Timer();
|
static HardwareTimer* get_IR_Timer();
|
||||||
|
|
||||||
void enable();
|
void enable();
|
||||||
@ -44,10 +46,9 @@ public:
|
|||||||
~IR_Encoder();
|
~IR_Encoder();
|
||||||
volatile bool ir_out_virtual;
|
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();
|
void _isr();
|
||||||
|
private:
|
||||||
|
void _sendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint8_t len);
|
||||||
|
|
||||||
void setDecoder_isSending();
|
void setDecoder_isSending();
|
||||||
void sendByte(uint8_t byte, bool *prev, bool LOW_FIRST);
|
void sendByte(uint8_t byte, bool *prev, bool LOW_FIRST);
|
||||||
|
10
IR_config.h
10
IR_config.h
@ -15,7 +15,7 @@
|
|||||||
IR_MSG_ACCEPT с адреса 0 воспринимается всеми устройствами
|
IR_MSG_ACCEPT с адреса 0 воспринимается всеми устройствами
|
||||||
*/
|
*/
|
||||||
//**** Контрольные точки ******
|
//**** Контрольные точки ******
|
||||||
#define IR_MAX_ADDR_CPU 64999
|
#define IR_MAX_ADDR_CPU 63999
|
||||||
#define IR_MIN_ADDR_CPU 32000
|
#define IR_MIN_ADDR_CPU 32000
|
||||||
|
|
||||||
// //***** Группы машинок ********
|
// //***** Группы машинок ********
|
||||||
@ -28,11 +28,11 @@
|
|||||||
|
|
||||||
//********* Машинки ***********
|
//********* Машинки ***********
|
||||||
#define IR_MAX_CAR 31999
|
#define IR_MAX_CAR 31999
|
||||||
#define IR_MIN_CAR 100
|
#define IR_MIN_CAR 1
|
||||||
|
|
||||||
//***** Пульты управления *****
|
//***** Пульты управления *****
|
||||||
#define IR_MAX_CONTROLLER 99
|
#define IR_MAX_CONTROLLER 64999
|
||||||
#define IR_MIN_CONTROLLER 0
|
#define IR_MIN_CONTROLLER 64000
|
||||||
/*
|
/*
|
||||||
|
|
||||||
/```````````````````````````````````````````````` data pack `````````````````````````````````````````````\
|
/```````````````````````````````````````````````` data pack `````````````````````````````````````````````\
|
||||||
@ -122,7 +122,7 @@ typedef uint16_t crc_t;
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef subBufferSize
|
#ifndef subBufferSize
|
||||||
#define subBufferSize 50 // Буфер для складирования фронтов, пока их не обработают (передатчик)
|
#define subBufferSize 250 // Буфер для складирования фронтов, пока их не обработают (передатчик)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define preambPulse 3
|
#define preambPulse 3
|
||||||
|
Reference in New Issue
Block a user