fix
This commit is contained in:
parent
d7436607d5
commit
5953a5d6e6
|
@ -20,8 +20,8 @@
|
|||
|
||||
// 红外循迹模块引脚
|
||||
// 模式选择
|
||||
// #define IR_MODE IRMode::IR_MODE_GPIO
|
||||
#define IR_MODE IRMode::IR_MODE_I2C
|
||||
// 1 GPIO 2 I2C
|
||||
#define IR_MODE 2
|
||||
#define IR_COUNT 8
|
||||
// 是否反转电平输出
|
||||
#define IR_OUTPUT_REVERSE 0
|
||||
|
|
|
@ -6,15 +6,9 @@
|
|||
#include <algorithm>
|
||||
#include "consts.h"
|
||||
|
||||
enum IRMode
|
||||
{
|
||||
IR_MODE_GPIO,
|
||||
IR_MODE_I2C
|
||||
};
|
||||
|
||||
struct IRData
|
||||
{
|
||||
IRMode mode;
|
||||
uint8_t mode;
|
||||
uint8_t pins[IR_COUNT];
|
||||
uint8_t count;
|
||||
uint8_t data[8];
|
||||
|
|
61
src/ir.cpp
61
src/ir.cpp
|
@ -8,7 +8,7 @@ void IR::init()
|
|||
Serial.println("IR Init");
|
||||
data.mode = IR_MODE;
|
||||
data.count = IR_COUNT;
|
||||
if (IR_MODE == IRMode::IR_MODE_GPIO)
|
||||
#if IR_MODE == 1
|
||||
{
|
||||
uint8_t pins[IR_COUNT] = IR_PINS;
|
||||
for (int i = 0; i < IR_COUNT; i++)
|
||||
|
@ -16,7 +16,7 @@ void IR::init()
|
|||
data.pins[i] = pins[i];
|
||||
};
|
||||
}
|
||||
else if (IR_MODE == IRMode::IR_MODE_I2C)
|
||||
#elif IR_MODE == 2
|
||||
{
|
||||
uint8_t pins[2] = IR_PINS;
|
||||
data.pins[0] = pins[0]; // SCL
|
||||
|
@ -34,11 +34,12 @@ void IR::init()
|
|||
Serial.println("Invalid I2C pins");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void IR::update()
|
||||
{
|
||||
if (data.mode == IRMode::IR_MODE_GPIO)
|
||||
#if IR_MODE == 1
|
||||
{
|
||||
for (int i = 0; i < data.count; i++)
|
||||
{
|
||||
|
@ -58,36 +59,40 @@ void IR::update()
|
|||
#endif
|
||||
}
|
||||
}
|
||||
else if (data.mode == IRMode::IR_MODE_I2C && i2c != nullptr)
|
||||
#elif IR_MODE == 2
|
||||
{
|
||||
byte value = 0;
|
||||
|
||||
delay(10);
|
||||
|
||||
i2c->requestFrom(0x12, 1);
|
||||
if(i2c->available()) {
|
||||
value = i2c->read();
|
||||
if (i2c != nullptr)
|
||||
{
|
||||
byte value = 0;
|
||||
|
||||
// 根据 IR_COUNT 读取数据
|
||||
for(int i = 0; i < std::min<int>(data.count, IR_COUNT); i++) {
|
||||
// 读取传感器数据
|
||||
bool sensorValue = !((value >> (7-i)) & 0x01);
|
||||
delay(10);
|
||||
|
||||
i2c->requestFrom(0x12, 1);
|
||||
if(i2c->available()) {
|
||||
value = i2c->read();
|
||||
|
||||
// 根据 IR_REVERSE 判断是否需要反转电平
|
||||
#if IR_OUTPUT_REVERSE
|
||||
sensorValue = !sensorValue;
|
||||
#endif
|
||||
// 根据 IR_COUNT 读取数据
|
||||
for(int i = 0; i < std::min<int>(data.count, IR_COUNT); i++) {
|
||||
// 读取传感器数据
|
||||
bool sensorValue = !((value >> (7-i)) & 0x01);
|
||||
|
||||
// 根据 IR_REVERSE 判断是否需要反转电平
|
||||
#if IR_OUTPUT_REVERSE
|
||||
sensorValue = !sensorValue;
|
||||
#endif
|
||||
|
||||
// 根据传感器排列方向存储数据
|
||||
#ifdef IR_DIRECTION_REVERSE
|
||||
data.data[std::min<int>(data.count, IR_COUNT) - 1 - i] = sensorValue;
|
||||
#else
|
||||
data.data[i] = sensorValue;
|
||||
#endif
|
||||
// 根据传感器排列方向存储数据
|
||||
#ifdef IR_DIRECTION_REVERSE
|
||||
data.data[std::min<int>(data.count, IR_COUNT) - 1 - i] = sensorValue;
|
||||
#else
|
||||
data.data[i] = sensorValue;
|
||||
#endif
|
||||
}
|
||||
} else {
|
||||
// 通信失败时清零数据
|
||||
memset(data.data, 0, IR_COUNT);
|
||||
}
|
||||
} else {
|
||||
// 通信失败时清零数据
|
||||
memset(data.data, 0, IR_COUNT);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
Loading…
Reference in New Issue