mirror of
https://github.com/Show-maket/IR-protocol.git
synced 2025-06-28 05:09:40 +00:00
Compare commits
5 Commits
Author | SHA1 | Date | |
---|---|---|---|
37522f974f | |||
6375c4eed5 | |||
c4000d6b75 | |||
fc02c79135 | |||
d068a576f7 |
2
.gitignore
vendored
2
.gitignore
vendored
@ -1,5 +1,3 @@
|
|||||||
.vscode/*
|
.vscode/*
|
||||||
bin/*
|
bin/*
|
||||||
!.vscode/arduino.json
|
|
||||||
!.vscode/launch.json
|
|
||||||
log/*
|
log/*
|
8
.vscode/arduino.json
vendored
8
.vscode/arduino.json
vendored
@ -1,8 +0,0 @@
|
|||||||
{
|
|
||||||
"configuration": "flash=2097152_0,freq=133,opt=Small,rtti=Disabled,stackprotect=Disabled,exceptions=Disabled,dbgport=Disabled,dbglvl=None,usbstack=picosdk,ipbtstack=ipv4only,uploadmethod=default",
|
|
||||||
"board": "rp2040:rp2040:rpipico",
|
|
||||||
"port": "COM17",
|
|
||||||
"output": "bin",
|
|
||||||
"prebuild": "if exist bin rd /s /q bin",
|
|
||||||
"sketch": "IR-protocol.ino"
|
|
||||||
}
|
|
20
.vscode/launch.json
vendored
20
.vscode/launch.json
vendored
@ -1,20 +0,0 @@
|
|||||||
{
|
|
||||||
// Use IntelliSense to learn about possible attributes.
|
|
||||||
// Hover to view descriptions of existing attributes.
|
|
||||||
// For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387
|
|
||||||
"version": "0.2.0",
|
|
||||||
"configurations": [
|
|
||||||
|
|
||||||
{
|
|
||||||
"cwd": "${workspaceFolder}",
|
|
||||||
"executable": "${workspaceFolder}/bin/${workspaceFolderBasename}.ino.elf",
|
|
||||||
"name": "Debug with ST-Link",
|
|
||||||
"request": "launch",
|
|
||||||
"type": "cortex-debug",
|
|
||||||
"runToEntryPoint": "main",
|
|
||||||
"showDevDebugOutput": "raw",
|
|
||||||
"servertype": "stlink",
|
|
||||||
"armToolchainPath": "C://Program Files (x86)//Arm GNU Toolchain arm-none-eabi//13.2 Rel1//bin"
|
|
||||||
}
|
|
||||||
]
|
|
||||||
}
|
|
678
IR-protocol.ino
678
IR-protocol.ino
@ -1,44 +1,17 @@
|
|||||||
#include "IR_Decoder.h"
|
#include "IR_Decoder.h"
|
||||||
#include "IR_Encoder.h"
|
#include "IR_Encoder.h"
|
||||||
#include "TimerStatic.h"
|
#include "TimerStatic.h"
|
||||||
// #include "MemoryCheck.h"
|
#include "MemoryCheck.h"
|
||||||
|
#include "CarCmdList.h"
|
||||||
/////////////// Pinout ///////////////
|
/////////////// Pinout ///////////////
|
||||||
|
|
||||||
#define dec0_PIN 0
|
#define encForward_PIN 0
|
||||||
#define dec1_PIN 1
|
#define encBackward_PIN 5
|
||||||
#define dec2_PIN 2
|
|
||||||
#define dec3_PIN 3
|
|
||||||
#define dec4_PIN 4
|
|
||||||
#define dec5_PIN 5
|
|
||||||
#define dec6_PIN 6
|
|
||||||
#define dec7_PIN 7
|
|
||||||
#define dec8_PIN 8
|
|
||||||
#define dec9_PIN 9
|
|
||||||
#define dec10_PIN 10
|
|
||||||
#define dec11_PIN 11
|
|
||||||
#define dec12_PIN 12
|
|
||||||
#define dec13_PIN 13
|
|
||||||
#define dec14_PIN 14
|
|
||||||
#define dec15_PIN 15
|
|
||||||
|
|
||||||
#define LoopOut 16
|
#define LoopOut 12
|
||||||
#define LoopOut1 17
|
#define ISR_Out 10
|
||||||
|
|
||||||
#define dec_ISR(n) \
|
#define TestOut 13
|
||||||
void dec_##n##_ISR() { dec##n.isr(); }
|
|
||||||
#define dec_Ini(n) \
|
|
||||||
IR_Decoder dec##n(dec##n##_PIN, n); \
|
|
||||||
dec_ISR(n)
|
|
||||||
|
|
||||||
#define decPinMode(n) pinMode(dec##n##_PIN, INPUT_PULLUP);
|
|
||||||
#define decAttach(n) attachInterrupt(dec##n##_PIN, dec_##n##_ISR, CHANGE);
|
|
||||||
#define decSetup(n) /* decPinMode(n); */ decAttach(n);
|
|
||||||
#define decTick(n) dec##n.tick();
|
|
||||||
#define decStat(n) rx_flag |= statusSimple(dec##n);
|
|
||||||
|
|
||||||
void digitalToggle(uint8_t pin){
|
|
||||||
digitalWrite(pin, !digitalRead(pin));
|
|
||||||
}
|
|
||||||
|
|
||||||
//////////////// Ini /////////////////
|
//////////////// Ini /////////////////
|
||||||
|
|
||||||
@ -46,356 +19,258 @@ void digitalToggle(uint8_t pin){
|
|||||||
#define SERIAL_SPEED 115200
|
#define SERIAL_SPEED 115200
|
||||||
|
|
||||||
//////////////// Var /////////////////
|
//////////////// Var /////////////////
|
||||||
// IR_Encoder encForward(PA5, 42 /* , &decBackward */);
|
|
||||||
|
|
||||||
IR_Encoder enc0(18, 42 /* , &decBackward */);
|
IR_Decoder decForward(2, 555);
|
||||||
IR_Encoder enc1(19, 127 /* , &decBackward */);
|
IR_Decoder decBackward(3, 777);
|
||||||
IR_Encoder enc2(20, 137 /* , &decBackward */);
|
|
||||||
IR_Encoder enc3(21, 777 /* , &decBackward */);
|
|
||||||
// IR_Encoder enc10(PC15, 555 /* , &decBackward */);
|
|
||||||
// IR_Encoder enc11(PC14, 127 /* , &decBackward */);
|
|
||||||
// IR_Encoder enc12(PC13, 137 /* , &decBackward */);
|
|
||||||
// IR_Encoder enc13(PA12, 777 /* , &decBackward */);
|
|
||||||
|
|
||||||
|
IR_Encoder encForward(42/* , &decBackward */);
|
||||||
|
// IR_Encoder encBackward(321, encBackward_PIN);
|
||||||
// IR_Encoder encTree(325, A2);
|
// IR_Encoder encTree(325, A2);
|
||||||
|
|
||||||
//////////////////////// Функции прерываний ////////////////////////
|
//////////////////////// Функции прерываний ////////////////////////
|
||||||
|
|
||||||
void EncoderISR()
|
void decForwardISR() {
|
||||||
{
|
decForward.isr();
|
||||||
IR_Encoder::isr();
|
|
||||||
// digitalToggle(LoopOut);
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
//-------------------------------------------------------------------
|
void decBackwardISR() {
|
||||||
|
decBackward.isr();
|
||||||
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);
|
|
||||||
|
|
||||||
|
static uint8_t* portOut;
|
||||||
|
ISR(TIMER2_COMPA_vect) {
|
||||||
|
encForward.isr();
|
||||||
|
// encBackward.isr();
|
||||||
|
// encTree.isr();
|
||||||
|
//TODO: Сделать выбор порта
|
||||||
|
*portOut = (*portOut & 0b11111110) |
|
||||||
|
(
|
||||||
|
encForward.ir_out_virtual << 0U
|
||||||
|
// | encBackward.ir_out_virtual << 6U
|
||||||
|
// | encTree.ir_out_virtual << 2U
|
||||||
|
);
|
||||||
|
}
|
||||||
/////////////////////////////////////////////////////////////////////
|
/////////////////////////////////////////////////////////////////////
|
||||||
uint8_t data0[] = {};
|
uint8_t data0 [] = { };
|
||||||
uint8_t data1[] = {42};
|
uint8_t data1 [] = { 42 };
|
||||||
uint8_t data2[] = {42, 127};
|
uint8_t data2 [] = { 42 , 127 };
|
||||||
uint8_t data3[] = {42, 127, 137};
|
uint8_t data3 [] = { 42 , 127, 137 };
|
||||||
uint8_t data4[] = {42, 127, 137, 255};
|
uint8_t data4 [] = { 42 , 127, 137, 255 };
|
||||||
|
|
||||||
uint32_t loopTimer;
|
uint32_t loopTimer;
|
||||||
uint8_t sig = 0;
|
uint8_t sig = 255;
|
||||||
|
|
||||||
uint16_t targetAddr = IR_Broadcast;
|
uint16_t targetAddr = IR_Broadcast;
|
||||||
Timer t1(500, millis, []()
|
Timer t1(750, millis, []() {
|
||||||
{
|
|
||||||
// Serial.println( digitalPinToBitMask(enc0.getPin()), BIN);
|
|
||||||
enc0.sendData(IR_Broadcast, data4, sizeof(data4));
|
|
||||||
enc1.sendData(IR_Broadcast, data3, sizeof(data3));
|
|
||||||
enc2.sendData(IR_Broadcast, data2, sizeof(data2));
|
|
||||||
enc3.sendData(IR_Broadcast, data1, sizeof(data1));
|
|
||||||
// enc10.sendData(IR_Broadcast, data4, sizeof(data4));
|
|
||||||
// enc11.sendData(IR_Broadcast, data3, sizeof(data3));
|
|
||||||
// enc12.sendData(IR_Broadcast, data2, sizeof(data2));
|
|
||||||
// enc13.sendData(IR_Broadcast, data1, sizeof(data1));
|
|
||||||
|
|
||||||
// Serial.println(sig);
|
// Serial.println(sig);
|
||||||
|
|
||||||
// switch (sig)
|
switch (sig) {
|
||||||
// {
|
case 0:
|
||||||
// case 0:
|
encForward.sendData(targetAddr);
|
||||||
// encForward.sendData(targetAddr);
|
break;
|
||||||
// break;
|
case 1:
|
||||||
// case 1:
|
encForward.sendData(targetAddr, data1, sizeof(data1));
|
||||||
// encForward.sendData(targetAddr, data1, sizeof(data1));
|
break;
|
||||||
// break;
|
case 2:
|
||||||
// case 2:
|
encForward.sendData(targetAddr, data2, sizeof(data2));
|
||||||
// encForward.sendData(targetAddr, data2, sizeof(data2));
|
break;
|
||||||
// break;
|
case 3:
|
||||||
// case 3:
|
encForward.sendData(targetAddr, data3, sizeof(data3));
|
||||||
// encForward.sendData(targetAddr, data3, sizeof(data3));
|
break;
|
||||||
// break;
|
case 4:
|
||||||
// case 4:
|
encForward.sendData(targetAddr, data4, sizeof(data4));
|
||||||
// encForward.sendData(targetAddr, data4, sizeof(data4));
|
break;
|
||||||
// break;
|
|
||||||
|
|
||||||
// case 10:
|
case 10:
|
||||||
// encForward.sendData(targetAddr, data0, sizeof(data0), true);
|
encForward.sendData(targetAddr, data0, sizeof(data0), true);
|
||||||
// break;
|
break;
|
||||||
// case 11:
|
case 11:
|
||||||
// encForward.sendData(targetAddr, data1, sizeof(data1), true);
|
encForward.sendData(targetAddr, data1, sizeof(data1), true);
|
||||||
// break;
|
break;
|
||||||
// case 12:
|
case 12:
|
||||||
// encForward.sendData(targetAddr, data2, sizeof(data2), true);
|
encForward.sendData(targetAddr, data2, sizeof(data2), true);
|
||||||
// break;
|
break;
|
||||||
// case 13:
|
case 13:
|
||||||
// encForward.sendData(targetAddr, data3, sizeof(data3), true);
|
encForward.sendData(targetAddr, data3, sizeof(data3), true);
|
||||||
// break;
|
break;
|
||||||
// case 14:
|
case 14:
|
||||||
// encForward.sendData(targetAddr, data4, sizeof(data4), true);
|
encForward.sendData(targetAddr, data4, sizeof(data4), true);
|
||||||
// break;
|
break;
|
||||||
|
|
||||||
// case 20:
|
|
||||||
// encForward.sendBack();
|
|
||||||
// break;
|
|
||||||
// case 21:
|
|
||||||
// encForward.sendBack(data1, sizeof(data1));
|
|
||||||
// break;
|
|
||||||
// case 22:
|
|
||||||
// encForward.sendBack(data2, sizeof(data2));
|
|
||||||
// break;
|
|
||||||
// case 23:
|
|
||||||
// encForward.sendBack(data3, sizeof(data3));
|
|
||||||
// break;
|
|
||||||
// case 24:
|
|
||||||
// encForward.sendBack(data4, sizeof(data4));
|
|
||||||
// break;
|
|
||||||
|
|
||||||
// case 30:
|
|
||||||
// encForward.sendBackTo(targetAddr);
|
|
||||||
// break;
|
|
||||||
// case 31:
|
|
||||||
// encForward.sendBackTo(targetAddr, data1, sizeof(data1));
|
|
||||||
// break;
|
|
||||||
// case 32:
|
|
||||||
// encForward.sendBackTo(targetAddr, data2, sizeof(data2));
|
|
||||||
// break;
|
|
||||||
// case 33:
|
|
||||||
// encForward.sendBackTo(targetAddr, data3, sizeof(data3));
|
|
||||||
// break;
|
|
||||||
// case 34:
|
|
||||||
// encForward.sendBackTo(targetAddr, data4, sizeof(data4));
|
|
||||||
// break;
|
|
||||||
|
|
||||||
// case 41:
|
case 20:
|
||||||
// encForward.sendRequest(targetAddr);
|
encForward.sendBack();
|
||||||
// break;
|
break;
|
||||||
// case 42:
|
case 21:
|
||||||
// encForward.sendAccept(targetAddr);
|
encForward.sendBack(data1, sizeof(data1));
|
||||||
// break;
|
break;
|
||||||
|
case 22:
|
||||||
|
encForward.sendBack(data2, sizeof(data2));
|
||||||
|
break;
|
||||||
|
case 23:
|
||||||
|
encForward.sendBack(data3, sizeof(data3));
|
||||||
|
break;
|
||||||
|
case 24:
|
||||||
|
encForward.sendBack(data4, sizeof(data4));
|
||||||
|
break;
|
||||||
|
|
||||||
// default:
|
case 30:
|
||||||
// break;
|
encForward.sendBackTo(targetAddr);
|
||||||
// }
|
break;
|
||||||
// encBackward.sendData(IR_Broadcast, data2);
|
case 31:
|
||||||
// encTree.sendData(IR_Broadcast, rawData3);
|
encForward.sendBackTo(targetAddr, data1, sizeof(data1));
|
||||||
});
|
break;
|
||||||
// Timer t2(50, millis, []()
|
case 32:
|
||||||
// { digitalToggle(LED_BUILTIN); });
|
encForward.sendBackTo(targetAddr, data2, sizeof(data2));
|
||||||
|
break;
|
||||||
|
case 33:
|
||||||
|
encForward.sendBackTo(targetAddr, data3, sizeof(data3));
|
||||||
|
break;
|
||||||
|
case 34:
|
||||||
|
encForward.sendBackTo(targetAddr, data4, sizeof(data4));
|
||||||
|
break;
|
||||||
|
|
||||||
Timer signalDetectTimer;
|
case 41:
|
||||||
|
encForward.sendRequest(targetAddr);
|
||||||
|
break;
|
||||||
|
case 42:
|
||||||
|
encForward.sendAccept(targetAddr);
|
||||||
|
break;
|
||||||
|
|
||||||
|
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
// encBackward.sendData(IR_Broadcast, data2);
|
||||||
|
// encTree.sendData(IR_Broadcast, rawData3);
|
||||||
|
});
|
||||||
|
Timer t2(500, millis, []() {
|
||||||
|
digitalToggle(13);
|
||||||
|
});
|
||||||
/////////////////////////////////////////////////////////////////////
|
/////////////////////////////////////////////////////////////////////
|
||||||
// HardwareTimer IR_Timer(TIM3);
|
void setup() {
|
||||||
// RPI_PICO_Timer IR_Timer(0);
|
IR_Encoder::timerSetup();
|
||||||
struct repeating_timer timer;
|
portOut = &PORTB;
|
||||||
|
|
||||||
bool TimerISRHandler(struct repeating_timer *t){
|
|
||||||
(void) t;
|
|
||||||
EncoderISR();
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
void setup()
|
|
||||||
{
|
|
||||||
pinMode(LoopOut1, OUTPUT);
|
|
||||||
add_repeating_timer_us(6, TimerISRHandler, NULL, &timer);
|
|
||||||
|
|
||||||
// IR_Timer.setOverflow(carrierFrec * 2, HERTZ_FORMAT);
|
|
||||||
// IR_Timer.attachInterrupt(1, EncoderISR);
|
|
||||||
// NVIC_SetPriority(IRQn_Type::TIM3_IRQn, 0);
|
|
||||||
// IR_Timer.resume();
|
|
||||||
|
|
||||||
Serial.begin(SERIAL_SPEED);
|
Serial.begin(SERIAL_SPEED);
|
||||||
Serial.println(F(INFO));
|
Serial.println(F(INFO));
|
||||||
|
|
||||||
|
pinMode(A0, INPUT_PULLUP);
|
||||||
|
pinMode(A1, INPUT_PULLUP);
|
||||||
|
pinMode(A2, INPUT_PULLUP);
|
||||||
|
pinMode(A3, INPUT_PULLUP);
|
||||||
|
|
||||||
pinMode(LoopOut, OUTPUT);
|
pinMode(LoopOut, OUTPUT);
|
||||||
// pinMode(SignalDetectLed, OUTPUT);
|
pinMode(ISR_Out, OUTPUT);
|
||||||
|
|
||||||
pinMode(dec1_PIN, INPUT_PULLUP);
|
pinMode(2, INPUT_PULLUP);
|
||||||
// pinMode(dec2_PIN, INPUT_PULLUP);
|
pinMode(3, INPUT_PULLUP);
|
||||||
|
|
||||||
static IR_DecoderRaw *blind[]{
|
pinMode(8, OUTPUT);
|
||||||
&dec0,
|
pinMode(9, OUTPUT);
|
||||||
&dec1,
|
pinMode(11, OUTPUT);
|
||||||
&dec2,
|
pinMode(13, OUTPUT);
|
||||||
&dec3,
|
pinMode(encForward_PIN, OUTPUT);
|
||||||
&dec4,
|
pinMode(encBackward_PIN, OUTPUT);
|
||||||
&dec5,
|
pinMode(13, OUTPUT);
|
||||||
&dec6,
|
pinMode(12, OUTPUT);
|
||||||
&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);
|
|
||||||
}
|
|
||||||
|
|
||||||
void loop()
|
// IR_DecoderRaw* blindFromForward [] { &decForward, &decBackward };
|
||||||
{
|
// encForward.setBlindDecoders(blindFromForward, sizeof(blindFromForward) / sizeof(IR_DecoderRaw*));
|
||||||
digitalToggle(LoopOut);
|
|
||||||
|
|
||||||
|
|
||||||
|
attachInterrupt(0, decForwardISR, CHANGE); // D2
|
||||||
|
attachInterrupt(1, decBackwardISR, CHANGE); // D3
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
bool testLed = false;
|
||||||
|
uint32_t testLed_timer;
|
||||||
|
|
||||||
void loop1()
|
void loop() {
|
||||||
{
|
// digitalToggle(LoopOut);
|
||||||
Timer::tick();
|
Timer::tick();
|
||||||
IR_Decoder::tick();
|
|
||||||
|
|
||||||
bool rx_flag;
|
decForward.tick();
|
||||||
decStat(0);
|
decBackward.tick();
|
||||||
decStat(1);
|
|
||||||
decStat(2);
|
status(decForward);
|
||||||
decStat(3);
|
status(decBackward);
|
||||||
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);
|
// Serial.println(micros() - loopTimer);
|
||||||
// loopTimer = micros();
|
// loopTimer = micros();
|
||||||
// delayMicroseconds(120*5);
|
// delayMicroseconds(120*5);
|
||||||
|
|
||||||
if (Serial.available())
|
if (Serial.available()) {
|
||||||
{
|
|
||||||
uint8_t in = Serial.parseInt();
|
uint8_t in = Serial.parseInt();
|
||||||
switch (in)
|
switch (in) {
|
||||||
{
|
case 100:
|
||||||
case 100:
|
targetAddr = IR_Broadcast;
|
||||||
targetAddr = IR_Broadcast;
|
break;
|
||||||
break;
|
case 101:
|
||||||
case 101:
|
targetAddr = 555;
|
||||||
targetAddr = 555;
|
break;
|
||||||
break;
|
case 102:
|
||||||
case 102:
|
targetAddr = 777;
|
||||||
targetAddr = 777;
|
break;
|
||||||
break;
|
|
||||||
|
|
||||||
default:
|
default:
|
||||||
sig = in;
|
sig = in;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
Serial.println(in);
|
|
||||||
}
|
}
|
||||||
digitalToggle(LoopOut1);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
if(testLed && millis() - testLed_timer > 100){
|
||||||
|
testLed=false;
|
||||||
|
digitalWrite(12, LOW);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
Timer statusSimpleDelay;
|
|
||||||
bool statusSimple(IR_Decoder &dec)
|
|
||||||
{
|
|
||||||
bool ret;
|
|
||||||
if (ret = dec.gotData.available())
|
|
||||||
{
|
|
||||||
Serial.print("DEC: ");
|
|
||||||
Serial.print(dec.getId());
|
|
||||||
Serial.print(" err: ");
|
|
||||||
Serial.print(dec.gotData.getErrorCount());
|
|
||||||
Serial.print("\n");
|
|
||||||
statusSimpleDelay.delay(100, millis, []()
|
|
||||||
{ Serial.print("\n\n\n\n"); });
|
|
||||||
}
|
}
|
||||||
return ret;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void detectSignal()
|
|
||||||
{
|
|
||||||
// digitalWrite(SignalDetectLed, HIGH);
|
|
||||||
// signalDetectTimer.delay(50, millis, []()
|
|
||||||
// { digitalWrite(SignalDetectLed, LOW); });
|
|
||||||
}
|
|
||||||
|
|
||||||
// test
|
|
||||||
void status(IR_Decoder &dec)
|
|
||||||
{
|
|
||||||
if (dec.gotData.available())
|
|
||||||
{
|
//test
|
||||||
detectSignal();
|
void status(IR_Decoder& dec) {
|
||||||
Serial.println(micros());
|
if (dec.gotData.available() && dec.gotData.getAddrFrom() != 42) {
|
||||||
|
|
||||||
|
digitalWrite(12, HIGH);
|
||||||
|
testLed = true;
|
||||||
|
testLed_timer = millis();
|
||||||
|
|
||||||
|
encForward.sendData(IR_Broadcast, CarCmd::stop); //<<<<<<<<<<<<<<<<<<<<<<<<<<< CMD IS HERE
|
||||||
|
|
||||||
|
|
||||||
String str;
|
String str;
|
||||||
if (/* dec.gotData.getDataPrt()[1] */ 1)
|
if (/* dec.gotData.getDataPrt()[1] */1) {
|
||||||
{
|
str += ("Data on pin "); str += (dec.isrPin); str += "\n";
|
||||||
str += ("Data on pin ");
|
|
||||||
str += (dec.getPin());
|
|
||||||
str += "\n";
|
|
||||||
|
|
||||||
uint8_t msg = dec.gotData.getMsgRAW();
|
uint8_t msg = dec.gotData.getMsgRAW();
|
||||||
str += (" MSG: ");
|
str += (" MSG: ");
|
||||||
for (size_t i = 0; i < 8; i++)
|
for (size_t i = 0; i < 8; i++) {
|
||||||
{
|
if (i == 3) str += " ";
|
||||||
if (i == 3)
|
|
||||||
str += " ";
|
|
||||||
str += (msg >> (7 - i)) & 1U;
|
str += (msg >> (7 - i)) & 1U;
|
||||||
}
|
}
|
||||||
|
|
||||||
str += "\n";
|
str += "\n";
|
||||||
|
|
||||||
str += (" DATA SIZE: ");
|
str += (" DATA SIZE: "); str += (dec.gotData.getDataSize()); str += "\n";
|
||||||
str += (dec.gotData.getDataSize());
|
str += (" ADDRESS FROM: "); str += (dec.gotData.getAddrFrom()); str += "\n";
|
||||||
str += "\n";
|
str += (" ADDRESS TO: "); str += (dec.gotData.getAddrTo()); str += "\n";
|
||||||
str += (" ADDRESS FROM: ");
|
|
||||||
str += (dec.gotData.getAddrFrom());
|
|
||||||
str += "\n";
|
|
||||||
str += (" ADDRESS TO: ");
|
|
||||||
str += (dec.gotData.getAddrTo());
|
|
||||||
str += "\n";
|
|
||||||
// str += (" CRC PACK: "); str += (dec.gotData.getCrcIN()); str += "\n";
|
// str += (" CRC PACK: "); str += (dec.gotData.getCrcIN()); str += "\n";
|
||||||
// str += (" CRC CALC: "); str += (dec.gotData.getCrcCALC()); str += "\n";
|
// str += (" CRC CALC: "); str += (dec.gotData.getCrcCALC()); str += "\n";
|
||||||
str += "\n";
|
str += "\n";
|
||||||
|
|
||||||
for (size_t i = 0; i < min(uint8_t(10), dec.gotData.getDataSize()); i++)
|
for (size_t i = 0; i < min(10, dec.gotData.getDataSize()); i++) {
|
||||||
{
|
switch (i) {
|
||||||
switch (i)
|
|
||||||
{
|
|
||||||
// case 0:
|
// case 0:
|
||||||
// str += (" ADDR: ");
|
// str += (" ADDR: ");
|
||||||
// break;
|
// break;
|
||||||
@ -403,71 +278,49 @@ void status(IR_Decoder &dec)
|
|||||||
// str += (" CMD: ");
|
// str += (" CMD: ");
|
||||||
// break;
|
// break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
str += (" Data[");
|
str += (" Data["); str += (i); str += ("]: ");
|
||||||
str += (i);
|
break;
|
||||||
str += ("]: ");
|
|
||||||
break;
|
|
||||||
}
|
}
|
||||||
str += (dec.gotData.getDataPrt()[i]);
|
str += (dec.gotData.getDataPrt()[i]); str += "\n";
|
||||||
str += "\n";
|
|
||||||
}
|
}
|
||||||
|
|
||||||
str += ("\n*******ErrAll: ");
|
|
||||||
str += (dec.gotData.getErrorCount());
|
str += ("\n*******ErrAll: "); str += (dec.gotData.getErrorCount()); str += "\n";
|
||||||
str += "\n";
|
str += ("**ErrDistance: "); str += ((int)(dec.gotData.getErrorHighSignal() - dec.gotData.getErrorLowSignal())); str += "\n";
|
||||||
str += ("**ErrDistance: ");
|
|
||||||
str += ((int)(dec.gotData.getErrorHighSignal() - dec.gotData.getErrorLowSignal()));
|
|
||||||
str += "\n";
|
|
||||||
|
|
||||||
str += "\n";
|
str += "\n";
|
||||||
}
|
} else {
|
||||||
else
|
str += ("SELF"); str += "\n";
|
||||||
{
|
|
||||||
str += ("SELF");
|
|
||||||
str += "\n";
|
|
||||||
str += "\n";
|
str += "\n";
|
||||||
}
|
}
|
||||||
// obj->resetAvailable();
|
// obj->resetAvailable();
|
||||||
Serial.write(str.c_str());
|
Serial.write(str.c_str());
|
||||||
}
|
}
|
||||||
|
|
||||||
if (dec.gotBackData.available())
|
if (dec.gotBackData.available()) {
|
||||||
{
|
|
||||||
detectSignal();
|
|
||||||
String str;
|
String str;
|
||||||
if (/* dec.gotData.getDataPrt()[1] */ 1)
|
if (/* dec.gotData.getDataPrt()[1] */1) {
|
||||||
{
|
str += ("BackData on pin "); str += (dec.isrPin); str += "\n";
|
||||||
str += ("BackData on pin ");
|
|
||||||
str += (dec.getPin());
|
|
||||||
str += "\n";
|
|
||||||
|
|
||||||
uint8_t msg = dec.gotBackData.getMsgRAW();
|
uint8_t msg = dec.gotBackData.getMsgRAW();
|
||||||
str += (" MSG: ");
|
str += (" MSG: ");
|
||||||
for (size_t i = 0; i < 8; i++)
|
for (size_t i = 0; i < 8; i++) {
|
||||||
{
|
if (i == 3) str += " ";
|
||||||
if (i == 3)
|
|
||||||
str += " ";
|
|
||||||
str += (msg >> (7 - i)) & 1U;
|
str += (msg >> (7 - i)) & 1U;
|
||||||
}
|
}
|
||||||
|
|
||||||
str += "\n";
|
str += "\n";
|
||||||
|
|
||||||
str += (" DATA SIZE: ");
|
str += (" DATA SIZE: "); str += (dec.gotBackData.getDataSize()); str += "\n";
|
||||||
str += (dec.gotBackData.getDataSize());
|
str += (" ADDRESS FROM: "); str += (dec.gotBackData.getAddrFrom()); str += "\n";
|
||||||
str += "\n";
|
|
||||||
str += (" ADDRESS FROM: ");
|
|
||||||
str += (dec.gotBackData.getAddrFrom());
|
|
||||||
str += "\n";
|
|
||||||
// str += (" ADDRESS TO: "); str += (dec.gotBackData.getAddrTo()); str += "\n";
|
// str += (" ADDRESS TO: "); str += (dec.gotBackData.getAddrTo()); str += "\n";
|
||||||
// str += (" CRC PACK: "); str += (dec.gotBackData.getCrcIN()); str += "\n";
|
// str += (" CRC PACK: "); str += (dec.gotBackData.getCrcIN()); str += "\n";
|
||||||
// str += (" CRC CALC: "); str += (dec.gotBackData.getCrcCALC()); str += "\n";
|
// str += (" CRC CALC: "); str += (dec.gotBackData.getCrcCALC()); str += "\n";
|
||||||
str += "\n";
|
str += "\n";
|
||||||
|
|
||||||
for (size_t i = 0; i < min(uint8_t(10), dec.gotBackData.getDataSize()); i++)
|
for (size_t i = 0; i < min(10, dec.gotBackData.getDataSize()); i++) {
|
||||||
{
|
switch (i) {
|
||||||
switch (i)
|
|
||||||
{
|
|
||||||
// case 0:
|
// case 0:
|
||||||
// str += (" ADDR: ");
|
// str += (" ADDR: ");
|
||||||
// break;
|
// break;
|
||||||
@ -475,135 +328,98 @@ void status(IR_Decoder &dec)
|
|||||||
// str += (" CMD: ");
|
// str += (" CMD: ");
|
||||||
// break;
|
// break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
str += (" Data[");
|
str += (" Data["); str += (i); str += ("]: ");
|
||||||
str += (i);
|
break;
|
||||||
str += ("]: ");
|
|
||||||
break;
|
|
||||||
}
|
}
|
||||||
str += (dec.gotBackData.getDataPrt()[i]);
|
str += (dec.gotBackData.getDataPrt()[i]); str += "\n";
|
||||||
str += "\n";
|
|
||||||
}
|
}
|
||||||
|
|
||||||
str += ("\n*******ErrAll: ");
|
|
||||||
str += (dec.gotBackData.getErrorCount());
|
str += ("\n*******ErrAll: "); str += (dec.gotBackData.getErrorCount()); str += "\n";
|
||||||
str += "\n";
|
str += ("**ErrDistance: "); str += ((int)(dec.gotBackData.getErrorHighSignal() - dec.gotBackData.getErrorLowSignal())); str += "\n";
|
||||||
str += ("**ErrDistance: ");
|
|
||||||
str += ((int)(dec.gotBackData.getErrorHighSignal() - dec.gotBackData.getErrorLowSignal()));
|
|
||||||
str += "\n";
|
|
||||||
|
|
||||||
str += "\n";
|
str += "\n";
|
||||||
}
|
} else {
|
||||||
else
|
str += ("SELF"); str += "\n";
|
||||||
{
|
|
||||||
str += ("SELF");
|
|
||||||
str += "\n";
|
|
||||||
str += "\n";
|
str += "\n";
|
||||||
}
|
}
|
||||||
// obj->resetAvailable();
|
// obj->resetAvailable();
|
||||||
Serial.write(str.c_str());
|
Serial.write(str.c_str());
|
||||||
}
|
}
|
||||||
|
|
||||||
if (dec.gotAccept.available())
|
if (dec.gotAccept.available()) {
|
||||||
{
|
|
||||||
detectSignal();
|
|
||||||
String str;
|
String str;
|
||||||
if (/* dec.gotData.getDataPrt()[1] */ 1)
|
if (/* dec.gotData.getDataPrt()[1] */1) {
|
||||||
{
|
str += ("Accept on pin "); str += (dec.isrPin); str += "\n";
|
||||||
str += ("Accept on pin ");
|
|
||||||
str += (dec.getPin());
|
|
||||||
str += "\n";
|
|
||||||
|
|
||||||
uint8_t msg = dec.gotAccept.getMsgRAW();
|
uint8_t msg = dec.gotAccept.getMsgRAW();
|
||||||
str += (" MSG: ");
|
str += (" MSG: ");
|
||||||
for (size_t i = 0; i < 8; i++)
|
for (size_t i = 0; i < 8; i++) {
|
||||||
{
|
if (i == 3) str += " ";
|
||||||
if (i == 3)
|
|
||||||
str += " ";
|
|
||||||
str += (msg >> (7 - i)) & 1U;
|
str += (msg >> (7 - i)) & 1U;
|
||||||
}
|
}
|
||||||
|
|
||||||
str += "\n";
|
str += "\n";
|
||||||
|
|
||||||
// str += (" DATA SIZE: "); str += (dec.gotAccept.getDataSize()); str += "\n";
|
// str += (" DATA SIZE: "); str += (dec.gotAccept.getDataSize()); str += "\n";
|
||||||
str += (" ADDRESS FROM: ");
|
str += (" ADDRESS FROM: "); str += (dec.gotAccept.getAddrFrom()); str += "\n";
|
||||||
str += (dec.gotAccept.getAddrFrom());
|
|
||||||
str += "\n";
|
|
||||||
// str += (" ADDRESS TO: "); str += (dec.gotAccept.getAddrTo()); str += "\n";
|
// str += (" ADDRESS TO: "); str += (dec.gotAccept.getAddrTo()); str += "\n";
|
||||||
// str += (" CRC PACK: "); str += (dec.gotAccept.getCrcIN()); str += "\n";
|
// str += (" CRC PACK: "); str += (dec.gotAccept.getCrcIN()); str += "\n";
|
||||||
// str += (" CRC CALC: "); str += (dec.gotAccept.getCrcCALC()); str += "\n";
|
// str += (" CRC CALC: "); str += (dec.gotAccept.getCrcCALC()); str += "\n";
|
||||||
str += "\n";
|
str += "\n";
|
||||||
|
|
||||||
str += (" Data: ");
|
str += (" Data: "); str += (dec.gotAccept.getCustomByte());
|
||||||
str += (dec.gotAccept.getCustomByte());
|
|
||||||
|
|
||||||
str += ("\n\n*******ErrAll: ");
|
|
||||||
str += (dec.gotAccept.getErrorCount());
|
|
||||||
str += "\n";
|
str += ("\n\n*******ErrAll: "); str += (dec.gotAccept.getErrorCount()); str += "\n";
|
||||||
str += ("**ErrDistance: ");
|
str += ("**ErrDistance: "); str += ((int)(dec.gotAccept.getErrorHighSignal() - dec.gotAccept.getErrorLowSignal())); str += "\n";
|
||||||
str += ((int)(dec.gotAccept.getErrorHighSignal() - dec.gotAccept.getErrorLowSignal()));
|
|
||||||
str += "\n";
|
|
||||||
|
|
||||||
str += "\n";
|
str += "\n";
|
||||||
}
|
} else {
|
||||||
else
|
str += ("SELF"); str += "\n";
|
||||||
{
|
|
||||||
str += ("SELF");
|
|
||||||
str += "\n";
|
|
||||||
str += "\n";
|
str += "\n";
|
||||||
}
|
}
|
||||||
// obj->resetAvailable();
|
// obj->resetAvailable();
|
||||||
Serial.write(str.c_str());
|
Serial.write(str.c_str());
|
||||||
}
|
}
|
||||||
|
|
||||||
if (dec.gotRequest.available())
|
if (dec.gotRequest.available()) {
|
||||||
{
|
|
||||||
detectSignal();
|
|
||||||
String str;
|
String str;
|
||||||
if (/* dec.gotData.getDataPrt()[1] */ 1)
|
if (/* dec.gotData.getDataPrt()[1] */1) {
|
||||||
{
|
str += ("Request on pin "); str += (dec.isrPin); str += "\n";
|
||||||
str += ("Request on pin ");
|
|
||||||
str += (dec.getPin());
|
|
||||||
str += "\n";
|
|
||||||
|
|
||||||
uint8_t msg = dec.gotRequest.getMsgRAW();
|
uint8_t msg = dec.gotRequest.getMsgRAW();
|
||||||
str += (" MSG: ");
|
str += (" MSG: ");
|
||||||
for (size_t i = 0; i < 8; i++)
|
for (size_t i = 0; i < 8; i++) {
|
||||||
{
|
if (i == 3) str += " ";
|
||||||
if (i == 3)
|
|
||||||
str += " ";
|
|
||||||
str += (msg >> (7 - i)) & 1U;
|
str += (msg >> (7 - i)) & 1U;
|
||||||
}
|
}
|
||||||
|
|
||||||
str += "\n";
|
str += "\n";
|
||||||
|
|
||||||
// str += (" DATA SIZE: "); str += (dec.gotRequest.getDataSize()); str += "\n";
|
// str += (" DATA SIZE: "); str += (dec.gotRequest.getDataSize()); str += "\n";
|
||||||
str += (" ADDRESS FROM: ");
|
str += (" ADDRESS FROM: "); str += (dec.gotRequest.getAddrFrom()); str += "\n";
|
||||||
str += (dec.gotRequest.getAddrFrom());
|
str += (" ADDRESS TO: "); str += (dec.gotRequest.getAddrTo()); str += "\n";
|
||||||
str += "\n";
|
|
||||||
str += (" ADDRESS TO: ");
|
|
||||||
str += (dec.gotRequest.getAddrTo());
|
|
||||||
str += "\n";
|
|
||||||
// str += (" CRC PACK: "); str += (dec.gotRequest.getCrcIN()); str += "\n";
|
// str += (" CRC PACK: "); str += (dec.gotRequest.getCrcIN()); str += "\n";
|
||||||
// str += (" CRC CALC: "); str += (dec.gotRequest.getCrcCALC()); str += "\n";
|
// str += (" CRC CALC: "); str += (dec.gotRequest.getCrcCALC()); str += "\n";
|
||||||
str += "\n";
|
str += "\n";
|
||||||
|
|
||||||
str += ("\n*******ErrAll: ");
|
|
||||||
str += (dec.gotRequest.getErrorCount());
|
str += ("\n*******ErrAll: "); str += (dec.gotRequest.getErrorCount()); str += "\n";
|
||||||
str += "\n";
|
str += ("**ErrDistance: "); str += ((int)(dec.gotRequest.getErrorHighSignal() - dec.gotRequest.getErrorLowSignal())); str += "\n";
|
||||||
str += ("**ErrDistance: ");
|
|
||||||
str += ((int)(dec.gotRequest.getErrorHighSignal() - dec.gotRequest.getErrorLowSignal()));
|
|
||||||
str += "\n";
|
|
||||||
|
|
||||||
str += "\n";
|
str += "\n";
|
||||||
}
|
} else {
|
||||||
else
|
str += ("SELF"); str += "\n";
|
||||||
{
|
|
||||||
str += ("SELF");
|
|
||||||
str += "\n";
|
|
||||||
str += "\n";
|
str += "\n";
|
||||||
}
|
}
|
||||||
// obj->resetAvailable();
|
// obj->resetAvailable();
|
||||||
Serial.write(str.c_str());
|
Serial.write(str.c_str());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -1,72 +0,0 @@
|
|||||||
#include "IR_Decoder.h"
|
|
||||||
|
|
||||||
std::list<IR_Decoder*>& IR_Decoder::get_dec_list() // определение функции
|
|
||||||
{
|
|
||||||
static std::list<IR_Decoder*> dec_list; // статическая локальная переменная
|
|
||||||
return dec_list; // возвращается ссылка на переменную
|
|
||||||
}
|
|
||||||
|
|
||||||
IR_Decoder::IR_Decoder(const uint8_t pin, uint16_t addr, IR_Encoder *encPair)
|
|
||||||
: IR_DecoderRaw(pin, addr, encPair)
|
|
||||||
{
|
|
||||||
get_dec_list().push_back(this);
|
|
||||||
};
|
|
||||||
|
|
||||||
IR_Decoder::~IR_Decoder()
|
|
||||||
{
|
|
||||||
IR_Decoder::get_dec_list().remove(this);
|
|
||||||
}
|
|
||||||
|
|
||||||
void IR_Decoder::tick()
|
|
||||||
{
|
|
||||||
for (const auto &element : IR_Decoder::get_dec_list())
|
|
||||||
{
|
|
||||||
element->_tick();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void IR_Decoder::_tick()
|
|
||||||
{
|
|
||||||
IR_DecoderRaw::tick();
|
|
||||||
if (availableRaw())
|
|
||||||
{
|
|
||||||
#ifdef IRDEBUG_INFO
|
|
||||||
Serial.println("PARSING RAW DATA");
|
|
||||||
#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;
|
|
||||||
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
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;
|
|
||||||
}
|
|
||||||
gotRaw.set(&packInfo, id);
|
|
||||||
}
|
|
||||||
if (isWaitingAcceptSend && millis() - acceptSendTimer > 75)
|
|
||||||
{
|
|
||||||
encoder->sendAccept(addrAcceptSendTo, acceptCustomByte);
|
|
||||||
isWaitingAcceptSend = false;
|
|
||||||
}
|
|
||||||
}
|
|
58
IR_Decoder.h
58
IR_Decoder.h
@ -5,11 +5,6 @@
|
|||||||
|
|
||||||
class IR_Decoder : public IR_DecoderRaw
|
class IR_Decoder : public IR_DecoderRaw
|
||||||
{
|
{
|
||||||
private:
|
|
||||||
// static std::list<IR_Decoder *> dec_list;
|
|
||||||
static std::list<IR_Decoder*>& get_dec_list();
|
|
||||||
void _tick();
|
|
||||||
|
|
||||||
uint32_t acceptSendTimer;
|
uint32_t acceptSendTimer;
|
||||||
bool isWaitingAcceptSend;
|
bool isWaitingAcceptSend;
|
||||||
uint16_t addrAcceptSendTo;
|
uint16_t addrAcceptSendTo;
|
||||||
@ -24,16 +19,59 @@ public:
|
|||||||
PacketTypes::Request gotRequest;
|
PacketTypes::Request gotRequest;
|
||||||
PacketTypes::BasePack gotRaw;
|
PacketTypes::BasePack gotRaw;
|
||||||
|
|
||||||
IR_Decoder(const uint8_t pin, uint16_t addr, IR_Encoder *encPair = nullptr);
|
IR_Decoder(const uint8_t isrPin, uint16_t addr, IR_Encoder *encPair = nullptr) : IR_DecoderRaw(isrPin, addr, encPair) {}
|
||||||
~IR_Decoder();
|
|
||||||
|
|
||||||
static void tick();
|
void tick()
|
||||||
|
{
|
||||||
|
IR_DecoderRaw::tick();
|
||||||
|
if (availableRaw())
|
||||||
|
{
|
||||||
|
#ifdef IRDEBUG_INFO
|
||||||
|
Serial.println("PARSING RAW DATA");
|
||||||
|
#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;
|
||||||
|
|
||||||
inline void setAcceptDelay(uint16_t acceptDelay)
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
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;
|
||||||
|
}
|
||||||
|
gotRaw.set(&packInfo, id);
|
||||||
|
}
|
||||||
|
if (isWaitingAcceptSend && millis() - acceptSendTimer > 75)
|
||||||
|
{
|
||||||
|
encoder->sendAccept(addrAcceptSendTo, acceptCustomByte);
|
||||||
|
isWaitingAcceptSend = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void setAcceptDelay(uint16_t acceptDelay)
|
||||||
{
|
{
|
||||||
this->acceptDelay = acceptDelay;
|
this->acceptDelay = acceptDelay;
|
||||||
}
|
}
|
||||||
inline uint16_t getAcceptDelay()
|
uint16_t getAcceptDelay()
|
||||||
{
|
{
|
||||||
return this->acceptDelay;
|
return this->acceptDelay;
|
||||||
}
|
}
|
||||||
|
@ -1,85 +1,58 @@
|
|||||||
#include "IR_DecoderRaw.h"
|
#include "IR_DecoderRaw.h"
|
||||||
#include "IR_Encoder.h"
|
#include "IR_Encoder.h"
|
||||||
|
|
||||||
IR_DecoderRaw::IR_DecoderRaw(const uint8_t pin, uint16_t addr, IR_Encoder *encPair) : encoder(encPair)
|
IR_DecoderRaw::IR_DecoderRaw(const uint8_t isrPin, uint16_t addr, IR_Encoder *encPair = nullptr) : isrPin(isrPin), encoder(encPair)
|
||||||
{
|
{
|
||||||
setPin(pin);
|
|
||||||
pinMode(pin, INPUT_PULLUP);
|
|
||||||
id = addr;
|
id = addr;
|
||||||
prevRise = prevFall = prevPrevFall = prevPrevRise = 0;
|
prevRise = prevFall = prevPrevFall = prevPrevRise = 0;
|
||||||
if (encPair != nullptr)
|
if (encPair != nullptr)
|
||||||
{
|
{
|
||||||
encPair->decPair = this;
|
encPair->decPair = this;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef IRDEBUG
|
|
||||||
pinMode(wrHigh, OUTPUT);
|
|
||||||
pinMode(wrLow, OUTPUT);
|
|
||||||
pinMode(writeOp, OUTPUT);
|
|
||||||
pinMode(errOut, OUTPUT);
|
|
||||||
pinMode(up, OUTPUT);
|
|
||||||
pinMode(down, OUTPUT);
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bool IR_DecoderRaw::isSubOverflow()
|
|
||||||
{
|
|
||||||
noInterrupts();
|
|
||||||
volatile bool ret = isSubBufferOverflow;
|
|
||||||
interrupts();
|
|
||||||
return ret;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool IR_DecoderRaw::availableRaw()
|
|
||||||
{
|
|
||||||
if (isAvailable)
|
|
||||||
{
|
|
||||||
isAvailable = false;
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
};
|
|
||||||
|
|
||||||
//////////////////////////////////// isr ///////////////////////////////////////////
|
//////////////////////////////////// isr ///////////////////////////////////////////
|
||||||
volatile uint32_t time_;
|
|
||||||
|
|
||||||
void IR_DecoderRaw::isr()
|
void IR_DecoderRaw::isr()
|
||||||
{
|
{
|
||||||
|
if (isPairSending)
|
||||||
if(isPairSending){
|
|
||||||
return;
|
return;
|
||||||
}
|
|
||||||
|
|
||||||
noInterrupts();
|
subBuffer[currentSubBufferIndex].next = nullptr;
|
||||||
// time_ = HAL_GetTick() * 1000 + ((SysTick->LOAD + 1 - SysTick->VAL) * 1000) / SysTick->LOAD + 1;
|
subBuffer[currentSubBufferIndex].dir = (PIND >> isrPin) & 1;
|
||||||
time_ = micros();
|
subBuffer[currentSubBufferIndex].time = micros();
|
||||||
interrupts();
|
|
||||||
if (time_ < oldTime)
|
if (firstUnHandledFront == nullptr)
|
||||||
{
|
{
|
||||||
#ifdef IRDEBUG
|
firstUnHandledFront = &subBuffer[currentSubBufferIndex]; // Если нет необработанных данных - добавляем их
|
||||||
Serial.print("\n");
|
isSubBufferOverflow = false;
|
||||||
Serial.print("count: ");
|
|
||||||
Serial.println(wrongCounter++);
|
|
||||||
Serial.print("time: ");
|
|
||||||
Serial.println(time_);
|
|
||||||
Serial.print("oldTime: ");
|
|
||||||
Serial.println(oldTime);
|
|
||||||
Serial.print("sub: ");
|
|
||||||
Serial.println(max((uint32_t)time_, oldTime) - min((uint32_t)time_, oldTime));
|
|
||||||
#endif
|
|
||||||
time_ += 1000;
|
|
||||||
}
|
}
|
||||||
oldTime = time_;
|
else
|
||||||
|
{
|
||||||
|
if (firstUnHandledFront == &subBuffer[currentSubBufferIndex])
|
||||||
|
{ // Если контроллер не успел обработать новый сигнал, принудительно пропускаем его
|
||||||
|
firstUnHandledFront = firstUnHandledFront->next;
|
||||||
|
isSubBufferOverflow = true;
|
||||||
|
|
||||||
FrontStorage edge;
|
#ifdef IRDEBUG_INFO
|
||||||
// edge.dir = port->IDR & mask;
|
// Serial.println();
|
||||||
edge.dir = digitalRead(pin);
|
Serial.println(" ISR BUFFER OVERFLOW ");
|
||||||
edge.time = time_;
|
// Serial.println();
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
subBuffer.push(edge);
|
if (lastFront == nullptr)
|
||||||
|
{
|
||||||
|
lastFront = &subBuffer[currentSubBufferIndex];
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
lastFront->next = &subBuffer[currentSubBufferIndex];
|
||||||
|
lastFront = &subBuffer[currentSubBufferIndex];
|
||||||
|
}
|
||||||
|
|
||||||
|
currentSubBufferIndex == (subBufferSize - 1) ? currentSubBufferIndex = 0 : currentSubBufferIndex++; // Закольцовка буффера
|
||||||
}
|
}
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////////
|
||||||
@ -105,9 +78,7 @@ void IR_DecoderRaw::firstRX()
|
|||||||
|
|
||||||
isPreamb = true;
|
isPreamb = true;
|
||||||
riseSyncTime = bitTime /* 1100 */;
|
riseSyncTime = bitTime /* 1100 */;
|
||||||
#ifdef IRDEBUG
|
|
||||||
wrCounter = 0;
|
|
||||||
#endif
|
|
||||||
memset(dataBuffer, 0x00, dataByteSizeMax);
|
memset(dataBuffer, 0x00, dataByteSizeMax);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -124,113 +95,53 @@ void IR_DecoderRaw::listenStart()
|
|||||||
void IR_DecoderRaw::tick()
|
void IR_DecoderRaw::tick()
|
||||||
{
|
{
|
||||||
FrontStorage currentFront;
|
FrontStorage currentFront;
|
||||||
noInterrupts();
|
uint8_t oldSREG = SREG;
|
||||||
|
cli();
|
||||||
listenStart();
|
listenStart();
|
||||||
FrontStorage *currentFrontPtr;
|
if (firstUnHandledFront == nullptr)
|
||||||
currentFrontPtr = subBuffer.pop();
|
|
||||||
if (currentFrontPtr == nullptr)
|
|
||||||
{
|
{
|
||||||
isSubBufferOverflow = false;
|
isSubBufferOverflow = false;
|
||||||
interrupts();
|
SREG = oldSREG;
|
||||||
return;
|
return;
|
||||||
} // Если данных нет - ничего не делаем
|
} // Если данных нет - ничего не делаем
|
||||||
currentFront = *currentFrontPtr;
|
currentFront = *((FrontStorage *)firstUnHandledFront); // найти следующий необработанный фронт/спад
|
||||||
interrupts();
|
SREG = oldSREG;
|
||||||
|
if (currentFront.next == nullptr)
|
||||||
|
{
|
||||||
|
isRecive = false;
|
||||||
|
return;
|
||||||
|
}
|
||||||
////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
||||||
|
|
||||||
if (currentFront.dir)
|
|
||||||
{ // Если __/``` ↑
|
|
||||||
if (currentFront.time - prevRise > riseTimeMax / 4 || highCount || lowCount)
|
|
||||||
{ // комплексный фикс рваной единицы
|
|
||||||
risePeriod = currentFront.time - prevRise;
|
|
||||||
highTime = currentFront.time - prevFall;
|
|
||||||
lowTime = prevFall - prevRise;
|
|
||||||
prevRise = currentFront.time;
|
|
||||||
|
|
||||||
if (
|
|
||||||
risePeriod > UINT32_MAX - IR_timeout * 10 ||
|
|
||||||
highTime > UINT32_MAX - IR_timeout * 10 ||
|
|
||||||
lowTime > UINT32_MAX - IR_timeout * 10 ||
|
|
||||||
prevRise > UINT32_MAX - IR_timeout * 10)
|
|
||||||
{
|
|
||||||
#ifdef IRDEBUG
|
|
||||||
errPulse(down, 50);
|
|
||||||
|
|
||||||
// Serial.print("\n");
|
|
||||||
|
|
||||||
// Serial.print("risePeriod: ");
|
|
||||||
// Serial.println(risePeriod);
|
|
||||||
|
|
||||||
// Serial.print("highTime: ");
|
|
||||||
// Serial.println(highTime);
|
|
||||||
|
|
||||||
// Serial.print("lowTime: ");
|
|
||||||
// Serial.println(lowTime);
|
|
||||||
|
|
||||||
// Serial.print("prevRise: ");
|
|
||||||
// Serial.println(prevRise);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
errors.other++;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{ // Если ```\__ ↓
|
|
||||||
|
|
||||||
if (currentFront.time - prevFall > riseTimeMin / 4)
|
|
||||||
{
|
|
||||||
prevFall = currentFront.time;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
errors.other++;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#ifdef IRDEBUG
|
|
||||||
// goto END; //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
|
|
||||||
#endif
|
|
||||||
//----------------------------------------------------------------------------------
|
|
||||||
#ifdef IRDEBUG
|
|
||||||
digitalWrite(errOut, currentFront.dir);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (currentFront.time > prevRise && currentFront.time - prevRise > IR_timeout * 2 && !isRecive)
|
if (currentFront.time > prevRise && currentFront.time - prevRise > IR_timeout * 2 && !isRecive)
|
||||||
{ // первый
|
{ // первый
|
||||||
#ifdef IRDEBUG
|
|
||||||
errPulse(up, 50);
|
|
||||||
errPulse(down, 50);
|
|
||||||
errPulse(up, 150);
|
|
||||||
errPulse(down, 150);
|
|
||||||
#endif
|
|
||||||
preambFrontCounter = preambFronts - 1U;
|
preambFrontCounter = preambFronts - 1U;
|
||||||
isPreamb = true;
|
|
||||||
|
|
||||||
isRecive = true;
|
if (!currentFront.dir)
|
||||||
isWrongPack = false;
|
{
|
||||||
|
#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)
|
||||||
{ // в преамбуле
|
{ // в преамбуле
|
||||||
#ifdef IRDEBUG
|
uint32_t risePeriod;
|
||||||
Serial.print("risePeriod: ");
|
risePeriod = currentFront.time - prevRise;
|
||||||
Serial.println(risePeriod);
|
|
||||||
#endif
|
|
||||||
if (currentFront.dir && risePeriod < IR_timeout)
|
if (currentFront.dir && risePeriod < IR_timeout)
|
||||||
{ // __/``` ↑ и мы в внутри пакета
|
{ // __/``` ↑ и мы в внутри пакета
|
||||||
|
|
||||||
if (risePeriod < riseTimeMin / 2)
|
if (risePeriod < riseTimeMin << 1)
|
||||||
{ // fix рваной единицы
|
{ // fix рваной единицы
|
||||||
preambFrontCounter += 2;
|
preambFrontCounter += 2;
|
||||||
errors.other++;
|
errors.other++;
|
||||||
#ifdef IRDEBUG
|
|
||||||
errPulse(down, 350);
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
@ -250,183 +161,196 @@ void IR_DecoderRaw::tick()
|
|||||||
{
|
{
|
||||||
if (isPreamb)
|
if (isPreamb)
|
||||||
{ // первый фронт после
|
{ // первый фронт после
|
||||||
// gotTune.set(riseSyncTime);
|
// gotTune.set(riseSyncTime);
|
||||||
isPreamb = false;
|
|
||||||
#ifdef IRDEBUG
|
|
||||||
errPulse(up, 50);
|
|
||||||
errPulse(down, 50);
|
|
||||||
#endif
|
|
||||||
prevRise += risePeriod / 2;
|
|
||||||
// prevRise = currentFront.time + riseTime;
|
|
||||||
goto END;
|
|
||||||
}
|
}
|
||||||
|
isPreamb = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (isPreamb)
|
|
||||||
{
|
|
||||||
goto END;
|
|
||||||
}
|
|
||||||
if (risePeriod > IR_timeout || isBufferOverflow || risePeriod < riseTimeMin || isWrongPack)
|
|
||||||
// ~Мы в пределах таймаута и буффер не переполнен и fix дроблёных единиц
|
|
||||||
{
|
|
||||||
goto END;
|
|
||||||
}
|
|
||||||
|
|
||||||
// определить направление фронта
|
// определить направление фронта
|
||||||
if (currentFront.dir)
|
if (currentFront.dir)
|
||||||
{ // Если __/``` ↑
|
{ // Если __/``` ↑
|
||||||
highCount = 0;
|
|
||||||
lowCount = 0;
|
uint16_t risePeriod = currentFront.time - prevRise;
|
||||||
allCount = 0;
|
uint16_t highTime = currentFront.time - prevFall;
|
||||||
|
uint16_t lowTime = prevFall - prevRise;
|
||||||
|
|
||||||
|
int8_t highCount = 0;
|
||||||
|
int8_t lowCount = 0;
|
||||||
|
int8_t allCount = 0;
|
||||||
bool invertErr = false;
|
bool invertErr = false;
|
||||||
|
|
||||||
|
if (!isPreamb)
|
||||||
|
{
|
||||||
|
if (risePeriod < IR_timeout && !isBufferOverflow && risePeriod > riseTimeMin && !isWrongPack)
|
||||||
|
{
|
||||||
|
// Мы в пределах таймаута и буффер не переполнен и fix дроблёных единиц
|
||||||
|
|
||||||
|
if (aroundRise(risePeriod))
|
||||||
|
{ // тактирование есть, сигнал хороший - без ошибок(?)
|
||||||
|
|
||||||
|
if (highTime > riseTimeMin >> 1)
|
||||||
|
{ // 1
|
||||||
#ifdef IRDEBUG
|
#ifdef IRDEBUG
|
||||||
Serial.print("\n");
|
digitalWrite(wrHigh, 1);
|
||||||
|
#endif
|
||||||
|
writeToBuffer(HIGH);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{ // 0
|
||||||
|
#ifdef IRDEBUG
|
||||||
|
digitalWrite(wrLow, 1);
|
||||||
|
#endif
|
||||||
|
writeToBuffer(LOW);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{ // пропущены такты! сигнал средний // ошибка пропуска
|
||||||
|
highCount = ceil_div(highTime, riseTime); // предполагаемое колличество HIGH битов
|
||||||
|
lowCount = ceil_div(lowTime, riseTime); // предполагаемое колличество LOW битов
|
||||||
|
allCount = ceil_div(risePeriod, riseTime); // предполагаемое колличество всего битов
|
||||||
|
|
||||||
Serial.print("wrCounter: ");
|
if (highCount == 0 && highTime > riseTime / 3)
|
||||||
Serial.println(wrCounter++);
|
{ // fix короткой единицы (?)после пропуска нулей(?)
|
||||||
|
highCount++;
|
||||||
|
errors.other++;
|
||||||
|
#ifdef IRDEBUG
|
||||||
|
errPulse(errOut, 2);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
Serial.print("risePeriod: ");
|
if (lowCount + highCount > allCount)
|
||||||
Serial.println(risePeriod);
|
{ // fix ошибочных сдвигов
|
||||||
|
if (lowCount > highCount)
|
||||||
|
{ // Лишние нули
|
||||||
|
lowCount = allCount - highCount;
|
||||||
|
errors.lowSignal += lowCount;
|
||||||
|
#ifdef IRDEBUG
|
||||||
|
errPulse(errOut, 3);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
else if (lowCount < highCount)
|
||||||
|
{ // Лишние единицы
|
||||||
|
highCount = allCount - lowCount;
|
||||||
|
errors.highSignal += highCount;
|
||||||
|
#ifdef IRDEBUG
|
||||||
|
errPulse(errOut, 4);
|
||||||
|
#endif
|
||||||
|
// неизвестный случай Инверсит след бит или соседние
|
||||||
|
// Очень редко
|
||||||
|
// TODO: Отловить проверить
|
||||||
|
}
|
||||||
|
else if (lowCount == highCount)
|
||||||
|
{
|
||||||
|
invertErr = true;
|
||||||
|
// Serial.print("...");
|
||||||
|
errors.other += allCount;
|
||||||
|
}
|
||||||
|
// errorCounter += allCount;
|
||||||
|
}
|
||||||
|
|
||||||
Serial.print("highTime: ");
|
// errorCounter += allCount;
|
||||||
Serial.println(highTime);
|
// errors.other+=allCount;
|
||||||
|
if (lowCount < highCount)
|
||||||
|
{
|
||||||
|
errors.highSignal += highCount;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
errors.lowSignal += lowCount;
|
||||||
|
}
|
||||||
|
|
||||||
Serial.print("lowTime: ");
|
#ifdef IRDEBUG
|
||||||
Serial.println(lowTime);
|
errPulse(errOut, 1);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (aroundRise(risePeriod))
|
for (int8_t i = 0; i < lowCount && 8 - i; i++)
|
||||||
{ // тактирование есть, сигнал хороший - без ошибок(?)
|
{ // отправка LOW битов, если есть
|
||||||
|
if (i == lowCount - 1 && invertErr)
|
||||||
|
{
|
||||||
|
invertErr = false;
|
||||||
|
writeToBuffer(!LOW);
|
||||||
|
#ifdef IRDEBUG
|
||||||
|
digitalWrite(wrLow, 1);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
writeToBuffer(LOW);
|
||||||
|
#ifdef IRDEBUG
|
||||||
|
digitalWrite(wrLow, 1);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
if (highTime > lowTime)
|
for (int8_t i = 0; i < highCount && 8 - i; i++)
|
||||||
{ // 1
|
{ // отправка HIGH битов, если есть
|
||||||
|
if (i == highCount - 1 && invertErr)
|
||||||
|
{
|
||||||
|
invertErr = false;
|
||||||
|
writeToBuffer(!HIGH);
|
||||||
#ifdef IRDEBUG
|
#ifdef IRDEBUG
|
||||||
errPulse(wrHigh, 1);
|
digitalWrite(wrLow, 1);
|
||||||
#endif
|
#endif
|
||||||
writeToBuffer(HIGH);
|
}
|
||||||
}
|
else
|
||||||
else
|
{
|
||||||
{ // 0
|
writeToBuffer(HIGH);
|
||||||
#ifdef IRDEBUG
|
#ifdef IRDEBUG
|
||||||
errPulse(wrLow, 1);
|
digitalWrite(wrHigh, 1);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#ifdef IRDEBUG
|
||||||
|
digitalWrite(wrHigh, 0);
|
||||||
|
digitalWrite(wrLow, 0);
|
||||||
#endif
|
#endif
|
||||||
writeToBuffer(LOW);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
if (risePeriod > riseTimeMax / 2 || highCount || lowCount)
|
||||||
|
{ // комплексный фикс рваной единицы
|
||||||
|
prevPrevRise = prevRise;
|
||||||
|
prevRise = currentFront.time;
|
||||||
|
}
|
||||||
else
|
else
|
||||||
{ // пропущены такты! сигнал средний // ошибка пропуска
|
{
|
||||||
highCount = ceil_div(highTime, riseTime); // предполагаемое колличество HIGH битов
|
errors.other++;
|
||||||
lowCount = ceil_div(lowTime, riseTime); // предполагаемое колличество LOW битов
|
|
||||||
allCount = ceil_div(risePeriod, riseTime); // предполагаемое колличество всего битов
|
|
||||||
|
|
||||||
if (highCount == 0 && highTime > riseTime / 3)
|
|
||||||
{ // fix короткой единицы (?)после пропуска нулей(?)
|
|
||||||
highCount++;
|
|
||||||
errors.other++;
|
|
||||||
#ifdef IRDEBUG
|
#ifdef IRDEBUG
|
||||||
errPulse(up, 50);
|
errPulse(errOut, 5);
|
||||||
#endif
|
#endif
|
||||||
}
|
|
||||||
|
|
||||||
if (lowCount + highCount > allCount)
|
|
||||||
{ // fix ошибочных сдвигов
|
|
||||||
if (lowCount > highCount)
|
|
||||||
{ // Лишние нули
|
|
||||||
lowCount = allCount - highCount;
|
|
||||||
errors.lowSignal += lowCount;
|
|
||||||
#ifdef IRDEBUG
|
|
||||||
// errPulse(errOut, 3);
|
|
||||||
errPulse(down, 40);
|
|
||||||
errPulse(up, 10);
|
|
||||||
errPulse(down, 40);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
else if (lowCount < highCount)
|
|
||||||
{ // Лишние единицы
|
|
||||||
highCount = allCount - lowCount;
|
|
||||||
errors.highSignal += highCount;
|
|
||||||
#ifdef IRDEBUG
|
|
||||||
errPulse(down, 10);
|
|
||||||
errPulse(up, 40);
|
|
||||||
errPulse(down, 10);
|
|
||||||
// errPulse(errOut, 4);
|
|
||||||
#endif
|
|
||||||
// неизвестный случай Инверсит след бит или соседние
|
|
||||||
// Очень редко
|
|
||||||
// TODO: Отловить проверить
|
|
||||||
}
|
|
||||||
else if (lowCount == highCount)
|
|
||||||
{
|
|
||||||
#ifdef IRDEBUG
|
|
||||||
errPulse(down, 40);
|
|
||||||
errPulse(up, 40);
|
|
||||||
errPulse(down, 40);
|
|
||||||
#endif
|
|
||||||
invertErr = true;
|
|
||||||
// Serial.print("...");
|
|
||||||
errors.other += allCount;
|
|
||||||
}
|
|
||||||
// errorCounter += allCount;
|
|
||||||
}
|
|
||||||
|
|
||||||
// errorCounter += allCount;
|
|
||||||
// errors.other+=allCount;
|
|
||||||
if (lowCount < highCount)
|
|
||||||
{
|
|
||||||
errors.highSignal += highCount;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
errors.lowSignal += lowCount;
|
|
||||||
}
|
|
||||||
|
|
||||||
// errPulse(errOut, 1);
|
|
||||||
|
|
||||||
for (int8_t i = 0; i < lowCount && 8 - i; i++)
|
|
||||||
{ // отправка LOW битов, если есть
|
|
||||||
if (i == lowCount - 1 && invertErr)
|
|
||||||
{
|
|
||||||
invertErr = false;
|
|
||||||
writeToBuffer(HIGH);
|
|
||||||
#ifdef IRDEBUG
|
|
||||||
errPulse(wrHigh, 1);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
writeToBuffer(LOW);
|
|
||||||
#ifdef IRDEBUG
|
|
||||||
errPulse(wrLow, 1);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
for (int8_t i = 0; i < highCount && 8 - i; i++)
|
|
||||||
{ // отправка HIGH битов, если есть
|
|
||||||
if (i == highCount - 1 && invertErr)
|
|
||||||
{
|
|
||||||
invertErr = false;
|
|
||||||
writeToBuffer(LOW);
|
|
||||||
#ifdef IRDEBUG
|
|
||||||
errPulse(wrLow, 1);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
writeToBuffer(HIGH);
|
|
||||||
#ifdef IRDEBUG
|
|
||||||
errPulse(wrHigh, 1);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{ // Если ```\__ ↓
|
{ // Если ```\__ ↓
|
||||||
|
|
||||||
|
if (currentFront.time - prevFall > riseTimeMin)
|
||||||
|
{
|
||||||
|
prevPrevFall = prevFall;
|
||||||
|
prevFall = currentFront.time;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
#ifdef IRDEBUG
|
||||||
|
// errPulse(errOut, 5);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
if (isPreamb && preambFrontCounter <= 0)
|
||||||
END:;
|
{
|
||||||
|
prevRise = currentFront.time + riseTime;
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef IRDEBUG
|
||||||
|
digitalWrite(writeOp, isPreamb);
|
||||||
|
#endif
|
||||||
|
////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
||||||
|
oldSREG = SREG;
|
||||||
|
cli();
|
||||||
|
if (firstUnHandledFront != nullptr)
|
||||||
|
{
|
||||||
|
firstUnHandledFront = firstUnHandledFront->next; // переместить флаг на следующий элемент для обработки (next or nullptr)
|
||||||
|
}
|
||||||
|
SREG = oldSREG;
|
||||||
}
|
}
|
||||||
|
|
||||||
void IR_DecoderRaw::writeToBuffer(bool bit)
|
void IR_DecoderRaw::writeToBuffer(bool bit)
|
||||||
@ -555,7 +479,7 @@ void IR_DecoderRaw::writeToBuffer(bool bit)
|
|||||||
if (packSize && (i_dataBuffer == packSize * bitPerByte))
|
if (packSize && (i_dataBuffer == packSize * bitPerByte))
|
||||||
{ // Конец
|
{ // Конец
|
||||||
#ifdef IRDEBUG_INFO
|
#ifdef IRDEBUG_INFO
|
||||||
Serial.print(" END DATA " + crcCheck(packSize - crcBytes, crcValue) ? "OK " : "ERR ");
|
Serial.print(" END DATA ");
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
packInfo.buffer = dataBuffer;
|
packInfo.buffer = dataBuffer;
|
||||||
@ -566,34 +490,6 @@ void IR_DecoderRaw::writeToBuffer(bool bit)
|
|||||||
|
|
||||||
isRecive = false;
|
isRecive = false;
|
||||||
isAvailable = crcCheck(packSize - crcBytes, crcValue);
|
isAvailable = crcCheck(packSize - crcBytes, crcValue);
|
||||||
|
|
||||||
#ifdef BRUTEFORCE_CHECK
|
|
||||||
if (!isAvailable) // Исправление первого бита // Очень большая затычка...
|
|
||||||
for (size_t i = 0; i < min(uint16_t(packSize - crcBytes * 2U), uint16_t(dataByteSizeMax)); ++i)
|
|
||||||
{
|
|
||||||
for (int j = 0; j < 8; ++j)
|
|
||||||
{
|
|
||||||
// инвертируем бит
|
|
||||||
dataBuffer[i] ^= 1 << j;
|
|
||||||
|
|
||||||
isAvailable = crcCheck(min(uint16_t(packSize - crcBytes), uint16_t(dataByteSizeMax - 1U)), crcValue);
|
|
||||||
// обратно инвертируем бит в исходное состояние
|
|
||||||
|
|
||||||
if (isAvailable)
|
|
||||||
{
|
|
||||||
#ifdef IRDEBUG_INFO
|
|
||||||
Serial.println("!!!INV!!!");
|
|
||||||
#endif
|
|
||||||
goto OUT_BRUTEFORCE;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
dataBuffer[i] ^= 1 << j;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
OUT_BRUTEFORCE:;
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1,18 +1,15 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
#include "IR_config.h"
|
#include "IR_config.h"
|
||||||
#include "RingBuffer.h"
|
|
||||||
|
|
||||||
// #define IRDEBUG
|
// #define IRDEBUG
|
||||||
|
|
||||||
#ifdef IRDEBUG
|
#ifdef IRDEBUG
|
||||||
#define wrHigh PA1 // Запись HIGH инициирована // green
|
#define wrHigh A3 // Запись HIGH инициирована // green
|
||||||
#define wrLow PA0 // Запись LOW инициирована // blue
|
#define wrLow A3 // Запись LOW инициирована // blue
|
||||||
#define writeOp PA5 // Операция записи, 1 пульс для 0 и 2 для 1 // orange
|
#define writeOp 13 // Операция записи, 1 пульс для 0 и 2 для 1 // orange
|
||||||
// Исправленные ошибки // purle
|
// Исправленные ошибки // purle
|
||||||
// 1 пульс: fix
|
// 1 пульс: fix
|
||||||
#define errOut PA4
|
#define errOut A3
|
||||||
#define up PA3
|
|
||||||
#define down PA2
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/////////////////////////////////////////////////////////////////////////////////////////////////
|
/////////////////////////////////////////////////////////////////////////////////////////////////
|
||||||
@ -32,22 +29,42 @@ class IR_DecoderRaw : virtual public IR_FOX
|
|||||||
protected:
|
protected:
|
||||||
PackInfo packInfo;
|
PackInfo packInfo;
|
||||||
IR_Encoder *encoder; // Указатель на парный передатчик
|
IR_Encoder *encoder; // Указатель на парный передатчик
|
||||||
bool availableRaw();
|
bool availableRaw()
|
||||||
|
{
|
||||||
|
if (isAvailable)
|
||||||
|
{
|
||||||
|
isAvailable = false;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
const uint8_t isrPin; // Пин прерывания
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////
|
||||||
/// @brief Конструктор
|
/// @brief Конструктор
|
||||||
/// @param pin Номер вывода прерывания/данных от приёмника (2 или 3 для atmega 328p)
|
/// @param isrPin Номер вывода прерывания/данных от приёмника (2 или 3 для atmega 328p)
|
||||||
/// @param addr Адрес приёмника
|
/// @param addr Адрес приёмника
|
||||||
/// @param encPair Указатель на передатчик, работающий в паре
|
/// @param encPair Указатель на передатчик, работающий в паре
|
||||||
IR_DecoderRaw(const uint8_t pin, uint16_t addr, IR_Encoder *encPair = nullptr);
|
IR_DecoderRaw(const uint8_t isrPin, uint16_t addr, IR_Encoder *encPair = nullptr);
|
||||||
|
|
||||||
void isr(); // Функция прерывания
|
void isr(); // Функция прерывания
|
||||||
void tick(); // Обработка приёмника, необходима для работы
|
void tick(); // Обработка приёмника, необходима для работы
|
||||||
|
|
||||||
inline bool isOverflow() { return isBufferOverflow; }; // Буффер переполнился
|
bool isOverflow() { return isBufferOverflow; }; // Буффер переполнился
|
||||||
bool isSubOverflow();
|
bool isSubOverflow()
|
||||||
inline bool isReciving() { return isBufferOverflow; }; // Возвращает true, если происходит приём пакета
|
{
|
||||||
|
uint8_t oldSREG = SREG;
|
||||||
|
cli();
|
||||||
|
volatile bool ret = isSubBufferOverflow;
|
||||||
|
SREG = oldSREG;
|
||||||
|
return ret;
|
||||||
|
};
|
||||||
|
bool isReciving() { return isBufferOverflow; }; // Возвращает true, если происходит приём пакета
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////
|
||||||
private:
|
private:
|
||||||
@ -65,38 +82,23 @@ private:
|
|||||||
uint16_t riseSyncTime = bitTime; // Подстраиваемое время бита в мкс
|
uint16_t riseSyncTime = bitTime; // Подстраиваемое время бита в мкс
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////
|
||||||
volatile uint32_t currentSubBufferIndex; // Счетчик текущей позиции во вспомогательном буфере фронтов/спадов
|
volatile uint8_t currentSubBufferIndex; // Счетчик текущей позиции во вспомогательном буфере фронтов/спадов
|
||||||
|
|
||||||
struct FrontStorage
|
struct FrontStorage
|
||||||
{ // Структура для хранения времени и направления фронта/спада
|
{ // Структура для хранения времени и направления фронта/спада
|
||||||
volatile uint32_t time = 0; // Время
|
volatile uint32_t time = 0; // Время
|
||||||
volatile bool dir = false; // Направление (true = ↑; false = ↓)
|
volatile bool dir = false; // Направление (true = ↑; false = ↓)
|
||||||
// volatile FrontStorage *next = nullptr; // Указатель на следующий связанный фронт/спад, или nullptr если конец
|
volatile FrontStorage *next = nullptr; // Указатель на следующий связанный фронт/спад, или nullptr если конец
|
||||||
};
|
};
|
||||||
volatile FrontStorage *lastFront = nullptr; // Указатель последнего фронта/спада
|
volatile FrontStorage *lastFront = nullptr; // Указатель последнего фронта/спада
|
||||||
volatile FrontStorage *firstUnHandledFront = nullptr; // Указатель первого необработанного фронта/спада
|
volatile FrontStorage *firstUnHandledFront = nullptr; // Указатель первого необработанного фронта/спада
|
||||||
// volatile FrontStorage subBuffer[subBufferSize]; // вспомогательный буфер для хранения необработанных фронтов/спадов
|
volatile FrontStorage subBuffer[subBufferSize]; // вспомогательный буфер для хранения необработанных фронтов/спадов
|
||||||
|
|
||||||
RingBuffer<FrontStorage, subBufferSize> subBuffer;
|
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////
|
||||||
uint8_t dataBuffer[dataByteSizeMax]{0}; // Буффер данных
|
uint8_t dataBuffer[dataByteSizeMax]{0}; // Буффер данных
|
||||||
volatile uint32_t prevRise, prevPrevRise, prevFall, prevPrevFall; // Время предыдущих фронтов/спадов
|
uint32_t prevRise, prevPrevRise, prevFall, prevPrevFall; // Время предыдущих фронтов/спадов
|
||||||
|
uint16_t errorCounter = 0; // Счётчик ошибок
|
||||||
volatile uint32_t risePeriod;
|
int8_t preambFrontCounter = 0; // Счётчик __/``` ↑ преамбулы
|
||||||
volatile uint32_t highTime;
|
int16_t bufBitPos = 0; // Позиция для записи бита в буффер
|
||||||
volatile uint32_t lowTime;
|
|
||||||
|
|
||||||
uint32_t oldTime;
|
|
||||||
uint16_t wrongCounter;
|
|
||||||
|
|
||||||
int8_t highCount;
|
|
||||||
int8_t lowCount;
|
|
||||||
int8_t allCount;
|
|
||||||
|
|
||||||
uint16_t errorCounter = 0; // Счётчик ошибок
|
|
||||||
int8_t preambFrontCounter = 0; // Счётчик __/``` ↑ преамбулы
|
|
||||||
int16_t bufBitPos = 0; // Позиция для записи бита в буффер
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
void listenStart(); // @brief Слушатель для работы isReciving()
|
void listenStart(); // @brief Слушатель для работы isReciving()
|
||||||
@ -128,7 +130,6 @@ private:
|
|||||||
uint16_t ceil_div(uint16_t val, uint16_t divider);
|
uint16_t ceil_div(uint16_t val, uint16_t divider);
|
||||||
|
|
||||||
#ifdef IRDEBUG
|
#ifdef IRDEBUG
|
||||||
uint32_t wrCounter;
|
|
||||||
inline void errPulse(uint8_t pin, uint8_t count);
|
inline void errPulse(uint8_t pin, uint8_t count);
|
||||||
inline void infoPulse(uint8_t pin, uint8_t count);
|
inline void infoPulse(uint8_t pin, uint8_t count);
|
||||||
#endif
|
#endif
|
||||||
|
110
IR_Encoder.cpp
110
IR_Encoder.cpp
@ -5,16 +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(uint16_t addr, IR_DecoderRaw *decPair = nullptr)
|
||||||
{
|
{
|
||||||
static std::list<IR_Encoder*> dec_list; // статическая локальная переменная
|
|
||||||
return dec_list; // возвращается ссылка на переменную
|
|
||||||
}
|
|
||||||
|
|
||||||
IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair)
|
|
||||||
{
|
|
||||||
setPin(pin);
|
|
||||||
pinMode(pin,OUTPUT);
|
|
||||||
id = addr;
|
id = addr;
|
||||||
this->decPair = decPair;
|
this->decPair = decPair;
|
||||||
signal = noSignal;
|
signal = noSignal;
|
||||||
@ -31,9 +23,7 @@ IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair)
|
|||||||
{
|
{
|
||||||
decPair->encoder = this;
|
decPair->encoder = this;
|
||||||
}
|
}
|
||||||
get_enc_list().push_back(this);
|
|
||||||
};
|
};
|
||||||
|
|
||||||
void IR_Encoder::setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count)
|
void IR_Encoder::setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count)
|
||||||
{
|
{
|
||||||
#if disablePairDec
|
#if disablePairDec
|
||||||
@ -48,10 +38,9 @@ IR_Encoder::~IR_Encoder()
|
|||||||
{
|
{
|
||||||
delete[] bitLow;
|
delete[] bitLow;
|
||||||
delete[] bitHigh;
|
delete[] bitHigh;
|
||||||
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 = false)
|
||||||
{
|
{
|
||||||
uint8_t *dataPtr = new uint8_t[1];
|
uint8_t *dataPtr = new uint8_t[1];
|
||||||
dataPtr[0] = dataByte;
|
dataPtr[0] = dataByte;
|
||||||
@ -59,7 +48,10 @@ void IR_Encoder::sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept)
|
|||||||
delete[] dataPtr;
|
delete[] dataPtr;
|
||||||
}
|
}
|
||||||
|
|
||||||
void IR_Encoder::sendData(uint16_t addrTo, uint8_t *data, uint8_t len, bool needAccept)
|
void IR_Encoder::sendData(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false){
|
||||||
|
sendData(id, addrTo, data, len, needAccept);
|
||||||
|
}
|
||||||
|
void IR_Encoder::sendData(uint16_t addrFrom, uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false)
|
||||||
{
|
{
|
||||||
if (len > bytePerPack)
|
if (len > bytePerPack)
|
||||||
{
|
{
|
||||||
@ -76,8 +68,8 @@ void IR_Encoder::sendData(uint16_t addrTo, uint8_t *data, uint8_t len, bool need
|
|||||||
sendBuffer[0] = msgType;
|
sendBuffer[0] = msgType;
|
||||||
|
|
||||||
// addr_self
|
// addr_self
|
||||||
sendBuffer[1] = id >> 8 & 0xFF;
|
sendBuffer[1] = addrFrom >> 8 & 0xFF;
|
||||||
sendBuffer[2] = id & 0xFF;
|
sendBuffer[2] = addrFrom & 0xFF;
|
||||||
|
|
||||||
// addr_to
|
// addr_to
|
||||||
sendBuffer[3] = addrTo >> 8 & 0xFF;
|
sendBuffer[3] = addrTo >> 8 & 0xFF;
|
||||||
@ -103,7 +95,7 @@ void IR_Encoder::sendData(uint16_t addrTo, uint8_t *data, uint8_t len, bool need
|
|||||||
rawSend(sendBuffer, packSize);
|
rawSend(sendBuffer, packSize);
|
||||||
}
|
}
|
||||||
|
|
||||||
void IR_Encoder::sendAccept(uint16_t addrTo, uint8_t customByte)
|
void IR_Encoder::sendAccept(uint16_t addrTo, uint8_t customByte = 0)
|
||||||
{
|
{
|
||||||
constexpr uint8_t packsize = msgBytes + addrBytes + 1U + crcBytes;
|
constexpr uint8_t packsize = msgBytes + addrBytes + 1U + crcBytes;
|
||||||
memset(sendBuffer, 0x00, dataByteSizeMax);
|
memset(sendBuffer, 0x00, dataByteSizeMax);
|
||||||
@ -152,13 +144,12 @@ void IR_Encoder::sendBack(uint8_t data)
|
|||||||
{
|
{
|
||||||
_sendBack(false, 0, &data, 1);
|
_sendBack(false, 0, &data, 1);
|
||||||
}
|
}
|
||||||
|
void IR_Encoder::sendBack(uint8_t *data = nullptr, uint8_t len = 0)
|
||||||
void IR_Encoder::sendBack(uint8_t *data , uint8_t len)
|
|
||||||
{
|
{
|
||||||
_sendBack(false, 0, data, len);
|
_sendBack(false, 0, data, len);
|
||||||
}
|
}
|
||||||
|
|
||||||
void IR_Encoder::sendBackTo(uint16_t addrTo, uint8_t *data, uint8_t len)
|
void IR_Encoder::sendBackTo(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0)
|
||||||
{
|
{
|
||||||
_sendBack(true, addrTo, data, len);
|
_sendBack(true, addrTo, data, len);
|
||||||
}
|
}
|
||||||
@ -172,7 +163,7 @@ void IR_Encoder::_sendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint
|
|||||||
memset(sendBuffer, 0x00, dataByteSizeMax);
|
memset(sendBuffer, 0x00, dataByteSizeMax);
|
||||||
uint8_t dataStart = msgBytes + addrBytes + (isAdressed ? addrBytes : 0);
|
uint8_t dataStart = msgBytes + addrBytes + (isAdressed ? addrBytes : 0);
|
||||||
|
|
||||||
uint8_t packSize = msgBytes + addrBytes + (isAdressed ? addrBytes : 0) + min(uint8_t(1), len) + crcBytes;
|
uint8_t packSize = msgBytes + addrBytes + (isAdressed ? addrBytes : 0) + min(1, len) + crcBytes;
|
||||||
uint8_t msgType =
|
uint8_t msgType =
|
||||||
((isAdressed ? IR_MSG_BACK_TO : IR_MSG_BACK) << 5) | ((packSize) & (IR_MASK_MSG_INFO >> 1));
|
((isAdressed ? IR_MSG_BACK_TO : IR_MSG_BACK) << 5) | ((packSize) & (IR_MASK_MSG_INFO >> 1));
|
||||||
|
|
||||||
@ -222,7 +213,7 @@ void IR_Encoder::rawSend(uint8_t *ptr, uint8_t len)
|
|||||||
|
|
||||||
setDecoder_isSending();
|
setDecoder_isSending();
|
||||||
|
|
||||||
// noInterrupts();
|
cli();
|
||||||
sendLen = len;
|
sendLen = len;
|
||||||
toggleCounter = preambToggle; // Первая генерация для первого signal
|
toggleCounter = preambToggle; // Первая генерация для первого signal
|
||||||
|
|
||||||
@ -239,28 +230,16 @@ void IR_Encoder::rawSend(uint8_t *ptr, uint8_t len)
|
|||||||
|
|
||||||
currentBitSequence = bitHigh;
|
currentBitSequence = bitHigh;
|
||||||
isSending = true;
|
isSending = true;
|
||||||
// interrupts();
|
sei();
|
||||||
}
|
}
|
||||||
|
|
||||||
void IR_Encoder::isr(){
|
void IR_Encoder::isr()
|
||||||
// Serial.println(get_enc_list().size());
|
|
||||||
for(const auto &element : get_enc_list()){
|
|
||||||
element->_isr();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void IR_Encoder::_isr()
|
|
||||||
{
|
{
|
||||||
if (!isSending)
|
if (!isSending)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
ir_out_virtual = !ir_out_virtual && state;
|
ir_out_virtual = !ir_out_virtual && state;
|
||||||
|
|
||||||
// port->ODR &= ~(mask);
|
|
||||||
// port->ODR |= mask & (ir_out_virtual ? (uint16_t)0xFFFF : (uint16_t)0x0000);
|
|
||||||
digitalWrite(pin, ir_out_virtual);
|
|
||||||
|
|
||||||
|
|
||||||
if (toggleCounter)
|
if (toggleCounter)
|
||||||
{
|
{
|
||||||
toggleCounter--;
|
toggleCounter--;
|
||||||
@ -356,6 +335,32 @@ void IR_Encoder::_isr()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void old()
|
||||||
|
{ ///////////////////////////////////////////////////////
|
||||||
|
// void IR_Encoder::rawSend(uint8_t* ptr, uint8_t len) {
|
||||||
|
// /*tmp*/bool LOW_FIRST = false;/*tmp*/
|
||||||
|
|
||||||
|
// if (decoders != nullptr) { decoders->isPairSending = true; }
|
||||||
|
|
||||||
|
// bool prev = 1;
|
||||||
|
// bool next;
|
||||||
|
|
||||||
|
// send_EMPTY(preambPulse); // преамбула
|
||||||
|
// for (uint16_t byteNum = 0; byteNum < len; byteNum++) {
|
||||||
|
// sendByte(ptr[byteNum], &prev, LOW_FIRST);
|
||||||
|
// if (byteNum < len - 1) {
|
||||||
|
// next = ptr[byteNum + 1] & (LOW_FIRST ? 0b00000001 : 0b10000000);
|
||||||
|
// } else {
|
||||||
|
// next = 0;
|
||||||
|
// }
|
||||||
|
// addSync(&prev, &next);
|
||||||
|
// }
|
||||||
|
|
||||||
|
// if (decoders != nullptr) { decoders->isPairSending = false; }
|
||||||
|
|
||||||
|
// }
|
||||||
|
}
|
||||||
|
|
||||||
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;
|
uint8_t mask = LOW_FIRST ? 0b00000001 : 0b10000000;
|
||||||
@ -393,9 +398,30 @@ void IR_Encoder::addSync(bool *prev, bool *next)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t* IR_Encoder::bitHigh = new uint8_t[2]{
|
void IR_Encoder::send_HIGH(bool prevBite = 1)
|
||||||
(bitPauseTakts) * 2 - 1,
|
{
|
||||||
(bitActiveTakts) * 2 - 1};
|
|
||||||
uint8_t* IR_Encoder::bitLow = new uint8_t[2]{
|
// if (/* prevBite */1) {
|
||||||
(bitPauseTakts/2 + bitActiveTakts) * 2 - 1,
|
// meanderBlock(bitPauseTakts * 2, halfPeriod, LOW);
|
||||||
(bitPauseTakts) - 1};
|
// meanderBlock(bitActiveTakts, halfPeriod, HIGH);
|
||||||
|
// } else { // более короткий HIGH после нуля
|
||||||
|
// meanderBlock(bitTakts - (bitActiveTakts - bitPauseTakts), halfPeriod, LOW);
|
||||||
|
// meanderBlock(bitActiveTakts - bitPauseTakts, halfPeriod, HIGH);
|
||||||
|
// }
|
||||||
|
}
|
||||||
|
|
||||||
|
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)
|
||||||
|
{
|
||||||
|
// for (size_t i = 0; i < count * 2; i++) {
|
||||||
|
// meanderBlock((bitPauseTakts * 2 + bitActiveTakts), halfPeriod, prevPreambBit);
|
||||||
|
// prevPreambBit = !prevPreambBit;
|
||||||
|
// }
|
||||||
|
// meanderBlock(bitPauseTakts * 2 + bitActiveTakts, halfPeriod, 0); //TODO: Отодвинуть преамбулу
|
||||||
|
}
|
||||||
|
53
IR_Encoder.h
53
IR_Encoder.h
@ -4,27 +4,52 @@
|
|||||||
// TODO: Отложенная передача после завершения приема
|
// TODO: Отложенная передача после завершения приема
|
||||||
|
|
||||||
class IR_DecoderRaw;
|
class IR_DecoderRaw;
|
||||||
class IR_Encoder : IR_FOX
|
class IR_Encoder : public IR_FOX
|
||||||
{
|
{
|
||||||
friend IR_DecoderRaw;
|
friend IR_DecoderRaw;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
private:
|
private:
|
||||||
uint16_t id; /// @brief Адрес передатчика
|
// uint16_t id; /// @brief Адрес передатчика
|
||||||
public:
|
|
||||||
|
|
||||||
|
public:
|
||||||
/// @brief Класс передатчика
|
/// @brief Класс передатчика
|
||||||
/// @param addr Адрес передатчика
|
/// @param addr Адрес передатчика
|
||||||
/// @param pin Вывод передатчика
|
/// @param pin Вывод передатчика
|
||||||
|
/// @param tune Подстройка несущей частоты
|
||||||
/// @param decPair Приёмник, для которого отключается приём в момент передачи передатчиком
|
/// @param decPair Приёмник, для которого отключается приём в момент передачи передатчиком
|
||||||
IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair = nullptr);
|
IR_Encoder(uint16_t addr, IR_DecoderRaw *decPair = nullptr);
|
||||||
static void isr();
|
|
||||||
|
|
||||||
void setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count);
|
static void timerSetup()
|
||||||
|
{
|
||||||
|
// TIMER2 Ini
|
||||||
|
uint8_t oldSREG = SREG; // Save global interupts settings
|
||||||
|
cli();
|
||||||
|
// DDRB |= (1 << PORTB3); //OC2A (17)
|
||||||
|
TCCR2A = 0;
|
||||||
|
TCCR2B = 0;
|
||||||
|
|
||||||
|
// TCCR2A |= (1 << COM2A0); //Переключение состояния
|
||||||
|
|
||||||
|
TCCR2A |= (1 << WGM21); // Clear Timer On Compare (Сброс по совпадению)
|
||||||
|
TCCR2B |= (1 << CS20); // Предделитель 1
|
||||||
|
TIMSK2 |= (1 << OCIE2A); // Прерывание по совпадению
|
||||||
|
|
||||||
|
OCR2A = /* 465 */ ((F_CPU / (38000 * 2)) - 2); // 38кГц
|
||||||
|
|
||||||
|
SREG = oldSREG; // Return interrupt settings
|
||||||
|
}
|
||||||
|
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 rawSend(uint8_t *ptr, uint8_t len);
|
||||||
|
|
||||||
void sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept = false);
|
void sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept = false);
|
||||||
void sendData(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false);
|
void sendData(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false);
|
||||||
|
void sendData(uint16_t addrFrom, uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false);
|
||||||
|
|
||||||
void sendAccept(uint16_t addrTo, uint8_t customByte = 0);
|
void sendAccept(uint16_t addrTo, uint8_t customByte = 0);
|
||||||
void sendRequest(uint16_t addrTo);
|
void sendRequest(uint16_t addrTo);
|
||||||
@ -33,16 +58,15 @@ public:
|
|||||||
void sendBack(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 sendBackTo(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0);
|
||||||
|
|
||||||
|
void isr();
|
||||||
|
|
||||||
~IR_Encoder();
|
~IR_Encoder();
|
||||||
volatile bool ir_out_virtual;
|
volatile bool ir_out_virtual;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
static std::list<IR_Encoder*>& get_enc_list();
|
void IR_Encoder::_sendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint8_t len);
|
||||||
void _sendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint8_t len);
|
|
||||||
void _isr();
|
|
||||||
|
|
||||||
void setDecoder_isSending();
|
void IR_Encoder::setDecoder_isSending();
|
||||||
void sendByte(uint8_t byte, bool *prev, bool LOW_FIRST);
|
void sendByte(uint8_t byte, bool *prev, bool LOW_FIRST);
|
||||||
void addSync(bool *prev, bool *next);
|
void addSync(bool *prev, bool *next);
|
||||||
void send_HIGH(bool = 1);
|
void send_HIGH(bool = 1);
|
||||||
@ -82,9 +106,12 @@ private:
|
|||||||
uint8_t low;
|
uint8_t low;
|
||||||
uint8_t high;
|
uint8_t high;
|
||||||
};
|
};
|
||||||
static uint8_t *bitHigh;
|
static inline uint8_t *bitHigh = new uint8_t[2]{
|
||||||
static uint8_t *bitLow;
|
(bitPauseTakts * 2) * 2 - 1,
|
||||||
|
(bitActiveTakts) * 2 - 1};
|
||||||
|
static inline uint8_t *bitLow = new uint8_t[2]{
|
||||||
|
(bitPauseTakts + bitActiveTakts) * 2 - 1,
|
||||||
|
(bitPauseTakts) * 2 - 1};
|
||||||
uint8_t *currentBitSequence = bitLow;
|
uint8_t *currentBitSequence = bitLow;
|
||||||
volatile SignalPart signal;
|
volatile SignalPart signal;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -1,34 +0,0 @@
|
|||||||
#include "IR_config.h"
|
|
||||||
|
|
||||||
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)
|
|
||||||
{
|
|
||||||
flag = false;
|
|
||||||
flag |= id == 0;
|
|
||||||
flag |= address == id;
|
|
||||||
flag |= address >= IR_Broadcast;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t IR_FOX::crc8(uint8_t *data, uint8_t start, uint8_t end, uint8_t poly)
|
|
||||||
{ // TODO: сделать возможность межбайтовой проверки
|
|
||||||
uint8_t crc = 0xff;
|
|
||||||
size_t i, j;
|
|
||||||
for (i = start; i < end; i++)
|
|
||||||
{
|
|
||||||
crc ^= data[i];
|
|
||||||
for (j = 0; j < 8; j++)
|
|
||||||
{
|
|
||||||
if ((crc & 0x80) != 0)
|
|
||||||
crc = (uint8_t)((crc << 1) ^ poly);
|
|
||||||
else
|
|
||||||
crc <<= 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
return crc;
|
|
||||||
};
|
|
171
IR_config.h
171
IR_config.h
@ -1,13 +1,12 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
#include <list>
|
|
||||||
// #define IRDEBUG_INFO
|
// #define IRDEBUG_INFO
|
||||||
/*//////////////////////////////////////////////////////////////////////////////////////
|
/*//////////////////////////////////////////////////////////////////////////////////////
|
||||||
|
|
||||||
Для работы в паре положить декодер в энкодер
|
Для работы в паре положить декодер в энкодер
|
||||||
|
|
||||||
*/
|
*/// Адресация с 1 до 65 499
|
||||||
// Адресация с 1 до 65 499
|
|
||||||
#define IR_Broadcast 65000 // 65 500 ~ 65 535 - широковещательные пакеты (всем), возможно разделить на 35 типов
|
#define IR_Broadcast 65000 // 65 500 ~ 65 535 - широковещательные пакеты (всем), возможно разделить на 35 типов
|
||||||
/*
|
/*
|
||||||
Адрес 0 запрещен и зарезервирован под NULL, либо тесты
|
Адрес 0 запрещен и зарезервирован под NULL, либо тесты
|
||||||
@ -41,59 +40,59 @@ msg type:
|
|||||||
// | xxx..... | = тип сообщения
|
// | xxx..... | = тип сообщения
|
||||||
// | ...xxxxx | = длина (максимум 31 бита)
|
// | ...xxxxx | = длина (максимум 31 бита)
|
||||||
// ---------- */
|
// ---------- */
|
||||||
#define IR_MSG_BACK 0U // | 000...... | = Задний сигнал машинки
|
#define IR_MSG_BACK 0U // | 000...... | = Задний сигнал машинки
|
||||||
#define IR_MSG_ACCEPT 1U // | 001..... | = подтверждение
|
#define IR_MSG_ACCEPT 1U // | 001..... | = подтверждение
|
||||||
#define IR_MSG_REQUEST 2U // | 010..... | = запрос
|
#define IR_MSG_REQUEST 2U // | 010..... | = запрос
|
||||||
// #define IR_MSG_ 3U // | 011..... | = ??
|
#define IR_MSG_ 3U // | 011..... | = ??
|
||||||
#define IR_MSG_BACK_TO 4U // | 100..... | = Задний сигнал машинки c адресацией
|
#define IR_MSG_BACK_TO 4U // | 100..... | = Задний сигнал машинки c адресацией
|
||||||
// #define IR_MSG_ 5U // | 101..... | = ??
|
#define IR_MSG_ 5U // | 101..... | = ??
|
||||||
#define IR_MSG_DATA_NOACCEPT 6U // | 110..... | = данные, не требующие подтверждения
|
#define IR_MSG_DATA_NOACCEPT 6U // | 110..... | = данные, не требующие подтверждения
|
||||||
#define IR_MSG_DATA_ACCEPT 7U // | 111..... | = данные требующие подтверждения
|
#define IR_MSG_DATA_ACCEPT 7U // | 111..... | = данные требующие подтверждения
|
||||||
; /* // ----------
|
;/* // ----------
|
||||||
|
|
||||||
/``````````````````````````````` подтверждение `````````````````````````````\ /``````````````````````````````````````` запрос ``````````````````````````````````\
|
/``````````````````````````````` подтверждение `````````````````````````````\ /``````````````````````````````````````` запрос ``````````````````````````````````\
|
||||||
|
|
||||||
{``````````} [````````````````````````] [``````````````````] [``````````````] {``````````} [````````````````````````] [````````````````````````] [``````````````]
|
{``````````} [````````````````````````] [``````````````````] [``````````````] {``````````} [````````````````````````] [````````````````````````] [``````````````]
|
||||||
{ msg type } [ addr_from uint16_t ] [=== customByte ===] [ CRC Bytes ] { msg type } [ addr_from uint16_t ] [ addr_to uint16_t ] [ CRC Bytes ]
|
{ msg type } [ addr_from uint16_t ] [=== customByte ===] [ CRC Bytes ] { msg type } [ addr_from uint16_t ] [ addr_to uint16_t ] [ CRC Bytes ]
|
||||||
{..........} [........................] [..................] [..............] {..........} [........................] [........................] [..............]
|
{..........} [........................] [..................] [..............] {..........} [........................] [........................] [..............]
|
||||||
|
|
||||||
{ 001..... } [addr_from_H][addr_from_L] [=== customByte ===] [ crc1 ][ crc2 ] { 010..... } [addr_from_H][addr_from_L] [addr_from_H][addr_from_L] [ crc1 ][ crc2 ]
|
{ 001..... } [addr_from_H][addr_from_L] [=== customByte ===] [ crc1 ][ crc2 ] { 010..... } [addr_from_H][addr_from_L] [addr_from_H][addr_from_L] [ crc1 ][ crc2 ]
|
||||||
| 0 1 2 3 4 5 | 0 1 2 3 4 5 6
|
| 0 1 2 3 4 5 | 0 1 2 3 4 5 6
|
||||||
\________________________________________________________________/ | \_____________________________________________________________________/ |
|
\________________________________________________________________/ | \_____________________________________________________________________/ |
|
||||||
| | | |
|
| | | |
|
||||||
\________________________________________________________________________/ \_____________________________________________________________________________/
|
\________________________________________________________________________/ \_____________________________________________________________________________/
|
||||||
|
|
||||||
customByte - контрольная сумма принятых данных по poly1
|
customByte - контрольная сумма принятых данных по poly1
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/`````````````````````` Задний сигнал машинки без адресации ``````````````````````\
|
/`````````````````````` Задний сигнал машинки без адресации ``````````````````````\
|
||||||
|
|
||||||
{``````````} [````````````````````````] [````````````````````````] [``````````````]
|
{``````````} [````````````````````````] [````````````````````````] [``````````````]
|
||||||
{ msg type } [ addr_from uint16_t ] [====== data bytes ======] [ CRC Bytes ]
|
{ msg type } [ addr_from uint16_t ] [====== data bytes ======] [ CRC Bytes ]
|
||||||
{..........} [........................] [........................] [..............]
|
{..........} [........................] [........................] [..............]
|
||||||
|
|
||||||
{ 0000xxxx } [addr_from_H][addr_from_L] [data_H][data_n..][data_L] [ crc1 ][ crc2 ]
|
{ 0000xxxx } [addr_from_H][addr_from_L] [data_H][data_n..][data_L] [ crc1 ][ crc2 ]
|
||||||
| 0 1 2 3 | |
|
| 0 1 2 3 | |
|
||||||
\_____________________________________________________________________/ |
|
\_____________________________________________________________________/ |
|
||||||
| |
|
| |
|
||||||
\_____________________________________________________________________________/
|
\_____________________________________________________________________________/
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/```````````````````````````````````` Задний сигнал машинки с адресацией ````````````````````````````````````\
|
/```````````````````````````````````` Задний сигнал машинки с адресацией ````````````````````````````````````\
|
||||||
|
|
||||||
{``````````} [````````````````````````] [````````````````````````] [````````````````````````] [``````````````]
|
{``````````} [````````````````````````] [````````````````````````] [````````````````````````] [``````````````]
|
||||||
{ msg type } [ addr_from uint16_t ] [ addr_to uint16_t ] [====== data bytes ======] [ CRC Bytes ]
|
{ msg type } [ addr_from uint16_t ] [ addr_to uint16_t ] [====== data bytes ======] [ CRC Bytes ]
|
||||||
{..........} [........................] [........................] [........................] [..............]
|
{..........} [........................] [........................] [........................] [..............]
|
||||||
|
|
||||||
{ 0001xxxx } [addr_from_H][addr_from_L] [addr_from_H][addr_from_L] [data_H][data_n..][data_L] [ crc1 ][ crc2 ]
|
{ 0001xxxx } [addr_from_H][addr_from_L] [addr_from_H][addr_from_L] [data_H][data_n..][data_L] [ crc1 ][ crc2 ]
|
||||||
| 0 1 2 3 4 5 | |
|
| 0 1 2 3 4 5 | |
|
||||||
\________________________________________________________________________________________________/ |
|
\________________________________________________________________________________________________/ |
|
||||||
| |
|
| |
|
||||||
\________________________________________________________________________________________________________/
|
\________________________________________________________________________________________________________/
|
||||||
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define IR_MASK_MSG_TYPE 0b00000111
|
#define IR_MASK_MSG_TYPE 0b00000111
|
||||||
#define IR_MASK_MSG_INFO 0b00011111
|
#define IR_MASK_MSG_INFO 0b00011111
|
||||||
@ -102,14 +101,13 @@ msg type:
|
|||||||
/////////////////////////////////////////////////////////////////////////////////////*/
|
/////////////////////////////////////////////////////////////////////////////////////*/
|
||||||
typedef uint16_t crc_t;
|
typedef uint16_t crc_t;
|
||||||
|
|
||||||
// #define BRUTEFORCE_CHECK // Перепроверяет пакет на 1 битные ошибки //TODO: зависает
|
#define bytePerPack 16 // колличество байтов в пакете
|
||||||
#define bytePerPack 16 // колличество байтов в пакете
|
|
||||||
#ifndef freeFrec
|
#ifndef freeFrec
|
||||||
#define freeFrec false
|
#define freeFrec true
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef subBufferSize
|
#ifndef subBufferSize
|
||||||
#define subBufferSize 50 // Буфер для складирования фронтов, пока их не обработают (передатчик)
|
#define subBufferSize 35 //Буфер для складирования фронтов, пока их не обработают (передатчик)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define preambPulse 3
|
#define preambPulse 3
|
||||||
@ -118,35 +116,33 @@ typedef uint16_t crc_t;
|
|||||||
|
|
||||||
/////////////////////////////////////////////////////////////////////////////////////
|
/////////////////////////////////////////////////////////////////////////////////////
|
||||||
|
|
||||||
#define bitPerByte 8U // Колличество бит в байте
|
#define bitPerByte 8U // Колличество бит в байте
|
||||||
#define addrBytes 2
|
#define addrBytes 2
|
||||||
#define msgBytes 1
|
#define msgBytes 1
|
||||||
#define crcBytes 2
|
#define crcBytes 2
|
||||||
#define poly1 0x31
|
#define poly1 0x31
|
||||||
#define poly2 0x8C
|
#define poly2 0x8C
|
||||||
#define syncBits 3U // количество битов синхронизации
|
#define syncBits 3U // количество битов синхронизации
|
||||||
|
|
||||||
#define dataByteSizeMax (msgBytes + addrBytes + addrBytes + bytePerPack + crcBytes)
|
#define dataByteSizeMax (msgBytes + addrBytes + addrBytes + bytePerPack + crcBytes)
|
||||||
|
|
||||||
#define preambFronts (preambPulse * 2) // количество фронтов преамбулы (Приём)
|
#define preambFronts (preambPulse*2) // количество фронтов преамбулы (Приём)
|
||||||
#define preambToggle ((bitPauseTakts * 2 + bitActiveTakts) * 2 - 1) // колличество переключений преамбулы (Передача)
|
#define preambToggle ((bitPauseTakts * 2 + bitActiveTakts) * 2 - 1) // колличество переключений преамбулы (Передача)
|
||||||
|
|
||||||
#define carrierFrec 38000U // частота несущей (Приём/Передача)
|
#define carrierFrec 38000U // частота несущей (Приём/Передача)
|
||||||
#define carrierPeriod (1000000U / carrierFrec) // период несущей в us (Приём)
|
#define carrierPeriod (1000000U/carrierFrec) // период несущей в us (Приём)
|
||||||
|
|
||||||
// В процессе работы значения будут отклонятся в соответствии с предыдущим битом
|
// В процессе работы значения будут отклонятся в соответствии с предыдущим битом
|
||||||
#define bitActiveTakts 25U // длительность высокого уровня в тактах
|
#define bitActiveTakts 25U // длительность высокого уровня в тактах
|
||||||
#define bitPauseTakts 12U // длительность низкого уровня в тактах
|
#define bitPauseTakts 6U // длительность низкого уровня в тактах
|
||||||
|
|
||||||
#define bitTakts (bitActiveTakts + bitPauseTakts) // Общая длительность бита в тактах
|
#define bitTakts (bitActiveTakts+(bitPauseTakts*2U)) // Общая длительность бита в тактах
|
||||||
#define bitTime (bitTakts * carrierPeriod) // Общая длительность бита
|
#define bitTime (bitTakts*carrierPeriod) // Общая длительность бита
|
||||||
#define tolerance 300U
|
#define tolerance 300U
|
||||||
|
|
||||||
class IR_FOX
|
class IR_FOX {
|
||||||
{
|
|
||||||
public:
|
public:
|
||||||
struct PackOffsets
|
struct PackOffsets {
|
||||||
{
|
|
||||||
uint8_t msgOffset;
|
uint8_t msgOffset;
|
||||||
uint8_t addrFromOffset;
|
uint8_t addrFromOffset;
|
||||||
uint8_t addrToOffset;
|
uint8_t addrToOffset;
|
||||||
@ -154,41 +150,54 @@ public:
|
|||||||
uint8_t crcOffset;
|
uint8_t crcOffset;
|
||||||
};
|
};
|
||||||
|
|
||||||
struct ErrorsStruct
|
struct ErrorsStruct {
|
||||||
{
|
|
||||||
uint8_t lowSignal = 0;
|
uint8_t lowSignal = 0;
|
||||||
uint8_t highSignal = 0;
|
uint8_t highSignal = 0;
|
||||||
uint8_t other = 0;
|
uint8_t other = 0;
|
||||||
|
|
||||||
void reset()
|
void reset() {
|
||||||
{
|
|
||||||
lowSignal = 0;
|
lowSignal = 0;
|
||||||
highSignal = 0;
|
highSignal = 0;
|
||||||
other = 0;
|
other = 0;
|
||||||
}
|
}
|
||||||
uint16_t all() { return lowSignal + highSignal + other; }
|
uint16_t all() { return lowSignal + highSignal + other; }
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
struct PackInfo
|
struct PackInfo {
|
||||||
{
|
uint8_t* buffer = nullptr;
|
||||||
uint8_t *buffer = nullptr;
|
|
||||||
uint8_t packSize = 0;
|
uint8_t packSize = 0;
|
||||||
uint16_t crc = 0;
|
uint16_t crc = 0;
|
||||||
ErrorsStruct err;
|
ErrorsStruct err;
|
||||||
uint16_t rTime = 0;
|
uint16_t rTime = 0;
|
||||||
};
|
};
|
||||||
|
|
||||||
inline uint16_t getId() { return id; }
|
static void checkAddressRuleApply(uint16_t address, uint16_t id, bool& flag) {
|
||||||
inline void setId(uint16_t id) { this->id = id; }
|
flag = false;
|
||||||
static void checkAddressRuleApply(uint16_t address, uint16_t id, bool &flag);
|
flag |= id == 0;
|
||||||
void setPin(uint8_t pin);
|
flag |= address == id;
|
||||||
inline uint8_t getPin(){return pin;};
|
flag |= address >= IR_Broadcast;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t getId() { return id; }
|
||||||
|
void setId(uint16_t id) { this->id = id; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
uint16_t id;
|
|
||||||
uint8_t pin;
|
|
||||||
// GPIO_TypeDef *port;
|
|
||||||
uint16_t mask;
|
|
||||||
ErrorsStruct errors;
|
ErrorsStruct errors;
|
||||||
uint8_t crc8(uint8_t *data, uint8_t start, uint8_t end, uint8_t poly);
|
uint16_t id;
|
||||||
|
uint8_t crc8(uint8_t* data, uint8_t start, uint8_t end, uint8_t poly) { //TODO: сделать возможность межбайтовой проверки
|
||||||
|
uint8_t crc = 0xff;
|
||||||
|
size_t i, j;
|
||||||
|
for (i = start; i < end; i++) {
|
||||||
|
crc ^= data[i];
|
||||||
|
for (j = 0; j < 8; j++) {
|
||||||
|
if ((crc & 0x80) != 0)
|
||||||
|
crc = (uint8_t)((crc << 1) ^ poly);
|
||||||
|
else
|
||||||
|
crc <<= 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return crc;
|
||||||
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
107
PacketTypes.cpp
107
PacketTypes.cpp
@ -1,107 +0,0 @@
|
|||||||
#include "PacketTypes.h"
|
|
||||||
|
|
||||||
namespace PacketTypes
|
|
||||||
{
|
|
||||||
bool BasePack::checkAddress() { return true; };
|
|
||||||
void BasePack::set(IR_FOX::PackInfo *packInfo, uint16_t id)
|
|
||||||
{
|
|
||||||
this->packInfo = packInfo;
|
|
||||||
this->id = id;
|
|
||||||
|
|
||||||
if (checkAddress())
|
|
||||||
{
|
|
||||||
isAvailable = true;
|
|
||||||
isRawAvailable = true;
|
|
||||||
#ifdef IRDEBUG_INFO
|
|
||||||
Serial.print(" OK ");
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
isRawAvailable = true;
|
|
||||||
#ifdef IRDEBUG_INFO
|
|
||||||
Serial.print(" NOT-OK ");
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
uint16_t BasePack::_getAddrFrom(BasePack *obj)
|
|
||||||
{
|
|
||||||
return (obj->packInfo->buffer[obj->addressFromOffset] << 8) | obj->packInfo->buffer[obj->addressFromOffset + 1];
|
|
||||||
};
|
|
||||||
uint16_t BasePack::_getAddrTo(BasePack *obj)
|
|
||||||
{
|
|
||||||
return (obj->packInfo->buffer[obj->addressToOffset] << 8) | obj->packInfo->buffer[obj->addressToOffset + 1];
|
|
||||||
};
|
|
||||||
|
|
||||||
uint8_t BasePack::_getDataSize(BasePack *obj)
|
|
||||||
{
|
|
||||||
return obj->packInfo->packSize - crcBytes - obj->DataOffset;
|
|
||||||
};
|
|
||||||
uint8_t *BasePack::_getDataPrt(BasePack *obj)
|
|
||||||
{
|
|
||||||
return obj->packInfo->buffer + obj->DataOffset;
|
|
||||||
};
|
|
||||||
uint8_t BasePack::_getDataRawSize(BasePack *obj)
|
|
||||||
{
|
|
||||||
return obj->packInfo->packSize;
|
|
||||||
};
|
|
||||||
|
|
||||||
bool BasePack::available()
|
|
||||||
{
|
|
||||||
if (isAvailable)
|
|
||||||
{
|
|
||||||
isAvailable = false;
|
|
||||||
isRawAvailable = false;
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
};
|
|
||||||
bool BasePack::availableRaw()
|
|
||||||
{
|
|
||||||
if (isRawAvailable)
|
|
||||||
{
|
|
||||||
isRawAvailable = false;
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
};
|
|
||||||
|
|
||||||
bool Data::checkAddress()
|
|
||||||
{
|
|
||||||
bool ret;
|
|
||||||
IR_FOX::checkAddressRuleApply(getAddrTo(), this->id, ret);
|
|
||||||
return ret;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool DataBack::checkAddress()
|
|
||||||
{
|
|
||||||
bool ret;
|
|
||||||
if (getMsgType() == IR_MSG_BACK_TO)
|
|
||||||
{
|
|
||||||
DataOffset = 5;
|
|
||||||
IR_FOX::checkAddressRuleApply((packInfo->buffer[addressToOffset] << 8) | packInfo->buffer[addressToOffset + 1], this->id, ret);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
DataOffset = 3;
|
|
||||||
ret = true;
|
|
||||||
}
|
|
||||||
return ret;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool Accept::checkAddress() { return true; }
|
|
||||||
|
|
||||||
bool Request::checkAddress()
|
|
||||||
{
|
|
||||||
bool ret;
|
|
||||||
IR_FOX::checkAddressRuleApply(getAddrTo(), this->id, ret);
|
|
||||||
return ret;
|
|
||||||
}
|
|
||||||
}
|
|
308
PacketTypes.h
308
PacketTypes.h
@ -21,28 +21,86 @@ namespace PacketTypes
|
|||||||
IR_FOX::PackInfo *packInfo;
|
IR_FOX::PackInfo *packInfo;
|
||||||
uint16_t id;
|
uint16_t id;
|
||||||
|
|
||||||
virtual bool checkAddress();
|
virtual bool checkAddress() { return true; };
|
||||||
void set(IR_FOX::PackInfo *packInfo, uint16_t id);
|
void set(IR_FOX::PackInfo *packInfo, uint16_t id)
|
||||||
|
{
|
||||||
|
this->packInfo = packInfo;
|
||||||
|
this->id = id;
|
||||||
|
|
||||||
static uint16_t _getAddrFrom(BasePack *obj);
|
if (checkAddress())
|
||||||
static uint16_t _getAddrTo(BasePack *obj);
|
{
|
||||||
static uint8_t _getDataSize(BasePack *obj);
|
isAvailable = true;
|
||||||
static uint8_t *_getDataPrt(BasePack *obj);
|
isRawAvailable = true;
|
||||||
static uint8_t _getDataRawSize(BasePack *obj);
|
#ifdef IRDEBUG_INFO
|
||||||
|
Serial.print(" OK ");
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
isRawAvailable = true;
|
||||||
|
#ifdef IRDEBUG_INFO
|
||||||
|
Serial.print(" NOT-OK ");
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
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)
|
||||||
|
{
|
||||||
|
return (obj->packInfo->buffer[obj->addressToOffset] << 8) | obj->packInfo->buffer[obj->addressToOffset + 1];
|
||||||
|
};
|
||||||
|
|
||||||
|
static uint8_t _getDataSize(BasePack *obj)
|
||||||
|
{
|
||||||
|
return obj->packInfo->packSize - crcBytes - obj->DataOffset;
|
||||||
|
};
|
||||||
|
static uint8_t *_getDataPrt(BasePack *obj)
|
||||||
|
{
|
||||||
|
return obj->packInfo->buffer + obj->DataOffset;
|
||||||
|
};
|
||||||
|
static uint8_t _getDataRawSize(BasePack *obj)
|
||||||
|
{
|
||||||
|
return obj->packInfo->packSize;
|
||||||
|
};
|
||||||
|
|
||||||
public:
|
public:
|
||||||
bool available();
|
bool available()
|
||||||
bool availableRaw();
|
{
|
||||||
|
if (isAvailable)
|
||||||
inline uint8_t getMsgInfo() { return packInfo->buffer[0] & IR_MASK_MSG_INFO; };
|
{
|
||||||
inline uint8_t getMsgType() { return (packInfo->buffer[0] >> 5) & IR_MASK_MSG_TYPE; };
|
isAvailable = false;
|
||||||
inline uint8_t getMsgRAW() { return packInfo->buffer[0]; };
|
isRawAvailable = false;
|
||||||
inline uint16_t getErrorCount() { return packInfo->err.all(); };
|
return true;
|
||||||
inline uint8_t getErrorLowSignal() { return packInfo->err.lowSignal; };
|
}
|
||||||
inline uint8_t getErrorHighSignal() { return packInfo->err.highSignal; };
|
else
|
||||||
inline uint8_t getErrorOther() { return packInfo->err.other; };
|
{
|
||||||
inline uint16_t getTunerTime() { return packInfo->rTime; };
|
return false;
|
||||||
inline uint8_t *getDataRawPtr() { return packInfo->buffer; };
|
}
|
||||||
|
};
|
||||||
|
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]; };
|
||||||
|
uint16_t getErrorCount() { return packInfo->err.all(); };
|
||||||
|
uint8_t getErrorLowSignal() { return packInfo->err.lowSignal; };
|
||||||
|
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; };
|
||||||
};
|
};
|
||||||
|
|
||||||
class Data : public BasePack
|
class Data : public BasePack
|
||||||
@ -56,15 +114,20 @@ namespace PacketTypes
|
|||||||
DataOffset = 5;
|
DataOffset = 5;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline uint16_t getAddrFrom() { return _getAddrFrom(this); };
|
uint16_t getAddrFrom() { return _getAddrFrom(this); };
|
||||||
inline uint16_t getAddrTo() { return _getAddrTo(this); };
|
uint16_t getAddrTo() { return _getAddrTo(this); };
|
||||||
|
|
||||||
inline uint8_t getDataSize() { return _getDataSize(this); };
|
uint8_t getDataSize() { return _getDataSize(this); };
|
||||||
inline uint8_t *getDataPrt() { return _getDataPrt(this); };
|
uint8_t *getDataPrt() { return _getDataPrt(this); };
|
||||||
inline uint8_t getDataRawSize() { return _getDataRawSize(this); };
|
uint8_t getDataRawSize() { return _getDataRawSize(this); };
|
||||||
|
|
||||||
private:
|
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
|
||||||
@ -78,15 +141,29 @@ namespace PacketTypes
|
|||||||
DataOffset = 3;
|
DataOffset = 3;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline uint16_t getAddrFrom() { return _getAddrFrom(this); };
|
uint16_t getAddrFrom() { return _getAddrFrom(this); };
|
||||||
inline uint16_t getAddrTo() { return _getAddrTo(this); };
|
uint16_t getAddrTo() { return _getAddrTo(this); };
|
||||||
|
|
||||||
inline uint8_t getDataSize() { return _getDataSize(this); };
|
uint8_t getDataSize() { return _getDataSize(this); };
|
||||||
inline uint8_t *getDataPrt() { return _getDataPrt(this); };
|
uint8_t *getDataPrt() { return _getDataPrt(this); };
|
||||||
inline uint8_t getDataRawSize() { return _getDataRawSize(this); };
|
uint8_t getDataRawSize() { return _getDataRawSize(this); };
|
||||||
|
|
||||||
private:
|
private:
|
||||||
bool checkAddress() override;
|
bool checkAddress() override
|
||||||
|
{
|
||||||
|
bool ret;
|
||||||
|
if (getMsgType() == IR_MSG_BACK_TO)
|
||||||
|
{
|
||||||
|
DataOffset = 5;
|
||||||
|
IR_FOX::checkAddressRuleApply((packInfo->buffer[addressToOffset] << 8) | packInfo->buffer[addressToOffset + 1], this->id, ret);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
DataOffset = 3;
|
||||||
|
ret = true;
|
||||||
|
}
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
class Accept : public BasePack
|
class Accept : public BasePack
|
||||||
@ -99,11 +176,11 @@ namespace PacketTypes
|
|||||||
DataOffset = 3;
|
DataOffset = 3;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline uint16_t getAddrFrom() { return _getAddrFrom(this); };
|
uint16_t getAddrFrom() { return _getAddrFrom(this); };
|
||||||
inline uint8_t getCustomByte() { return packInfo->buffer[DataOffset]; };
|
uint8_t getCustomByte() { return packInfo->buffer[DataOffset]; };
|
||||||
|
|
||||||
private:
|
private:
|
||||||
bool checkAddress() override;
|
bool checkAddress() override { return true; }
|
||||||
};
|
};
|
||||||
|
|
||||||
class Request : public BasePack
|
class Request : public BasePack
|
||||||
@ -117,11 +194,168 @@ namespace PacketTypes
|
|||||||
DataOffset = 3;
|
DataOffset = 3;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline uint16_t getAddrFrom() { return _getAddrFrom(this); };
|
uint16_t getAddrFrom() { return _getAddrFrom(this); };
|
||||||
inline uint16_t getAddrTo() { return _getAddrTo(this); };
|
uint16_t getAddrTo() { return _getAddrTo(this); };
|
||||||
|
|
||||||
private:
|
private:
|
||||||
bool checkAddress() override;
|
bool checkAddress() override
|
||||||
|
{
|
||||||
|
bool ret;
|
||||||
|
IR_FOX::checkAddressRuleApply(getAddrTo(), this->id, ret);
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// class IOffsets {
|
||||||
|
// protected:
|
||||||
|
// uint8_t msgOffset;
|
||||||
|
// uint8_t addressFromOffset;
|
||||||
|
// uint8_t addressToOffset;
|
||||||
|
// uint8_t DataOffset;
|
||||||
|
// };
|
||||||
|
|
||||||
|
// class IPackInfo {
|
||||||
|
// public:
|
||||||
|
// IR_FOX::PackInfo* packInfo;
|
||||||
|
// };
|
||||||
|
|
||||||
|
// class IBaseEmptyPack : virtual public IOffsets, virtual public IPackInfo {
|
||||||
|
// };
|
||||||
|
|
||||||
|
// class IR_Decoder;
|
||||||
|
// class IEmptyPack : virtual protected IBaseEmptyPack, virtual public IR_FOX {
|
||||||
|
// friend IR_Decoder;
|
||||||
|
// bool isAvailable;
|
||||||
|
// bool isRawAvailable;
|
||||||
|
// bool isNeedAccept;
|
||||||
|
|
||||||
|
// protected:
|
||||||
|
// uint16_t id;
|
||||||
|
|
||||||
|
// virtual bool checkAddress() {};
|
||||||
|
|
||||||
|
// virtual void set(IR_FOX::PackInfo* packInfo, uint16_t id, bool isNeedAccept = false) {
|
||||||
|
// IBaseEmptyPack::IPackInfo::packInfo = packInfo;
|
||||||
|
// this->id = id;
|
||||||
|
// this->isNeedAccept = isNeedAccept;
|
||||||
|
|
||||||
|
// if (isAvailable = checkAddress()) {
|
||||||
|
// isAvailable = true;
|
||||||
|
// isRawAvailable = true;
|
||||||
|
// Serial.print(" OK ");
|
||||||
|
// } else {
|
||||||
|
// isRawAvailable = true;
|
||||||
|
// Serial.print(" NOT-OK ");
|
||||||
|
// }
|
||||||
|
// }
|
||||||
|
|
||||||
|
// public:
|
||||||
|
// virtual bool available() { if (isAvailable) { isAvailable = false; isRawAvailable = false; return true; } else { return false; } };
|
||||||
|
// virtual bool availableRaw() { if (isRawAvailable) { isRawAvailable = false; return true; } else { return false; } };
|
||||||
|
// virtual uint8_t getMsgInfo() { return packInfo->buffer[0] & IR_MASK_MSG_INFO; };
|
||||||
|
// virtual uint8_t getMsgType() { return (packInfo->buffer[0] >> 5) & IR_MASK_MSG_TYPE; };
|
||||||
|
// virtual uint8_t getMsgRAW() { return packInfo->buffer[0]; };
|
||||||
|
// virtual uint16_t getErrorCount() { return packInfo->err.all(); };
|
||||||
|
// virtual uint8_t getErrorLowSignal() { return packInfo->err.lowSignal; };
|
||||||
|
// virtual uint8_t getErrorHighSignal() { return packInfo->err.highSignal; };
|
||||||
|
// virtual uint8_t getErrorOther() { return packInfo->err.other; };
|
||||||
|
// virtual uint16_t getTunerTime() { return packInfo->rTime; };
|
||||||
|
// };
|
||||||
|
|
||||||
|
// class IHasAddresFrom : virtual protected IBaseEmptyPack {
|
||||||
|
// public:
|
||||||
|
// virtual uint16_t getAddrFrom() { return (packInfo->buffer[addressFromOffset] << 8) | packInfo->buffer[addressFromOffset + 1]; };
|
||||||
|
// };
|
||||||
|
|
||||||
|
// class IHasAddresTo : virtual protected IBaseEmptyPack {
|
||||||
|
// public:
|
||||||
|
// virtual uint16_t getAddrTo() { return (packInfo->buffer[addressToOffset] << 8) | packInfo->buffer[addressToOffset + 1]; };
|
||||||
|
// };
|
||||||
|
|
||||||
|
// class IHasAddresData : virtual protected IBaseEmptyPack {
|
||||||
|
// public:
|
||||||
|
// 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; };
|
||||||
|
// };
|
||||||
|
|
||||||
|
// /////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
||||||
|
|
||||||
|
// class Data :
|
||||||
|
// virtual public IEmptyPack,
|
||||||
|
// virtual public IHasAddresFrom,
|
||||||
|
// virtual public IHasAddresTo,
|
||||||
|
// virtual public IHasAddresData {
|
||||||
|
// public:
|
||||||
|
// Data() {
|
||||||
|
// msgOffset = 0;
|
||||||
|
// addressFromOffset = 1;
|
||||||
|
// addressToOffset = 3;
|
||||||
|
// DataOffset = 5;
|
||||||
|
// }
|
||||||
|
// protected:
|
||||||
|
// bool checkAddress() override {
|
||||||
|
// bool ret;
|
||||||
|
// checkAddressRuleApply(getAddrTo(), this->id, ret);
|
||||||
|
// return ret;
|
||||||
|
// }
|
||||||
|
// };
|
||||||
|
|
||||||
|
// class DataBack :
|
||||||
|
// virtual public IEmptyPack,
|
||||||
|
// virtual public IHasAddresFrom,
|
||||||
|
// virtual public IHasAddresData {
|
||||||
|
// public:
|
||||||
|
// DataBack() {
|
||||||
|
// msgOffset = 0;
|
||||||
|
// addressFromOffset = 1;
|
||||||
|
// addressToOffset = 3;
|
||||||
|
// DataOffset = 3;
|
||||||
|
// }
|
||||||
|
// protected:
|
||||||
|
// bool checkAddress() override {
|
||||||
|
// bool ret;
|
||||||
|
// if (getMsgType() == IR_MSG_BACK_TO) {
|
||||||
|
// DataOffset = 5;
|
||||||
|
// checkAddressRuleApply((packInfo->buffer[addressToOffset] << 8) | packInfo->buffer[addressToOffset + 1], this->id, ret);
|
||||||
|
// } else {
|
||||||
|
// DataOffset = 3;
|
||||||
|
// ret = true;
|
||||||
|
// }
|
||||||
|
// return ret;
|
||||||
|
// }
|
||||||
|
// };
|
||||||
|
|
||||||
|
// class Request :
|
||||||
|
// virtual public IEmptyPack,
|
||||||
|
// virtual public IHasAddresFrom,
|
||||||
|
// virtual public IHasAddresTo {
|
||||||
|
// public:
|
||||||
|
// Request() {
|
||||||
|
// msgOffset = 0;
|
||||||
|
// addressFromOffset = 1;
|
||||||
|
// addressToOffset = 3;
|
||||||
|
// DataOffset = 3;
|
||||||
|
// }
|
||||||
|
// protected:
|
||||||
|
// bool checkAddress() override {
|
||||||
|
// bool ret;
|
||||||
|
// checkAddressRuleApply(getAddrTo(), this->id, ret);
|
||||||
|
// return ret;
|
||||||
|
// }
|
||||||
|
// };
|
||||||
|
|
||||||
|
// class Accept :
|
||||||
|
// virtual public IEmptyPack,
|
||||||
|
// virtual public IHasAddresFrom {
|
||||||
|
// public:
|
||||||
|
// Accept() {
|
||||||
|
// msgOffset = 0;
|
||||||
|
// addressFromOffset = 1;
|
||||||
|
// DataOffset = 1;
|
||||||
|
// }
|
||||||
|
// protected:
|
||||||
|
// };
|
||||||
|
39
RingBuffer.h
39
RingBuffer.h
@ -1,39 +0,0 @@
|
|||||||
#pragma once
|
|
||||||
#include "Arduino.h"
|
|
||||||
template <typename T, unsigned int BufferSize>
|
|
||||||
class RingBuffer {
|
|
||||||
public:
|
|
||||||
RingBuffer() : start(0), end(0) {}
|
|
||||||
|
|
||||||
bool isFull() const {
|
|
||||||
return ((end + 1) % BufferSize) == start;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool isEmpty() const {
|
|
||||||
return start == end;
|
|
||||||
}
|
|
||||||
|
|
||||||
void push(T element) {
|
|
||||||
noInterrupts();
|
|
||||||
if (!isFull()) {
|
|
||||||
data[end] = element;
|
|
||||||
end = (end + 1) % BufferSize;
|
|
||||||
}
|
|
||||||
interrupts();
|
|
||||||
}
|
|
||||||
|
|
||||||
T* pop() {
|
|
||||||
noInterrupts();
|
|
||||||
T* value = nullptr;
|
|
||||||
if (!isEmpty()) {
|
|
||||||
value = &data[start];
|
|
||||||
start = (start + 1) % BufferSize;
|
|
||||||
}
|
|
||||||
interrupts();
|
|
||||||
return value;
|
|
||||||
}
|
|
||||||
|
|
||||||
private:
|
|
||||||
T data[BufferSize];
|
|
||||||
unsigned int start, end;
|
|
||||||
};
|
|
Reference in New Issue
Block a user