mirror of
https://github.com/Show-maket/IR-protocol.git
synced 2025-05-03 14:50:20 +00:00
formatting
This commit is contained in:
parent
3e3601e009
commit
8d0f45ddf1
@ -22,7 +22,7 @@
|
||||
IR_Decoder decForward(2, 555);
|
||||
IR_Decoder decBackward(3, 777);
|
||||
|
||||
IR_Encoder encForward(42, &decBackward);
|
||||
IR_Encoder encForward(42/* , &decBackward */);
|
||||
// IR_Encoder encBackward(321, encBackward_PIN);
|
||||
// IR_Encoder encTree(325, A2);
|
||||
|
||||
@ -32,9 +32,9 @@ void decForwardISR() {
|
||||
decForward.isr();
|
||||
}
|
||||
|
||||
void decBackwardISR() {
|
||||
decBackward.isr();
|
||||
}
|
||||
// void decBackwardISR() {
|
||||
// decBackward.isr();
|
||||
// }
|
||||
|
||||
static uint8_t* portOut;
|
||||
ISR(TIMER2_COMPA_vect) {
|
||||
@ -57,7 +57,7 @@ uint8_t data3 [] = { 42 , 127, 137 };
|
||||
uint8_t data4 [] = { 42 , 127, 137, 255 };
|
||||
|
||||
uint32_t loopTimer;
|
||||
uint8_t sig = 255;
|
||||
uint8_t sig = 0;
|
||||
|
||||
uint16_t targetAddr = IR_Broadcast;
|
||||
Timer t1(500, millis, []() {
|
||||
@ -177,12 +177,12 @@ void setup() {
|
||||
|
||||
|
||||
|
||||
IR_DecoderRaw* blindFromForward [] { &decForward, &decBackward };
|
||||
encForward.setBlindDecoders(blindFromForward, sizeof(blindFromForward) / sizeof(IR_DecoderRaw*));
|
||||
// IR_DecoderRaw* blindFromForward [] { &decForward, &decBackward };
|
||||
// encForward.setBlindDecoders(blindFromForward, sizeof(blindFromForward) / sizeof(IR_DecoderRaw*));
|
||||
|
||||
|
||||
attachInterrupt(0, decForwardISR, CHANGE); // D2
|
||||
attachInterrupt(1, decBackwardISR, CHANGE); // D3
|
||||
// attachInterrupt(1, decBackwardISR, CHANGE); // D3
|
||||
}
|
||||
|
||||
void loop() {
|
||||
@ -193,7 +193,7 @@ void loop() {
|
||||
decBackward.tick();
|
||||
|
||||
status(decForward);
|
||||
status(decBackward);
|
||||
// status(decBackward);
|
||||
|
||||
|
||||
// Serial.println(micros() - loopTimer);
|
||||
|
66
IR_Decoder.h
66
IR_Decoder.h
@ -3,7 +3,8 @@
|
||||
#include "PacketTypes.h"
|
||||
#include "IR_Encoder.h"
|
||||
|
||||
class IR_Decoder : public IR_DecoderRaw {
|
||||
class IR_Decoder : public IR_DecoderRaw
|
||||
{
|
||||
uint32_t acceptSendTimer;
|
||||
bool isWaitingAcceptSend;
|
||||
uint16_t addrAcceptSendTo;
|
||||
@ -12,59 +13,66 @@ class IR_Decoder : public IR_DecoderRaw {
|
||||
uint8_t acceptCustomByte;
|
||||
|
||||
public:
|
||||
|
||||
PacketTypes::Data gotData;
|
||||
PacketTypes::DataBack gotBackData;
|
||||
PacketTypes::Accept gotAccept;
|
||||
PacketTypes::Request gotRequest;
|
||||
PacketTypes::BasePack gotRaw;
|
||||
|
||||
IR_Decoder(const uint8_t isrPin, uint16_t addr, IR_Encoder* encPair = nullptr) : IR_DecoderRaw(isrPin, addr, encPair) {}
|
||||
IR_Decoder(const uint8_t isrPin, uint16_t addr, IR_Encoder *encPair = nullptr) : IR_DecoderRaw(isrPin, addr, encPair) {}
|
||||
|
||||
void tick() {
|
||||
void tick()
|
||||
{
|
||||
IR_DecoderRaw::tick();
|
||||
if (availableRaw()) {
|
||||
#ifdef IRDEBUG_INFO
|
||||
if (availableRaw())
|
||||
{
|
||||
#ifdef IRDEBUG_INFO
|
||||
Serial.println("PARSING RAW DATA");
|
||||
#endif
|
||||
#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;
|
||||
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;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
if (gotData.isAvailable && (gotData.getMsgType() == IR_MSG_DATA_ACCEPT)) {
|
||||
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;
|
||||
if (addrAcceptSendTo && addrAcceptSendTo < IR_Broadcast)
|
||||
isWaitingAcceptSend = true;
|
||||
}
|
||||
gotRaw.set(&packInfo, id);
|
||||
}
|
||||
if (isWaitingAcceptSend && millis() - acceptSendTimer > 75) {
|
||||
if (isWaitingAcceptSend && millis() - acceptSendTimer > 75)
|
||||
{
|
||||
encoder->sendAccept(addrAcceptSendTo, acceptCustomByte);
|
||||
isWaitingAcceptSend = false;
|
||||
}
|
||||
}
|
||||
|
||||
void setAcceptDelay(uint16_t acceptDelay) {
|
||||
void setAcceptDelay(uint16_t acceptDelay)
|
||||
{
|
||||
this->acceptDelay = acceptDelay;
|
||||
}
|
||||
uint16_t getAcceptDelay() {
|
||||
uint16_t getAcceptDelay()
|
||||
{
|
||||
return this->acceptDelay;
|
||||
}
|
||||
};
|
||||
|
@ -1,43 +1,53 @@
|
||||
#include "IR_DecoderRaw.h"
|
||||
#include "IR_Encoder.h"
|
||||
|
||||
|
||||
IR_DecoderRaw::IR_DecoderRaw(const uint8_t isrPin, uint16_t addr, IR_Encoder* encPair = nullptr) : isrPin(isrPin), encoder(encPair) {
|
||||
IR_DecoderRaw::IR_DecoderRaw(const uint8_t isrPin, uint16_t addr, IR_Encoder *encPair = nullptr) : isrPin(isrPin), encoder(encPair)
|
||||
{
|
||||
id = addr;
|
||||
prevRise = prevFall = prevPrevFall = prevPrevRise = 0;
|
||||
if (encPair != nullptr) {
|
||||
if (encPair != nullptr)
|
||||
{
|
||||
encPair->decPair = this;
|
||||
}
|
||||
}
|
||||
|
||||
//////////////////////////////////// isr ///////////////////////////////////////////
|
||||
|
||||
void IR_DecoderRaw::isr() {
|
||||
if (isPairSending) return;
|
||||
void IR_DecoderRaw::isr()
|
||||
{
|
||||
if (isPairSending)
|
||||
return;
|
||||
|
||||
subBuffer[currentSubBufferIndex].next = nullptr;
|
||||
subBuffer[currentSubBufferIndex].dir = (PIND >> isrPin) & 1;
|
||||
subBuffer[currentSubBufferIndex].time = micros();
|
||||
|
||||
if (firstUnHandledFront == nullptr) {
|
||||
if (firstUnHandledFront == nullptr)
|
||||
{
|
||||
firstUnHandledFront = &subBuffer[currentSubBufferIndex]; // Если нет необработанных данных - добавляем их
|
||||
isSubBufferOverflow = false;
|
||||
} else {
|
||||
if (firstUnHandledFront == &subBuffer[currentSubBufferIndex]) { // Если контроллер не успел обработать новый сигнал, принудительно пропускаем его
|
||||
}
|
||||
else
|
||||
{
|
||||
if (firstUnHandledFront == &subBuffer[currentSubBufferIndex])
|
||||
{ // Если контроллер не успел обработать новый сигнал, принудительно пропускаем его
|
||||
firstUnHandledFront = firstUnHandledFront->next;
|
||||
isSubBufferOverflow = true;
|
||||
|
||||
#ifdef IRDEBUG_INFO
|
||||
#ifdef IRDEBUG_INFO
|
||||
// Serial.println();
|
||||
Serial.println(" ISR BUFFER OVERFLOW ");
|
||||
// Serial.println();
|
||||
#endif
|
||||
// Serial.println();
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
if (lastFront == nullptr) {
|
||||
if (lastFront == nullptr)
|
||||
{
|
||||
lastFront = &subBuffer[currentSubBufferIndex];
|
||||
} else {
|
||||
}
|
||||
else
|
||||
{
|
||||
lastFront->next = &subBuffer[currentSubBufferIndex];
|
||||
lastFront = &subBuffer[currentSubBufferIndex];
|
||||
}
|
||||
@ -47,11 +57,12 @@ void IR_DecoderRaw::isr() {
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
void IR_DecoderRaw::firstRX() {
|
||||
void IR_DecoderRaw::firstRX()
|
||||
{
|
||||
|
||||
#ifdef IRDEBUG_INFO
|
||||
#ifdef IRDEBUG_INFO
|
||||
Serial.print("\nRX>");
|
||||
#endif
|
||||
#endif
|
||||
|
||||
errors.reset();
|
||||
packSize = 0;
|
||||
@ -66,69 +77,97 @@ void IR_DecoderRaw::firstRX() {
|
||||
isWrongPack = false;
|
||||
|
||||
isPreamb = true;
|
||||
riseSyncTime = bitTime /* 1100 */;
|
||||
riseSyncTime = bitTime /* 1100 */;
|
||||
|
||||
memset(dataBuffer, 0x00, dataByteSizeMax);
|
||||
}
|
||||
|
||||
void IR_DecoderRaw::listenStart() {
|
||||
if (isRecive && ((micros() - prevRise) > IR_timeout * 2)) {
|
||||
void IR_DecoderRaw::listenStart()
|
||||
{
|
||||
if (isRecive && ((micros() - prevRise) > IR_timeout * 2))
|
||||
{
|
||||
// Serial.print("\nlis>");
|
||||
isRecive = false;
|
||||
firstRX();
|
||||
}
|
||||
}
|
||||
|
||||
void IR_DecoderRaw::tick() {
|
||||
void IR_DecoderRaw::tick()
|
||||
{
|
||||
FrontStorage currentFront;
|
||||
uint8_t oldSREG = SREG;
|
||||
cli();
|
||||
listenStart();
|
||||
if (firstUnHandledFront == nullptr) { isSubBufferOverflow = false; SREG = oldSREG; return; } //Если данных нет - ничего не делаем
|
||||
currentFront = *((FrontStorage*)firstUnHandledFront); //найти следующий необработанный фронт/спад
|
||||
if (firstUnHandledFront == nullptr)
|
||||
{
|
||||
isSubBufferOverflow = false;
|
||||
SREG = oldSREG;
|
||||
return;
|
||||
} // Если данных нет - ничего не делаем
|
||||
currentFront = *((FrontStorage *)firstUnHandledFront); // найти следующий необработанный фронт/спад
|
||||
SREG = oldSREG;
|
||||
if (currentFront.next == nullptr) { isRecive = false; return; }
|
||||
if (currentFront.next == nullptr)
|
||||
{
|
||||
isRecive = false;
|
||||
return;
|
||||
}
|
||||
////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
if (currentFront.time > prevRise && currentFront.time - prevRise > IR_timeout * 2 && !isRecive) { // первый
|
||||
if (currentFront.time > prevRise && currentFront.time - prevRise > IR_timeout * 2 && !isRecive)
|
||||
{ // первый
|
||||
preambFrontCounter = preambFronts - 1U;
|
||||
|
||||
|
||||
if (!currentFront.dir) {
|
||||
#ifdef IRDEBUG_INFO
|
||||
// Serial.print(" currentFront.time: "); Serial.print(currentFront.time);
|
||||
// Serial.print(" currentFront.dir: "); Serial.print(currentFront.dir ? "UP" : "DOWN");
|
||||
// Serial.print(" next: "); Serial.print(currentFront.next == nullptr);
|
||||
// Serial.print(" prevRise: "); Serial.print(prevRise);
|
||||
// Serial.print(" SUB: "); Serial.println(currentFront.time - prevRise);
|
||||
#endif
|
||||
if (!currentFront.dir)
|
||||
{
|
||||
#ifdef IRDEBUG_INFO
|
||||
// Serial.print(" currentFront.time: "); Serial.print(currentFront.time);
|
||||
// Serial.print(" currentFront.dir: "); Serial.print(currentFront.dir ? "UP" : "DOWN");
|
||||
// Serial.print(" next: "); Serial.print(currentFront.next == nullptr);
|
||||
// Serial.print(" prevRise: "); Serial.print(prevRise);
|
||||
// Serial.print(" SUB: "); Serial.println(currentFront.time - prevRise);
|
||||
#endif
|
||||
isRecive = true;
|
||||
isWrongPack = false;
|
||||
}
|
||||
}
|
||||
|
||||
if (preambFrontCounter) { // в преамбуле
|
||||
if (preambFrontCounter)
|
||||
{ // в преамбуле
|
||||
uint32_t risePeriod;
|
||||
risePeriod = currentFront.time - prevRise;
|
||||
if (currentFront.dir && risePeriod < IR_timeout) { // __/``` ↑ и мы в внутри пакета
|
||||
if (currentFront.dir && risePeriod < IR_timeout)
|
||||
{ // __/``` ↑ и мы в внутри пакета
|
||||
|
||||
if (risePeriod < riseTimeMin << 1) { // fix рваной единицы
|
||||
if (risePeriod < riseTimeMin << 1)
|
||||
{ // fix рваной единицы
|
||||
preambFrontCounter += 2;
|
||||
errors.other++;
|
||||
} else {
|
||||
if (freeFrec) { riseSyncTime = (riseSyncTime + risePeriod / 2) / 2; } // tuner
|
||||
}
|
||||
} else { /* riseSyncTime = bitTime; */ } // сброс тюнера
|
||||
else
|
||||
{
|
||||
if (freeFrec)
|
||||
{
|
||||
riseSyncTime = (riseSyncTime + risePeriod / 2) / 2;
|
||||
} // tuner
|
||||
}
|
||||
}
|
||||
else
|
||||
{ /* riseSyncTime = bitTime; */
|
||||
} // сброс тюнера
|
||||
preambFrontCounter--;
|
||||
// Serial.print("preambFrontCounter: "); Serial.println(preambFrontCounter);
|
||||
} else {
|
||||
if (isPreamb) {// первый фронт после
|
||||
}
|
||||
else
|
||||
{
|
||||
if (isPreamb)
|
||||
{ // первый фронт после
|
||||
// gotTune.set(riseSyncTime);
|
||||
}
|
||||
isPreamb = false;
|
||||
}
|
||||
// определить направление фронта
|
||||
if (currentFront.dir) { // Если __/``` ↑
|
||||
if (currentFront.dir)
|
||||
{ // Если __/``` ↑
|
||||
|
||||
uint16_t risePeriod = currentFront.time - prevRise;
|
||||
uint16_t highTime = currentFront.time - prevFall;
|
||||
@ -139,176 +178,214 @@ void IR_DecoderRaw::tick() {
|
||||
int8_t allCount = 0;
|
||||
bool invertErr = false;
|
||||
|
||||
if (!isPreamb) {
|
||||
if (risePeriod < IR_timeout && !isBufferOverflow && risePeriod > riseTimeMin && !isWrongPack) {
|
||||
if (!isPreamb)
|
||||
{
|
||||
if (risePeriod < IR_timeout && !isBufferOverflow && risePeriod > riseTimeMin && !isWrongPack)
|
||||
{
|
||||
// Мы в пределах таймаута и буффер не переполнен и fix дроблёных единиц
|
||||
|
||||
if (aroundRise(risePeriod)) { // тактирование есть, сигнал хороший - без ошибок(?)
|
||||
if (aroundRise(risePeriod))
|
||||
{ // тактирование есть, сигнал хороший - без ошибок(?)
|
||||
|
||||
if (highTime > riseTimeMin >> 1) { // 1
|
||||
#ifdef IRDEBUG
|
||||
if (highTime > riseTimeMin >> 1)
|
||||
{ // 1
|
||||
#ifdef IRDEBUG
|
||||
digitalWrite(wrHigh, 1);
|
||||
#endif
|
||||
#endif
|
||||
writeToBuffer(HIGH);
|
||||
} else { // 0
|
||||
#ifdef IRDEBUG
|
||||
}
|
||||
else
|
||||
{ // 0
|
||||
#ifdef IRDEBUG
|
||||
digitalWrite(wrLow, 1);
|
||||
#endif
|
||||
#endif
|
||||
writeToBuffer(LOW);
|
||||
}
|
||||
}
|
||||
else
|
||||
{ // пропущены такты! сигнал средний // ошибка пропуска
|
||||
highCount = ceil_div(highTime, riseTime); // предполагаемое колличество HIGH битов
|
||||
lowCount = ceil_div(lowTime, riseTime); // предполагаемое колличество LOW битов
|
||||
allCount = ceil_div(risePeriod, riseTime); // предполагаемое колличество всего битов
|
||||
|
||||
} else { // пропущены такты! сигнал средний // ошибка пропуска
|
||||
highCount = ceil_div(highTime, riseTime); // предполагаемое колличество HIGH битов
|
||||
lowCount = ceil_div(lowTime, riseTime); // предполагаемое колличество LOW битов
|
||||
allCount = ceil_div(risePeriod, riseTime); // предполагаемое колличество всего битов
|
||||
|
||||
if (highCount == 0 && highTime > riseTime / 3) { // fix короткой единицы (?)после пропуска нулей(?)
|
||||
if (highCount == 0 && highTime > riseTime / 3)
|
||||
{ // fix короткой единицы (?)после пропуска нулей(?)
|
||||
highCount++;
|
||||
errors.other++;
|
||||
#ifdef IRDEBUG
|
||||
#ifdef IRDEBUG
|
||||
errPulse(errOut, 2);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
if (lowCount + highCount > allCount) { // fix ошибочных сдвигов
|
||||
if (lowCount > highCount) { // Лишние нули
|
||||
if (lowCount + highCount > allCount)
|
||||
{ // fix ошибочных сдвигов
|
||||
if (lowCount > highCount)
|
||||
{ // Лишние нули
|
||||
lowCount = allCount - highCount;
|
||||
errors.lowSignal += lowCount;
|
||||
#ifdef IRDEBUG
|
||||
#ifdef IRDEBUG
|
||||
errPulse(errOut, 3);
|
||||
#endif
|
||||
} else if (lowCount < highCount) { // Лишние единицы
|
||||
#endif
|
||||
}
|
||||
else if (lowCount < highCount)
|
||||
{ // Лишние единицы
|
||||
highCount = allCount - lowCount;
|
||||
errors.highSignal += highCount;
|
||||
#ifdef IRDEBUG
|
||||
#ifdef IRDEBUG
|
||||
errPulse(errOut, 4);
|
||||
#endif
|
||||
#endif
|
||||
// неизвестный случай Инверсит след бит или соседние
|
||||
// Очень редко
|
||||
// TODO: Отловить проверить
|
||||
} else if (lowCount == highCount) {
|
||||
}
|
||||
else if (lowCount == highCount)
|
||||
{
|
||||
invertErr = true;
|
||||
// Serial.print("...");
|
||||
errors.other += allCount;
|
||||
}
|
||||
// errorCounter += allCount;
|
||||
|
||||
}
|
||||
|
||||
// errorCounter += allCount;
|
||||
// errors.other+=allCount;
|
||||
if (lowCount < highCount) {
|
||||
if (lowCount < highCount)
|
||||
{
|
||||
errors.highSignal += highCount;
|
||||
} else {
|
||||
}
|
||||
else
|
||||
{
|
||||
errors.lowSignal += lowCount;
|
||||
}
|
||||
|
||||
#ifdef IRDEBUG
|
||||
#ifdef IRDEBUG
|
||||
errPulse(errOut, 1);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
for (int8_t i = 0; i < lowCount && 8 - i; i++) { // отправка LOW битов, если есть
|
||||
if (i == lowCount - 1 && invertErr) {
|
||||
for (int8_t i = 0; i < lowCount && 8 - i; i++)
|
||||
{ // отправка LOW битов, если есть
|
||||
if (i == lowCount - 1 && invertErr)
|
||||
{
|
||||
invertErr = false;
|
||||
writeToBuffer(!LOW);
|
||||
#ifdef IRDEBUG
|
||||
#ifdef IRDEBUG
|
||||
digitalWrite(wrLow, 1);
|
||||
#endif
|
||||
} else {
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
writeToBuffer(LOW);
|
||||
#ifdef IRDEBUG
|
||||
#ifdef IRDEBUG
|
||||
digitalWrite(wrLow, 1);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
for (int8_t i = 0; i < highCount && 8 - i; i++) { // отправка HIGH битов, если есть
|
||||
if (i == highCount - 1 && invertErr) {
|
||||
for (int8_t i = 0; i < highCount && 8 - i; i++)
|
||||
{ // отправка HIGH битов, если есть
|
||||
if (i == highCount - 1 && invertErr)
|
||||
{
|
||||
invertErr = false;
|
||||
writeToBuffer(!HIGH);
|
||||
#ifdef IRDEBUG
|
||||
#ifdef IRDEBUG
|
||||
digitalWrite(wrLow, 1);
|
||||
#endif
|
||||
} else {
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
writeToBuffer(HIGH);
|
||||
#ifdef IRDEBUG
|
||||
#ifdef IRDEBUG
|
||||
digitalWrite(wrHigh, 1);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
#ifdef IRDEBUG
|
||||
#ifdef IRDEBUG
|
||||
digitalWrite(wrHigh, 0);
|
||||
digitalWrite(wrLow, 0);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
}
|
||||
if (risePeriod > riseTimeMax / 2 || highCount || lowCount) { // комплексный фикс рваной единицы
|
||||
if (risePeriod > riseTimeMax / 2 || highCount || lowCount)
|
||||
{ // комплексный фикс рваной единицы
|
||||
prevPrevRise = prevRise;
|
||||
prevRise = currentFront.time;
|
||||
} else {
|
||||
errors.other++;
|
||||
#ifdef IRDEBUG
|
||||
errPulse(errOut, 5);
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
errors.other++;
|
||||
#ifdef IRDEBUG
|
||||
errPulse(errOut, 5);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
else
|
||||
{ // Если ```\__ ↓
|
||||
|
||||
} else { // Если ```\__ ↓
|
||||
|
||||
if (currentFront.time - prevFall > riseTimeMin) {
|
||||
if (currentFront.time - prevFall > riseTimeMin)
|
||||
{
|
||||
prevPrevFall = prevFall;
|
||||
prevFall = currentFront.time;
|
||||
} else {
|
||||
#ifdef IRDEBUG
|
||||
//errPulse(errOut, 5);
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
#ifdef IRDEBUG
|
||||
// errPulse(errOut, 5);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
if (isPreamb && preambFrontCounter <= 0) {
|
||||
if (isPreamb && preambFrontCounter <= 0)
|
||||
{
|
||||
prevRise = currentFront.time + riseTime;
|
||||
}
|
||||
|
||||
#ifdef IRDEBUG
|
||||
#ifdef IRDEBUG
|
||||
digitalWrite(writeOp, isPreamb);
|
||||
#endif
|
||||
#endif
|
||||
////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
||||
oldSREG = SREG;
|
||||
cli();
|
||||
if (firstUnHandledFront != nullptr) {
|
||||
firstUnHandledFront = firstUnHandledFront->next; //переместить флаг на следующий элемент для обработки (next or nullptr)
|
||||
if (firstUnHandledFront != nullptr)
|
||||
{
|
||||
firstUnHandledFront = firstUnHandledFront->next; // переместить флаг на следующий элемент для обработки (next or nullptr)
|
||||
}
|
||||
SREG = oldSREG;
|
||||
}
|
||||
|
||||
void IR_DecoderRaw::writeToBuffer(bool bit) {
|
||||
if (i_dataBuffer > dataByteSizeMax * 8) {// проверка переполнения
|
||||
//TODO: Буффер переполнен!
|
||||
#ifdef IRDEBUG_INFO
|
||||
void IR_DecoderRaw::writeToBuffer(bool bit)
|
||||
{
|
||||
if (i_dataBuffer > dataByteSizeMax * 8)
|
||||
{ // проверка переполнения
|
||||
// TODO: Буффер переполнен!
|
||||
#ifdef IRDEBUG_INFO
|
||||
Serial.println("OverBuf");
|
||||
#endif
|
||||
#endif
|
||||
isBufferOverflow = true;
|
||||
}
|
||||
if (isBufferOverflow || isPreamb || isWrongPack) {
|
||||
if (isBufferOverflow || isPreamb || isWrongPack)
|
||||
{
|
||||
isRecive = false;
|
||||
return;
|
||||
}
|
||||
|
||||
// Переключение флага, data или syncBit
|
||||
if (bufBitPos == nextControlBit) {
|
||||
if (bufBitPos == nextControlBit)
|
||||
{
|
||||
nextControlBit += (isData ? syncBits : bitPerByte); // маркер следующего переключения
|
||||
isData = !isData;
|
||||
i_syncBit = 0; // сброс счетчика битов синхронизации
|
||||
err_syncBit = 0; // сброс счетчика ошибок синхронизации
|
||||
#ifdef IRDEBUG_INFO
|
||||
i_syncBit = 0; // сброс счетчика битов синхронизации
|
||||
err_syncBit = 0; // сброс счетчика ошибок синхронизации
|
||||
#ifdef IRDEBUG_INFO
|
||||
Serial.print(" ");
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
if (isData) { // Запись битов в dataBuffer
|
||||
#ifdef IRDEBUG_INFO
|
||||
if (isData)
|
||||
{ // Запись битов в dataBuffer
|
||||
#ifdef IRDEBUG_INFO
|
||||
Serial.print(bit);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// if (i_dataBuffer % 8 == 7) {
|
||||
// // Serial.print("+");
|
||||
@ -317,15 +394,21 @@ void IR_DecoderRaw::writeToBuffer(bool bit) {
|
||||
dataBuffer[(i_dataBuffer / 8)] |= bit << (7 - i_dataBuffer % 8); // Запись в буффер
|
||||
i_dataBuffer++;
|
||||
bufBitPos++;
|
||||
} else {
|
||||
}
|
||||
else
|
||||
{
|
||||
//********************************* Проверка контрольных sync битов*******************************//
|
||||
////////////////////// Исправление лишнего нуля ///////////////////////
|
||||
if (i_syncBit == 0) { // Первый бит синхронизации
|
||||
if (i_syncBit == 0)
|
||||
{ // Первый бит синхронизации
|
||||
// Serial.print("~");
|
||||
if (bit != (dataBuffer[((i_dataBuffer - 1) / 8)] >> (7 - (i_dataBuffer - 1) % 8) & 1)) {
|
||||
if (bit != (dataBuffer[((i_dataBuffer - 1) / 8)] >> (7 - (i_dataBuffer - 1) % 8) & 1))
|
||||
{
|
||||
bufBitPos++;
|
||||
i_syncBit++;
|
||||
} else {
|
||||
}
|
||||
else
|
||||
{
|
||||
i_syncBit = 0;
|
||||
errors.other++;
|
||||
// Serial.print("E");
|
||||
@ -333,50 +416,71 @@ void IR_DecoderRaw::writeToBuffer(bool bit) {
|
||||
// Serial.print("bit: "); Serial.println(bit);
|
||||
// Serial.print("dataBuffer: "); Serial.println(dataBuffer[((i_dataBuffer - 1) / 8)] & 1 << (7 - ((i_dataBuffer - 1) & ~(~0 << 3))));
|
||||
}
|
||||
} else { // Последующие биты синхронизации
|
||||
}
|
||||
else
|
||||
{ // Последующие биты синхронизации
|
||||
// Serial.print("`");
|
||||
bufBitPos++;
|
||||
i_syncBit++;
|
||||
}
|
||||
////////////////////// Проверка наличия битов синхранизации //////////////////////
|
||||
if (isWrongPack = (err_syncBit >= syncBits)) {
|
||||
#ifdef IRDEBUG_INFO
|
||||
if (isWrongPack = (err_syncBit >= syncBits))
|
||||
{
|
||||
#ifdef IRDEBUG_INFO
|
||||
Serial.print("****************");
|
||||
#endif
|
||||
|
||||
#endif
|
||||
};
|
||||
|
||||
}//**************************************************************************************************//
|
||||
} //**************************************************************************************************//
|
||||
|
||||
// Serial.print(bit);
|
||||
#ifdef IRDEBUG
|
||||
// Serial.print(bit);
|
||||
#ifdef IRDEBUG
|
||||
bit ? infoPulse(writeOp, 2) : infoPulse(writeOp, 1);
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
#ifdef IRDEBUG_INFO
|
||||
if (isData) {
|
||||
if (i_dataBuffer == ((msgBytes)*bitPerByte)) { Serial.print(" -> "); Serial.print(dataBuffer[0] & IR_MASK_MSG_INFO); Serial.print(" ->"); }
|
||||
if (i_dataBuffer == ((msgBytes + addrBytes) * bitPerByte)) { Serial.print(" |"); }
|
||||
if (i_dataBuffer == ((msgBytes + addrBytes + addrBytes) * bitPerByte)) { Serial.print(" ->"); }
|
||||
if (i_dataBuffer == (((dataBuffer[0] & IR_MASK_MSG_INFO) - 2) * bitPerByte)) { Serial.print(" <-"); }
|
||||
#ifdef IRDEBUG_INFO
|
||||
if (isData)
|
||||
{
|
||||
if (i_dataBuffer == ((msgBytes)*bitPerByte))
|
||||
{
|
||||
Serial.print(" -> ");
|
||||
Serial.print(dataBuffer[0] & IR_MASK_MSG_INFO);
|
||||
Serial.print(" ->");
|
||||
}
|
||||
if (i_dataBuffer == ((msgBytes + addrBytes) * bitPerByte))
|
||||
{
|
||||
Serial.print(" |");
|
||||
}
|
||||
if (i_dataBuffer == ((msgBytes + addrBytes + addrBytes) * bitPerByte))
|
||||
{
|
||||
Serial.print(" ->");
|
||||
}
|
||||
if (i_dataBuffer == (((dataBuffer[0] & IR_MASK_MSG_INFO) - 2) * bitPerByte))
|
||||
{
|
||||
Serial.print(" <-");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
if (!isAvailable && isData && !isWrongPack) {
|
||||
if (i_dataBuffer == 8 * msgBytes) {// Ппервый байт
|
||||
if (!isAvailable && isData && !isWrongPack)
|
||||
{
|
||||
if (i_dataBuffer == 8 * msgBytes)
|
||||
{ // Ппервый байт
|
||||
packSize = dataBuffer[0] & IR_MASK_MSG_INFO;
|
||||
#ifdef IRDEBUG_INFO
|
||||
Serial.print(" ["); Serial.print(packSize); Serial.print("] ");
|
||||
#endif
|
||||
#ifdef IRDEBUG_INFO
|
||||
Serial.print(" [");
|
||||
Serial.print(packSize);
|
||||
Serial.print("] ");
|
||||
#endif
|
||||
}
|
||||
|
||||
if (packSize && (i_dataBuffer == packSize * bitPerByte)) { // Конец
|
||||
#ifdef IRDEBUG_INFO
|
||||
if (packSize && (i_dataBuffer == packSize * bitPerByte))
|
||||
{ // Конец
|
||||
#ifdef IRDEBUG_INFO
|
||||
Serial.print(" END DATA ");
|
||||
#endif
|
||||
#endif
|
||||
|
||||
packInfo.buffer = dataBuffer;
|
||||
packInfo.crc = crcValue;
|
||||
@ -392,7 +496,8 @@ void IR_DecoderRaw::writeToBuffer(bool bit) {
|
||||
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
||||
}
|
||||
|
||||
bool IR_DecoderRaw::crcCheck(uint8_t len, crc_t& crc) {
|
||||
bool IR_DecoderRaw::crcCheck(uint8_t len, crc_t &crc)
|
||||
{
|
||||
bool crcOK = false;
|
||||
|
||||
crc = 0;
|
||||
@ -402,42 +507,44 @@ bool IR_DecoderRaw::crcCheck(uint8_t len, crc_t& crc) {
|
||||
if (
|
||||
crc &&
|
||||
dataBuffer[len] == (crc >> 8) & 0xFF &&
|
||||
dataBuffer[len + 1] == (crc & 0xFF)
|
||||
) {
|
||||
dataBuffer[len + 1] == (crc & 0xFF))
|
||||
{
|
||||
crcOK = true;
|
||||
} else {
|
||||
}
|
||||
else
|
||||
{
|
||||
crcOK = false;
|
||||
}
|
||||
|
||||
|
||||
return crcOK;
|
||||
}
|
||||
|
||||
uint16_t IR_DecoderRaw::ceil_div(uint16_t val, uint16_t divider) {
|
||||
uint16_t IR_DecoderRaw::ceil_div(uint16_t val, uint16_t divider)
|
||||
{
|
||||
int ret = val / divider;
|
||||
if ((val << 4) / divider - (ret << 4) >= 8)
|
||||
ret++;
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
|
||||
// IRDEBUG FUNC
|
||||
#ifdef IRDEBUG
|
||||
inline void IR_DecoderRaw::errPulse(uint8_t pin, uint8_t count) {
|
||||
for (size_t i = 0; i < count; i++) {
|
||||
inline void IR_DecoderRaw::errPulse(uint8_t pin, uint8_t count)
|
||||
{
|
||||
for (size_t i = 0; i < count; i++)
|
||||
{
|
||||
digitalWrite(pin, 1);
|
||||
digitalWrite(pin, 0);
|
||||
}
|
||||
digitalWrite(pin, 0);
|
||||
}
|
||||
|
||||
inline void IR_DecoderRaw::infoPulse(uint8_t pin, uint8_t count) {
|
||||
for (size_t i = 0; i < count; i++) {
|
||||
inline void IR_DecoderRaw::infoPulse(uint8_t pin, uint8_t count)
|
||||
{
|
||||
for (size_t i = 0; i < count; i++)
|
||||
{
|
||||
digitalWrite(pin, 1);
|
||||
digitalWrite(pin, 0);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
|
116
IR_DecoderRaw.h
116
IR_DecoderRaw.h
@ -1,49 +1,63 @@
|
||||
#pragma once
|
||||
#include "IR_config.h"
|
||||
|
||||
//#define IRDEBUG
|
||||
// #define IRDEBUG
|
||||
|
||||
#ifdef IRDEBUG
|
||||
#define wrHigh A3 // Запись HIGH инициирована // green
|
||||
#define wrLow A3 // Запись LOW инициирована // blue
|
||||
#define writeOp 13 // Операция записи, 1 пульс для 0 и 2 для 1 // orange
|
||||
#ifdef IRDEBUG
|
||||
#define wrHigh A3 // Запись HIGH инициирована // green
|
||||
#define wrLow A3 // Запись LOW инициирована // blue
|
||||
#define writeOp 13 // Операция записи, 1 пульс для 0 и 2 для 1 // orange
|
||||
// Исправленные ошибки // purle
|
||||
// 1 пульс: fix
|
||||
#define errOut A3
|
||||
// 1 пульс: fix
|
||||
#define errOut A3
|
||||
#endif
|
||||
|
||||
/////////////////////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
#define riseTime riseSyncTime //* bitTime */ 893U // TODO: Должно высчитываться медианой
|
||||
#define riseTolerance tolerance /* 250U */ // погрешность
|
||||
#define riseTime riseSyncTime //* bitTime */ 893U // TODO: Должно высчитываться медианой
|
||||
#define riseTolerance tolerance /* 250U */ // погрешность
|
||||
#define riseTimeMax (riseTime + riseTolerance)
|
||||
#define riseTimeMin (riseTime - riseTolerance)
|
||||
#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
|
||||
|
||||
class IR_Encoder;
|
||||
class IR_DecoderRaw : virtual public IR_FOX {
|
||||
class IR_DecoderRaw : virtual public IR_FOX
|
||||
{
|
||||
friend IR_Encoder;
|
||||
|
||||
protected:
|
||||
PackInfo packInfo;
|
||||
IR_Encoder* encoder; // Указатель на парный передатчик
|
||||
bool availableRaw() { if (isAvailable) { isAvailable = false; return true; } else { return false; } };
|
||||
IR_Encoder *encoder; // Указатель на парный передатчик
|
||||
bool availableRaw()
|
||||
{
|
||||
if (isAvailable)
|
||||
{
|
||||
isAvailable = false;
|
||||
return true;
|
||||
}
|
||||
else
|
||||
{
|
||||
return false;
|
||||
}
|
||||
};
|
||||
|
||||
public:
|
||||
const uint8_t isrPin; // Пин прерывания
|
||||
const uint8_t isrPin; // Пин прерывания
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////
|
||||
/// @brief Конструктор
|
||||
/// @param isrPin Номер вывода прерывания/данных от приёмника (2 или 3 для atmega 328p)
|
||||
/// @param addr Адрес приёмника
|
||||
/// @param encPair Указатель на передатчик, работающий в паре
|
||||
IR_DecoderRaw(const uint8_t isrPin, uint16_t addr, IR_Encoder* encPair = nullptr);
|
||||
IR_DecoderRaw(const uint8_t isrPin, uint16_t addr, IR_Encoder *encPair = nullptr);
|
||||
|
||||
void isr(); // Функция прерывания
|
||||
void tick(); // Обработка приёмника, необходима для работы
|
||||
void isr(); // Функция прерывания
|
||||
void tick(); // Обработка приёмника, необходима для работы
|
||||
|
||||
bool isOverflow() { return isBufferOverflow; }; // Буффер переполнился
|
||||
bool isSubOverflow() {
|
||||
bool isOverflow() { return isBufferOverflow; }; // Буффер переполнился
|
||||
bool isSubOverflow()
|
||||
{
|
||||
uint8_t oldSREG = SREG;
|
||||
cli();
|
||||
volatile bool ret = isSubBufferOverflow;
|
||||
@ -58,56 +72,56 @@ private:
|
||||
bool isAvailable = false;
|
||||
uint16_t packSize;
|
||||
uint16_t crcValue;
|
||||
volatile uint16_t isPairSending = 0; // Флаг передачи парного передатчика
|
||||
volatile bool isRecive = false; // Флаг приёма
|
||||
volatile bool isPreamb = false; // флаг начальной последовости
|
||||
volatile uint16_t isPairSending = 0; // Флаг передачи парного передатчика
|
||||
volatile bool isRecive = false; // Флаг приёма
|
||||
volatile bool isPreamb = false; // флаг начальной последовости
|
||||
volatile bool isSubBufferOverflow = false;
|
||||
bool isBufferOverflow = false; // Флаг переполнения буффера данных
|
||||
bool isWrongPack = false; // Флаг битого пакета
|
||||
bool isBufferOverflow = false; // Флаг переполнения буффера данных
|
||||
bool isWrongPack = false; // Флаг битого пакета
|
||||
|
||||
uint16_t riseSyncTime = bitTime; // Подстраиваемое время бита в мкс
|
||||
uint16_t riseSyncTime = bitTime; // Подстраиваемое время бита в мкс
|
||||
|
||||
////////////////////////////////////////////////////////////////////////
|
||||
volatile uint8_t currentSubBufferIndex; // Счетчик текущей позиции во вспомогательном буфере фронтов/спадов
|
||||
volatile uint8_t currentSubBufferIndex; // Счетчик текущей позиции во вспомогательном буфере фронтов/спадов
|
||||
|
||||
struct FrontStorage { // Структура для хранения времени и направления фронта/спада
|
||||
volatile uint32_t time = 0; // Время
|
||||
volatile bool dir = false; // Направление (true = ↑; false = ↓)
|
||||
volatile FrontStorage* next = nullptr; // Указатель на следующий связанный фронт/спад, или nullptr если конец
|
||||
struct FrontStorage
|
||||
{ // Структура для хранения времени и направления фронта/спада
|
||||
volatile uint32_t time = 0; // Время
|
||||
volatile bool dir = false; // Направление (true = ↑; false = ↓)
|
||||
volatile FrontStorage *next = nullptr; // Указатель на следующий связанный фронт/спад, или nullptr если конец
|
||||
};
|
||||
volatile FrontStorage* lastFront = nullptr; // Указатель последнего фронта/спада
|
||||
volatile FrontStorage* firstUnHandledFront = nullptr; // Указатель первого необработанного фронта/спада
|
||||
volatile FrontStorage subBuffer[subBufferSize]; // вспомогательный буфер для хранения необработанных фронтов/спадов
|
||||
volatile FrontStorage *lastFront = nullptr; // Указатель последнего фронта/спада
|
||||
volatile FrontStorage *firstUnHandledFront = nullptr; // Указатель первого необработанного фронта/спада
|
||||
volatile FrontStorage subBuffer[subBufferSize]; // вспомогательный буфер для хранения необработанных фронтов/спадов
|
||||
////////////////////////////////////////////////////////////////////////
|
||||
uint8_t dataBuffer[dataByteSizeMax] { 0 }; // Буффер данных
|
||||
uint32_t prevRise, prevPrevRise, prevFall, prevPrevFall; // Время предыдущих фронтов/спадов
|
||||
uint16_t errorCounter = 0; // Счётчик ошибок
|
||||
int8_t preambFrontCounter = 0; // Счётчик __/``` ↑ преамбулы
|
||||
int16_t bufBitPos = 0; // Позиция для записи бита в буффер
|
||||
uint8_t dataBuffer[dataByteSizeMax]{0}; // Буффер данных
|
||||
uint32_t prevRise, prevPrevRise, prevFall, prevPrevFall; // Время предыдущих фронтов/спадов
|
||||
uint16_t errorCounter = 0; // Счётчик ошибок
|
||||
int8_t preambFrontCounter = 0; // Счётчик __/``` ↑ преамбулы
|
||||
int16_t bufBitPos = 0; // Позиция для записи бита в буффер
|
||||
|
||||
private:
|
||||
void listenStart(); // @brief Слушатель для работы isReciving()
|
||||
void listenStart(); // @brief Слушатель для работы isReciving()
|
||||
|
||||
/// @brief Проверка CRC. Проверяет len байт со значением crc, пришедшим в пакете
|
||||
/// @param len Длина в байтах проверяемых данных
|
||||
/// @param crc Результат рассчёта crc (Выходной параметр)
|
||||
/// @return true если crc верно
|
||||
bool crcCheck(uint8_t len, uint16_t& crc);
|
||||
bool crcCheck(uint8_t len, uint16_t &crc);
|
||||
|
||||
////////////////////////////////////////////////////////////////////////
|
||||
bool isData = true; // Флаг относится ли бит к данным, или битам синхронизации
|
||||
uint16_t i_dataBuffer; // Счётчик буфера данных
|
||||
uint8_t nextControlBit = bitPerByte; // Метка для смены флага isData
|
||||
uint8_t i_syncBit; // Счётчик битов синхронизации
|
||||
uint8_t err_syncBit; // Счётчик ошибок синхронизации
|
||||
bool isData = true; // Флаг относится ли бит к данным, или битам синхронизации
|
||||
uint16_t i_dataBuffer; // Счётчик буфера данных
|
||||
uint8_t nextControlBit = bitPerByte; // Метка для смены флага isData
|
||||
uint8_t i_syncBit; // Счётчик битов синхронизации
|
||||
uint8_t err_syncBit; // Счётчик ошибок синхронизации
|
||||
|
||||
/// @brief Запиь бита в буффер, а так же проверка битов синхранизации и их фильтрация
|
||||
/// @param Бит данных
|
||||
void writeToBuffer(bool);
|
||||
////////////////////////////////////////////////////////////////////////
|
||||
|
||||
|
||||
void firstRX(); /// @brief Установка и сброс начальных значений и флагов в готовность к приёму данных
|
||||
void firstRX(); /// @brief Установка и сброс начальных значений и флагов в готовность к приёму данных
|
||||
|
||||
/// @brief Целочисленное деление с округлением вверх
|
||||
/// @param val Значение
|
||||
@ -115,10 +129,8 @@ private:
|
||||
/// @return Результат
|
||||
uint16_t ceil_div(uint16_t val, uint16_t divider);
|
||||
|
||||
#ifdef IRDEBUG
|
||||
#ifdef IRDEBUG
|
||||
inline void errPulse(uint8_t pin, uint8_t count);
|
||||
inline void infoPulse(uint8_t pin, uint8_t count);
|
||||
#endif
|
||||
|
||||
|
||||
#endif
|
||||
};
|
302
IR_Encoder.cpp
302
IR_Encoder.cpp
@ -5,43 +5,55 @@
|
||||
#define ISR_Out 10
|
||||
#define TestOut 13
|
||||
|
||||
IR_Encoder::IR_Encoder(uint16_t addr, IR_DecoderRaw* decPair = nullptr) {
|
||||
IR_Encoder::IR_Encoder(uint16_t addr, IR_DecoderRaw *decPair = nullptr)
|
||||
{
|
||||
id = addr;
|
||||
this->decPair = decPair;
|
||||
signal = noSignal;
|
||||
isSending = false;
|
||||
#if disablePairDec
|
||||
if (decPair != nullptr) {
|
||||
blindDecoders = new IR_DecoderRaw * [1] {decPair};
|
||||
#if disablePairDec
|
||||
if (decPair != nullptr)
|
||||
{
|
||||
blindDecoders = new IR_DecoderRaw *[1]
|
||||
{ decPair };
|
||||
decodersCount = 1;
|
||||
}
|
||||
#endif
|
||||
if (decPair != nullptr) {
|
||||
#endif
|
||||
if (decPair != nullptr)
|
||||
{
|
||||
decPair->encoder = this;
|
||||
}
|
||||
};
|
||||
void IR_Encoder::setBlindDecoders(IR_DecoderRaw* decoders [], uint8_t count) {
|
||||
#if disablePairDec
|
||||
if (blindDecoders != nullptr) delete [] blindDecoders;
|
||||
#endif
|
||||
void IR_Encoder::setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count)
|
||||
{
|
||||
#if disablePairDec
|
||||
if (blindDecoders != nullptr)
|
||||
delete[] blindDecoders;
|
||||
#endif
|
||||
decodersCount = count;
|
||||
blindDecoders = decoders;
|
||||
}
|
||||
|
||||
IR_Encoder::~IR_Encoder() {
|
||||
delete [] bitLow;
|
||||
delete [] bitHigh;
|
||||
IR_Encoder::~IR_Encoder()
|
||||
{
|
||||
delete[] bitLow;
|
||||
delete[] bitHigh;
|
||||
};
|
||||
|
||||
void IR_Encoder::sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept = false) {
|
||||
uint8_t* dataPtr = new uint8_t[1];
|
||||
void IR_Encoder::sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept = false)
|
||||
{
|
||||
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 = nullptr, uint8_t len = 0, bool needAccept = false) {
|
||||
if (len > bytePerPack) { return; }
|
||||
void IR_Encoder::sendData(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false)
|
||||
{
|
||||
if (len > bytePerPack)
|
||||
{
|
||||
return;
|
||||
}
|
||||
constexpr uint8_t dataStart = msgBytes + addrBytes + addrBytes;
|
||||
memset(sendBuffer, 0x00, dataByteSizeMax);
|
||||
uint8_t packSize = msgBytes + addrBytes + addrBytes + len + crcBytes;
|
||||
@ -60,8 +72,9 @@ void IR_Encoder::sendData(uint16_t addrTo, uint8_t* data = nullptr, uint8_t len
|
||||
sendBuffer[3] = addrTo >> 8 & 0xFF;
|
||||
sendBuffer[4] = addrTo & 0xFF;
|
||||
|
||||
for (uint16_t i = dataStart; (i < dataStart + len) && (data != nullptr); i++) {
|
||||
sendBuffer[i] = ((uint8_t*)data)[i - dataStart];
|
||||
for (uint16_t i = dataStart; (i < dataStart + len) && (data != nullptr); i++)
|
||||
{
|
||||
sendBuffer[i] = ((uint8_t *)data)[i - dataStart];
|
||||
}
|
||||
|
||||
// data crc
|
||||
@ -79,7 +92,8 @@ void IR_Encoder::sendData(uint16_t addrTo, uint8_t* data = nullptr, uint8_t len
|
||||
rawSend(sendBuffer, packSize);
|
||||
}
|
||||
|
||||
void IR_Encoder::sendAccept(uint16_t addrTo, uint8_t customByte = 0) {
|
||||
void IR_Encoder::sendAccept(uint16_t addrTo, uint8_t customByte = 0)
|
||||
{
|
||||
constexpr uint8_t packsize = msgBytes + addrBytes + 1U + crcBytes;
|
||||
memset(sendBuffer, 0x00, dataByteSizeMax);
|
||||
sendBuffer[0] = IR_MSG_ACCEPT << 5;
|
||||
@ -101,7 +115,8 @@ void IR_Encoder::sendAccept(uint16_t addrTo, uint8_t customByte = 0) {
|
||||
rawSend(sendBuffer, packsize);
|
||||
}
|
||||
|
||||
void IR_Encoder::sendRequest(uint16_t addrTo) {
|
||||
void IR_Encoder::sendRequest(uint16_t addrTo)
|
||||
{
|
||||
constexpr uint8_t packsize = msgBytes + addrBytes + addrBytes + crcBytes;
|
||||
memset(sendBuffer, 0x00, dataByteSizeMax);
|
||||
sendBuffer[0] = IR_MSG_REQUEST << 5;
|
||||
@ -111,7 +126,7 @@ void IR_Encoder::sendRequest(uint16_t addrTo) {
|
||||
sendBuffer[1] = id >> 8 & 0xFF;
|
||||
sendBuffer[2] = id & 0xFF;
|
||||
|
||||
//addr_to
|
||||
// addr_to
|
||||
sendBuffer[3] = addrTo >> 8 & 0xFF;
|
||||
sendBuffer[4] = addrTo & 0xFF;
|
||||
|
||||
@ -122,16 +137,22 @@ void IR_Encoder::sendRequest(uint16_t addrTo) {
|
||||
rawSend(sendBuffer, packsize);
|
||||
}
|
||||
|
||||
void IR_Encoder::sendBack(uint8_t* data = nullptr, uint8_t len = 0) {
|
||||
void IR_Encoder::sendBack(uint8_t *data = nullptr, uint8_t len = 0)
|
||||
{
|
||||
_sendBack(false, 0, data, len);
|
||||
}
|
||||
|
||||
void IR_Encoder::sendBackTo(uint16_t addrTo, uint8_t* data = nullptr, uint8_t len = 0) {
|
||||
void IR_Encoder::sendBackTo(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0)
|
||||
{
|
||||
_sendBack(true, addrTo, data, len);
|
||||
}
|
||||
|
||||
void IR_Encoder::_sendBack(bool isAdressed, uint16_t addrTo, uint8_t* data, uint8_t len) {
|
||||
if (len > bytePerPack) { return; }
|
||||
void IR_Encoder::_sendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint8_t len)
|
||||
{
|
||||
if (len > bytePerPack)
|
||||
{
|
||||
return;
|
||||
}
|
||||
memset(sendBuffer, 0x00, dataByteSizeMax);
|
||||
uint8_t dataStart = msgBytes + addrBytes + (isAdressed ? addrBytes : 0);
|
||||
|
||||
@ -151,8 +172,9 @@ void IR_Encoder::_sendBack(bool isAdressed, uint16_t addrTo, uint8_t* data, uint
|
||||
sendBuffer[3] = addrTo >> 8 & 0xFF;
|
||||
sendBuffer[4] = addrTo & 0xFF;
|
||||
|
||||
for (uint16_t i = dataStart; i < dataStart + len; i++) {
|
||||
sendBuffer[i] = ((uint8_t*)data)[i - dataStart];
|
||||
for (uint16_t i = dataStart; i < dataStart + len; i++)
|
||||
{
|
||||
sendBuffer[i] = ((uint8_t *)data)[i - dataStart];
|
||||
}
|
||||
|
||||
// data crc
|
||||
@ -163,18 +185,22 @@ void IR_Encoder::_sendBack(bool isAdressed, uint16_t addrTo, uint8_t* data, uint
|
||||
rawSend(sendBuffer, packSize);
|
||||
}
|
||||
|
||||
void IR_Encoder::setDecoder_isSending() {
|
||||
if (decodersCount) {
|
||||
for (uint8_t i = 0; i < decodersCount; i++) {
|
||||
void IR_Encoder::setDecoder_isSending()
|
||||
{
|
||||
if (decodersCount)
|
||||
{
|
||||
for (uint8_t i = 0; i < decodersCount; i++)
|
||||
{
|
||||
blindDecoders[i]->isPairSending ^= id;
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
void IR_Encoder::rawSend(uint8_t* ptr, uint8_t len) {
|
||||
if (isSending) {
|
||||
//TODO: Обработка повторной отправки
|
||||
void IR_Encoder::rawSend(uint8_t *ptr, uint8_t len)
|
||||
{
|
||||
if (isSending)
|
||||
{
|
||||
// TODO: Обработка повторной отправки
|
||||
return;
|
||||
}
|
||||
|
||||
@ -200,94 +226,110 @@ void IR_Encoder::rawSend(uint8_t* ptr, uint8_t len) {
|
||||
sei();
|
||||
}
|
||||
|
||||
|
||||
|
||||
void IR_Encoder::isr() {
|
||||
if (!isSending) return;
|
||||
void IR_Encoder::isr()
|
||||
{
|
||||
if (!isSending)
|
||||
return;
|
||||
|
||||
ir_out_virtual = !ir_out_virtual && state;
|
||||
|
||||
if (toggleCounter) {
|
||||
if (toggleCounter)
|
||||
{
|
||||
toggleCounter--;
|
||||
} else {
|
||||
}
|
||||
else
|
||||
{
|
||||
IsrStart:
|
||||
switch (signal) {
|
||||
case noSignal:
|
||||
signal = preamb;
|
||||
// сброс счетчиков
|
||||
// ...
|
||||
isSending = false;
|
||||
setDecoder_isSending();
|
||||
return;
|
||||
break;
|
||||
switch (signal)
|
||||
{
|
||||
case noSignal:
|
||||
signal = preamb;
|
||||
// сброс счетчиков
|
||||
// ...
|
||||
isSending = false;
|
||||
setDecoder_isSending();
|
||||
return;
|
||||
break;
|
||||
|
||||
case preamb:
|
||||
if (preambFrontCounter) {
|
||||
preambFrontCounter--;
|
||||
toggleCounter = preambToggle; // Вторая и последующие генерации для этого signal
|
||||
} else {// Конец преамбулы, переход на следующий signal
|
||||
signal = data;
|
||||
state = !LOW; // Инверсное состояние первой генерации следующего signal
|
||||
goto IsrStart; // Применение новых параметров в этй же итерации прерывания
|
||||
case preamb:
|
||||
if (preambFrontCounter)
|
||||
{
|
||||
preambFrontCounter--;
|
||||
toggleCounter = preambToggle; // Вторая и последующие генерации для этого signal
|
||||
}
|
||||
else
|
||||
{ // Конец преамбулы, переход на следующий signal
|
||||
signal = data;
|
||||
state = !LOW; // Инверсное состояние первой генерации следующего signal
|
||||
goto IsrStart; // Применение новых параметров в этй же итерации прерывания
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case data:
|
||||
if (dataSequenceCounter)
|
||||
{
|
||||
if (!(dataSequenceCounter & 1U))
|
||||
{ // если чётный - смена бита
|
||||
currentBitSequence = ((sendBuffer[dataByteCounter] >> dataBitCounter) & 1U) ? bitHigh : bitLow; // определение текущего бита
|
||||
dataBitCounter--;
|
||||
}
|
||||
toggleCounter = currentBitSequence[!state];
|
||||
dataSequenceCounter--;
|
||||
}
|
||||
else
|
||||
{ // Конец data, переход на следующий signal
|
||||
syncLastBit = ((sendBuffer[dataByteCounter]) & 1U);
|
||||
dataByteCounter++;
|
||||
dataBitCounter = bitPerByte - 1;
|
||||
dataSequenceCounter = bitPerByte * 2;
|
||||
signal = sync;
|
||||
goto IsrStart; // Применение новых параметров в этй же итерации прерывания
|
||||
}
|
||||
break;
|
||||
|
||||
break;
|
||||
|
||||
case data:
|
||||
if (dataSequenceCounter) {
|
||||
if (!(dataSequenceCounter & 1U)) { // если чётный - смена бита
|
||||
currentBitSequence = ((sendBuffer[dataByteCounter] >> dataBitCounter) & 1U) ? bitHigh : bitLow; // определение текущего бита
|
||||
dataBitCounter--;
|
||||
case sync:
|
||||
if (syncSequenceCounter)
|
||||
{
|
||||
if (!(syncSequenceCounter & 1U))
|
||||
{ // если чётный - смена бита
|
||||
if (syncSequenceCounter == 2)
|
||||
{ // Если последний бит
|
||||
currentBitSequence = ((sendBuffer[dataByteCounter]) & 0b10000000) ? bitLow : bitHigh;
|
||||
}
|
||||
else
|
||||
{
|
||||
currentBitSequence = syncLastBit ? bitLow : bitHigh; // определение текущего бита
|
||||
syncLastBit = !syncLastBit;
|
||||
}
|
||||
toggleCounter = currentBitSequence[!state];
|
||||
dataSequenceCounter--;
|
||||
} else { // Конец data, переход на следующий signal
|
||||
syncLastBit = ((sendBuffer[dataByteCounter]) & 1U);
|
||||
dataByteCounter++;
|
||||
dataBitCounter = bitPerByte - 1;
|
||||
dataSequenceCounter = bitPerByte * 2;
|
||||
signal = sync;
|
||||
goto IsrStart; // Применение новых параметров в этй же итерации прерывания
|
||||
}
|
||||
break;
|
||||
toggleCounter = currentBitSequence[!state];
|
||||
syncSequenceCounter--;
|
||||
}
|
||||
else
|
||||
{ // Конец sync, переход на следующий signal
|
||||
signal = data;
|
||||
syncSequenceCounter = syncBits * 2;
|
||||
|
||||
case sync:
|
||||
if (syncSequenceCounter) {
|
||||
if (!(syncSequenceCounter & 1U)) { // если чётный - смена бита
|
||||
if (syncSequenceCounter == 2) { // Если последний бит
|
||||
currentBitSequence = ((sendBuffer[dataByteCounter]) & 0b10000000) ? bitLow : bitHigh;
|
||||
} else {
|
||||
currentBitSequence = syncLastBit ? bitLow : bitHigh; // определение текущего бита
|
||||
syncLastBit = !syncLastBit;
|
||||
}
|
||||
}
|
||||
toggleCounter = currentBitSequence[!state];
|
||||
syncSequenceCounter--;
|
||||
} else { // Конец sync, переход на следующий signal
|
||||
signal = data;
|
||||
syncSequenceCounter = syncBits * 2;
|
||||
|
||||
if (dataByteCounter >= sendLen) { // определение конца данных
|
||||
signal = noSignal;
|
||||
}
|
||||
goto IsrStart; // Применение новых параметров в этй же итерации прерывания
|
||||
if (dataByteCounter >= sendLen)
|
||||
{ // определение конца данных
|
||||
signal = noSignal;
|
||||
}
|
||||
break;
|
||||
goto IsrStart; // Применение новых параметров в этй же итерации прерывания
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
return;
|
||||
break;
|
||||
default:
|
||||
return;
|
||||
break;
|
||||
}
|
||||
|
||||
state = !state;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
void old() {///////////////////////////////////////////////////////
|
||||
void old()
|
||||
{ ///////////////////////////////////////////////////////
|
||||
// void IR_Encoder::rawSend(uint8_t* ptr, uint8_t len) {
|
||||
// /*tmp*/bool LOW_FIRST = false;/*tmp*/
|
||||
|
||||
@ -312,12 +354,14 @@ void old() {///////////////////////////////////////////////////////
|
||||
// }
|
||||
}
|
||||
|
||||
void IR_Encoder::sendByte(uint8_t byte, bool* prev, bool LOW_FIRST) {
|
||||
void IR_Encoder::sendByte(uint8_t byte, bool *prev, bool LOW_FIRST)
|
||||
{
|
||||
uint8_t mask = LOW_FIRST ? 0b00000001 : 0b10000000;
|
||||
for (uint8_t bitShift = 8; bitShift; bitShift--) {
|
||||
for (uint8_t bitShift = 8; bitShift; bitShift--)
|
||||
{
|
||||
// digitalWrite(9, HIGH);
|
||||
// digitalWrite(9, LOW);
|
||||
byte& mask ? send_HIGH(prev) : send_LOW();
|
||||
byte &mask ? send_HIGH(prev) : send_LOW();
|
||||
*prev = byte & mask;
|
||||
LOW_FIRST ? mask <<= 1 : mask >>= 1;
|
||||
// digitalWrite(9, HIGH);
|
||||
@ -325,25 +369,30 @@ void IR_Encoder::sendByte(uint8_t byte, bool* prev, bool LOW_FIRST) {
|
||||
}
|
||||
}
|
||||
|
||||
void IR_Encoder::addSync(bool* prev, bool* next) {
|
||||
switch (syncBits) {
|
||||
case 0: break;
|
||||
case 1:
|
||||
void IR_Encoder::addSync(bool *prev, bool *next)
|
||||
{
|
||||
switch (syncBits)
|
||||
{
|
||||
case 0:
|
||||
break;
|
||||
case 1:
|
||||
*prev ? send_LOW() : send_HIGH();
|
||||
*prev = !*prev;
|
||||
break;
|
||||
default:
|
||||
for (int16_t i = 0; i < syncBits - 1; i++)
|
||||
{
|
||||
*prev ? send_LOW() : send_HIGH();
|
||||
*prev = !*prev;
|
||||
break;
|
||||
default:
|
||||
for (int16_t i = 0; i < syncBits - 1; i++) {
|
||||
*prev ? send_LOW() : send_HIGH();
|
||||
*prev = !*prev;
|
||||
}
|
||||
*next ? send_LOW() : send_HIGH(0);
|
||||
*prev = !*next;
|
||||
break;
|
||||
}
|
||||
*next ? send_LOW() : send_HIGH(0);
|
||||
*prev = !*next;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void IR_Encoder::send_HIGH(bool prevBite = 1) {
|
||||
void IR_Encoder::send_HIGH(bool prevBite = 1)
|
||||
{
|
||||
|
||||
// if (/* prevBite */1) {
|
||||
// meanderBlock(bitPauseTakts * 2, halfPeriod, LOW);
|
||||
@ -352,21 +401,20 @@ void IR_Encoder::send_HIGH(bool prevBite = 1) {
|
||||
// meanderBlock(bitTakts - (bitActiveTakts - bitPauseTakts), halfPeriod, LOW);
|
||||
// meanderBlock(bitActiveTakts - bitPauseTakts, halfPeriod, HIGH);
|
||||
// }
|
||||
|
||||
}
|
||||
|
||||
void IR_Encoder::send_LOW() {
|
||||
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) {
|
||||
void IR_Encoder::send_EMPTY(uint8_t count)
|
||||
{
|
||||
// for (size_t i = 0; i < count * 2; i++) {
|
||||
// meanderBlock((bitPauseTakts * 2 + bitActiveTakts), halfPeriod, prevPreambBit);
|
||||
// meanderBlock((bitPauseTakts * 2 + bitActiveTakts), halfPeriod, prevPreambBit);
|
||||
// prevPreambBit = !prevPreambBit;
|
||||
// }
|
||||
// meanderBlock(bitPauseTakts * 2 + bitActiveTakts, halfPeriod, 0); //TODO: Отодвинуть преамбулу
|
||||
}
|
||||
|
||||
|
||||
|
91
IR_Encoder.h
91
IR_Encoder.h
@ -1,28 +1,29 @@
|
||||
#pragma once
|
||||
#include "IR_config.h"
|
||||
|
||||
//TODO: Отложенная передача после завершения приема
|
||||
// TODO: Отложенная передача после завершения приема
|
||||
|
||||
class IR_DecoderRaw;
|
||||
class IR_Encoder : IR_FOX {
|
||||
class IR_Encoder : IR_FOX
|
||||
{
|
||||
friend IR_DecoderRaw;
|
||||
public:
|
||||
|
||||
public:
|
||||
private:
|
||||
uint16_t id; /// @brief Адрес передатчика
|
||||
uint16_t id; /// @brief Адрес передатчика
|
||||
|
||||
public:
|
||||
|
||||
/// @brief Класс передатчика
|
||||
/// @param addr Адрес передатчика
|
||||
/// @param pin Вывод передатчика
|
||||
/// @param tune Подстройка несущей частоты
|
||||
/// @param decPair Приёмник, для которого отключается приём в момент передачи передатчиком
|
||||
IR_Encoder(uint16_t addr, IR_DecoderRaw* decPair = nullptr);
|
||||
IR_Encoder(uint16_t addr, IR_DecoderRaw *decPair = nullptr);
|
||||
|
||||
static void timerSetup() {
|
||||
static void timerSetup()
|
||||
{
|
||||
// TIMER2 Ini
|
||||
uint8_t oldSREG = SREG; // Save global interupts settings
|
||||
uint8_t oldSREG = SREG; // Save global interupts settings
|
||||
cli();
|
||||
// DDRB |= (1 << PORTB3); //OC2A (17)
|
||||
TCCR2A = 0;
|
||||
@ -30,88 +31,84 @@ public:
|
||||
|
||||
// TCCR2A |= (1 << COM2A0); //Переключение состояния
|
||||
|
||||
TCCR2A |= (1 << WGM21); // Clear Timer On Compare (Сброс по совпадению)
|
||||
TCCR2B |= (1 << CS20); // Предделитель 1
|
||||
TIMSK2 |= (1 << OCIE2A); // Прерывание по совпадению
|
||||
TCCR2A |= (1 << WGM21); // Clear Timer On Compare (Сброс по совпадению)
|
||||
TCCR2B |= (1 << CS20); // Предделитель 1
|
||||
TIMSK2 |= (1 << OCIE2A); // Прерывание по совпадению
|
||||
|
||||
OCR2A = /* 465 */((F_CPU / (38000 * 2)) - 2); //38кГц
|
||||
OCR2A = /* 465 */ ((F_CPU / (38000 * 2)) - 2); // 38кГц
|
||||
|
||||
|
||||
SREG = oldSREG; // Return interrupt settings
|
||||
SREG = oldSREG; // Return interrupt settings
|
||||
}
|
||||
static void timerOFFSetup(){
|
||||
TIMSK2 &= ~(1 << OCIE2A); // Прерывание по совпадению выкл
|
||||
static void timerOFFSetup()
|
||||
{
|
||||
TIMSK2 &= ~(1 << OCIE2A); // Прерывание по совпадению выкл
|
||||
}
|
||||
|
||||
void IR_Encoder::setBlindDecoders(IR_DecoderRaw* decoders [], uint8_t count);
|
||||
void rawSend(uint8_t* ptr, uint8_t len);
|
||||
void IR_Encoder::setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count);
|
||||
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* 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 sendAccept(uint16_t addrTo, uint8_t customByte = 0);
|
||||
void sendRequest(uint16_t addrTo);
|
||||
void sendBack(uint8_t* data = nullptr, uint8_t len = 0);
|
||||
void sendBackTo(uint16_t addrTo, 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 isr();
|
||||
|
||||
~IR_Encoder();
|
||||
volatile bool ir_out_virtual;
|
||||
|
||||
private:
|
||||
void IR_Encoder::_sendBack(bool isAdressed, uint16_t addrTo, uint8_t* data, uint8_t len);
|
||||
void IR_Encoder::_sendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint8_t len);
|
||||
|
||||
void IR_Encoder::setDecoder_isSending();
|
||||
void sendByte(uint8_t byte, bool* prev, bool LOW_FIRST);
|
||||
void addSync(bool* prev, bool* next);
|
||||
void sendByte(uint8_t byte, bool *prev, bool LOW_FIRST);
|
||||
void addSync(bool *prev, bool *next);
|
||||
void send_HIGH(bool = 1);
|
||||
void send_LOW();
|
||||
void send_EMPTY(uint8_t count);
|
||||
|
||||
enum SignalPart : uint8_t {
|
||||
enum SignalPart : uint8_t
|
||||
{
|
||||
noSignal = 0,
|
||||
preamb = 1,
|
||||
data = 2,
|
||||
sync = 3
|
||||
};
|
||||
|
||||
IR_DecoderRaw* decPair;
|
||||
IR_DecoderRaw** blindDecoders;
|
||||
IR_DecoderRaw *decPair;
|
||||
IR_DecoderRaw **blindDecoders;
|
||||
uint8_t decodersCount;
|
||||
|
||||
uint8_t sendLen;
|
||||
uint8_t sendBuffer[dataByteSizeMax] { 0 }; /// @brief Буффер данных для отправки
|
||||
uint8_t sendBuffer[dataByteSizeMax]{0}; /// @brief Буффер данных для отправки
|
||||
|
||||
volatile bool isSending;
|
||||
volatile bool state; /// @brief Текущий уровень генерации
|
||||
volatile bool state; /// @brief Текущий уровень генерации
|
||||
|
||||
volatile uint8_t dataByteCounter;
|
||||
|
||||
volatile uint8_t toggleCounter; /// @brief Счётчик переключений
|
||||
volatile uint8_t dataBitCounter;
|
||||
volatile uint8_t toggleCounter; /// @brief Счётчик переключений
|
||||
volatile uint8_t dataBitCounter;
|
||||
|
||||
volatile uint8_t preambFrontCounter;
|
||||
volatile uint8_t dataSequenceCounter;
|
||||
volatile uint8_t syncSequenceCounter;
|
||||
volatile bool syncLastBit;
|
||||
volatile uint8_t dataSequenceCounter;
|
||||
volatile uint8_t syncSequenceCounter;
|
||||
volatile bool syncLastBit;
|
||||
|
||||
struct BitSequence {
|
||||
struct BitSequence
|
||||
{
|
||||
uint8_t low;
|
||||
uint8_t high;
|
||||
};
|
||||
static inline uint8_t* bitHigh = new uint8_t[2] {
|
||||
static inline uint8_t *bitHigh = new uint8_t[2]{
|
||||
(bitPauseTakts * 2) * 2 - 1,
|
||||
(bitActiveTakts) * 2 - 1
|
||||
};
|
||||
static inline uint8_t* bitLow = new uint8_t[2] {
|
||||
(bitActiveTakts) * 2 - 1};
|
||||
static inline uint8_t *bitLow = new uint8_t[2]{
|
||||
(bitPauseTakts + bitActiveTakts) * 2 - 1,
|
||||
(bitPauseTakts) * 2 - 1
|
||||
};
|
||||
uint8_t* currentBitSequence = bitLow;
|
||||
(bitPauseTakts) * 2 - 1};
|
||||
uint8_t *currentBitSequence = bitLow;
|
||||
volatile SignalPart signal;
|
||||
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
||||
|
131
PacketTypes.h
131
PacketTypes.h
@ -2,9 +2,12 @@
|
||||
#include "IR_config.h"
|
||||
|
||||
class IR_Decoder;
|
||||
namespace PacketTypes {
|
||||
class BasePack {
|
||||
namespace PacketTypes
|
||||
{
|
||||
class BasePack
|
||||
{
|
||||
friend IR_Decoder;
|
||||
|
||||
protected:
|
||||
bool isAvailable;
|
||||
bool isRawAvailable;
|
||||
@ -15,49 +18,80 @@ namespace PacketTypes {
|
||||
uint8_t addressToOffset;
|
||||
uint8_t DataOffset;
|
||||
|
||||
IR_FOX::PackInfo* packInfo;
|
||||
IR_FOX::PackInfo *packInfo;
|
||||
uint16_t id;
|
||||
|
||||
virtual bool checkAddress(){return true;};
|
||||
void set(IR_FOX::PackInfo* packInfo, uint16_t id) {
|
||||
virtual bool checkAddress() { return true; };
|
||||
void set(IR_FOX::PackInfo *packInfo, uint16_t id)
|
||||
{
|
||||
this->packInfo = packInfo;
|
||||
this->id = id;
|
||||
|
||||
if (checkAddress()) {
|
||||
if (checkAddress())
|
||||
{
|
||||
isAvailable = true;
|
||||
isRawAvailable = true;
|
||||
#ifdef IRDEBUG_INFO
|
||||
#ifdef IRDEBUG_INFO
|
||||
Serial.print(" OK ");
|
||||
#endif
|
||||
} else {
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
isRawAvailable = true;
|
||||
#ifdef IRDEBUG_INFO
|
||||
#ifdef IRDEBUG_INFO
|
||||
Serial.print(" NOT-OK ");
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
static uint16_t _getAddrFrom(BasePack* obj) {
|
||||
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) {
|
||||
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) {
|
||||
static uint8_t _getDataSize(BasePack *obj)
|
||||
{
|
||||
return obj->packInfo->packSize - crcBytes - obj->DataOffset;
|
||||
};
|
||||
static uint8_t* _getDataPrt(BasePack* obj) {
|
||||
static uint8_t *_getDataPrt(BasePack *obj)
|
||||
{
|
||||
return obj->packInfo->buffer + obj->DataOffset;
|
||||
};
|
||||
static uint8_t _getDataRawSize(BasePack* obj) {
|
||||
static uint8_t _getDataRawSize(BasePack *obj)
|
||||
{
|
||||
return obj->packInfo->packSize;
|
||||
};
|
||||
|
||||
public:
|
||||
bool available() { if (isAvailable) { isAvailable = false; isRawAvailable = false; return true; } else { return false; } };
|
||||
bool availableRaw() { if (isRawAvailable) { isRawAvailable = false; return true; } else { return false; } };
|
||||
bool available()
|
||||
{
|
||||
if (isAvailable)
|
||||
{
|
||||
isAvailable = false;
|
||||
isRawAvailable = false;
|
||||
return true;
|
||||
}
|
||||
else
|
||||
{
|
||||
return false;
|
||||
}
|
||||
};
|
||||
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]; };
|
||||
@ -66,56 +100,65 @@ namespace PacketTypes {
|
||||
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; };
|
||||
uint8_t *getDataRawPtr() { return packInfo->buffer; };
|
||||
};
|
||||
|
||||
|
||||
class Data : public BasePack {
|
||||
class Data : public BasePack
|
||||
{
|
||||
public:
|
||||
Data() {
|
||||
Data()
|
||||
{
|
||||
msgOffset = 0;
|
||||
addressFromOffset = 1;
|
||||
addressToOffset = 3;
|
||||
DataOffset = 5;
|
||||
}
|
||||
|
||||
uint16_t getAddrFrom() { return _getAddrFrom(this); };
|
||||
uint16_t getAddrFrom() { return _getAddrFrom(this); };
|
||||
uint16_t getAddrTo() { return _getAddrTo(this); };
|
||||
|
||||
uint8_t getDataSize() { return _getDataSize(this); };
|
||||
uint8_t* getDataPrt() { return _getDataPrt(this); };
|
||||
uint8_t *getDataPrt() { return _getDataPrt(this); };
|
||||
uint8_t getDataRawSize() { return _getDataRawSize(this); };
|
||||
|
||||
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
|
||||
{
|
||||
public:
|
||||
DataBack() {
|
||||
DataBack()
|
||||
{
|
||||
msgOffset = 0;
|
||||
addressFromOffset = 1;
|
||||
addressToOffset = 3;
|
||||
DataOffset = 3;
|
||||
}
|
||||
|
||||
uint16_t getAddrFrom() { return _getAddrFrom(this); };
|
||||
uint16_t getAddrFrom() { return _getAddrFrom(this); };
|
||||
uint16_t getAddrTo() { return _getAddrTo(this); };
|
||||
|
||||
uint8_t getDataSize() { return _getDataSize(this); };
|
||||
uint8_t* getDataPrt() { return _getDataPrt(this); };
|
||||
uint8_t *getDataPrt() { return _getDataPrt(this); };
|
||||
uint8_t getDataRawSize() { return _getDataRawSize(this); };
|
||||
|
||||
private:
|
||||
bool checkAddress() override {
|
||||
bool checkAddress() override
|
||||
{
|
||||
bool ret;
|
||||
if (getMsgType() == IR_MSG_BACK_TO) {
|
||||
if (getMsgType() == IR_MSG_BACK_TO)
|
||||
{
|
||||
DataOffset = 5;
|
||||
IR_FOX::checkAddressRuleApply((packInfo->buffer[addressToOffset] << 8) | packInfo->buffer[addressToOffset + 1], this->id, ret);
|
||||
} else {
|
||||
}
|
||||
else
|
||||
{
|
||||
DataOffset = 3;
|
||||
ret = true;
|
||||
}
|
||||
@ -123,34 +166,40 @@ namespace PacketTypes {
|
||||
}
|
||||
};
|
||||
|
||||
class Accept : public BasePack {
|
||||
class Accept : public BasePack
|
||||
{
|
||||
public:
|
||||
Accept() {
|
||||
Accept()
|
||||
{
|
||||
msgOffset = 0;
|
||||
addressFromOffset = 1;
|
||||
DataOffset = 3;
|
||||
}
|
||||
|
||||
uint16_t getAddrFrom() { return _getAddrFrom(this); };
|
||||
uint16_t getAddrFrom() { return _getAddrFrom(this); };
|
||||
uint8_t getCustomByte() { return packInfo->buffer[DataOffset]; };
|
||||
|
||||
private:
|
||||
bool checkAddress() override { return true; }
|
||||
};
|
||||
|
||||
class Request : public BasePack {
|
||||
class Request : public BasePack
|
||||
{
|
||||
public:
|
||||
Request() {
|
||||
Request()
|
||||
{
|
||||
msgOffset = 0;
|
||||
addressFromOffset = 1;
|
||||
addressToOffset = 3;
|
||||
DataOffset = 3;
|
||||
}
|
||||
|
||||
uint16_t getAddrFrom() { return _getAddrFrom(this); };
|
||||
uint16_t getAddrFrom() { return _getAddrFrom(this); };
|
||||
uint16_t getAddrTo() { return _getAddrTo(this); };
|
||||
|
||||
private:
|
||||
bool checkAddress() override {
|
||||
bool checkAddress() override
|
||||
{
|
||||
bool ret;
|
||||
IR_FOX::checkAddressRuleApply(getAddrTo(), this->id, ret);
|
||||
return ret;
|
||||
@ -227,7 +276,7 @@ namespace PacketTypes {
|
||||
|
||||
// class IHasAddresData : virtual protected IBaseEmptyPack {
|
||||
// public:
|
||||
// virtual uint8_t getDataSize() { return packInfo->packSize - crcBytes - DataOffset; };
|
||||
// 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; };
|
||||
|
Loading…
x
Reference in New Issue
Block a user