Merge branch 'main' into STM32

This commit is contained in:
DashyFox
2026-03-11 17:06:06 +03:00
committed by GitHub
4 changed files with 103 additions and 92 deletions

2
.gitignore vendored
View File

@ -1,5 +1,3 @@
.vscode/* .vscode/*
bin/* bin/*
!.vscode/launch.json
log/* log/*
/.vscode

View File

@ -2,26 +2,16 @@
#include "IR_Encoder.h" #include "IR_Encoder.h"
#include "TimerStatic.h" #include "TimerStatic.h"
#include "MemoryCheck.h" #include "MemoryCheck.h"
#include "CarCmdList.h"
/////////////// Pinout /////////////// /////////////// Pinout ///////////////
#define dec0_PIN PIN_KT1_IN #define encForward_PIN 0
#define dec1_PIN PIN_KT2_IN #define encBackward_PIN 5
#define dec2_PIN PIN_KT3_IN
#define dec3_PIN PIN_KT4_IN
#define dec4_PIN PIN_KT5_IN
#define dec5_PIN PIN_KT6_IN
#define dec6_PIN PIN_KT7_IN
#define dec7_PIN PIN_KT8_IN
// #define dec8_PIN PB8
// #define dec9_PIN PB9
// #define dec10_PIN PB10
// #define dec11_PIN PB11
// #define dec12_PIN PB12
// #define dec13_PIN PB13
// #define dec14_PIN PB14
// #define dec15_PIN PB15
#define LoopOut PC13 #define LoopOut 12
#define ISR_Out 10
#define TestOut 13
//////////////// Ini ///////////////// //////////////// Ini /////////////////
@ -49,13 +39,35 @@ void EncoderISR()
IR_Encoder::isr(); IR_Encoder::isr();
} }
//------------------------------------------------------------------- void decBackwardISR() {
decBackward.isr();
}
IR_Decoder dec0(dec0_PIN, 0); static uint8_t* portOut;
void dec_0_ISR() { dec0.isr(); } ISR(TIMER2_COMPA_vect) {
encForward.isr();
// encBackward.isr();
// encTree.isr();
//TODO: Сделать выбор порта
*portOut = (*portOut & 0b11111110) |
(
encForward.ir_out_virtual << 0U
// | encBackward.ir_out_virtual << 6U
// | encTree.ir_out_virtual << 2U
);
}
/////////////////////////////////////////////////////////////////////
uint8_t data0 [] = { };
uint8_t data1 [] = { 42 };
uint8_t data2 [] = { 42 , 127 };
uint8_t data3 [] = { 42 , 127, 137 };
uint8_t data4 [] = { 42 , 127, 137, 255 };
IR_Decoder dec1(dec1_PIN, 1); uint32_t loopTimer;
void dec_1_ISR() { dec1.isr(); } uint8_t sig = 255;
uint16_t targetAddr = IR_Broadcast;
Timer t1(750, millis, []() {
IR_Decoder dec2(dec2_PIN, 2); IR_Decoder dec2(dec2_PIN, 2);
void dec_2_ISR() { dec2.isr(); } void dec_2_ISR() { dec2.isr(); }
@ -81,8 +93,19 @@ void dec_7_ISR() { dec7.isr(); }
// IR_Decoder dec9(dec9_PIN, 9); // IR_Decoder dec9(dec9_PIN, 9);
// void dec_9_ISR() { dec9.isr(); } // void dec_9_ISR() { dec9.isr(); }
// IR_Decoder dec10(dec10_PIN, 10); default:
// void dec_10_ISR() { dec10.isr(); } break;
}
// encBackward.sendData(IR_Broadcast, data2);
// encTree.sendData(IR_Broadcast, rawData3);
});
Timer t2(500, millis, []() {
digitalToggle(13);
});
/////////////////////////////////////////////////////////////////////
void setup() {
IR_Encoder::timerSetup();
portOut = &PORTB;
// IR_Decoder dec11(dec11_PIN, 11); // IR_Decoder dec11(dec11_PIN, 11);
// void dec_11_ISR() { dec11.isr(); } // void dec_11_ISR() { dec11.isr(); }
@ -100,9 +123,14 @@ uint8_t data2[] = {42, 127};
uint8_t data3[] = {42, 127, 137}; uint8_t data3[] = {42, 127, 137};
uint8_t data4[] = {42, 127, 137, 255}; uint8_t data4[] = {42, 127, 137, 255};
uint32_t loopTimer; pinMode(8, OUTPUT);
uint8_t sig = 0; pinMode(9, OUTPUT);
uint16_t targetAddr = IR_Broadcast; pinMode(11, OUTPUT);
pinMode(13, OUTPUT);
pinMode(encForward_PIN, OUTPUT);
pinMode(encBackward_PIN, OUTPUT);
pinMode(13, OUTPUT);
pinMode(12, OUTPUT);
Timer t1(500, millis, []() Timer t1(500, millis, []()
{ {
@ -217,61 +245,30 @@ void setup()
pinMode(LoopOut, OUTPUT); pinMode(LoopOut, OUTPUT);
pinMode(dec0_PIN, INPUT_PULLUP); attachInterrupt(0, decForwardISR, CHANGE); // D2
pinMode(dec1_PIN, INPUT_PULLUP); attachInterrupt(1, decBackwardISR, CHANGE); // D3
pinMode(dec2_PIN, INPUT_PULLUP);
pinMode(dec3_PIN, INPUT_PULLUP);
pinMode(dec4_PIN, INPUT_PULLUP);
pinMode(dec5_PIN, INPUT_PULLUP);
pinMode(dec6_PIN, INPUT_PULLUP);
pinMode(dec7_PIN, INPUT_PULLUP);
// pinMode(dec8_PIN, INPUT_PULLUP);
// pinMode(dec9_PIN, INPUT_PULLUP);
// pinMode(dec10_PIN, INPUT_PULLUP);
// pinMode(dec11_PIN, INPUT_PULLUP);
// pinMode(dec12_PIN, INPUT_PULLUP);
// pinMode(dec13_PIN, INPUT_PULLUP);
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()
{ bool testLed = false;
digitalToggle(LoopOut); uint32_t testLed_timer;
void loop() {
// digitalToggle(LoopOut);
Timer::tick(); Timer::tick();
IR_Decoder::tick();
bool rx_flag = false; decForward.tick();
rx_flag |= status(dec0); decBackward.tick();
rx_flag |= status(dec1);
rx_flag |= status(dec2);
rx_flag |= status(dec3);
rx_flag |= status(dec4);
rx_flag |= status(dec5);
rx_flag |= status(dec6);
rx_flag |= status(dec7);
// rx_flag |= status(dec8);
// rx_flag |= status(dec9);
// rx_flag |= status(dec10);
// rx_flag |= status(dec11);
// rx_flag |= status(dec12);
// rx_flag |= status(dec13);
if (Serial.available()) status(decForward);
{ status(decBackward);
// Serial.println(micros() - loopTimer);
// loopTimer = micros();
// delayMicroseconds(120*5);
if (Serial.available()) {
uint8_t in = Serial.parseInt(); uint8_t in = Serial.parseInt();
switch (in) switch (in)
{ {
@ -289,6 +286,13 @@ void loop()
break; break;
} }
} }
if(testLed && millis() - testLed_timer > 100){
testLed=false;
digitalWrite(12, LOW);
}
} }
@ -316,13 +320,19 @@ void detectSignal()
// { digitalWrite(SignalDetectLed, LOW); }); // { digitalWrite(SignalDetectLed, LOW); });
} }
// test
bool status(IR_Decoder &dec)
{ //test
if (dec.gotData.available()) void status(IR_Decoder& dec) {
{ if (dec.gotData.available() && dec.gotData.getAddrFrom() != 42) {
detectSignal();
// Serial.println(micros()); digitalWrite(12, HIGH);
testLed = true;
testLed_timer = millis();
encForward.sendData(IR_Broadcast, CarCmd::stop); //<<<<<<<<<<<<<<<<<<<<<<<<<<< CMD IS HERE
String str; String str;
if (/* dec.gotData.getDataPrt()[1] */ 1) if (/* dec.gotData.getDataPrt()[1] */ 1)
{ {

View File

@ -321,7 +321,10 @@ IR_SendResult IR_Encoder::sendData(uint16_t addrTo, uint8_t *data, uint8_t len,
return sendDataFULL(id, addrTo, data, len, needAccept); return sendDataFULL(id, addrTo, data, len, needAccept);
} }
IR_SendResult IR_Encoder::sendDataFULL(uint16_t addrFrom, uint16_t addrTo, uint8_t *data, uint8_t len, bool needAccept) void IR_Encoder::sendData(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false){
sendData(id, addrTo, data, len, needAccept);
}
void IR_Encoder::sendData(uint16_t addrFrom, uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false)
{ {
if (len > bytePerPack) if (len > bytePerPack)
{ {

View File

@ -20,7 +20,8 @@ class IR_Encoder : public IR_FOX
static IR_Encoder *last; static IR_Encoder *last;
IR_Encoder *next; IR_Encoder *next;
public: public:
static HardwareTimer* IR_Timer; private:
// uint16_t id; /// @brief Адрес передатчика
struct IR_TxGateRun { struct IR_TxGateRun {
uint16_t lenTicks; // number of timer ticks at carrierFrec*2 uint16_t lenTicks; // number of timer ticks at carrierFrec*2
@ -60,10 +61,9 @@ public:
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);
IR_SendResult sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept = false); void sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept = false);
IR_SendResult 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);
IR_SendResult sendDataFULL(uint16_t addrFrom, uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false); void sendData(uint16_t addrFrom, uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false);
IR_SendResult sendAccept(uint16_t addrTo, uint8_t customByte = 0); IR_SendResult sendAccept(uint16_t addrTo, uint8_t customByte = 0);
IR_SendResult sendRequest(uint16_t addrTo); IR_SendResult sendRequest(uint16_t addrTo);