结合“天尘 83086510”所提供的 WifiRobot 控制程序,设计了如下 Arduino 控制程序,主要是将小车的动作交给 UART 控制:
#include
/*
This is the first program for YM3 smart Car.
using Nano.
resource:
PIN2 --- input, interrupt, encode pulse sample
PIN6 --- output, Motor PWM, YM3's Ctrl1
PIN7 --- output, Motor Ctrl, YM3's Ctrl2
PIN8 --- output, Motor Ctrl. YM3's Ctrl3
PIN9 --- output, Servo
Motor control logic:
Ctrl1 Ctrl2 Ctrl3 Drv1 Drv2 Drv3 Drv4 电机状态
X 0 0 0/截止 0/导通 0/截止 0/导通 刹车
PWM 1 0 PWM 1/截止 0/截止 0/导通 反转
PWM 0 1 0/截止 0/导通 PWM 1/截止 正转
0 1 1 0/截止 1/截止 0/截止 1/截止 惰行
1 1 1 1/导通 1/截止 1/导通 1/截止 刹车
-------------------------- 20110426 -----------------------------------
在YM3_Try 的基础上增加串口控制,以便于作为 WifiRobot 的小车控制器。
因为轮子安装的位置关系,将正、反转状态对调。
因为 DB120 路由中的控制命令相对简单,所以简化小车控制命令,暂时采用短帧方式,
且不需要应答帧。
命令帧格式初步定义为:
55 AA 命令字(1字节) 命令参数(1字节)
所有命令均为 4 字节
初步拟定以下控制命令:
1、电机控制
命令字:0x11 —— 前进 0x12 —— 后退 0x13 —— 刹车 0x14 —— 惰行
对应命令参数为 PWM 值 : 0 - 255,数字越大,电机功率越大。
刹车和惰行命令参数无效。
2、行走脉冲设置
命令字:0x2? ,高半字为 2,低半字和命令参数合并,为设置的脉冲数。
命令参数:命令字的高半字和命令参数合并,范围:0 —— 1023,对应距离为 0 —— 约 2.5m ( 2.51mm/脉冲)
3、舵机控制命令
命令字:0x30
命令参数:舵机角度,0 -180 度
暂时设计以上命令。
行走脉冲设置应先做,此命令只是设置一个减计数器加载值,但不处发计数。
只有在设置电机行走命令时,才去读行走脉冲值,并将其置入减计数器,触发计数。
如果计数值为“0”,则表示连续运转,直到收到刹车或惰行命令。
舵机命令收到后即刻执行。
*/
#define MOTOR_COMMAND 0x10
#define RUN_NUM 0x20
#define SERVO_COMMAND 0x30
#define FORWARD 1
#define BACKWARD 2
#define BRAKE 3
#define FLOAT 4
#define SERVO_PLUS 254 // 在当前舵机值基础上 +1
#define SERVO_MINUS 255 // 在当前舵机值基础上 -1
int pulse = 0; // interrupt No
int Ctrl1 = 6; // for Motor
int Ctrl2 = 7;
int Ctrl3 = 8;
int ServoPWM = 9; // for Servo
Servo myServo;
int LED = 13;
int gc_iRunCount; // 行走脉冲累计
int g_iRunNumSet; // 行走脉冲设置值
int gc_iRunNumCnt; // 行走脉冲减计数器
unsigned char g_ucRcvBytes; // 串口收到的字节数
unsigned char ga_ucRcvBuf[8]; // 接收缓冲区
unsigned char gi_ucSavePtr; // 存数指针
unsigned int g_uiCommand; // 控制命令
unsigned char g_ucServoVal; // 舵机当前值
void setup()
{
// init pulse Sample
attachInterrupt(pulse, pulseSample,FALLING);
// init Motor Control pin
pinMode(Ctrl1, OUTPUT);
pinMode(Ctrl2, OUTPUT);
pinMode(Ctrl3, OUTPUT);
// init Servo Control
myServo.attach(ServoPWM);
pinMode(LED,OUTPUT);
// init UART
Serial.begin(115200); // 因为路由器的 Baud 是 115200 8 N 1
}
void loop()
{
// 初始化小车控制参数及状态
initial();
while(1)
{
g_ucRcvBytes = (unsigned char)(Serial.available());
if(g_ucRcvBytes > 0)
{
// 收到通讯数据,检测
g_uiCommand = dataFrame_OK(g_ucRcvBytes);
if(g_uiCommand !=0)
{
// 收到命令,处理
digitalWrite(LED,LOW); //灭 LED 指示命令开始
doCommand(g_uiCommand);
delay(1000); // 为显示明确,延时 1s
digitalWrite(LED,HIGH); //点亮 LED 指示结束,等待下一命令
}
}
}
}
/* 小车控制参数及状态初始化 */
void initial()
{
digitalWrite(LED,HIGH); //点亮 LED 作为指示
delay(1000); // 延时 1s
g_ucServoVal = 90;
myServo.write(g_ucServoVal);// 将舵机归位到正中,注:此时可以拔下舵机,手工调整轮子使其位于正前方,再插上舵机。
// 如觉得不正(因舵机插孔的齿密度有限),可以用舵机命令控制,使其处于正前方,记下此值作为偏置。
gc_iRunNumCnt = 0;
g_iRunNumSet =0;
Motor(FLOAT,0); // 初始化电机为惰行,以免手工去转动车轮感觉阻力较大
gi_ucSavePtr = 0; // 初始化通讯参数
}
/* 脉冲中断采集程序 */
void pulseSample()
{
gc_iRunCount++;
if(gc_iRunNumCnt > 0)
{
gc_iRunNumCnt--;
if(gc_iRunNumCnt == 0)
{
Motor(BRAKE,0);
}
}
}
/* 电机驱动 */
void Motor(int iMode,unsigned char ucPwmVal)
{
switch (iMode)
{
case FORWARD:
{
digitalWrite(Ctrl1,LOW); // OFF H Bridge
digitalWrite(Ctrl2,LOW);
digitalWrite(Ctrl3,HIGH);
analogWrite(Ctrl1,ucPwmVal); // Start Motor
break;
}
case BACKWARD:
{
digitalWrite(Ctrl1,LOW); // OFF H Bridge
digitalWrite(Ctrl2,HIGH);
digitalWrite(Ctrl3,LOW);
analogWrite(Ctrl1,ucPwmVal); // Start Motor
break;
}
case BRAKE:
{
digitalWrite(Ctrl1,LOW); // OFF H Bridge
digitalWrite(Ctrl2,LOW);
digitalWrite(Ctrl3,LOW);
break;
}
case FLOAT:
{
digitalWrite(Ctrl1,LOW); // OFF H Bridge
digitalWrite(Ctrl2,HIGH);
digitalWrite(Ctrl3,HIGH);
break;
}
default: break;
}
}
/*---------- 通讯接收帧检测 -----------------------
输入收到的字节数
返回收到的命令,如果为 “0”,则表示没有收到正确的命令。
---------------------------------------------------*/
unsigned int dataFrame_OK(unsigned char ucRcvBytes)
{
unsigned char ucBytes,k,i;
unsigned int uiCommand = 0;
ucBytes = ucRcvBytes;
while(ucBytes > 0)
{
ga_ucRcvBuf[gi_ucSavePtr] = (unsigned char) (Serial.read()); // 读取一字节
gi_ucSavePtr = (gi_ucSavePtr + 1)&0x07; // 指针 + 1, 环形处理,缓冲区只有 8个单元
// 检测帧头 0x55 0xAA
k = 0;
i = (gi_ucSavePtr - 4)&0x07;
if(ga_ucRcvBuf[i] == 0x55)
{
k++;
}
i = (gi_ucSavePtr - 3)&0x07;
if(ga_ucRcvBuf[i] == 0xAA)
{
k++;
}
if(k == 2)
{
//帧头正确,启动数据区接收
i = (gi_ucSavePtr - 2)&0x07; // 取命令
uiCommand = (unsigned int)ga_ucRcvBuf[i];
uiCommand = uiCommand << 8;
i = (gi_ucSavePtr - 1)&0x07; // 取命令参数
uiCommand += (unsigned int)ga_ucRcvBuf[i];
ucBytes = 0;
}
else
{
ucBytes--;
}
}
return (uiCommand);
}
/*---------- 命令处理 -----------------------
输入收到的命令
---------------------------------------------------*/
void doCommand(unsigned int uiCommand)
{
unsigned char ucOpCommand,ucMotorOp,ucPara;
int iRunNum;
ucOpCommand = (unsigned char)((uiCommand & 0xF000) >> 8); // 操作命令
switch(ucOpCommand)
{
case MOTOR_COMMAND:
{
ucMotorOp = (unsigned char)((uiCommand & 0x0F00)>>8); // 电机操作命令
ucPara = (unsigned char)(uiCommand & 0x00FF); // PWM
gc_iRunNumCnt = g_iRunNumSet; // 初始化行走计数器
Motor(ucMotorOp,ucPara); // 驱动电机
break;
}
case RUN_NUM:
{
iRunNum = int(uiCommand & 0x0FFF); // 取脉冲设置值
g_iRunNumSet = iRunNum;
break;
}
case SERVO_COMMAND:
{
ucPara = (unsigned char)(uiCommand & 0x00FF);
if(ucPara <= 180)
{
g_ucServoVal = ucPara;
}
else
{
if(ucPara == SERVO_PLUS)
{
if(g_ucServoVal < 180)
{
g_ucServoVal++;
}
ucPara = 0;
}
if(ucPara == SERVO_MINUS )
{
if(g_ucServoVal > 0)
{
g_ucServoVal --;
}
ucPara = 0;
}
if(ucPara >180)
{
g_ucServoVal = 180;
}
}
myServo.write(g_ucServoVal);
break;
}
default:break;
}
}
凭心而论, Arduino 的程序确实好编,基本不用去考虑硬件,我对 Mega168 基本是“外行”,从未深入研究过,但这样用起来丝毫不觉得费力。
作为业余爱好活动的手段,值得推荐!