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/*
|
||||
bin/*
|
||||
!.vscode/arduino.json
|
||||
!.vscode/launch.json
|
||||
log/*
|
8
.vscode/arduino.json
vendored
8
.vscode/arduino.json
vendored
@ -1,8 +0,0 @@
|
||||
{
|
||||
"configuration": "pnum=BLUEPILL_F103C8,upload_method=swdMethod,xserial=none,usb=CDCgen,xusb=FS,opt=osstd,dbg=none,rtlib=nano",
|
||||
"board": "STMicroelectronics:stm32:GenF1",
|
||||
"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"
|
||||
}
|
||||
]
|
||||
}
|
406
IR-protocol.ino
406
IR-protocol.ino
@ -2,30 +2,16 @@
|
||||
#include "IR_Encoder.h"
|
||||
#include "TimerStatic.h"
|
||||
#include "MemoryCheck.h"
|
||||
#include "CarCmdList.h"
|
||||
/////////////// Pinout ///////////////
|
||||
|
||||
#define encForward_PIN PA0
|
||||
#define encBackward_PIN PA1
|
||||
#define encForward_PIN 0
|
||||
#define encBackward_PIN 5
|
||||
|
||||
#define dec0_PIN PB0
|
||||
#define dec1_PIN PB1
|
||||
#define dec2_PIN PB2
|
||||
#define dec3_PIN PB3
|
||||
#define dec4_PIN PB4
|
||||
#define dec5_PIN PB5
|
||||
#define dec6_PIN PB6
|
||||
#define dec7_PIN PB7
|
||||
#define dec8_PIN PB8
|
||||
#define dec9_PIN PB9
|
||||
#define dec10_PIN PB10
|
||||
#define dec11_PIN PB11
|
||||
#define dec12_PIN PB12
|
||||
#define dec13_PIN PB13
|
||||
#define dec14_PIN PB14
|
||||
#define dec15_PIN PB15
|
||||
|
||||
#define LoopOut PC13
|
||||
#define LoopOut 12
|
||||
#define ISR_Out 10
|
||||
|
||||
#define TestOut 13
|
||||
|
||||
//////////////// Ini /////////////////
|
||||
|
||||
@ -34,48 +20,52 @@
|
||||
|
||||
//////////////// Var /////////////////
|
||||
|
||||
IR_Decoder dec0(dec1_PIN, 0);
|
||||
IR_Decoder dec1(dec2_PIN, 1);
|
||||
IR_Decoder decForward(2, 555);
|
||||
IR_Decoder decBackward(3, 777);
|
||||
|
||||
IR_Encoder encForward(42 /* , &decBackward */);
|
||||
IR_Encoder encForward(42/* , &decBackward */);
|
||||
// IR_Encoder encBackward(321, encBackward_PIN);
|
||||
// IR_Encoder encTree(325, A2);
|
||||
|
||||
//////////////////////// Функции прерываний ////////////////////////
|
||||
|
||||
void EncoderISR()
|
||||
{
|
||||
void decForwardISR() {
|
||||
decForward.isr();
|
||||
}
|
||||
|
||||
void decBackwardISR() {
|
||||
decBackward.isr();
|
||||
}
|
||||
|
||||
static uint8_t* portOut;
|
||||
ISR(TIMER2_COMPA_vect) {
|
||||
encForward.isr();
|
||||
// encBackward.isr();
|
||||
// encTree.isr();
|
||||
|
||||
digitalWrite(PB5, encForward.ir_out_virtual);
|
||||
//TODO: Сделать выбор порта
|
||||
*portOut = (*portOut & 0b11111110) |
|
||||
(
|
||||
encForward.ir_out_virtual << 0U
|
||||
// | encBackward.ir_out_virtual << 6U
|
||||
// | encTree.ir_out_virtual << 2U
|
||||
);
|
||||
}
|
||||
|
||||
//------------------------------------------------------------------
|
||||
#define dec_ISR(n) \
|
||||
void dec_##n##_ISR() { dec##n.isr(); }
|
||||
|
||||
dec_ISR(0);
|
||||
dec_ISR(1);
|
||||
|
||||
|
||||
/////////////////////////////////////////////////////////////////////
|
||||
uint8_t data0[] = {};
|
||||
uint8_t data1[] = {42};
|
||||
uint8_t data2[] = {42, 127};
|
||||
uint8_t data3[] = {42, 127, 137};
|
||||
uint8_t data4[] = {42, 127, 137, 255};
|
||||
uint8_t data0 [] = { };
|
||||
uint8_t data1 [] = { 42 };
|
||||
uint8_t data2 [] = { 42 , 127 };
|
||||
uint8_t data3 [] = { 42 , 127, 137 };
|
||||
uint8_t data4 [] = { 42 , 127, 137, 255 };
|
||||
|
||||
uint32_t loopTimer;
|
||||
uint8_t sig = 0;
|
||||
uint8_t sig = 255;
|
||||
|
||||
uint16_t targetAddr = IR_Broadcast;
|
||||
Timer t1(500, millis, []()
|
||||
{
|
||||
Timer t1(750, millis, []() {
|
||||
|
||||
// Serial.println(sig);
|
||||
|
||||
switch (sig)
|
||||
{
|
||||
switch (sig) {
|
||||
case 0:
|
||||
encForward.sendData(targetAddr);
|
||||
break;
|
||||
@ -108,6 +98,8 @@ Timer t1(500, millis, []()
|
||||
encForward.sendData(targetAddr, data4, sizeof(data4), true);
|
||||
break;
|
||||
|
||||
|
||||
|
||||
case 20:
|
||||
encForward.sendBack();
|
||||
break;
|
||||
@ -147,75 +139,76 @@ Timer t1(500, millis, []()
|
||||
encForward.sendAccept(targetAddr);
|
||||
break;
|
||||
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
// encBackward.sendData(IR_Broadcast, data2);
|
||||
// encTree.sendData(IR_Broadcast, rawData3);
|
||||
});
|
||||
// Timer t2(50, millis, []()
|
||||
// { digitalToggle(LED_BUILTIN); });
|
||||
|
||||
Timer signalDetectTimer;
|
||||
});
|
||||
Timer t2(500, millis, []() {
|
||||
digitalToggle(13);
|
||||
});
|
||||
/////////////////////////////////////////////////////////////////////
|
||||
HardwareTimer IR_Timer(TIM3);
|
||||
HardwareTimer MicrosTimer(TIM1);
|
||||
void setup() {
|
||||
IR_Encoder::timerSetup();
|
||||
portOut = &PORTB;
|
||||
|
||||
void MicrosTimerISR(){
|
||||
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(SERIAL_SPEED);
|
||||
Serial.println(F(INFO));
|
||||
|
||||
IR_Timer.setOverflow(carrierFrec*2, HERTZ_FORMAT);
|
||||
IR_Timer.attachInterrupt(1, EncoderISR);
|
||||
pinMode(A0, INPUT_PULLUP);
|
||||
pinMode(A1, INPUT_PULLUP);
|
||||
pinMode(A2, INPUT_PULLUP);
|
||||
pinMode(A3, INPUT_PULLUP);
|
||||
|
||||
pinMode(LoopOut, OUTPUT);
|
||||
pinMode(ISR_Out, OUTPUT);
|
||||
|
||||
pinMode(2, INPUT_PULLUP);
|
||||
pinMode(3, INPUT_PULLUP);
|
||||
|
||||
pinMode(8, OUTPUT);
|
||||
pinMode(9, OUTPUT);
|
||||
pinMode(11, OUTPUT);
|
||||
pinMode(13, OUTPUT);
|
||||
pinMode(encForward_PIN, OUTPUT);
|
||||
pinMode(encBackward_PIN, OUTPUT);
|
||||
pinMode(13, OUTPUT);
|
||||
pinMode(12, OUTPUT);
|
||||
|
||||
|
||||
|
||||
// IR_DecoderRaw* blindFromForward [] { &decForward, &decBackward };
|
||||
// encForward.setBlindDecoders(blindFromForward, sizeof(blindFromForward) / sizeof(IR_DecoderRaw*));
|
||||
|
||||
|
||||
pinMode(encForward_PIN, OUTPUT);
|
||||
pinMode(encBackward_PIN, OUTPUT);
|
||||
pinMode(LED_BUILTIN, OUTPUT);
|
||||
|
||||
#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);
|
||||
|
||||
decSetup(0);
|
||||
|
||||
attachInterrupt(0, decForwardISR, CHANGE); // D2
|
||||
attachInterrupt(1, decBackwardISR, CHANGE); // D3
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
digitalToggle(LoopOut);
|
||||
|
||||
bool testLed = false;
|
||||
uint32_t testLed_timer;
|
||||
|
||||
void loop() {
|
||||
// digitalToggle(LoopOut);
|
||||
Timer::tick();
|
||||
|
||||
decForward.tick();
|
||||
decBackward.tick();
|
||||
|
||||
status(decForward);
|
||||
status(decBackward);
|
||||
|
||||
|
||||
decTick(0);
|
||||
decTick(1);
|
||||
// Serial.println(micros() - loopTimer);
|
||||
// loopTimer = micros();
|
||||
// delayMicroseconds(120*5);
|
||||
|
||||
bool rx_flag;
|
||||
decStat(0);
|
||||
decStat(1);
|
||||
|
||||
if(rx_flag){
|
||||
Serial.print("\n\n\n\n");
|
||||
}
|
||||
|
||||
if (Serial.available())
|
||||
{
|
||||
if (Serial.available()) {
|
||||
uint8_t in = Serial.parseInt();
|
||||
switch (in)
|
||||
{
|
||||
switch (in) {
|
||||
case 100:
|
||||
targetAddr = IR_Broadcast;
|
||||
break;
|
||||
@ -231,65 +224,53 @@ bool rx_flag;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void detectSignal()
|
||||
{
|
||||
// digitalWrite(SignalDetectLed, HIGH);
|
||||
// signalDetectTimer.delay(50, millis, []()
|
||||
// { digitalWrite(SignalDetectLed, LOW); });
|
||||
}
|
||||
if(testLed && millis() - testLed_timer > 100){
|
||||
testLed=false;
|
||||
digitalWrite(12, LOW);
|
||||
|
||||
// test
|
||||
|
||||
bool statusSimple(IR_Decoder &dec){
|
||||
if (dec.gotData.available())
|
||||
{
|
||||
Serial.print("DEC "); Serial.println(dec.id);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void status(IR_Decoder &dec)
|
||||
{
|
||||
if (dec.gotData.available())
|
||||
{
|
||||
detectSignal();
|
||||
Serial.println(micros());
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//test
|
||||
void status(IR_Decoder& dec) {
|
||||
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;
|
||||
if (/* dec.gotData.getDataPrt()[1] */ 1)
|
||||
{
|
||||
str += ("Data on pin ");
|
||||
str += (dec.isrPin);
|
||||
str += "\n";
|
||||
if (/* dec.gotData.getDataPrt()[1] */1) {
|
||||
str += ("Data on pin "); str += (dec.isrPin); str += "\n";
|
||||
|
||||
uint8_t msg = dec.gotData.getMsgRAW();
|
||||
str += (" MSG: ");
|
||||
for (size_t i = 0; i < 8; i++)
|
||||
{
|
||||
if (i == 3)
|
||||
str += " ";
|
||||
for (size_t i = 0; i < 8; i++) {
|
||||
if (i == 3) str += " ";
|
||||
str += (msg >> (7 - i)) & 1U;
|
||||
}
|
||||
|
||||
str += "\n";
|
||||
|
||||
str += (" DATA SIZE: ");
|
||||
str += (dec.gotData.getDataSize());
|
||||
str += "\n";
|
||||
str += (" ADDRESS FROM: ");
|
||||
str += (dec.gotData.getAddrFrom());
|
||||
str += "\n";
|
||||
str += (" ADDRESS TO: ");
|
||||
str += (dec.gotData.getAddrTo());
|
||||
str += "\n";
|
||||
str += (" DATA SIZE: "); str += (dec.gotData.getDataSize()); 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 CALC: "); str += (dec.gotData.getCrcCALC()); str += "\n";
|
||||
str += "\n";
|
||||
|
||||
for (size_t i = 0; i < min(uint8_t(10), dec.gotData.getDataSize()); i++)
|
||||
{
|
||||
switch (i)
|
||||
{
|
||||
for (size_t i = 0; i < min(10, dec.gotData.getDataSize()); i++) {
|
||||
switch (i) {
|
||||
// case 0:
|
||||
// str += (" ADDR: ");
|
||||
// break;
|
||||
@ -298,70 +279,48 @@ void status(IR_Decoder &dec)
|
||||
// break;
|
||||
|
||||
default:
|
||||
str += (" Data[");
|
||||
str += (i);
|
||||
str += ("]: ");
|
||||
str += (" Data["); str += (i); str += ("]: ");
|
||||
break;
|
||||
}
|
||||
str += (dec.gotData.getDataPrt()[i]);
|
||||
str += "\n";
|
||||
str += (dec.gotData.getDataPrt()[i]); str += "\n";
|
||||
}
|
||||
|
||||
str += ("\n*******ErrAll: ");
|
||||
str += (dec.gotData.getErrorCount());
|
||||
str += "\n";
|
||||
str += ("**ErrDistance: ");
|
||||
str += ((int)(dec.gotData.getErrorHighSignal() - dec.gotData.getErrorLowSignal()));
|
||||
str += "\n";
|
||||
|
||||
str += ("\n*******ErrAll: "); str += (dec.gotData.getErrorCount()); str += "\n";
|
||||
str += ("**ErrDistance: "); str += ((int)(dec.gotData.getErrorHighSignal() - dec.gotData.getErrorLowSignal())); str += "\n";
|
||||
|
||||
str += "\n";
|
||||
}
|
||||
else
|
||||
{
|
||||
str += ("SELF");
|
||||
str += "\n";
|
||||
} else {
|
||||
str += ("SELF"); str += "\n";
|
||||
str += "\n";
|
||||
}
|
||||
// obj->resetAvailable();
|
||||
Serial.write(str.c_str());
|
||||
}
|
||||
|
||||
if (dec.gotBackData.available())
|
||||
{
|
||||
detectSignal();
|
||||
if (dec.gotBackData.available()) {
|
||||
String str;
|
||||
if (/* dec.gotData.getDataPrt()[1] */ 1)
|
||||
{
|
||||
str += ("BackData on pin ");
|
||||
str += (dec.isrPin);
|
||||
str += "\n";
|
||||
if (/* dec.gotData.getDataPrt()[1] */1) {
|
||||
str += ("BackData on pin "); str += (dec.isrPin); str += "\n";
|
||||
|
||||
uint8_t msg = dec.gotBackData.getMsgRAW();
|
||||
str += (" MSG: ");
|
||||
for (size_t i = 0; i < 8; i++)
|
||||
{
|
||||
if (i == 3)
|
||||
str += " ";
|
||||
for (size_t i = 0; i < 8; i++) {
|
||||
if (i == 3) str += " ";
|
||||
str += (msg >> (7 - i)) & 1U;
|
||||
}
|
||||
|
||||
str += "\n";
|
||||
|
||||
str += (" DATA SIZE: ");
|
||||
str += (dec.gotBackData.getDataSize());
|
||||
str += "\n";
|
||||
str += (" ADDRESS FROM: ");
|
||||
str += (dec.gotBackData.getAddrFrom());
|
||||
str += "\n";
|
||||
str += (" DATA SIZE: "); str += (dec.gotBackData.getDataSize()); str += "\n";
|
||||
str += (" ADDRESS FROM: "); str += (dec.gotBackData.getAddrFrom()); str += "\n";
|
||||
// str += (" ADDRESS TO: "); str += (dec.gotBackData.getAddrTo()); str += "\n";
|
||||
// str += (" CRC PACK: "); str += (dec.gotBackData.getCrcIN()); str += "\n";
|
||||
// str += (" CRC CALC: "); str += (dec.gotBackData.getCrcCALC()); str += "\n";
|
||||
str += "\n";
|
||||
|
||||
for (size_t i = 0; i < min(uint8_t(10), dec.gotBackData.getDataSize()); i++)
|
||||
{
|
||||
switch (i)
|
||||
{
|
||||
for (size_t i = 0; i < min(10, dec.gotBackData.getDataSize()); i++) {
|
||||
switch (i) {
|
||||
// case 0:
|
||||
// str += (" ADDR: ");
|
||||
// break;
|
||||
@ -370,134 +329,97 @@ void status(IR_Decoder &dec)
|
||||
// break;
|
||||
|
||||
default:
|
||||
str += (" Data[");
|
||||
str += (i);
|
||||
str += ("]: ");
|
||||
str += (" Data["); str += (i); str += ("]: ");
|
||||
break;
|
||||
}
|
||||
str += (dec.gotBackData.getDataPrt()[i]);
|
||||
str += "\n";
|
||||
str += (dec.gotBackData.getDataPrt()[i]); str += "\n";
|
||||
}
|
||||
|
||||
str += ("\n*******ErrAll: ");
|
||||
str += (dec.gotBackData.getErrorCount());
|
||||
str += "\n";
|
||||
str += ("**ErrDistance: ");
|
||||
str += ((int)(dec.gotBackData.getErrorHighSignal() - dec.gotBackData.getErrorLowSignal()));
|
||||
str += "\n";
|
||||
|
||||
str += ("\n*******ErrAll: "); str += (dec.gotBackData.getErrorCount()); str += "\n";
|
||||
str += ("**ErrDistance: "); str += ((int)(dec.gotBackData.getErrorHighSignal() - dec.gotBackData.getErrorLowSignal())); str += "\n";
|
||||
|
||||
str += "\n";
|
||||
}
|
||||
else
|
||||
{
|
||||
str += ("SELF");
|
||||
str += "\n";
|
||||
} else {
|
||||
str += ("SELF"); str += "\n";
|
||||
str += "\n";
|
||||
}
|
||||
// obj->resetAvailable();
|
||||
Serial.write(str.c_str());
|
||||
}
|
||||
|
||||
if (dec.gotAccept.available())
|
||||
{
|
||||
detectSignal();
|
||||
if (dec.gotAccept.available()) {
|
||||
String str;
|
||||
if (/* dec.gotData.getDataPrt()[1] */ 1)
|
||||
{
|
||||
str += ("Accept on pin ");
|
||||
str += (dec.isrPin);
|
||||
str += "\n";
|
||||
if (/* dec.gotData.getDataPrt()[1] */1) {
|
||||
str += ("Accept on pin "); str += (dec.isrPin); str += "\n";
|
||||
|
||||
uint8_t msg = dec.gotAccept.getMsgRAW();
|
||||
str += (" MSG: ");
|
||||
for (size_t i = 0; i < 8; i++)
|
||||
{
|
||||
if (i == 3)
|
||||
str += " ";
|
||||
for (size_t i = 0; i < 8; i++) {
|
||||
if (i == 3) str += " ";
|
||||
str += (msg >> (7 - i)) & 1U;
|
||||
}
|
||||
|
||||
str += "\n";
|
||||
|
||||
// str += (" DATA SIZE: "); str += (dec.gotAccept.getDataSize()); str += "\n";
|
||||
str += (" ADDRESS FROM: ");
|
||||
str += (dec.gotAccept.getAddrFrom());
|
||||
str += "\n";
|
||||
str += (" ADDRESS FROM: "); str += (dec.gotAccept.getAddrFrom()); str += "\n";
|
||||
// str += (" ADDRESS TO: "); str += (dec.gotAccept.getAddrTo()); str += "\n";
|
||||
// str += (" CRC PACK: "); str += (dec.gotAccept.getCrcIN()); str += "\n";
|
||||
// str += (" CRC CALC: "); str += (dec.gotAccept.getCrcCALC()); str += "\n";
|
||||
str += "\n";
|
||||
|
||||
str += (" Data: ");
|
||||
str += (dec.gotAccept.getCustomByte());
|
||||
str += (" Data: "); str += (dec.gotAccept.getCustomByte());
|
||||
|
||||
str += ("\n\n*******ErrAll: ");
|
||||
str += (dec.gotAccept.getErrorCount());
|
||||
str += "\n";
|
||||
str += ("**ErrDistance: ");
|
||||
str += ((int)(dec.gotAccept.getErrorHighSignal() - dec.gotAccept.getErrorLowSignal()));
|
||||
str += "\n";
|
||||
|
||||
|
||||
str += ("\n\n*******ErrAll: "); str += (dec.gotAccept.getErrorCount()); str += "\n";
|
||||
str += ("**ErrDistance: "); str += ((int)(dec.gotAccept.getErrorHighSignal() - dec.gotAccept.getErrorLowSignal())); str += "\n";
|
||||
|
||||
str += "\n";
|
||||
}
|
||||
else
|
||||
{
|
||||
str += ("SELF");
|
||||
str += "\n";
|
||||
} else {
|
||||
str += ("SELF"); str += "\n";
|
||||
str += "\n";
|
||||
}
|
||||
// obj->resetAvailable();
|
||||
Serial.write(str.c_str());
|
||||
}
|
||||
|
||||
if (dec.gotRequest.available())
|
||||
{
|
||||
detectSignal();
|
||||
if (dec.gotRequest.available()) {
|
||||
String str;
|
||||
if (/* dec.gotData.getDataPrt()[1] */ 1)
|
||||
{
|
||||
str += ("Request on pin ");
|
||||
str += (dec.isrPin);
|
||||
str += "\n";
|
||||
if (/* dec.gotData.getDataPrt()[1] */1) {
|
||||
str += ("Request on pin "); str += (dec.isrPin); str += "\n";
|
||||
|
||||
uint8_t msg = dec.gotRequest.getMsgRAW();
|
||||
str += (" MSG: ");
|
||||
for (size_t i = 0; i < 8; i++)
|
||||
{
|
||||
if (i == 3)
|
||||
str += " ";
|
||||
for (size_t i = 0; i < 8; i++) {
|
||||
if (i == 3) str += " ";
|
||||
str += (msg >> (7 - i)) & 1U;
|
||||
}
|
||||
|
||||
str += "\n";
|
||||
|
||||
// str += (" DATA SIZE: "); str += (dec.gotRequest.getDataSize()); str += "\n";
|
||||
str += (" ADDRESS FROM: ");
|
||||
str += (dec.gotRequest.getAddrFrom());
|
||||
str += "\n";
|
||||
str += (" ADDRESS TO: ");
|
||||
str += (dec.gotRequest.getAddrTo());
|
||||
str += "\n";
|
||||
str += (" ADDRESS FROM: "); str += (dec.gotRequest.getAddrFrom()); str += "\n";
|
||||
str += (" ADDRESS TO: "); str += (dec.gotRequest.getAddrTo()); str += "\n";
|
||||
// str += (" CRC PACK: "); str += (dec.gotRequest.getCrcIN()); str += "\n";
|
||||
// str += (" CRC CALC: "); str += (dec.gotRequest.getCrcCALC()); str += "\n";
|
||||
str += "\n";
|
||||
|
||||
str += ("\n*******ErrAll: ");
|
||||
str += (dec.gotRequest.getErrorCount());
|
||||
str += "\n";
|
||||
str += ("**ErrDistance: ");
|
||||
str += ((int)(dec.gotRequest.getErrorHighSignal() - dec.gotRequest.getErrorLowSignal()));
|
||||
str += "\n";
|
||||
|
||||
str += ("\n*******ErrAll: "); str += (dec.gotRequest.getErrorCount()); str += "\n";
|
||||
str += ("**ErrDistance: "); str += ((int)(dec.gotRequest.getErrorHighSignal() - dec.gotRequest.getErrorLowSignal())); str += "\n";
|
||||
|
||||
str += "\n";
|
||||
}
|
||||
else
|
||||
{
|
||||
str += ("SELF");
|
||||
str += "\n";
|
||||
} else {
|
||||
str += ("SELF"); str += "\n";
|
||||
str += "\n";
|
||||
}
|
||||
// obj->resetAvailable();
|
||||
Serial.write(str.c_str());
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
@ -1,7 +1,7 @@
|
||||
#include "IR_DecoderRaw.h"
|
||||
#include "IR_Encoder.h"
|
||||
|
||||
IR_DecoderRaw::IR_DecoderRaw(const uint8_t isrPin, uint16_t addr, IR_Encoder *encPair) : isrPin(isrPin), encoder(encPair)
|
||||
IR_DecoderRaw::IR_DecoderRaw(const uint8_t isrPin, uint16_t addr, IR_Encoder *encPair = nullptr) : isrPin(isrPin), encoder(encPair)
|
||||
{
|
||||
id = addr;
|
||||
prevRise = prevFall = prevPrevFall = prevPrevRise = 0;
|
||||
@ -9,53 +9,54 @@ IR_DecoderRaw::IR_DecoderRaw(const uint8_t isrPin, uint16_t addr, IR_Encoder *en
|
||||
{
|
||||
encPair->decPair = this;
|
||||
}
|
||||
|
||||
#ifdef IRDEBUG
|
||||
pinMode(wrHigh, OUTPUT);
|
||||
pinMode(wrLow, OUTPUT);
|
||||
pinMode(writeOp, OUTPUT);
|
||||
pinMode(errOut, OUTPUT);
|
||||
pinMode(up, OUTPUT);
|
||||
pinMode(down, OUTPUT);
|
||||
#endif
|
||||
}
|
||||
|
||||
//////////////////////////////////// isr ///////////////////////////////////////////
|
||||
volatile uint32_t time_;
|
||||
|
||||
void IR_DecoderRaw::isr()
|
||||
{
|
||||
noInterrupts();
|
||||
// time_ = HAL_GetTick() * 1000 + ((SysTick->LOAD + 1 - SysTick->VAL) * 1000) / SysTick->LOAD + 1;
|
||||
time_ = micros();
|
||||
interrupts();
|
||||
if (time_ < oldTime)
|
||||
if (isPairSending)
|
||||
return;
|
||||
|
||||
subBuffer[currentSubBufferIndex].next = nullptr;
|
||||
subBuffer[currentSubBufferIndex].dir = (PIND >> isrPin) & 1;
|
||||
subBuffer[currentSubBufferIndex].time = micros();
|
||||
|
||||
if (firstUnHandledFront == nullptr)
|
||||
{
|
||||
#ifdef IRDEBUG
|
||||
Serial.print("\n");
|
||||
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;
|
||||
firstUnHandledFront = &subBuffer[currentSubBufferIndex]; // Если нет необработанных данных - добавляем их
|
||||
isSubBufferOverflow = false;
|
||||
}
|
||||
oldTime = time_;
|
||||
else
|
||||
{
|
||||
if (firstUnHandledFront == &subBuffer[currentSubBufferIndex])
|
||||
{ // Если контроллер не успел обработать новый сигнал, принудительно пропускаем его
|
||||
firstUnHandledFront = firstUnHandledFront->next;
|
||||
isSubBufferOverflow = true;
|
||||
|
||||
FrontStorage edge;
|
||||
edge.dir = digitalRead(isrPin);
|
||||
edge.time = time_;
|
||||
#ifdef IRDEBUG_INFO
|
||||
// Serial.println();
|
||||
Serial.println(" ISR BUFFER OVERFLOW ");
|
||||
// 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++; // Закольцовка буффера
|
||||
}
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
uint32_t wrCounter;
|
||||
void IR_DecoderRaw::firstRX()
|
||||
{
|
||||
|
||||
@ -78,8 +79,6 @@ void IR_DecoderRaw::firstRX()
|
||||
isPreamb = true;
|
||||
riseSyncTime = bitTime /* 1100 */;
|
||||
|
||||
wrCounter = 0;
|
||||
|
||||
memset(dataBuffer, 0x00, dataByteSizeMax);
|
||||
}
|
||||
|
||||
@ -92,116 +91,57 @@ void IR_DecoderRaw::listenStart()
|
||||
firstRX();
|
||||
}
|
||||
}
|
||||
|
||||
void IR_DecoderRaw::tick()
|
||||
{
|
||||
FrontStorage currentFront;
|
||||
noInterrupts();
|
||||
uint8_t oldSREG = SREG;
|
||||
cli();
|
||||
listenStart();
|
||||
FrontStorage *currentFrontPtr;
|
||||
currentFrontPtr = subBuffer.pop();
|
||||
if (currentFrontPtr == nullptr)
|
||||
if (firstUnHandledFront == nullptr)
|
||||
{
|
||||
isSubBufferOverflow = false;
|
||||
interrupts();
|
||||
SREG = oldSREG;
|
||||
return;
|
||||
} // Если данных нет - ничего не делаем
|
||||
currentFront = *currentFrontPtr;
|
||||
interrupts();
|
||||
|
||||
currentFront = *((FrontStorage *)firstUnHandledFront); // найти следующий необработанный фронт/спад
|
||||
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)
|
||||
{ // первый
|
||||
#ifdef IRDEBUG
|
||||
errPulse(up, 50);
|
||||
errPulse(down, 50);
|
||||
errPulse(up, 150);
|
||||
errPulse(down, 150);
|
||||
#endif
|
||||
preambFrontCounter = preambFronts - 1U;
|
||||
isPreamb = true;
|
||||
|
||||
if (!currentFront.dir)
|
||||
{
|
||||
#ifdef IRDEBUG_INFO
|
||||
// Serial.print(" currentFront.time: "); Serial.print(currentFront.time);
|
||||
// Serial.print(" currentFront.dir: "); Serial.print(currentFront.dir ? "UP" : "DOWN");
|
||||
// Serial.print(" next: "); Serial.print(currentFront.next == nullptr);
|
||||
// Serial.print(" prevRise: "); Serial.print(prevRise);
|
||||
// Serial.print(" SUB: "); Serial.println(currentFront.time - prevRise);
|
||||
#endif
|
||||
isRecive = true;
|
||||
isWrongPack = false;
|
||||
}
|
||||
|
||||
//-------------------------------------------------------------------------------------------------------
|
||||
}
|
||||
|
||||
if (preambFrontCounter)
|
||||
{ // в преамбуле
|
||||
#ifdef IRDEBUG
|
||||
Serial.print("risePeriod: ");
|
||||
Serial.println(risePeriod);
|
||||
#endif
|
||||
uint32_t risePeriod;
|
||||
risePeriod = currentFront.time - prevRise;
|
||||
if (currentFront.dir && risePeriod < IR_timeout)
|
||||
{ // __/``` ↑ и мы в внутри пакета
|
||||
|
||||
if (risePeriod < riseTimeMin / 2)
|
||||
if (risePeriod < riseTimeMin << 1)
|
||||
{ // fix рваной единицы
|
||||
preambFrontCounter += 2;
|
||||
errors.other++;
|
||||
#ifdef IRDEBUG
|
||||
errPulse(down, 350);
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -222,64 +162,42 @@ void IR_DecoderRaw::tick()
|
||||
if (isPreamb)
|
||||
{ // первый фронт после
|
||||
// gotTune.set(riseSyncTime);
|
||||
}
|
||||
isPreamb = false;
|
||||
#ifdef IRDEBUG
|
||||
errPulse(up, 50);
|
||||
errPulse(down, 50);
|
||||
#endif
|
||||
prevRise += risePeriod / 2;
|
||||
// prevRise = currentFront.time + riseTime;
|
||||
goto END;
|
||||
}
|
||||
}
|
||||
|
||||
if (isPreamb)
|
||||
{
|
||||
goto END;
|
||||
}
|
||||
if (risePeriod > IR_timeout || isBufferOverflow || risePeriod < riseTimeMin || isWrongPack)
|
||||
// ~Мы в пределах таймаута и буффер не переполнен и fix дроблёных единиц
|
||||
{
|
||||
goto END;
|
||||
}
|
||||
|
||||
// определить направление фронта
|
||||
if (currentFront.dir)
|
||||
{ // Если __/``` ↑
|
||||
highCount = 0;
|
||||
lowCount = 0;
|
||||
allCount = 0;
|
||||
|
||||
uint16_t risePeriod = currentFront.time - prevRise;
|
||||
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;
|
||||
#ifdef IRDEBUG
|
||||
Serial.print("\n");
|
||||
|
||||
Serial.print("wrCounter: ");
|
||||
Serial.println(wrCounter++);
|
||||
|
||||
Serial.print("risePeriod: ");
|
||||
Serial.println(risePeriod);
|
||||
|
||||
Serial.print("highTime: ");
|
||||
Serial.println(highTime);
|
||||
|
||||
Serial.print("lowTime: ");
|
||||
Serial.println(lowTime);
|
||||
#endif
|
||||
if (!isPreamb)
|
||||
{
|
||||
if (risePeriod < IR_timeout && !isBufferOverflow && risePeriod > riseTimeMin && !isWrongPack)
|
||||
{
|
||||
// Мы в пределах таймаута и буффер не переполнен и fix дроблёных единиц
|
||||
|
||||
if (aroundRise(risePeriod))
|
||||
{ // тактирование есть, сигнал хороший - без ошибок(?)
|
||||
|
||||
if (highTime > lowTime)
|
||||
if (highTime > riseTimeMin >> 1)
|
||||
{ // 1
|
||||
#ifdef IRDEBUG
|
||||
errPulse(wrHigh, 1);
|
||||
digitalWrite(wrHigh, 1);
|
||||
#endif
|
||||
writeToBuffer(HIGH);
|
||||
}
|
||||
else
|
||||
{ // 0
|
||||
#ifdef IRDEBUG
|
||||
errPulse(wrLow, 1);
|
||||
digitalWrite(wrLow, 1);
|
||||
#endif
|
||||
writeToBuffer(LOW);
|
||||
}
|
||||
@ -295,7 +213,7 @@ void IR_DecoderRaw::tick()
|
||||
highCount++;
|
||||
errors.other++;
|
||||
#ifdef IRDEBUG
|
||||
errPulse(up, 50);
|
||||
errPulse(errOut, 2);
|
||||
#endif
|
||||
}
|
||||
|
||||
@ -306,10 +224,7 @@ void IR_DecoderRaw::tick()
|
||||
lowCount = allCount - highCount;
|
||||
errors.lowSignal += lowCount;
|
||||
#ifdef IRDEBUG
|
||||
// errPulse(errOut, 3);
|
||||
errPulse(down, 40);
|
||||
errPulse(up, 10);
|
||||
errPulse(down, 40);
|
||||
errPulse(errOut, 3);
|
||||
#endif
|
||||
}
|
||||
else if (lowCount < highCount)
|
||||
@ -317,10 +232,7 @@ void IR_DecoderRaw::tick()
|
||||
highCount = allCount - lowCount;
|
||||
errors.highSignal += highCount;
|
||||
#ifdef IRDEBUG
|
||||
errPulse(down, 10);
|
||||
errPulse(up, 40);
|
||||
errPulse(down, 10);
|
||||
// errPulse(errOut, 4);
|
||||
errPulse(errOut, 4);
|
||||
#endif
|
||||
// неизвестный случай Инверсит след бит или соседние
|
||||
// Очень редко
|
||||
@ -328,11 +240,6 @@ void IR_DecoderRaw::tick()
|
||||
}
|
||||
else if (lowCount == highCount)
|
||||
{
|
||||
#ifdef IRDEBUG
|
||||
errPulse(down, 40);
|
||||
errPulse(up, 40);
|
||||
errPulse(down, 40);
|
||||
#endif
|
||||
invertErr = true;
|
||||
// Serial.print("...");
|
||||
errors.other += allCount;
|
||||
@ -351,23 +258,25 @@ void IR_DecoderRaw::tick()
|
||||
errors.lowSignal += lowCount;
|
||||
}
|
||||
|
||||
// errPulse(errOut, 1);
|
||||
#ifdef IRDEBUG
|
||||
errPulse(errOut, 1);
|
||||
#endif
|
||||
|
||||
for (int8_t i = 0; i < lowCount && 8 - i; i++)
|
||||
{ // отправка LOW битов, если есть
|
||||
if (i == lowCount - 1 && invertErr)
|
||||
{
|
||||
invertErr = false;
|
||||
writeToBuffer(HIGH);
|
||||
writeToBuffer(!LOW);
|
||||
#ifdef IRDEBUG
|
||||
errPulse(wrHigh, 1);
|
||||
digitalWrite(wrLow, 1);
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
writeToBuffer(LOW);
|
||||
#ifdef IRDEBUG
|
||||
errPulse(wrLow, 1);
|
||||
digitalWrite(wrLow, 1);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
@ -377,27 +286,71 @@ void IR_DecoderRaw::tick()
|
||||
if (i == highCount - 1 && invertErr)
|
||||
{
|
||||
invertErr = false;
|
||||
writeToBuffer(LOW);
|
||||
writeToBuffer(!HIGH);
|
||||
#ifdef IRDEBUG
|
||||
errPulse(wrLow, 1);
|
||||
digitalWrite(wrLow, 1);
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
writeToBuffer(HIGH);
|
||||
#ifdef IRDEBUG
|
||||
errPulse(wrHigh, 1);
|
||||
digitalWrite(wrHigh, 1);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
#ifdef IRDEBUG
|
||||
digitalWrite(wrHigh, 0);
|
||||
digitalWrite(wrLow, 0);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
if (risePeriod > riseTimeMax / 2 || highCount || lowCount)
|
||||
{ // комплексный фикс рваной единицы
|
||||
prevPrevRise = prevRise;
|
||||
prevRise = currentFront.time;
|
||||
}
|
||||
else
|
||||
{
|
||||
errors.other++;
|
||||
#ifdef IRDEBUG
|
||||
errPulse(errOut, 5);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
else
|
||||
{ // Если ```\__ ↓
|
||||
|
||||
if (currentFront.time - prevFall > riseTimeMin)
|
||||
{
|
||||
prevPrevFall = prevFall;
|
||||
prevFall = currentFront.time;
|
||||
}
|
||||
else
|
||||
{
|
||||
#ifdef IRDEBUG
|
||||
// errPulse(errOut, 5);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
||||
END:;
|
||||
if (isPreamb && preambFrontCounter <= 0)
|
||||
{
|
||||
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)
|
||||
@ -526,7 +479,7 @@ void IR_DecoderRaw::writeToBuffer(bool bit)
|
||||
if (packSize && (i_dataBuffer == packSize * bitPerByte))
|
||||
{ // Конец
|
||||
#ifdef IRDEBUG_INFO
|
||||
Serial.print(" END DATA " + crcCheck(packSize - crcBytes, crcValue) ? "OK " : "ERR ");
|
||||
Serial.print(" END DATA ");
|
||||
#endif
|
||||
|
||||
packInfo.buffer = dataBuffer;
|
||||
@ -537,34 +490,6 @@ void IR_DecoderRaw::writeToBuffer(bool bit)
|
||||
|
||||
isRecive = false;
|
||||
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,21 +1,16 @@
|
||||
#pragma once
|
||||
#include "IR_config.h"
|
||||
#include "RingBuffer.h"
|
||||
|
||||
// #define IRDEBUG
|
||||
|
||||
#ifdef IRDEBUG
|
||||
#define wrHigh PA1 // Запись HIGH инициирована // green
|
||||
#define wrLow PA0 // Запись LOW инициирована // blue
|
||||
#define writeOp PA5 // Операция записи, 1 пульс для 0 и 2 для 1 // orange
|
||||
#define wrHigh A3 // Запись HIGH инициирована // green
|
||||
#define wrLow A3 // Запись LOW инициирована // blue
|
||||
#define writeOp 13 // Операция записи, 1 пульс для 0 и 2 для 1 // orange
|
||||
// Исправленные ошибки // purle
|
||||
// 1 пульс: fix
|
||||
#define errOut PA4
|
||||
#define up PA3
|
||||
#define down PA2
|
||||
#define errOut A3
|
||||
#endif
|
||||
#define up PA3
|
||||
#define down PA2
|
||||
|
||||
/////////////////////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
@ -59,15 +54,14 @@ public:
|
||||
|
||||
void isr(); // Функция прерывания
|
||||
void tick(); // Обработка приёмника, необходима для работы
|
||||
void tickOld();
|
||||
|
||||
bool isOverflow() { return isBufferOverflow; }; // Буффер переполнился
|
||||
bool isSubOverflow()
|
||||
{
|
||||
|
||||
// noInterrupts();
|
||||
uint8_t oldSREG = SREG;
|
||||
cli();
|
||||
volatile bool ret = isSubBufferOverflow;
|
||||
// interrupts();
|
||||
SREG = oldSREG;
|
||||
return ret;
|
||||
};
|
||||
bool isReciving() { return isBufferOverflow; }; // Возвращает true, если происходит приём пакета
|
||||
@ -88,35 +82,20 @@ private:
|
||||
uint16_t riseSyncTime = bitTime; // Подстраиваемое время бита в мкс
|
||||
|
||||
////////////////////////////////////////////////////////////////////////
|
||||
volatile uint32_t currentSubBufferIndex; // Счетчик текущей позиции во вспомогательном буфере фронтов/спадов
|
||||
volatile uint8_t currentSubBufferIndex; // Счетчик текущей позиции во вспомогательном буфере фронтов/спадов
|
||||
|
||||
struct FrontStorage
|
||||
{ // Структура для хранения времени и направления фронта/спада
|
||||
volatile uint32_t time = 0; // Время
|
||||
volatile bool dir = false; // Направление (true = ↑; false = ↓)
|
||||
// volatile FrontStorage *next = nullptr; // Указатель на следующий связанный фронт/спад, или nullptr если конец
|
||||
volatile FrontStorage *next = nullptr; // Указатель на следующий связанный фронт/спад, или nullptr если конец
|
||||
};
|
||||
volatile FrontStorage *lastFront = nullptr; // Указатель последнего фронта/спада
|
||||
volatile FrontStorage *firstUnHandledFront = nullptr; // Указатель первого необработанного фронта/спада
|
||||
// volatile FrontStorage subBuffer[subBufferSize]; // вспомогательный буфер для хранения необработанных фронтов/спадов
|
||||
|
||||
RingBuffer<FrontStorage, subBufferSize> subBuffer;
|
||||
|
||||
volatile FrontStorage subBuffer[subBufferSize]; // вспомогательный буфер для хранения необработанных фронтов/спадов
|
||||
////////////////////////////////////////////////////////////////////////
|
||||
uint8_t dataBuffer[dataByteSizeMax]{0}; // Буффер данных
|
||||
volatile uint32_t prevRise, prevPrevRise, prevFall, prevPrevFall; // Время предыдущих фронтов/спадов
|
||||
|
||||
volatile uint32_t risePeriod;
|
||||
volatile uint32_t highTime;
|
||||
volatile uint32_t lowTime;
|
||||
|
||||
uint32_t oldTime;
|
||||
uint16_t wrongCounter;
|
||||
|
||||
int8_t highCount;
|
||||
int8_t lowCount;
|
||||
int8_t allCount;
|
||||
|
||||
uint32_t prevRise, prevPrevRise, prevFall, prevPrevFall; // Время предыдущих фронтов/спадов
|
||||
uint16_t errorCounter = 0; // Счётчик ошибок
|
||||
int8_t preambFrontCounter = 0; // Счётчик __/``` ↑ преамбулы
|
||||
int16_t bufBitPos = 0; // Позиция для записи бита в буффер
|
||||
@ -150,7 +129,7 @@ private:
|
||||
/// @return Результат
|
||||
uint16_t ceil_div(uint16_t val, uint16_t divider);
|
||||
|
||||
#if true //def IRDEBUG
|
||||
#ifdef IRDEBUG
|
||||
inline void errPulse(uint8_t pin, uint8_t count);
|
||||
inline void infoPulse(uint8_t pin, uint8_t count);
|
||||
#endif
|
||||
|
@ -5,7 +5,7 @@
|
||||
#define ISR_Out 10
|
||||
#define TestOut 13
|
||||
|
||||
IR_Encoder::IR_Encoder(uint16_t addr, IR_DecoderRaw *decPair)
|
||||
IR_Encoder::IR_Encoder(uint16_t addr, IR_DecoderRaw *decPair = nullptr)
|
||||
{
|
||||
id = addr;
|
||||
this->decPair = decPair;
|
||||
@ -40,7 +40,7 @@ IR_Encoder::~IR_Encoder()
|
||||
delete[] bitHigh;
|
||||
};
|
||||
|
||||
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];
|
||||
dataPtr[0] = dataByte;
|
||||
@ -48,7 +48,10 @@ void IR_Encoder::sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept)
|
||||
delete[] dataPtr;
|
||||
}
|
||||
|
||||
void IR_Encoder::sendData(uint16_t addrTo, uint8_t *data, uint8_t len, bool needAccept)
|
||||
void IR_Encoder::sendData(uint16_t addrTo, uint8_t *data = 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)
|
||||
{
|
||||
@ -65,8 +68,8 @@ void IR_Encoder::sendData(uint16_t addrTo, uint8_t *data, uint8_t len, bool need
|
||||
sendBuffer[0] = msgType;
|
||||
|
||||
// addr_self
|
||||
sendBuffer[1] = id >> 8 & 0xFF;
|
||||
sendBuffer[2] = id & 0xFF;
|
||||
sendBuffer[1] = addrFrom >> 8 & 0xFF;
|
||||
sendBuffer[2] = addrFrom & 0xFF;
|
||||
|
||||
// addr_to
|
||||
sendBuffer[3] = addrTo >> 8 & 0xFF;
|
||||
@ -92,7 +95,7 @@ void IR_Encoder::sendData(uint16_t addrTo, uint8_t *data, uint8_t len, bool need
|
||||
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;
|
||||
memset(sendBuffer, 0x00, dataByteSizeMax);
|
||||
@ -141,12 +144,12 @@ void IR_Encoder::sendBack(uint8_t data)
|
||||
{
|
||||
_sendBack(false, 0, &data, 1);
|
||||
}
|
||||
void IR_Encoder::sendBack(uint8_t *data , uint8_t len)
|
||||
void IR_Encoder::sendBack(uint8_t *data = nullptr, uint8_t len = 0)
|
||||
{
|
||||
_sendBack(false, 0, data, len);
|
||||
}
|
||||
|
||||
void IR_Encoder::sendBackTo(uint16_t addrTo, uint8_t *data, uint8_t len)
|
||||
void IR_Encoder::sendBackTo(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0)
|
||||
{
|
||||
_sendBack(true, addrTo, data, len);
|
||||
}
|
||||
@ -160,7 +163,7 @@ void IR_Encoder::_sendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint
|
||||
memset(sendBuffer, 0x00, dataByteSizeMax);
|
||||
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 =
|
||||
((isAdressed ? IR_MSG_BACK_TO : IR_MSG_BACK) << 5) | ((packSize) & (IR_MASK_MSG_INFO >> 1));
|
||||
|
||||
@ -210,7 +213,7 @@ void IR_Encoder::rawSend(uint8_t *ptr, uint8_t len)
|
||||
|
||||
setDecoder_isSending();
|
||||
|
||||
// noInterrupts();
|
||||
cli();
|
||||
sendLen = len;
|
||||
toggleCounter = preambToggle; // Первая генерация для первого signal
|
||||
|
||||
@ -227,7 +230,7 @@ void IR_Encoder::rawSend(uint8_t *ptr, uint8_t len)
|
||||
|
||||
currentBitSequence = bitHigh;
|
||||
isSending = true;
|
||||
// interrupts();
|
||||
sei();
|
||||
}
|
||||
|
||||
void IR_Encoder::isr()
|
||||
@ -332,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)
|
||||
{
|
||||
uint8_t mask = LOW_FIRST ? 0b00000001 : 0b10000000;
|
||||
@ -369,7 +398,7 @@ void IR_Encoder::addSync(bool *prev, bool *next)
|
||||
}
|
||||
}
|
||||
|
||||
void IR_Encoder::send_HIGH(bool prevBite)
|
||||
void IR_Encoder::send_HIGH(bool prevBite = 1)
|
||||
{
|
||||
|
||||
// if (/* prevBite */1) {
|
||||
@ -396,10 +425,3 @@ void IR_Encoder::send_EMPTY(uint8_t count)
|
||||
// }
|
||||
// meanderBlock(bitPauseTakts * 2 + bitActiveTakts, halfPeriod, 0); //TODO: Отодвинуть преамбулу
|
||||
}
|
||||
|
||||
uint8_t* IR_Encoder::bitHigh = new uint8_t[2]{
|
||||
(bitPauseTakts) * 2 - 1,
|
||||
(bitActiveTakts) * 2 - 1};
|
||||
uint8_t* IR_Encoder::bitLow = new uint8_t[2]{
|
||||
(bitPauseTakts/2 + bitActiveTakts) * 2 - 1,
|
||||
(bitPauseTakts) - 1};
|
60
IR_Encoder.h
60
IR_Encoder.h
@ -4,13 +4,13 @@
|
||||
// TODO: Отложенная передача после завершения приема
|
||||
|
||||
class IR_DecoderRaw;
|
||||
class IR_Encoder : IR_FOX
|
||||
class IR_Encoder : public IR_FOX
|
||||
{
|
||||
friend IR_DecoderRaw;
|
||||
|
||||
public:
|
||||
private:
|
||||
uint16_t id; /// @brief Адрес передатчика
|
||||
// uint16_t id; /// @brief Адрес передатчика
|
||||
|
||||
public:
|
||||
/// @brief Класс передатчика
|
||||
@ -20,37 +20,36 @@ public:
|
||||
/// @param decPair Приёмник, для которого отключается приём в момент передачи передатчиком
|
||||
IR_Encoder(uint16_t addr, IR_DecoderRaw *decPair = nullptr);
|
||||
|
||||
// static void timerSetup()
|
||||
// {
|
||||
// // // TIMER2 Ini
|
||||
// // uint8_t oldSREG = SREG; // Save global interupts settings
|
||||
// // cli();
|
||||
// // // DDRB |= (1 << PORTB3); //OC2A (17)
|
||||
// // TCCR2A = 0;
|
||||
// // TCCR2B = 0;
|
||||
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 << COM2A0); //Переключение состояния
|
||||
|
||||
// // TCCR2A |= (1 << WGM21); // Clear Timer On Compare (Сброс по совпадению)
|
||||
// // TCCR2B |= (1 << CS20); // Предделитель 1
|
||||
// // TIMSK2 |= (1 << OCIE2A); // Прерывание по совпадению
|
||||
TCCR2A |= (1 << WGM21); // Clear Timer On Compare (Сброс по совпадению)
|
||||
TCCR2B |= (1 << CS20); // Предделитель 1
|
||||
TIMSK2 |= (1 << OCIE2A); // Прерывание по совпадению
|
||||
|
||||
// // OCR2A = /* 465 */ ((F_CPU / (38000 * 2)) - 2); // 38кГц
|
||||
OCR2A = /* 465 */ ((F_CPU / (38000 * 2)) - 2); // 38кГц
|
||||
|
||||
// // SREG = oldSREG; // Return interrupt settings
|
||||
SREG = oldSREG; // Return interrupt settings
|
||||
}
|
||||
static void timerOFFSetup()
|
||||
{
|
||||
TIMSK2 &= ~(1 << OCIE2A); // Прерывание по совпадению выкл
|
||||
}
|
||||
|
||||
|
||||
// }
|
||||
// static void timerOFFSetup()
|
||||
// {
|
||||
// TIMSK2 &= ~(1 << OCIE2A); // Прерывание по совпадению выкл
|
||||
// }
|
||||
|
||||
void setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count);
|
||||
void IR_Encoder::setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count);
|
||||
void rawSend(uint8_t *ptr, uint8_t len);
|
||||
|
||||
void sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept = false);
|
||||
void sendData(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false);
|
||||
void sendData(uint16_t 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 sendRequest(uint16_t addrTo);
|
||||
@ -65,9 +64,9 @@ public:
|
||||
volatile bool ir_out_virtual;
|
||||
|
||||
private:
|
||||
void _sendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint8_t len);
|
||||
void IR_Encoder::_sendBack(bool isAdressed, uint16_t addrTo, uint8_t *data, uint8_t len);
|
||||
|
||||
void setDecoder_isSending();
|
||||
void IR_Encoder::setDecoder_isSending();
|
||||
void sendByte(uint8_t byte, bool *prev, bool LOW_FIRST);
|
||||
void addSync(bool *prev, bool *next);
|
||||
void send_HIGH(bool = 1);
|
||||
@ -107,9 +106,12 @@ private:
|
||||
uint8_t low;
|
||||
uint8_t high;
|
||||
};
|
||||
static uint8_t *bitHigh;
|
||||
static uint8_t *bitLow;
|
||||
static inline uint8_t *bitHigh = new uint8_t[2]{
|
||||
(bitPauseTakts * 2) * 2 - 1,
|
||||
(bitActiveTakts) * 2 - 1};
|
||||
static inline uint8_t *bitLow = new uint8_t[2]{
|
||||
(bitPauseTakts + bitActiveTakts) * 2 - 1,
|
||||
(bitPauseTakts) * 2 - 1};
|
||||
uint8_t *currentBitSequence = bitLow;
|
||||
volatile SignalPart signal;
|
||||
};
|
||||
|
||||
|
14
IR_config.h
14
IR_config.h
@ -1,7 +1,7 @@
|
||||
#pragma once
|
||||
#include <Arduino.h>
|
||||
|
||||
#define IRDEBUG_INFO
|
||||
// #define IRDEBUG_INFO
|
||||
/*//////////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
Для работы в паре положить декодер в энкодер
|
||||
@ -101,14 +101,13 @@ customByte - контрольная сумма принятых данных п
|
||||
/////////////////////////////////////////////////////////////////////////////////////*/
|
||||
typedef uint16_t crc_t;
|
||||
|
||||
#define BRUTEFORCE_CHECK // Перепроверяет пакет на 1 битные ошибки //TODO: зависает
|
||||
#define bytePerPack 16 // колличество байтов в пакете
|
||||
#ifndef freeFrec
|
||||
#define freeFrec false
|
||||
#define freeFrec true
|
||||
#endif
|
||||
|
||||
#ifndef subBufferSize
|
||||
#define subBufferSize 5 //Буфер для складирования фронтов, пока их не обработают (передатчик)
|
||||
#define subBufferSize 35 //Буфер для складирования фронтов, пока их не обработают (передатчик)
|
||||
#endif
|
||||
|
||||
#define preambPulse 3
|
||||
@ -135,11 +134,12 @@ typedef uint16_t crc_t;
|
||||
|
||||
// В процессе работы значения будут отклонятся в соответствии с предыдущим битом
|
||||
#define bitActiveTakts 25U // длительность высокого уровня в тактах
|
||||
#define bitPauseTakts 12U // длительность низкого уровня в тактах
|
||||
#define bitPauseTakts 6U // длительность низкого уровня в тактах
|
||||
|
||||
#define bitTakts (bitActiveTakts+bitPauseTakts) // Общая длительность бита в тактах
|
||||
#define bitTakts (bitActiveTakts+(bitPauseTakts*2U)) // Общая длительность бита в тактах
|
||||
#define bitTime (bitTakts*carrierPeriod) // Общая длительность бита
|
||||
#define tolerance 300U
|
||||
|
||||
class IR_FOX {
|
||||
public:
|
||||
struct PackOffsets {
|
||||
@ -182,9 +182,9 @@ public:
|
||||
uint16_t getId() { return id; }
|
||||
void setId(uint16_t id) { this->id = id; }
|
||||
|
||||
uint16_t id;
|
||||
protected:
|
||||
ErrorsStruct errors;
|
||||
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;
|
||||
|
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