mirror of
https://github.com/Show-maket/IR-protocol.git
synced 2025-06-27 20:59:37 +00:00
Compare commits
5 Commits
277985f79a
...
main
Author | SHA1 | Date | |
---|---|---|---|
37522f974f | |||
6375c4eed5 | |||
c4000d6b75 | |||
fc02c79135 | |||
d068a576f7 |
4
.gitignore
vendored
4
.gitignore
vendored
@ -1 +1,3 @@
|
||||
.vscode/*
|
||||
.vscode/*
|
||||
bin/*
|
||||
log/*
|
@ -2,10 +2,11 @@
|
||||
#include "IR_Encoder.h"
|
||||
#include "TimerStatic.h"
|
||||
#include "MemoryCheck.h"
|
||||
#include "CarCmdList.h"
|
||||
/////////////// Pinout ///////////////
|
||||
|
||||
#define encForward_PIN 5
|
||||
#define encBackward_PIN 6
|
||||
#define encForward_PIN 0
|
||||
#define encBackward_PIN 5
|
||||
|
||||
#define LoopOut 12
|
||||
#define ISR_Out 10
|
||||
@ -32,9 +33,9 @@ void decForwardISR() {
|
||||
decForward.isr();
|
||||
}
|
||||
|
||||
// void decBackwardISR() {
|
||||
// decBackward.isr();
|
||||
// }
|
||||
void decBackwardISR() {
|
||||
decBackward.isr();
|
||||
}
|
||||
|
||||
static uint8_t* portOut;
|
||||
ISR(TIMER2_COMPA_vect) {
|
||||
@ -42,9 +43,9 @@ ISR(TIMER2_COMPA_vect) {
|
||||
// encBackward.isr();
|
||||
// encTree.isr();
|
||||
//TODO: Сделать выбор порта
|
||||
*portOut = (*portOut & 0b11001111) |
|
||||
*portOut = (*portOut & 0b11111110) |
|
||||
(
|
||||
encForward.ir_out_virtual << 5U
|
||||
encForward.ir_out_virtual << 0U
|
||||
// | encBackward.ir_out_virtual << 6U
|
||||
// | encTree.ir_out_virtual << 2U
|
||||
);
|
||||
@ -57,10 +58,10 @@ uint8_t data3 [] = { 42 , 127, 137 };
|
||||
uint8_t data4 [] = { 42 , 127, 137, 255 };
|
||||
|
||||
uint32_t loopTimer;
|
||||
uint8_t sig = 0;
|
||||
uint8_t sig = 255;
|
||||
|
||||
uint16_t targetAddr = IR_Broadcast;
|
||||
Timer t1(500, millis, []() {
|
||||
Timer t1(750, millis, []() {
|
||||
|
||||
// Serial.println(sig);
|
||||
|
||||
@ -151,7 +152,7 @@ Timer t2(500, millis, []() {
|
||||
/////////////////////////////////////////////////////////////////////
|
||||
void setup() {
|
||||
IR_Encoder::timerSetup();
|
||||
portOut = &PORTD;
|
||||
portOut = &PORTB;
|
||||
|
||||
Serial.begin(SERIAL_SPEED);
|
||||
Serial.println(F(INFO));
|
||||
@ -174,6 +175,7 @@ void setup() {
|
||||
pinMode(encForward_PIN, OUTPUT);
|
||||
pinMode(encBackward_PIN, OUTPUT);
|
||||
pinMode(13, OUTPUT);
|
||||
pinMode(12, OUTPUT);
|
||||
|
||||
|
||||
|
||||
@ -182,18 +184,22 @@ void setup() {
|
||||
|
||||
|
||||
attachInterrupt(0, decForwardISR, CHANGE); // D2
|
||||
// attachInterrupt(1, decBackwardISR, CHANGE); // D3
|
||||
attachInterrupt(1, decBackwardISR, CHANGE); // D3
|
||||
}
|
||||
|
||||
|
||||
bool testLed = false;
|
||||
uint32_t testLed_timer;
|
||||
|
||||
void loop() {
|
||||
digitalToggle(LoopOut);
|
||||
// digitalToggle(LoopOut);
|
||||
Timer::tick();
|
||||
|
||||
decForward.tick();
|
||||
decBackward.tick();
|
||||
|
||||
status(decForward);
|
||||
// status(decBackward);
|
||||
status(decBackward);
|
||||
|
||||
|
||||
// Serial.println(micros() - loopTimer);
|
||||
@ -218,6 +224,13 @@ void loop() {
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if(testLed && millis() - testLed_timer > 100){
|
||||
testLed=false;
|
||||
digitalWrite(12, LOW);
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
@ -227,7 +240,15 @@ void loop() {
|
||||
|
||||
//test
|
||||
void status(IR_Decoder& dec) {
|
||||
if (dec.gotData.available()) {
|
||||
if (dec.gotData.available() && dec.gotData.getAddrFrom() != 42) {
|
||||
|
||||
digitalWrite(12, HIGH);
|
||||
testLed = true;
|
||||
testLed_timer = millis();
|
||||
|
||||
encForward.sendData(IR_Broadcast, CarCmd::stop); //<<<<<<<<<<<<<<<<<<<<<<<<<<< CMD IS HERE
|
||||
|
||||
|
||||
String str;
|
||||
if (/* dec.gotData.getDataPrt()[1] */1) {
|
||||
str += ("Data on pin "); str += (dec.isrPin); str += "\n";
|
||||
|
@ -48,7 +48,10 @@ void IR_Encoder::sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept = f
|
||||
delete[] dataPtr;
|
||||
}
|
||||
|
||||
void IR_Encoder::sendData(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false)
|
||||
void IR_Encoder::sendData(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false){
|
||||
sendData(id, addrTo, data, len, needAccept);
|
||||
}
|
||||
void IR_Encoder::sendData(uint16_t addrFrom, uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false)
|
||||
{
|
||||
if (len > bytePerPack)
|
||||
{
|
||||
@ -65,8 +68,8 @@ void IR_Encoder::sendData(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len
|
||||
sendBuffer[0] = msgType;
|
||||
|
||||
// addr_self
|
||||
sendBuffer[1] = id >> 8 & 0xFF;
|
||||
sendBuffer[2] = id & 0xFF;
|
||||
sendBuffer[1] = addrFrom >> 8 & 0xFF;
|
||||
sendBuffer[2] = addrFrom & 0xFF;
|
||||
|
||||
// addr_to
|
||||
sendBuffer[3] = addrTo >> 8 & 0xFF;
|
||||
|
@ -4,13 +4,13 @@
|
||||
// TODO: Отложенная передача после завершения приема
|
||||
|
||||
class IR_DecoderRaw;
|
||||
class IR_Encoder : IR_FOX
|
||||
class IR_Encoder : public IR_FOX
|
||||
{
|
||||
friend IR_DecoderRaw;
|
||||
|
||||
public:
|
||||
private:
|
||||
uint16_t id; /// @brief Адрес передатчика
|
||||
// uint16_t id; /// @brief Адрес передатчика
|
||||
|
||||
public:
|
||||
/// @brief Класс передатчика
|
||||
@ -49,6 +49,7 @@ public:
|
||||
|
||||
void sendData(uint16_t addrTo, uint8_t dataByte, bool needAccept = false);
|
||||
void sendData(uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false);
|
||||
void sendData(uint16_t addrFrom, uint16_t addrTo, uint8_t *data = nullptr, uint8_t len = 0, bool needAccept = false);
|
||||
|
||||
void sendAccept(uint16_t addrTo, uint8_t customByte = 0);
|
||||
void sendRequest(uint16_t addrTo);
|
||||
|
Reference in New Issue
Block a user