广东创意机器人
陆空协同机器人
陆地车系统(自主巡线)以Arduino Uno主控板,红外循迹传感器,以及电机驱动等为核心硬件。使用代码编程,通过定义电机、红外循迹传感器引脚,撰写电机控制和巡线处理函数,实现陆地车的红外传感器识别场景中绘制的黑色线路进行自主巡线,让它在复杂地形中也能运行。
陆地车编程
基于UNO 开发板和四个红外传感器的巡线小车,前方左右两个红外传感器分别收到1和0时左转,0和0时直行,0和1时右转,1和1时进入第一个节点,左转一段时间T0,一直到左侧传感检测到黑线,原地右转一段时间T1,直走直到检测到1和1时进入第二个节点,原地转向返回第一个节点,进入第一个节点后左转一段时间T0一直到左侧传感检测到黑线,原地右转一段时间T1,直走直到检测到1和1时进入第三个节点,右转一段时间T0,直到右侧传感器检测到黑线,原地左转一段时间 T1,直走直到检测到1和1时 进入第四个节点,原地转向返回第三个节点,进入第三个节点后右转一段时间T0,一直到右侧传感器检测到黑线原地左转一段时间T1,直走直到检测到第五个节点,然后重复第一个节点和第二个节点的动作。这是巡线小车的运行路线,简化这段表述用于后续程序逻辑的编写。
提示词
想要替换 delay()函数,还可以使用什么定时器方法
millis(): 非阻塞时间判断,最常用。用 unsigned long t = millis(); if (millis() - t >= interval) { …; t = millis(); } 来替代 delay()。适合大多数巡线/状态机场景。 micros(): 更高精度(微秒级),适合要求短延时或高分辨率测量,但注意溢出和开销。 为什么用 millis() 替代最常见:delay() 会阻塞 CPU,影响传感器读取、串口通讯、PWM 控制等实时行为。millis() 允许主循环继续运行并处理其它任务。
millis() 替换模式(经典模板)
//
// 红外传感器引脚定义
#define IR_DOWN 5 // 0号红外循迹模块右侧下方
#define IR_UP 6 // 1号红外循迹模块右侧上方
#define IR_RIGHT 7 // 2号红外循迹模块前方右侧
#define IR_LEFT 8 // 3号红外循迹模块前方左侧
// 定义常量
unsigned long nodeStartTime = 0; // 用于节点动作计时器的动作超时控制
unsigned long stepStart = 0; // 用于非阻塞子步骤流程控制(每个节点使用同一组 step 变量,进入新节点时重置)
int nodeStep = 0; // 当前节点的子步骤计数
// 电机引脚定义
#define LEFT_MOTOR_PIN1 3 // 左电机引脚1
#define LEFT_MOTOR_PIN2 9 // 左电机引脚2
#define RIGHT_MOTOR_PIN1 10 // 右电机引脚1
#define RIGHT_MOTOR_PIN2 11 // 右电机引脚2
// 电机控制函数
const int LEFT_MOTOR_SPEED = 80; // 左电机速度(可微调)
const int RIGHT_MOTOR_SPEED = 80; // 右电机速度(可微调)
// PWM 差速校准系数(用于补偿电机硬件差异)
// 范围 [0.8, 1.2]:如果某电机偏慢,增大系数;偏快,减小系数
const float LEFT_SPEED_FACTOR = 1.0f; // 左电机校准系数
const float RIGHT_SPEED_FACTOR = 1.0f; // 右电机校准系数
void STOP()
{
digitalWrite(LEFT_MOTOR_PIN1, 0);
digitalWrite(LEFT_MOTOR_PIN2, 0);
digitalWrite(RIGHT_MOTOR_PIN1, 0);
digitalWrite(RIGHT_MOTOR_PIN2, 0);
}
// 差速驱动辅助函数:根据校准系数调整 PWM,以补偿电机差异
void driveWithDifferential(int leftPwm, int rightPwm)
{
// 应用校准系数
int adjLeft = (int)(leftPwm * LEFT_SPEED_FACTOR);
int adjRight = (int)(rightPwm * RIGHT_SPEED_FACTOR);
// 确保 PWM 值在 [0, 255] 范围内
adjLeft = constrain(adjLeft, 0, 255);
adjRight = constrain(adjRight, 0, 255);
analogWrite(LEFT_MOTOR_PIN2, adjLeft);
analogWrite(RIGHT_MOTOR_PIN1, adjRight);
}
void QJ()
{
digitalWrite(LEFT_MOTOR_PIN1, 0);
driveWithDifferential(LEFT_MOTOR_SPEED, RIGHT_MOTOR_SPEED);
digitalWrite(RIGHT_MOTOR_PIN2, 0);
}
void HT()
{
digitalWrite(LEFT_MOTOR_PIN1, LEFT_MOTOR_SPEED);
analogWrite(LEFT_MOTOR_PIN2, 0);
analogWrite(RIGHT_MOTOR_PIN1, 0);
digitalWrite(RIGHT_MOTOR_PIN2, RIGHT_MOTOR_SPEED);
}
void YDZZ()
{
analogWrite(LEFT_MOTOR_PIN1, (int)(LEFT_MOTOR_SPEED * LEFT_SPEED_FACTOR));
digitalWrite(LEFT_MOTOR_PIN2, 0);
analogWrite(RIGHT_MOTOR_PIN1, (int)(RIGHT_MOTOR_SPEED * RIGHT_SPEED_FACTOR));
digitalWrite(RIGHT_MOTOR_PIN2, 0);
}
void YDYZ()
{
digitalWrite(LEFT_MOTOR_PIN1, 0);
analogWrite(LEFT_MOTOR_PIN2, (int)(LEFT_MOTOR_SPEED * LEFT_SPEED_FACTOR));
digitalWrite(RIGHT_MOTOR_PIN1, 0);
analogWrite(RIGHT_MOTOR_PIN2, (int)(RIGHT_MOTOR_SPEED * RIGHT_SPEED_FACTOR));
}
// 读取前方左右红外传感器
void readSensors(int &left, int &right, int &down, int &up)
{
left = digitalRead(IR_LEFT); // 输出 1 表示检测到黑线;输出 0 表示未检测到黑线
right = digitalRead(IR_RIGHT);
down = digitalRead(IR_DOWN); // 靠近地面的右下传感器
up = digitalRead(IR_UP); // 右上(前方)传感器,用于预检测
}
// 巡线逻辑处理函数
// 返回值:true=检测到节点(1,1),false=未检测到
bool handleLineFollow(int left, int right)
{
if (left == 1 && right == 0)
{
YDZZ();
}
else if (left == 0 && right == 0)
{
QJ();
}
else if (left == 0 && right == 1)
{
YDYZ();
}
else if (left == 1 && right == 1)
{
return true; // 检测到节点,返回true
}
return false; // 未检测到节点,返回false
}
// 细化的右侧边缘跟随:带去抖、搜索与恢复策略,非阻塞实现
bool handleEdgeFollow(int down, int up)
{
// unsigned long now = millis();
if (up == 1 && down == 1)
{
return true; // 检测到节点,返回true
}
else if (up == 0 && down == 1)
{
YDZZ();
}
else if (up == 1 && down == 0)
{
// 边缘在前方:微调向左靠近(使下传感器接触边缘)
YDYZ();
}
else if (up == 0 && down == 0)// up==0 && down==0
{
QJ();
}
return false; // 保持接口兼容,外部由前方传感器决定节点
}
// 节点状态
enum NodeState
{
EDGE_FOLLOW, // 右侧边缘跟随
START, // 起点
NODE1_ACTION, // 第一个节点的动作
NODE2_ACTION, // 第二个节点的动作
NODE3_ACTION,
NODE4_ACTION,
NODE5_ACTION,
NODE6_ACTION,
END // 终点
};
NodeState state = START;
#include <Arduino.h>
#include <main.h>
// 大地图 路程大约700cm,需要150秒内完成
void setup()
{
Serial.begin(115200);
pinMode(LEFT_MOTOR_PIN1, OUTPUT);
pinMode(LEFT_MOTOR_PIN2, OUTPUT);
pinMode(RIGHT_MOTOR_PIN1, OUTPUT);
pinMode(RIGHT_MOTOR_PIN2, OUTPUT);
pinMode(IR_LEFT, INPUT);
pinMode(IR_RIGHT, INPUT);
pinMode(IR_DOWN, INPUT);
pinMode(IR_UP, INPUT);
STOP();
}
// 轮询周期(ms)
static const unsigned long LOOP_INTERVAL_MS = 20UL;
static unsigned long lastLoop = 0UL;
void loop()
{
int left, right, down, up;
readSensors(left, right, down, up);
unsigned long now = millis();
switch (state)
{
case EDGE_FOLLOW:
{
// YDYZ();
if (now - lastLoop < LOOP_INTERVAL_MS)
return;
lastLoop = now;
if(handleEdgeFollow(down, up))
{
QJ();
stepStart = now;
if (now - stepStart < 800)
{
}
else if (now - stepStart < 800 + 200)
{
YDZZ();
stepStart = now;
}
}
if (left == 1 && right == 1)
{
// state = START;
// STOP();
// // 进入永久停止(示例),如果需要可改为进入其它 state
// while (true)
// {
// // 保持停止,防止继续运行。
// delay(1000);
// }
}
}
break;
case START:
if (handleLineFollow(left, right))
{
nodeStep = 0;
QJ();
stepStart = now;
state = NODE1_ACTION;
}
break;
case NODE1_ACTION:
{
if (nodeStep == 0)
{
if (now - stepStart >= 1000)
{
STOP();
stepStart = now;
nodeStep = 1;
}
}
else if (nodeStep == 1)
{
if (now - stepStart >= 1000)
{
YDZZ();
nodeStartTime = now;
nodeStep = 2;
}
}
else if (nodeStep == 2)
{
if (left == 1 || now - nodeStartTime > 3400)
{
STOP();
stepStart = now;
nodeStep = 3;
}
}
else if (nodeStep == 3)
{
if (now - stepStart < 100)
{
}
else if (now - stepStart < 100 + 200)
{
// YDZZ();
}
else if (now - stepStart < 100 + 200 + 100)
{
STOP();
}
else
{
if (handleLineFollow(left, right))
{
QJ();
nodeStep = -2;
stepStart = now;
state = NODE2_ACTION;
}
}
}
}
break;
case NODE2_ACTION:
{
if (nodeStep == -2)
{
if (now - stepStart >= 1600)
{
STOP();
stepStart = now;
nodeStep = -1;
}
}
else if (nodeStep == -1)
{
if (now - stepStart >= 500)
{
HT();
stepStart = now;
nodeStep = 0;
}
}
else if (nodeStep == 0)
{
if (now - stepStart >= 500)
{
STOP();
stepStart = now;
nodeStep = 1;
}
}
else if (nodeStep == 1)
{
if (now - stepStart >= 100)
{
YDZZ();
nodeStartTime = now;
nodeStep = 2;
}
}
else if (nodeStep == 2)
{
if (left == 1 || now - nodeStartTime > 3400)
{
STOP();
stepStart = now;
nodeStep = 3;
}
}
else if (nodeStep == 3)
{
if (now - stepStart < 100)
{
}
else if (now - stepStart < 100 + 200)
{
// YDZZ();
}
else if (now - stepStart < 100 + 200 + 100)
{
STOP();
}
else
{
if (handleLineFollow(left, right))
{
QJ();
stepStart = now;
nodeStep = 4;
}
}
}
else if (nodeStep == 4)
{
if (now - stepStart >= 1000)
{
STOP();
stepStart = now;
nodeStep = 5;
}
}
else if (nodeStep == 5)
{
if (now - stepStart >= 1000)
{
YDZZ();
nodeStartTime = now;
nodeStep = 6;
}
}
else if (nodeStep == 6)
{
if (left == 1 || now - nodeStartTime > 3400)
{
STOP();
stepStart = now;
nodeStep = 7;
}
}
else if (nodeStep == 7)
{
if (now - stepStart < 100)
{
}
else if (now - stepStart < 100 + 200)
{
// YDZZ();
}
else if (now - stepStart < 100 + 200 + 100)
{
STOP();
}
else
{
if (handleLineFollow(left, right))
{
QJ();
nodeStep = 0;
stepStart = now;
state = NODE3_ACTION;
}
}
}
}
break;
case NODE3_ACTION:
{
if (nodeStep == 0)
{
if (now - stepStart >= 1000)
{
STOP();
stepStart = now;
nodeStep = 1;
}
}
else if (nodeStep == 1)
{
if (now - stepStart >= 1000)
{
YDYZ();
nodeStartTime = now;
nodeStep = 2;
}
}
else if (nodeStep == 2)
{
if (right == 1 || now - nodeStartTime > 3400)
{
STOP();
stepStart = now;
nodeStep = 3;
}
}
else if (nodeStep == 3)
{
if (now - stepStart < 100)
{
}
else if (now - stepStart < 100 + 200)
{
// YDYZ();
}
else if (now - stepStart < 100 + 200 + 100)
{
STOP();
}
else
{
if (handleLineFollow(left, right))
{
QJ();
nodeStep = -2;
stepStart = now;
state = NODE4_ACTION;
}
}
}
}
break;
case NODE4_ACTION:
{
if (nodeStep == -2)
{
if (now - stepStart >= 1600)
{
STOP();
stepStart = now;
nodeStep = -1;
}
}
else if (nodeStep == -1)
{
if (now - stepStart >= 500)
{
HT();
stepStart = now;
nodeStep = 0;
}
}
else if (nodeStep == 0)
{
if (now - stepStart >= 500)
{
STOP();
stepStart = now;
nodeStep = 1;
}
}
else if (nodeStep == 1)
{
if (now - stepStart >= 100)
{
YDZZ();
nodeStartTime = now;
nodeStep = 2;
}
}
else if (nodeStep == 2)
{
if (left == 1 || now - nodeStartTime > 3400)
{
STOP();
stepStart = now;
nodeStep = 3;
}
}
else if (nodeStep == 3)
{
if (now - stepStart < 100)
{
}
else if (now - stepStart < 100 + 200)
{
// YDZZ();
}
else if (now - stepStart < 100 + 200 + 100)
{
STOP();
}
else
{
if (handleLineFollow(left, right))
{
QJ();
stepStart = now;
nodeStep = 4;
}
}
}
else if (nodeStep == 4)
{
if (now - stepStart >= 1000)
{
STOP();
stepStart = now;
nodeStep = 5;
}
}
else if (nodeStep == 5)
{
if (now - stepStart >= 1000)
{
YDYZ();
nodeStartTime = now;
nodeStep = 6;
}
}
else if (nodeStep == 6)
{
if (right == 1 || now - nodeStartTime > 3200)
{
STOP();
stepStart = now;
nodeStep = 7;
}
}
else if (nodeStep == 7)
{
if (now - stepStart < 100)
{
}
else if (now - stepStart < 100 + 200)
{
// YDYZ();
}
else if (now - stepStart < 100 + 200 + 100)
{
STOP();
}
else
{
if (handleLineFollow(left, right))
{
QJ();
nodeStep = 0;
stepStart = now;
state = NODE5_ACTION;
}
}
}
}
break;
case NODE5_ACTION:
{
if (nodeStep == 0)
{
if (now - stepStart >= 1000)
{
STOP();
stepStart = now;
nodeStep = 1;
}
}
else if (nodeStep == 1)
{
if (now - stepStart >= 1000)
{
YDZZ();
nodeStartTime = now;
nodeStep = 2;
}
}
else if (nodeStep == 2)
{
if (left == 1 || now - nodeStartTime > 3400)
{
STOP();
stepStart = now;
nodeStep = 3;
}
}
else if (nodeStep == 3)
{
if (now - stepStart < 100)
{
}
else if (now - stepStart < 100 + 200)
{
// YDZZ();
}
else if (now - stepStart < 100 + 200 + 100)
{
STOP();
}
else
{
if (handleLineFollow(left, right))
{
QJ();
nodeStep = -2;
stepStart = now;
state = NODE6_ACTION;
}
}
}
}
break;
case NODE6_ACTION:
{
if (nodeStep == -2)
{
if (now - stepStart >= 1600)
{
STOP();
stepStart = now;
nodeStep = -1;
}
}
else if (nodeStep == -1)
{
if (now - stepStart >= 500)
{
HT();
stepStart = now;
nodeStep = 0;
}
}
else if (nodeStep == 0)
{
if (now - stepStart >= 500)
{
STOP();
stepStart = now;
nodeStep = 1;
}
}
else if (nodeStep == 1)
{
if (now - stepStart >= 100)
{
YDZZ();
nodeStartTime = now;
nodeStep = 2;
}
}
else if (nodeStep == 2)
{
if (left == 1 || now - nodeStartTime > 3400)
{
STOP();
stepStart = now;
nodeStep = 3;
}
}
else if (nodeStep == 3)
{
if (now - stepStart < 100)
{
}
else if (now - stepStart < 100 + 200)
{
// YDZZ();
}
else if (now - stepStart < 100 + 200 + 100)
{
STOP();
}
else
{
if (handleLineFollow(left, right))
{
QJ();
stepStart = now;
nodeStep = 4;
}
}
}
else if (nodeStep == 4)
{
if (now - stepStart >= 1000)
{
STOP();
stepStart = now;
nodeStep = 5;
}
}
else if (nodeStep == 5)
{
if (now - stepStart >= 1000)
{
YDZZ();
nodeStartTime = now;
nodeStep = 6;
}
}
else if (nodeStep == 6)
{
if (left == 1 || now - nodeStartTime > 3400)
{
STOP();
stepStart = now;
nodeStep = 7;
}
}
else if (nodeStep == 7)
{
if (now - stepStart < 100)
{
}
else if (now - stepStart < 100 + 200)
{
// YDZZ();
}
else if (now - stepStart < 100 + 200 + 100)
{
STOP();
}
else
{
if (handleLineFollow(left, right))
{
QJ();
nodeStep = 0;
stepStart = now;
state = END;
}
}
}
}
break;
case END:
if (now - stepStart >= 4500)
{
STOP();
}
break;
}
}
山路然后是巡线,山路目前还是左右传感器的边缘检测。 左右电机的速度差还没有解决。
Visual Studio Code - The open source AI code editor
Your Gateway to Embedded Software Development Excellence · PlatformIO