mirror of
				https://github.com/Show-maket/IR-protocol.git
				synced 2025-10-29 10:02:36 +00:00 
			
		
		
		
	Compare commits
	
		
			2 Commits
		
	
	
		
			STM32-opti
			...
			dev-STM32
		
	
	| Author | SHA1 | Date | |
|---|---|---|---|
| 59d6e7aa23 | |||
| b2dfee5495 | 
							
								
								
									
										4
									
								
								.gitignore
									
									
									
									
										vendored
									
									
								
							
							
						
						
									
										4
									
								
								.gitignore
									
									
									
									
										vendored
									
									
								
							| @ -1,5 +1,5 @@ | |||||||
| .vscode/* | .vscode/* | ||||||
| bin/* | bin/* | ||||||
|  | !.vscode/arduino.json | ||||||
| !.vscode/launch.json | !.vscode/launch.json | ||||||
| log/* | log/* | ||||||
| /.vscode |  | ||||||
							
								
								
									
										7
									
								
								.vscode/arduino.json
									
									
									
									
										vendored
									
									
								
							
							
						
						
									
										7
									
								
								.vscode/arduino.json
									
									
									
									
										vendored
									
									
								
							| @ -1,5 +1,8 @@ | |||||||
| { | { | ||||||
|     "board": "STMicroelectronics:stm32:GenF4", |     "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", |     "port": "COM17", | ||||||
|     "prebuild": "if exist bin rd /s /q bin" |     "output": "bin", | ||||||
|  |     "prebuild": "if exist bin rd /s /q bin", | ||||||
|  |     "sketch": "IR-protocol.ino" | ||||||
| } | } | ||||||
							
								
								
									
										379
									
								
								IR-protocol.ino
									
									
									
									
									
								
							
							
						
						
									
										379
									
								
								IR-protocol.ino
									
									
									
									
									
								
							| @ -4,94 +4,61 @@ | |||||||
| #include "MemoryCheck.h" | #include "MemoryCheck.h" | ||||||
| /////////////// Pinout /////////////// | /////////////// Pinout /////////////// | ||||||
|  |  | ||||||
| #define dec0_PIN PIN_KT1_IN | #define encForward_PIN PA0 | ||||||
| #define dec1_PIN PIN_KT2_IN | #define encBackward_PIN PA1 | ||||||
| #define dec2_PIN PIN_KT3_IN |  | ||||||
| #define dec3_PIN PIN_KT4_IN | #define dec0_PIN PB0 | ||||||
| #define dec4_PIN PIN_KT5_IN | #define dec1_PIN PB1 | ||||||
| #define dec5_PIN PIN_KT6_IN | #define dec2_PIN PB2 | ||||||
| #define dec6_PIN PIN_KT7_IN | #define dec3_PIN PB3 | ||||||
| #define dec7_PIN PIN_KT8_IN | #define dec4_PIN PB4 | ||||||
| // #define dec8_PIN PB8 | #define dec5_PIN PB5 | ||||||
| // #define dec9_PIN PB9 | #define dec6_PIN PB6 | ||||||
| // #define dec10_PIN PB10 | #define dec7_PIN PB7 | ||||||
| // #define dec11_PIN PB11 | #define dec8_PIN PB8 | ||||||
| // #define dec12_PIN PB12 | #define dec9_PIN PB9 | ||||||
| // #define dec13_PIN PB13 | #define dec10_PIN PB10 | ||||||
| // #define dec14_PIN PB14 | #define dec11_PIN PB11 | ||||||
| // #define dec15_PIN PB15 | #define dec12_PIN PB12 | ||||||
|  | #define dec13_PIN PB13 | ||||||
|  | #define dec14_PIN PB14 | ||||||
|  | #define dec15_PIN PB15 | ||||||
|  |  | ||||||
| #define LoopOut PC13 | #define LoopOut PC13 | ||||||
|  |  | ||||||
|  |  | ||||||
| //////////////// Ini ///////////////// | //////////////// Ini ///////////////// | ||||||
|  |  | ||||||
| #define INFO "IR_FOX TEST" | #define INFO "IR_FOX TEST" | ||||||
| #define SERIAL_SPEED 115200 | #define SERIAL_SPEED 115200 | ||||||
|  |  | ||||||
| //////////////// Var ///////////////// | //////////////// Var ///////////////// | ||||||
| // IR_Encoder encForward(PA5, 42 /* , &decBackward */); |  | ||||||
|  |  | ||||||
| IR_Encoder enc0(PIN_KT8_OUT, 42 /* , &decBackward */); | IR_Decoder dec0(dec1_PIN, 0); | ||||||
| // IR_Encoder enc1(PA1, 127 /* , &decBackward */); | IR_Decoder dec1(dec2_PIN, 1); | ||||||
| // IR_Encoder enc2(PA2, 137 /* , &decBackward */); |  | ||||||
| // IR_Encoder enc3(PA3, 777 /* , &decBackward */); |  | ||||||
| // IR_Encoder enc10(PA4, 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 EncoderISR() | ||||||
| { | { | ||||||
|     IR_Encoder::isr(); |     encForward.isr(); | ||||||
|  |     // encBackward.isr(); | ||||||
|  |     // encTree.isr(); | ||||||
|  |  | ||||||
|  |     digitalWrite(PB5, encForward.ir_out_virtual); | ||||||
| } | } | ||||||
|  |  | ||||||
| //------------------------------------------------------------------- | //------------------------------------------------------------------ | ||||||
|  | #define dec_ISR(n) \ | ||||||
|  | void dec_##n##_ISR() { dec##n.isr(); } | ||||||
|  |  | ||||||
| IR_Decoder dec0(dec0_PIN, 0); | dec_ISR(0); | ||||||
| void dec_0_ISR() { dec0.isr(); } | dec_ISR(1); | ||||||
|  |  | ||||||
| IR_Decoder dec1(dec1_PIN, 1); |  | ||||||
| void dec_1_ISR() { dec1.isr(); } |  | ||||||
|  |  | ||||||
| IR_Decoder dec2(dec2_PIN, 2); |  | ||||||
| void dec_2_ISR() { dec2.isr(); } |  | ||||||
|  |  | ||||||
| IR_Decoder dec3(dec3_PIN, 3); |  | ||||||
| void dec_3_ISR() { dec3.isr(); } |  | ||||||
|  |  | ||||||
| IR_Decoder dec4(dec4_PIN, 4); |  | ||||||
| void dec_4_ISR() { dec4.isr(); } |  | ||||||
|  |  | ||||||
| IR_Decoder dec5(dec5_PIN, 5); |  | ||||||
| void dec_5_ISR() { dec5.isr(); } |  | ||||||
|  |  | ||||||
| IR_Decoder dec6(dec6_PIN, 6); |  | ||||||
| void dec_6_ISR() { dec6.isr(); } |  | ||||||
|  |  | ||||||
| IR_Decoder dec7(dec7_PIN, 7); |  | ||||||
| void dec_7_ISR() { dec7.isr(); } |  | ||||||
|  |  | ||||||
| // IR_Decoder dec8(dec8_PIN, 8); |  | ||||||
| // void dec_8_ISR() { dec8.isr(); } |  | ||||||
|  |  | ||||||
| // IR_Decoder dec9(dec9_PIN, 9); |  | ||||||
| // void dec_9_ISR() { dec9.isr(); } |  | ||||||
|  |  | ||||||
| // IR_Decoder dec10(dec10_PIN, 10); |  | ||||||
| // void dec_10_ISR() { dec10.isr(); } |  | ||||||
|  |  | ||||||
| // IR_Decoder dec11(dec11_PIN, 11); |  | ||||||
| // void dec_11_ISR() { dec11.isr(); } |  | ||||||
|  |  | ||||||
| // IR_Decoder dec12(dec12_PIN, 12); |  | ||||||
| // void dec_12_ISR() { dec12.isr(); } |  | ||||||
|  |  | ||||||
| // IR_Decoder dec13(dec13_PIN, 13); |  | ||||||
| // void dec_13_ISR() { dec13.isr(); } |  | ||||||
|  |  | ||||||
| ///////////////////////////////////////////////////////////////////// | ///////////////////////////////////////////////////////////////////// | ||||||
| uint8_t data0[] = {}; | uint8_t data0[] = {}; | ||||||
| @ -103,172 +70,146 @@ uint8_t data4[] = {42, 127, 137, 255}; | |||||||
| uint32_t loopTimer; | uint32_t loopTimer; | ||||||
| uint8_t sig = 0; | uint8_t sig = 0; | ||||||
| uint16_t targetAddr = IR_Broadcast; | uint16_t targetAddr = IR_Broadcast; | ||||||
|  |  | ||||||
| Timer t1(500, millis, []() | Timer t1(500, 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: |              case 20: | ||||||
|              //      encForward.sendBack(); |                  encForward.sendBack(); | ||||||
|              //      break; |                  break; | ||||||
|              //  case 21: |              case 21: | ||||||
|              //      encForward.sendBack(data1, sizeof(data1)); |                  encForward.sendBack(data1, sizeof(data1)); | ||||||
|              //      break; |                  break; | ||||||
|              //  case 22: |              case 22: | ||||||
|              //      encForward.sendBack(data2, sizeof(data2)); |                  encForward.sendBack(data2, sizeof(data2)); | ||||||
|              //      break; |                  break; | ||||||
|              //  case 23: |              case 23: | ||||||
|              //      encForward.sendBack(data3, sizeof(data3)); |                  encForward.sendBack(data3, sizeof(data3)); | ||||||
|              //      break; |                  break; | ||||||
|              //  case 24: |              case 24: | ||||||
|              //      encForward.sendBack(data4, sizeof(data4)); |                  encForward.sendBack(data4, sizeof(data4)); | ||||||
|              //      break; |                  break; | ||||||
|  |  | ||||||
|              //  case 30: |              case 30: | ||||||
|              //      encForward.sendBackTo(targetAddr); |                  encForward.sendBackTo(targetAddr); | ||||||
|              //      break; |                  break; | ||||||
|              //  case 31: |              case 31: | ||||||
|              //      encForward.sendBackTo(targetAddr, data1, sizeof(data1)); |                  encForward.sendBackTo(targetAddr, data1, sizeof(data1)); | ||||||
|              //      break; |                  break; | ||||||
|              //  case 32: |              case 32: | ||||||
|              //      encForward.sendBackTo(targetAddr, data2, sizeof(data2)); |                  encForward.sendBackTo(targetAddr, data2, sizeof(data2)); | ||||||
|              //      break; |                  break; | ||||||
|              //  case 33: |              case 33: | ||||||
|              //      encForward.sendBackTo(targetAddr, data3, sizeof(data3)); |                  encForward.sendBackTo(targetAddr, data3, sizeof(data3)); | ||||||
|              //      break; |                  break; | ||||||
|              //  case 34: |              case 34: | ||||||
|              //      encForward.sendBackTo(targetAddr, data4, sizeof(data4)); |                  encForward.sendBackTo(targetAddr, data4, sizeof(data4)); | ||||||
|              //      break; |                  break; | ||||||
|  |  | ||||||
|              //  case 41: |              case 41: | ||||||
|              //      encForward.sendRequest(targetAddr); |                  encForward.sendRequest(targetAddr); | ||||||
|              //      break; |                  break; | ||||||
|              //  case 42: |              case 42: | ||||||
|              //      encForward.sendAccept(targetAddr); |                  encForward.sendAccept(targetAddr); | ||||||
|              //      break; |                  break; | ||||||
|  |  | ||||||
|              //  default: |              default: | ||||||
|              //      break; |                  break; | ||||||
|              //  } |              } | ||||||
|              // encBackward.sendData(IR_Broadcast, data2); |              // encBackward.sendData(IR_Broadcast, data2); | ||||||
|              // encTree.sendData(IR_Broadcast, rawData3); |              // encTree.sendData(IR_Broadcast, rawData3); | ||||||
|          }); |          }); | ||||||
|  |  | ||||||
| // Timer t2(50, millis, []() | // Timer t2(50, millis, []() | ||||||
| //          { digitalToggle(LED_BUILTIN); }); | //          { digitalToggle(LED_BUILTIN); }); | ||||||
|  |  | ||||||
| Timer signalDetectTimer; | Timer signalDetectTimer; | ||||||
| ///////////////////////////////////////////////////////////////////// | ///////////////////////////////////////////////////////////////////// | ||||||
| HardwareTimer IR_Timer(TIM3); | HardwareTimer IR_Timer(TIM3); | ||||||
|  | HardwareTimer MicrosTimer(TIM1); | ||||||
|  |  | ||||||
|  | void MicrosTimerISR(){ | ||||||
|  |  | ||||||
|  | } | ||||||
|  |  | ||||||
| void setup() | void setup() | ||||||
| { | { | ||||||
|     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)); | ||||||
|  |  | ||||||
|  |     IR_Timer.setOverflow(carrierFrec*2, HERTZ_FORMAT); | ||||||
|  |     IR_Timer.attachInterrupt(1, EncoderISR); | ||||||
|  |      | ||||||
|     pinMode(LoopOut, OUTPUT); |     pinMode(LoopOut, OUTPUT); | ||||||
|  |  | ||||||
|     pinMode(dec0_PIN, INPUT_PULLUP); |     // IR_DecoderRaw* blindFromForward [] { &decForward, &decBackward }; | ||||||
|     pinMode(dec1_PIN, INPUT_PULLUP); |     // encForward.setBlindDecoders(blindFromForward, sizeof(blindFromForward) / sizeof(IR_DecoderRaw*)); | ||||||
|     pinMode(dec2_PIN, INPUT_PULLUP); |  | ||||||
|     pinMode(dec3_PIN, INPUT_PULLUP); |  | ||||||
|     pinMode(dec4_PIN, INPUT_PULLUP); |     pinMode(encForward_PIN, OUTPUT); | ||||||
|     pinMode(dec5_PIN, INPUT_PULLUP); |     pinMode(encBackward_PIN, OUTPUT); | ||||||
|     pinMode(dec6_PIN, INPUT_PULLUP); |     pinMode(LED_BUILTIN, OUTPUT); | ||||||
|     pinMode(dec7_PIN, INPUT_PULLUP); |  | ||||||
|     // pinMode(dec8_PIN, INPUT_PULLUP); | #define decPinMode(n) pinMode(dec##n##_PIN, INPUT_PULLUP); | ||||||
|     // pinMode(dec9_PIN, INPUT_PULLUP); | #define decAttach(n) attachInterrupt(dec##n##_PIN, dec_##n##_ISR, CHANGE);  | ||||||
|     // pinMode(dec10_PIN, INPUT_PULLUP); | #define decSetup(n) /* decPinMode(n); */ decAttach(n); | ||||||
|     // pinMode(dec11_PIN, INPUT_PULLUP); | #define decTick(n) dec##n.tick(); | ||||||
|     // pinMode(dec12_PIN, INPUT_PULLUP); | #define decStat(n) rx_flag |= statusSimple(dec##n); | ||||||
|     // pinMode(dec13_PIN, INPUT_PULLUP); |  | ||||||
|  | decSetup(0); | ||||||
|  |  | ||||||
|     attachInterrupt(dec0_PIN, dec_0_ISR, CHANGE); |  | ||||||
|     attachInterrupt(dec1_PIN, dec_1_ISR, CHANGE); |  | ||||||
|     attachInterrupt(dec2_PIN, dec_2_ISR, CHANGE); |  | ||||||
|     attachInterrupt(dec3_PIN, dec_3_ISR, CHANGE); |  | ||||||
|     attachInterrupt(dec4_PIN, dec_4_ISR, CHANGE); |  | ||||||
|     attachInterrupt(dec5_PIN, dec_5_ISR, CHANGE); |  | ||||||
|     attachInterrupt(dec6_PIN, dec_6_ISR, CHANGE); |  | ||||||
|     attachInterrupt(dec7_PIN, dec_7_ISR, CHANGE); |  | ||||||
|     // attachInterrupt(dec8_PIN, dec_8_ISR, CHANGE); |  | ||||||
|     // attachInterrupt(dec9_PIN, dec_9_ISR, CHANGE); |  | ||||||
|     // attachInterrupt(dec10_PIN, dec_10_ISR, CHANGE); |  | ||||||
|     // attachInterrupt(dec11_PIN, dec_11_ISR, CHANGE); |  | ||||||
|     // attachInterrupt(dec12_PIN, dec_12_ISR, CHANGE); |  | ||||||
|     // attachInterrupt(dec13_PIN, dec_13_ISR, CHANGE); |  | ||||||
| } | } | ||||||
|  |  | ||||||
| void loop() | void loop() | ||||||
| { | { | ||||||
|     digitalToggle(LoopOut); |     digitalToggle(LoopOut); | ||||||
|     Timer::tick(); |     Timer::tick(); | ||||||
|     IR_Decoder::tick(); |  | ||||||
|  |  | ||||||
|     bool rx_flag = false; |  | ||||||
|     rx_flag |= status(dec0); |  | ||||||
|     rx_flag |= status(dec1); |     decTick(0); | ||||||
|     rx_flag |= status(dec2); |     decTick(1); | ||||||
|     rx_flag |= status(dec3); |  | ||||||
|     rx_flag |= status(dec4); | bool rx_flag; | ||||||
|     rx_flag |= status(dec5); |     decStat(0); | ||||||
|     rx_flag |= status(dec6); |     decStat(1); | ||||||
|     rx_flag |= status(dec7); |  | ||||||
|     // rx_flag |= status(dec8); |     if(rx_flag){ | ||||||
|     // rx_flag |= status(dec9); |         Serial.print("\n\n\n\n"); | ||||||
|     // rx_flag |= status(dec10); |     } | ||||||
|     // rx_flag |= status(dec11); |  | ||||||
|     // rx_flag |= status(dec12); |  | ||||||
|     // rx_flag |= status(dec13); |  | ||||||
|  |  | ||||||
|     if (Serial.available()) |     if (Serial.available()) | ||||||
|     { |     { | ||||||
| @ -284,6 +225,7 @@ void loop() | |||||||
|         case 102: |         case 102: | ||||||
|             targetAddr = 777; |             targetAddr = 777; | ||||||
|             break; |             break; | ||||||
|  |  | ||||||
|         default: |         default: | ||||||
|             sig = in; |             sig = in; | ||||||
|             break; |             break; | ||||||
| @ -291,24 +233,6 @@ void loop() | |||||||
|     } |     } | ||||||
| } | } | ||||||
|  |  | ||||||
|  |  | ||||||
| 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() | void detectSignal() | ||||||
| { | { | ||||||
|     // digitalWrite(SignalDetectLed, HIGH); |     // digitalWrite(SignalDetectLed, HIGH); | ||||||
| @ -317,17 +241,25 @@ void detectSignal() | |||||||
| } | } | ||||||
|  |  | ||||||
| // test | // test | ||||||
| bool status(IR_Decoder &dec) |  | ||||||
|  | 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()) |     if (dec.gotData.available()) | ||||||
|     { |     { | ||||||
|         detectSignal(); |         detectSignal(); | ||||||
|         // Serial.println(micros()); |         Serial.println(micros()); | ||||||
|         String str; |         String str; | ||||||
|         if (/* dec.gotData.getDataPrt()[1] */ 1) |         if (/* dec.gotData.getDataPrt()[1] */ 1) | ||||||
|         { |         { | ||||||
|             str += ("Data on pin "); |             str += ("Data on pin "); | ||||||
|             str += (dec.getPin()); |             str += (dec.isrPin); | ||||||
|             str += "\n"; |             str += "\n"; | ||||||
|  |  | ||||||
|             uint8_t msg = dec.gotData.getMsgRAW(); |             uint8_t msg = dec.gotData.getMsgRAW(); | ||||||
| @ -401,7 +333,7 @@ bool status(IR_Decoder &dec) | |||||||
|         if (/* dec.gotData.getDataPrt()[1] */ 1) |         if (/* dec.gotData.getDataPrt()[1] */ 1) | ||||||
|         { |         { | ||||||
|             str += ("BackData on pin "); |             str += ("BackData on pin "); | ||||||
|             str += (dec.getPin()); |             str += (dec.isrPin); | ||||||
|             str += "\n"; |             str += "\n"; | ||||||
|  |  | ||||||
|             uint8_t msg = dec.gotBackData.getMsgRAW(); |             uint8_t msg = dec.gotBackData.getMsgRAW(); | ||||||
| @ -473,7 +405,7 @@ bool status(IR_Decoder &dec) | |||||||
|         if (/* dec.gotData.getDataPrt()[1] */ 1) |         if (/* dec.gotData.getDataPrt()[1] */ 1) | ||||||
|         { |         { | ||||||
|             str += ("Accept on pin "); |             str += ("Accept on pin "); | ||||||
|             str += (dec.getPin()); |             str += (dec.isrPin); | ||||||
|             str += "\n"; |             str += "\n"; | ||||||
|  |  | ||||||
|             uint8_t msg = dec.gotAccept.getMsgRAW(); |             uint8_t msg = dec.gotAccept.getMsgRAW(); | ||||||
| @ -525,7 +457,7 @@ bool status(IR_Decoder &dec) | |||||||
|         if (/* dec.gotData.getDataPrt()[1] */ 1) |         if (/* dec.gotData.getDataPrt()[1] */ 1) | ||||||
|         { |         { | ||||||
|             str += ("Request on pin "); |             str += ("Request on pin "); | ||||||
|             str += (dec.getPin()); |             str += (dec.isrPin); | ||||||
|             str += "\n"; |             str += "\n"; | ||||||
|  |  | ||||||
|             uint8_t msg = dec.gotRequest.getMsgRAW(); |             uint8_t msg = dec.gotRequest.getMsgRAW(); | ||||||
| @ -568,5 +500,4 @@ bool status(IR_Decoder &dec) | |||||||
|         // obj->resetAvailable(); |         // obj->resetAvailable(); | ||||||
|         Serial.write(str.c_str()); |         Serial.write(str.c_str()); | ||||||
|     } |     } | ||||||
|     return false; |  | ||||||
| } | } | ||||||
|  | |||||||
							
								
								
									
										105
									
								
								IR_Decoder.cpp
									
									
									
									
									
								
							
							
						
						
									
										105
									
								
								IR_Decoder.cpp
									
									
									
									
									
								
							| @ -1,105 +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() {}; |  | ||||||
| IR_Decoder::IR_Decoder(const uint8_t pin, uint16_t addr, IR_Encoder *encPair, bool autoHandle) |  | ||||||
|     : IR_DecoderRaw(pin, addr, encPair) |  | ||||||
| { |  | ||||||
|     get_dec_list().push_back(this); |  | ||||||
|     if(autoHandle){ |  | ||||||
|         enable(); |  | ||||||
|     } |  | ||||||
| }; |  | ||||||
|  |  | ||||||
| void IR_Decoder::enable() |  | ||||||
| { |  | ||||||
|     auto &dec_list = get_dec_list(); |  | ||||||
|     if (std::find(dec_list.begin(), dec_list.end(), this) == dec_list.end()) |  | ||||||
|     { |  | ||||||
|         dec_list.push_back(this); |  | ||||||
|     } |  | ||||||
|     pinMode(pin, INPUT_PULLUP); |  | ||||||
|     attachInterrupt(pin, (*this)(), CHANGE); |  | ||||||
| } |  | ||||||
|  |  | ||||||
| void IR_Decoder::disable() |  | ||||||
| { |  | ||||||
|     detachInterrupt(pin); |  | ||||||
|     pinMode(pin, INPUT); |  | ||||||
|     auto &dec_list = get_dec_list(); |  | ||||||
|     auto it = std::find(dec_list.begin(), dec_list.end(), this); |  | ||||||
|     if (it != dec_list.end()) |  | ||||||
|     { |  | ||||||
|         dec_list.erase(it); |  | ||||||
|     } |  | ||||||
| } |  | ||||||
|  |  | ||||||
|  |  | ||||||
| std::function<void()> IR_Decoder::operator()() |  | ||||||
| { |  | ||||||
|     return std::bind(&IR_Decoder::isr, 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 > acceptDelay) |  | ||||||
|     { |  | ||||||
|         encoder->sendAccept(addrAcceptSendTo, acceptCustomByte); |  | ||||||
|         isWaitingAcceptSend = false; |  | ||||||
|     } |  | ||||||
| } |  | ||||||
							
								
								
									
										65
									
								
								IR_Decoder.h
									
									
									
									
									
								
							
							
						
						
									
										65
									
								
								IR_Decoder.h
									
									
									
									
									
								
							| @ -5,16 +5,11 @@ | |||||||
|  |  | ||||||
| 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; | ||||||
|  |  | ||||||
|     uint16_t acceptDelay = IR_ResponseDelay; |     uint16_t acceptDelay = 75; | ||||||
|     uint8_t acceptCustomByte; |     uint8_t acceptCustomByte; | ||||||
|  |  | ||||||
| public: | public: | ||||||
| @ -24,23 +19,59 @@ public: | |||||||
|     PacketTypes::Request gotRequest; |     PacketTypes::Request gotRequest; | ||||||
|     PacketTypes::BasePack gotRaw; |     PacketTypes::BasePack gotRaw; | ||||||
|  |  | ||||||
|     // IR_Decoder(); |     IR_Decoder(const uint8_t isrPin, uint16_t addr, IR_Encoder *encPair = nullptr) : IR_DecoderRaw(isrPin, addr, encPair) {} | ||||||
|     IR_Decoder(const uint8_t pin, uint16_t addr = 0, IR_Encoder *encPair = nullptr, bool autoHandle = true); |  | ||||||
|  |  | ||||||
|     std::function<void()> operator()(); |     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; | ||||||
|  |  | ||||||
|     void enable(); |             default: | ||||||
|     void disable(); |                 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; | ||||||
|  |         } | ||||||
|  |     } | ||||||
|  |  | ||||||
|     ~IR_Decoder(); |     void setAcceptDelay(uint16_t acceptDelay) | ||||||
|  |  | ||||||
|     static void tick(); |  | ||||||
|  |  | ||||||
|     inline 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,9 +1,8 @@ | |||||||
| #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) : isrPin(isrPin), encoder(encPair) | ||||||
| { | { | ||||||
|     setPin(pin); |  | ||||||
|     id = addr; |     id = addr; | ||||||
|     prevRise = prevFall = prevPrevFall = prevPrevRise = 0; |     prevRise = prevFall = prevPrevFall = prevPrevRise = 0; | ||||||
|     if (encPair != nullptr) |     if (encPair != nullptr) | ||||||
| @ -21,45 +20,18 @@ IR_DecoderRaw::IR_DecoderRaw(const uint8_t pin, uint16_t addr, IR_Encoder *encPa | |||||||
| #endif | #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_; | volatile uint32_t time_; | ||||||
|  |  | ||||||
| void IR_DecoderRaw::isr() | void IR_DecoderRaw::isr() | ||||||
| { | { | ||||||
|     // Serial.print("ISR\n"); |  | ||||||
|     if(isPairSending){ |  | ||||||
|         return; |  | ||||||
|     } |  | ||||||
|  |  | ||||||
|     noInterrupts(); |     noInterrupts(); | ||||||
|     // time_ = HAL_GetTick() * 1000 + ((SysTick->LOAD + 1 - SysTick->VAL) * 1000) / SysTick->LOAD + 1; |     // time_ = HAL_GetTick() * 1000 + ((SysTick->LOAD + 1 - SysTick->VAL) * 1000) / SysTick->LOAD + 1; | ||||||
|     time_ = micros(); |     time_ = micros(); | ||||||
|     interrupts(); |     interrupts(); | ||||||
|     if (time_ < oldTime) |     if (time_ < oldTime) | ||||||
|     { |     { | ||||||
|  | #ifdef IRDEBUG | ||||||
| #ifdef  IRDEBUG |  | ||||||
|         Serial.print("\n"); |         Serial.print("\n"); | ||||||
|         Serial.print("count:         "); |         Serial.print("count:         "); | ||||||
|         Serial.println(wrongCounter++); |         Serial.println(wrongCounter++); | ||||||
| @ -75,7 +47,7 @@ void IR_DecoderRaw::isr() | |||||||
|     oldTime = time_; |     oldTime = time_; | ||||||
|  |  | ||||||
|     FrontStorage edge; |     FrontStorage edge; | ||||||
|     edge.dir = port->IDR & mask; |     edge.dir = digitalRead(isrPin); | ||||||
|     edge.time = time_; |     edge.time = time_; | ||||||
|  |  | ||||||
|     subBuffer.push(edge); |     subBuffer.push(edge); | ||||||
| @ -83,6 +55,7 @@ void IR_DecoderRaw::isr() | |||||||
|  |  | ||||||
| //////////////////////////////////////////////////////////////////////////////////// | //////////////////////////////////////////////////////////////////////////////////// | ||||||
|  |  | ||||||
|  | uint32_t wrCounter; | ||||||
| void IR_DecoderRaw::firstRX() | void IR_DecoderRaw::firstRX() | ||||||
| { | { | ||||||
|  |  | ||||||
| @ -104,9 +77,9 @@ void IR_DecoderRaw::firstRX() | |||||||
|  |  | ||||||
|     isPreamb = true; |     isPreamb = true; | ||||||
|     riseSyncTime = bitTime /* 1100 */; |     riseSyncTime = bitTime /* 1100 */; | ||||||
| #ifdef IRDEBUG |  | ||||||
|     wrCounter = 0; |     wrCounter = 0; | ||||||
| #endif |  | ||||||
|     memset(dataBuffer, 0x00, dataByteSizeMax); |     memset(dataBuffer, 0x00, dataByteSizeMax); | ||||||
| } | } | ||||||
|  |  | ||||||
| @ -119,7 +92,6 @@ void IR_DecoderRaw::listenStart() | |||||||
|         firstRX(); |         firstRX(); | ||||||
|     } |     } | ||||||
| } | } | ||||||
|  |  | ||||||
| void IR_DecoderRaw::tick() | void IR_DecoderRaw::tick() | ||||||
| { | { | ||||||
|     FrontStorage currentFront; |     FrontStorage currentFront; | ||||||
| @ -567,31 +539,31 @@ void IR_DecoderRaw::writeToBuffer(bool bit) | |||||||
|             isAvailable = crcCheck(packSize - crcBytes, crcValue); |             isAvailable = crcCheck(packSize - crcBytes, crcValue); | ||||||
|  |  | ||||||
| #ifdef BRUTEFORCE_CHECK | #ifdef BRUTEFORCE_CHECK | ||||||
|             if (!isAvailable) // Исправление первого бита // Очень большая затычка... |                 if (!isAvailable) // Исправление первого бита // Очень большая затычка... | ||||||
|                 for (size_t i = 0; i < min(uint16_t(packSize - crcBytes * 2U), uint16_t(dataByteSizeMax)); ++i) |                     for (size_t i = 0; i < min(uint16_t(packSize - crcBytes*2U), uint16_t(dataByteSizeMax)); ++i) | ||||||
|                 { |  | ||||||
|                     for (int j = 0; j < 8; ++j) |  | ||||||
|                     { |                     { | ||||||
|                         // инвертируем бит |                         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; |                             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:; | ||||||
|         OUT_BRUTEFORCE:; |  | ||||||
| #endif | #endif | ||||||
|         } |         } | ||||||
|     } |     } | ||||||
|  | |||||||
| @ -14,6 +14,8 @@ | |||||||
| #define up PA3 | #define up PA3 | ||||||
| #define down PA2 | #define down PA2 | ||||||
| #endif | #endif | ||||||
|  | #define up PA3 | ||||||
|  | #define down PA2 | ||||||
|  |  | ||||||
| ///////////////////////////////////////////////////////////////////////////////////////////////// | ///////////////////////////////////////////////////////////////////////////////////////////////// | ||||||
|  |  | ||||||
| @ -23,7 +25,6 @@ | |||||||
| #define riseTimeMin (riseTime - riseTolerance) | #define riseTimeMin (riseTime - riseTolerance) | ||||||
| #define aroundRise(t) (riseTimeMin < t && t < riseTimeMax) | #define aroundRise(t) (riseTimeMin < t && t < riseTimeMax) | ||||||
| #define IR_timeout (riseTimeMax * (8 + syncBits + 1)) // us // таймаут в 8 data + 3 sync + 1 | #define IR_timeout (riseTimeMax * (8 + syncBits + 1)) // us // таймаут в 8 data + 3 sync + 1 | ||||||
| constexpr uint16_t IR_ResponseDelay = ((uint16_t)(((bitTime+riseTolerance) * (8 + syncBits + 1))*2.7735))/1000; |  | ||||||
|  |  | ||||||
| class IR_Encoder; | class IR_Encoder; | ||||||
| class IR_DecoderRaw : virtual public IR_FOX | class IR_DecoderRaw : virtual public IR_FOX | ||||||
| @ -33,22 +34,43 @@ 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(); // Обработка приёмника, необходима для работы | ||||||
|  |     void tickOld(); | ||||||
|  |  | ||||||
|     inline bool isOverflow() { return isBufferOverflow; }; // Буффер переполнился |     bool isOverflow() { return isBufferOverflow; }; // Буффер переполнился | ||||||
|     bool isSubOverflow(); |     bool isSubOverflow() | ||||||
|     inline bool isReciving() { return isBufferOverflow; }; // Возвращает true, если происходит приём пакета |     { | ||||||
|  |  | ||||||
|  |         // noInterrupts(); | ||||||
|  |         volatile bool ret = isSubBufferOverflow; | ||||||
|  |         // interrupts(); | ||||||
|  |         return ret; | ||||||
|  |     }; | ||||||
|  |     bool isReciving() { return isBufferOverflow; }; // Возвращает true, если происходит приём пакета | ||||||
|  |  | ||||||
|     ////////////////////////////////////////////////////////////////////////// |     ////////////////////////////////////////////////////////////////////////// | ||||||
| private: | private: | ||||||
| @ -128,9 +150,8 @@ private: | |||||||
|     /// @return Результат |     /// @return Результат | ||||||
|     uint16_t ceil_div(uint16_t val, uint16_t divider); |     uint16_t ceil_div(uint16_t val, uint16_t divider); | ||||||
|  |  | ||||||
| #ifdef IRDEBUG | #if true //def 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 | ||||||
| }; | }; | ||||||
							
								
								
									
										186
									
								
								IR_Encoder.cpp
									
									
									
									
									
								
							
							
						
						
									
										186
									
								
								IR_Encoder.cpp
									
									
									
									
									
								
							| @ -5,12 +5,8 @@ | |||||||
| #define ISR_Out 10 | #define ISR_Out 10 | ||||||
| #define TestOut 13 | #define TestOut 13 | ||||||
|  |  | ||||||
| IR_Encoder *IR_Encoder::head = nullptr; | IR_Encoder::IR_Encoder(uint16_t addr, IR_DecoderRaw *decPair) | ||||||
| IR_Encoder *IR_Encoder::last = nullptr; |  | ||||||
|  |  | ||||||
| IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair, bool autoHandle) |  | ||||||
| { | { | ||||||
|     setPin(pin); |  | ||||||
|     id = addr; |     id = addr; | ||||||
|     this->decPair = decPair; |     this->decPair = decPair; | ||||||
|     signal = noSignal; |     signal = noSignal; | ||||||
| @ -18,7 +14,8 @@ IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair, bool | |||||||
| #if disablePairDec | #if disablePairDec | ||||||
|     if (decPair != nullptr) |     if (decPair != nullptr) | ||||||
|     { |     { | ||||||
|         blindDecoders = new IR_DecoderRaw *[1]{decPair}; |         blindDecoders = new IR_DecoderRaw *[1] | ||||||
|  |         { decPair }; | ||||||
|         decodersCount = 1; |         decodersCount = 1; | ||||||
|     } |     } | ||||||
| #endif | #endif | ||||||
| @ -26,94 +23,7 @@ IR_Encoder::IR_Encoder(uint8_t pin, uint16_t addr, IR_DecoderRaw *decPair, bool | |||||||
|     { |     { | ||||||
|         decPair->encoder = this; |         decPair->encoder = this; | ||||||
|     } |     } | ||||||
|  |  | ||||||
|     if (autoHandle) |  | ||||||
|     { |  | ||||||
|         if (IR_Encoder::head == nullptr) |  | ||||||
|         { |  | ||||||
|         IR_Encoder::head = this; |  | ||||||
|         } |  | ||||||
|         if (last != nullptr) |  | ||||||
|         { |  | ||||||
|         last->next = this; |  | ||||||
|         } |  | ||||||
|         last = this; |  | ||||||
|     } |  | ||||||
| }; | }; | ||||||
|   |  | ||||||
| HardwareTimer* IR_Encoder::IR_Timer = nullptr; |  | ||||||
|  |  | ||||||
| inline HardwareTimer* IR_Encoder::get_IR_Timer(){return IR_Encoder::IR_Timer;} |  | ||||||
|  |  | ||||||
| void IR_Encoder::begin(HardwareTimer* timer, uint8_t channel, IRQn_Type IRQn, uint8_t priority, void(*isrCallback)()){ |  | ||||||
|     IR_Timer = timer; |  | ||||||
|     if(IR_Timer == nullptr) return; |  | ||||||
|     IR_Timer->setOverflow(carrierFrec * 2, HERTZ_FORMAT); |  | ||||||
|     IR_Timer->attachInterrupt(channel, (isrCallback == nullptr ? IR_Encoder::isr : isrCallback)); |  | ||||||
|     NVIC_SetPriority(IRQn, priority); |  | ||||||
|     IR_Timer->resume(); |  | ||||||
| } |  | ||||||
|  |  | ||||||
|  |  | ||||||
| void IR_Encoder::enable() |  | ||||||
| { |  | ||||||
|     bool exist = false; |  | ||||||
|     IR_Encoder *current = IR_Encoder::head; |  | ||||||
|     while (current != nullptr) |  | ||||||
|     { |  | ||||||
|         exist = (current == this); |  | ||||||
|         if (exist) break; |  | ||||||
|         current = current->next; |  | ||||||
|     } |  | ||||||
|     if (!exist) |  | ||||||
|     { |  | ||||||
|         if (IR_Encoder::head == nullptr) |  | ||||||
|         { |  | ||||||
|             IR_Encoder::head = this; |  | ||||||
|             last = this; |  | ||||||
|         } |  | ||||||
|         else |  | ||||||
|         { |  | ||||||
|             last->next = this; |  | ||||||
|             last = this; |  | ||||||
|         } |  | ||||||
|         this->next = nullptr; // Указываем, что следующий за этим элементом — nullptr |  | ||||||
|     } |  | ||||||
|     pinMode(pin, OUTPUT); |  | ||||||
| } |  | ||||||
|  |  | ||||||
| void IR_Encoder::disable() |  | ||||||
| { |  | ||||||
|     IR_Encoder *current = IR_Encoder::head; |  | ||||||
|     IR_Encoder *prev = nullptr; |  | ||||||
|  |  | ||||||
|     while (current != nullptr) |  | ||||||
|     { |  | ||||||
|         if (current == this) break; |  | ||||||
|         prev = current; |  | ||||||
|         current = current->next; |  | ||||||
|     } |  | ||||||
|  |  | ||||||
|     if (current != nullptr) // Элемент найден в списке |  | ||||||
|     { |  | ||||||
|         if (prev != nullptr) |  | ||||||
|         { |  | ||||||
|             prev->next = current->next; // Убираем текущий элемент из списка |  | ||||||
|         } |  | ||||||
|         else |  | ||||||
|         { |  | ||||||
|             IR_Encoder::head = current->next; // Удаляемый элемент был первым |  | ||||||
|         } |  | ||||||
|  |  | ||||||
|         if (current == last) |  | ||||||
|         { |  | ||||||
|             last = prev; // Если удаляется последний элемент, обновляем last |  | ||||||
|         } |  | ||||||
|     } |  | ||||||
|  |  | ||||||
|     pinMode(pin, INPUT); |  | ||||||
| } |  | ||||||
|  |  | ||||||
| void IR_Encoder::setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count) | void IR_Encoder::setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count) | ||||||
| { | { | ||||||
| #if disablePairDec | #if disablePairDec | ||||||
| @ -124,18 +34,21 @@ void IR_Encoder::setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count) | |||||||
|     blindDecoders = decoders; |     blindDecoders = decoders; | ||||||
| } | } | ||||||
|  |  | ||||||
| IR_Encoder::~IR_Encoder(){}; | IR_Encoder::~IR_Encoder() | ||||||
|  | { | ||||||
|  |     delete[] bitLow; | ||||||
|  |     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) | ||||||
| { | { | ||||||
|     sendData(addrTo, &dataByte, 1, needAccept); |     uint8_t *dataPtr = new uint8_t[1]; | ||||||
|  |     dataPtr[0] = dataByte; | ||||||
|  |     sendData(addrTo, dataPtr, 1, needAccept); | ||||||
|  |     delete[] dataPtr; | ||||||
| } | } | ||||||
|  |  | ||||||
| void IR_Encoder::sendData(uint16_t addrTo, uint8_t *data, uint8_t len, bool needAccept){ | void IR_Encoder::sendData(uint16_t addrTo, uint8_t *data, uint8_t len, bool needAccept) | ||||||
|     sendDataFULL(id, addrTo, data, len, needAccept); |  | ||||||
| } |  | ||||||
|  |  | ||||||
| void IR_Encoder::sendDataFULL(uint16_t addrFrom, uint16_t addrTo, uint8_t *data, uint8_t len, bool needAccept) |  | ||||||
| { | { | ||||||
|     if (len > bytePerPack) |     if (len > bytePerPack) | ||||||
|     { |     { | ||||||
| @ -152,8 +65,8 @@ void IR_Encoder::sendDataFULL(uint16_t addrFrom, uint16_t addrTo, uint8_t *data, | |||||||
|     sendBuffer[0] = msgType; |     sendBuffer[0] = msgType; | ||||||
|  |  | ||||||
|     // addr_self |     // addr_self | ||||||
|     sendBuffer[1] = addrFrom >> 8 & 0xFF; |     sendBuffer[1] = id >> 8 & 0xFF; | ||||||
|     sendBuffer[2] = addrFrom & 0xFF; |     sendBuffer[2] = id & 0xFF; | ||||||
|  |  | ||||||
|     // addr_to |     // addr_to | ||||||
|     sendBuffer[3] = addrTo >> 8 & 0xFF; |     sendBuffer[3] = addrTo >> 8 & 0xFF; | ||||||
| @ -228,8 +141,7 @@ void IR_Encoder::sendBack(uint8_t data) | |||||||
| { | { | ||||||
|     _sendBack(false, 0, &data, 1); |     _sendBack(false, 0, &data, 1); | ||||||
| } | } | ||||||
|  | void IR_Encoder::sendBack(uint8_t *data , uint8_t len) | ||||||
| void IR_Encoder::sendBack(uint8_t *data, uint8_t len) |  | ||||||
| { | { | ||||||
|     _sendBack(false, 0, data, len); |     _sendBack(false, 0, data, len); | ||||||
| } | } | ||||||
| @ -284,10 +196,6 @@ void IR_Encoder::setDecoder_isSending() | |||||||
|         for (uint8_t i = 0; i < decodersCount; i++) |         for (uint8_t i = 0; i < decodersCount; i++) | ||||||
|         { |         { | ||||||
|             blindDecoders[i]->isPairSending ^= id; |             blindDecoders[i]->isPairSending ^= id; | ||||||
|             // Serial.print("setDecoder_isSending()   id = "); |  | ||||||
|             // Serial.print(id); |  | ||||||
|             // Serial.print("   isPairSending = "); |  | ||||||
|             // Serial.println(blindDecoders[i]->isPairSending); |  | ||||||
|         } |         } | ||||||
|     } |     } | ||||||
| } | } | ||||||
| @ -299,7 +207,7 @@ void IR_Encoder::rawSend(uint8_t *ptr, uint8_t len) | |||||||
|         // TODO: Обработка повторной отправки |         // TODO: Обработка повторной отправки | ||||||
|         return; |         return; | ||||||
|     } |     } | ||||||
|     // Serial.println("START"); |  | ||||||
|     setDecoder_isSending(); |     setDecoder_isSending(); | ||||||
|  |  | ||||||
|     // noInterrupts(); |     // noInterrupts(); | ||||||
| @ -323,25 +231,12 @@ void IR_Encoder::rawSend(uint8_t *ptr, uint8_t len) | |||||||
| } | } | ||||||
|  |  | ||||||
| void IR_Encoder::isr() | void IR_Encoder::isr() | ||||||
| { |  | ||||||
|     IR_Encoder *current = IR_Encoder::head; |  | ||||||
|     while (current != nullptr) |  | ||||||
|     { |  | ||||||
|       current->_isr(); |  | ||||||
|       current = current->next; |  | ||||||
|     } |  | ||||||
| } |  | ||||||
|  |  | ||||||
| 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); |  | ||||||
|  |  | ||||||
|     if (toggleCounter) |     if (toggleCounter) | ||||||
|     { |     { | ||||||
|         toggleCounter--; |         toggleCounter--; | ||||||
| @ -356,9 +251,7 @@ void IR_Encoder::_isr() | |||||||
|             // сброс счетчиков |             // сброс счетчиков | ||||||
|             // ... |             // ... | ||||||
|             isSending = false; |             isSending = false; | ||||||
|             // Serial.println("STOP"); |  | ||||||
|             setDecoder_isSending(); |             setDecoder_isSending(); | ||||||
|             // Serial.println(); |  | ||||||
|             return; |             return; | ||||||
|             break; |             break; | ||||||
|  |  | ||||||
| @ -476,16 +369,37 @@ void IR_Encoder::addSync(bool *prev, bool *next) | |||||||
|     } |     } | ||||||
| } | } | ||||||
|  |  | ||||||
| uint8_t IR_Encoder::bitHigh[2] = { | void IR_Encoder::send_HIGH(bool prevBite) | ||||||
|     (bitPauseTakts) * 2 - 1, | { | ||||||
|     (bitActiveTakts) * 2 - 1}; |  | ||||||
| uint8_t IR_Encoder::bitLow[2] = { |  | ||||||
|     (bitPauseTakts / 2 + bitActiveTakts) * 2 - 1, |  | ||||||
|     (bitPauseTakts)-1}; |  | ||||||
|  |  | ||||||
| // uint8_t* IR_Encoder::bitHigh = new uint8_t[2]{ |     // if (/* prevBite */1) { | ||||||
| //         (bitPauseTakts) * 2 - 0, |     //     meanderBlock(bitPauseTakts * 2, halfPeriod, LOW); | ||||||
| //         (bitActiveTakts) * 2 - 0}; |     //     meanderBlock(bitActiveTakts, halfPeriod, HIGH); | ||||||
| // uint8_t* IR_Encoder::bitLow = new uint8_t[2]{ |     // } else {                                                    // более короткий HIGH после нуля | ||||||
| //         (bitPauseTakts/2 + bitActiveTakts) * 2 - 0, |     //     meanderBlock(bitTakts - (bitActiveTakts - bitPauseTakts), halfPeriod, LOW); | ||||||
| //         (bitPauseTakts) - 0}; |     //     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: Отодвинуть преамбулу | ||||||
|  | } | ||||||
|  |  | ||||||
|  | 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}; | ||||||
							
								
								
									
										51
									
								
								IR_Encoder.h
									
									
									
									
									
								
							
							
						
						
									
										51
									
								
								IR_Encoder.h
									
									
									
									
									
								
							| @ -4,36 +4,53 @@ | |||||||
| // TODO: Отложенная передача после завершения приема | // TODO: Отложенная передача после завершения приема | ||||||
|  |  | ||||||
| class IR_DecoderRaw; | class IR_DecoderRaw; | ||||||
| class IR_Encoder : public IR_FOX | class IR_Encoder : IR_FOX | ||||||
| { | { | ||||||
|     friend IR_DecoderRaw; |     friend IR_DecoderRaw; | ||||||
|     static IR_Encoder *head; |  | ||||||
|     static IR_Encoder *last; |  | ||||||
|     IR_Encoder *next; |  | ||||||
| public: | public: | ||||||
|     static HardwareTimer* IR_Timer; |  | ||||||
| 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 = 0, IR_DecoderRaw *decPair = nullptr, bool autoHandle = true); |     IR_Encoder(uint16_t addr, IR_DecoderRaw *decPair = nullptr); | ||||||
|     static void isr(); |  | ||||||
|     static void begin(HardwareTimer* timer, uint8_t channel, IRQn_Type IRQn, uint8_t priority, void(*isrCallback)() = nullptr); |  | ||||||
|     static HardwareTimer* get_IR_Timer(); |  | ||||||
|  |  | ||||||
|     void enable(); |     // static void timerSetup() | ||||||
|     void disable(); |     // { | ||||||
|  |     // //     // 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 setBlindDecoders(IR_DecoderRaw *decoders[], uint8_t count); |     void 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 sendDataFULL(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); | ||||||
| @ -42,11 +59,11 @@ 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; | ||||||
|  |  | ||||||
|     void _isr(); |  | ||||||
| private: | private: | ||||||
|     void _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); | ||||||
|  |  | ||||||
| @ -90,8 +107,8 @@ private: | |||||||
|         uint8_t low; |         uint8_t low; | ||||||
|         uint8_t high; |         uint8_t high; | ||||||
|     }; |     }; | ||||||
|     static uint8_t bitHigh[2]; |     static uint8_t *bitHigh; | ||||||
|     static uint8_t bitLow[2]; |     static uint8_t *bitLow; | ||||||
|     uint8_t *currentBitSequence = bitLow; |     uint8_t *currentBitSequence = bitLow; | ||||||
|     volatile SignalPart signal; |     volatile SignalPart signal; | ||||||
| }; | }; | ||||||
|  | |||||||
| @ -1,33 +0,0 @@ | |||||||
| #include "IR_config.h" |  | ||||||
|  |  | ||||||
| void IR_FOX::setPin(uint8_t pin){ |  | ||||||
|     this->pin = pin; |  | ||||||
|     port = digitalPinToPort(pin); |  | ||||||
|     mask = digitalPinToBitMask(pin); |  | ||||||
| } |  | ||||||
|  |  | ||||||
| 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; |  | ||||||
| }; |  | ||||||
							
								
								
									
										225
									
								
								IR_config.h
									
									
									
									
									
								
							
							
						
						
									
										225
									
								
								IR_config.h
									
									
									
									
									
								
							| @ -1,39 +1,25 @@ | |||||||
| #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 - широковещательные пакеты (всем) |  | ||||||
| /* | /* | ||||||
| *Адресное пространство: | Адрес 0 запрещен и зарезервирован под NULL, либо тесты | ||||||
|     Адрес 0 запрещен и зарезервирован под NULL, либо тесты | IR_MSG_ACCEPT с адреса 0 воспринимается всеми устройствами | ||||||
|     IR_MSG_ACCEPT с адреса 0 воспринимается всеми устройствами |  | ||||||
| */  |  | ||||||
| //**** Контрольные точки ****** |  | ||||||
| #define IR_MAX_ADDR_CPU 63999 |  | ||||||
| #define IR_MIN_ADDR_CPU 32000 |  | ||||||
|  |  | ||||||
| // //***** Группы машинок ******** |  | ||||||
| // #define IR_MAX_CAR_GROUP 31999 |  | ||||||
| // #define IR_MIN_CAR_GROUP 30000 |  | ||||||
|  |  | ||||||
| // //********** FREE ************* | Адресное пространство: | ||||||
| // #define IR_MAX_FREE 31999 |  | ||||||
| // #define IR_MIN_FREE 2000 | Излучатели контрольных точек: 1000 ~ 1999 | ||||||
|  | Излучатели без обратной связиЖ 2000 ~ 2999 | ||||||
|  | Излучатели светофоров: 3000 ~ 3999 | ||||||
|  |  | ||||||
| //********* Машинки *********** |  | ||||||
| #define IR_MAX_CAR 31999 |  | ||||||
| #define IR_MIN_CAR 1 |  | ||||||
|  |  | ||||||
| //***** Пульты управления ***** |  | ||||||
| #define IR_MAX_CONTROLLER 64999 |  | ||||||
| #define IR_MIN_CONTROLLER 64000 |  | ||||||
| /* |  | ||||||
|  |  | ||||||
| /```````````````````````````````````````````````` data pack `````````````````````````````````````````````\                                   | /```````````````````````````````````````````````` data pack `````````````````````````````````````````````\                                   | ||||||
|                                                                                                           |                                                                                                           | ||||||
| @ -54,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 | ||||||
| @ -115,14 +101,14 @@ msg type: | |||||||
| /////////////////////////////////////////////////////////////////////////////////////*/ | /////////////////////////////////////////////////////////////////////////////////////*/ | ||||||
| typedef uint16_t crc_t; | typedef uint16_t crc_t; | ||||||
|  |  | ||||||
| // #define BRUTEFORCE_CHECK                            // Перепроверяет пакет на 1 битные ошибки //TODO: зависает | #define BRUTEFORCE_CHECK                            // Перепроверяет пакет на 1 битные ошибки //TODO: зависает | ||||||
| #define bytePerPack 16 // колличество байтов в пакете | #define bytePerPack 16                              // колличество байтов в пакете | ||||||
| #ifndef freeFrec | #ifndef freeFrec | ||||||
| #define freeFrec false | #define freeFrec false | ||||||
| #endif | #endif | ||||||
|  |  | ||||||
| #ifndef subBufferSize | #ifndef subBufferSize | ||||||
| #define subBufferSize 50 // Буфер для складирования фронтов, пока их не обработают (передатчик) | #define subBufferSize 5 //Буфер для складирования фронтов, пока их не обработают (передатчик) | ||||||
| #endif | #endif | ||||||
|  |  | ||||||
| #define preambPulse 3 | #define preambPulse 3 | ||||||
| @ -131,40 +117,32 @@ 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 12U                                    // длительность низкого уровня в тактах | ||||||
|  |  | ||||||
| #define bitTakts (bitActiveTakts + bitPauseTakts) // Общая длительность бита в тактах | #define bitTakts (bitActiveTakts+bitPauseTakts)          // Общая длительность бита в тактах | ||||||
| #define bitTime (bitTakts * carrierPeriod)        // Общая длительность бита | #define bitTime (bitTakts*carrierPeriod)                    // Общая длительность бита | ||||||
| #define tolerance 300U | #define tolerance 300U | ||||||
|  | class IR_FOX { | ||||||
| constexpr uint16_t test_all_Time = bitTime; |  | ||||||
| constexpr uint16_t test_all_Takts = bitTakts * 2; |  | ||||||
| constexpr uint16_t test_hi = ((bitPauseTakts) * 2 - 0) + ((bitActiveTakts) * 2 - 0); |  | ||||||
| constexpr uint16_t test_low = ((bitPauseTakts / 2 + bitActiveTakts) * 2 - 0) + ((bitPauseTakts)-0); |  | ||||||
|  |  | ||||||
| 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; | ||||||
| @ -172,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() const { 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: |  | ||||||
|     uint16_t id; |     uint16_t id; | ||||||
|     uint8_t pin; | protected: | ||||||
|     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); |     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: | ||||||
|  | // }; | ||||||
|  | |||||||
		Reference in New Issue
	
	Block a user