能亲手制作智能车、机器人,大概是我们每一位marker都想实现的事情,那么今天我们就来看看如何制作一辆可以红外、蓝牙控制,并且可以用openmv摄像头实时追踪色块的智能车吧。
现在我们手上有一套智能车模型套件、红外遥控器及传感器、蓝牙模块、一块OpenMV摄像头模块。
那就让我们开始实现以上的想法吧,JUST DO IT!
做这个项目之前,你需要有:
做完这个项目,你可以掌握:
材料 | 数量 |
---|---|
arduino模块 | 1块 |
L298N电机驱动模块 | 1块 |
红外接收模块 | 1块 |
红外遥控器 | 1件 |
蓝牙模块 | 1块 |
USB转TTL模块(可选) | 1块 |
OpenMV3 摄像头模块 | 1块 |
9-12V电源(博主使用三节18560串联,推荐) | 1件 |
杜邦线 | 若干 |
螺丝、螺母、铜柱 | 若干 |
热熔胶枪 | 1把 |
螺丝刀套件 | 1套 |
L298N电机驱动模块 | 1块 |
焊烙铁(可选) | 1件 |
剥线钳(可选) | 1把 |
电压表(可选) | 1件 |
android手机(使用软件) | 1部 |
按照说明书装配小车模型。
电子模块我是如下图安装的,当然大家可以按照自己的习惯安装。
注意:
准备工作都做好了,那我们开始动手制作最简单的红外小车吧。
//红外小车代码及解释
#include //打开IDE:项目→加载库→添加→搜索IRremote→安装IRredmote库
int RECV_PIN = 11;//红外接收端口
IRrecv irrecv(RECV_PIN);
decode_results results;//结构声明
//==============================
int Left_motor_back=3; //左电机后退(IN1)
int Left_motor_go=4; //左电机前进(IN2)
int Right_motor_go=9; // 右电机前进(IN3)
int Right_motor_back=10; // 右电机后退(IN4)
void setup()
{
//初始化电机驱动IO为输出方式
pinMode(Left_motor_go,OUTPUT); // PIN 5 (PWM)
pinMode(Left_motor_back,OUTPUT); // PIN 6 (PWM)
pinMode(Right_motor_go,OUTPUT);// PIN 9 (PWM)
pinMode(Right_motor_back,OUTPUT);// PIN 10 (PWM)
pinMode(13, OUTPUT);////端口模式,输出
Serial.begin(9600); //波特率9600
irrecv.enableIRIn(); // Start the receiver
}
void run() // 前进
{
digitalWrite(Right_motor_go,HIGH); // 右电机前进
digitalWrite(Right_motor_back,LOW);
digitalWrite(Left_motor_go,HIGH); // 左电机前进
digitalWrite(Left_motor_back,LOW);
}
void brake() //刹车,停车
{
digitalWrite(Right_motor_go,LOW);
digitalWrite(Right_motor_back,LOW);
digitalWrite(Left_motor_go,LOW);
digitalWrite(Left_motor_back,LOW);
}
void left() //左转(左轮不动,右轮前进)
{
digitalWrite(Right_motor_go,HIGH); // 右电机前进
digitalWrite(Right_motor_back,LOW);
digitalWrite(Left_motor_go,LOW); //左轮不动
digitalWrite(Left_motor_back,LOW);
}
void spin_left() //左转(左轮后退,右轮前进)
{
digitalWrite(Right_motor_go,HIGH); // 右电机前进
digitalWrite(Right_motor_back,LOW);
digitalWrite(Left_motor_go,LOW); //左轮后退
digitalWrite(Left_motor_back,HIGH);
}
void right() //右转(右轮不动,左轮前进)
{
digitalWrite(Right_motor_go,LOW); //右电机不动
digitalWrite(Right_motor_back,LOW);
digitalWrite(Left_motor_go,HIGH);//左电机前进
digitalWrite(Left_motor_back,LOW);
}
void spin_right() //右转(右轮后退,左轮前进)
{
digitalWrite(Right_motor_go,LOW); //右电机后退
digitalWrite(Right_motor_back,HIGH);
digitalWrite(Left_motor_go,HIGH);//左电机前进
digitalWrite(Left_motor_back,LOW);
}
void back() //后退
{
digitalWrite(Right_motor_go,LOW); //右轮后退
digitalWrite(Right_motor_back,HIGH);
digitalWrite(Left_motor_go,LOW); //左轮后退
digitalWrite(Left_motor_back,HIGH);
}
//=============================================================================
//读取各个按键需要用到这段代码
//=============================================================================
void read_key()
{
if(irrecv.decode(&results)){ //如果接收到信息
Serial.print("code:");
Serial.println(results.value,HEX);//results.value为16进制,unsigned long
Serial.print("bits:");
Serial.println(results.bits);//输出元位数
irrecv.resume();
}
}
void loop()
{
read_key();
if(irrecv.decode(&results)){ //如果接收到信息
switch(results.value){
case 0xFF18E7: //前,对应2
run();
break;
case 0xFF4AB5: //后,对应8
back();
break;
case 0xFF10EF: //左,对应4
left();
break;
case 0xFF5AA5: //右,对应6
right();
break;
case 0xFF38C7: //停止,对应5
brake();
break;
default:
break;
}
irrecv.resume();
}
}
//蓝牙小车代码及解释
#include //打开IDE:项目→加载库→添加→搜索IRremote→安装IRredmote库
int RECV_PIN = 11;//红外接收端口
IRrecv irrecv(RECV_PIN);
decode_results results;//结构声明
//==============================
int Left_motor_back=3; //左电机后退(IN1)
int Left_motor_go=4; //左电机前进(IN2)
int Right_motor_go=9; // 右电机前进(IN3)
int Right_motor_back=10; // 右电机后退(IN4)
void setup()
{
//初始化电机驱动IO为输出方式
pinMode(Left_motor_go,OUTPUT); // PIN 5 (PWM)
pinMode(Left_motor_back,OUTPUT); // PIN 6 (PWM)
pinMode(Right_motor_go,OUTPUT);// PIN 9 (PWM)
pinMode(Right_motor_back,OUTPUT);// PIN 10 (PWM)
pinMode(13, OUTPUT);////端口模式,输出
Serial.begin(9600); //波特率9600
irrecv.enableIRIn(); // Start the receiver
}
void run() // 前进
{
digitalWrite(Right_motor_go,HIGH); // 右电机前进
digitalWrite(Right_motor_back,LOW);
digitalWrite(Left_motor_go,HIGH); // 左电机前进
digitalWrite(Left_motor_back,LOW);
}
void brake() //刹车,停车
{
digitalWrite(Right_motor_go,LOW);
digitalWrite(Right_motor_back,LOW);
digitalWrite(Left_motor_go,LOW);
digitalWrite(Left_motor_back,LOW);
}
void left() //左转(左轮不动,右轮前进)
{
digitalWrite(Right_motor_go,HIGH); // 右电机前进
digitalWrite(Right_motor_back,LOW);
digitalWrite(Left_motor_go,LOW); //左轮不动
digitalWrite(Left_motor_back,LOW);
}
void spin_left() //左转(左轮后退,右轮前进)
{
digitalWrite(Right_motor_go,HIGH); // 右电机前进
digitalWrite(Right_motor_back,LOW);
digitalWrite(Left_motor_go,LOW); //左轮后退
digitalWrite(Left_motor_back,HIGH);
}
void right() //右转(右轮不动,左轮前进)
{
digitalWrite(Right_motor_go,LOW); //右电机不动
digitalWrite(Right_motor_back,LOW);
digitalWrite(Left_motor_go,HIGH);//左电机前进
digitalWrite(Left_motor_back,LOW);
}
void spin_right() //右转(右轮后退,左轮前进)
{
digitalWrite(Right_motor_go,LOW); //右电机后退
digitalWrite(Right_motor_back,HIGH);
digitalWrite(Left_motor_go,HIGH);//左电机前进
digitalWrite(Left_motor_back,LOW);
}
void back() //后退
{
digitalWrite(Right_motor_go,LOW); //右轮后退
digitalWrite(Right_motor_back,HIGH);
digitalWrite(Left_motor_go,LOW); //左轮后退
digitalWrite(Left_motor_back,HIGH);
}
//=============================================================================
//读取各个按键需要用到这段代码
//=============================================================================
void read_key()
{
if(irrecv.decode(&results)){ //如果接收到信息
Serial.print("code:");
Serial.println(results.value,HEX);//results.value为16进制,unsigned long
Serial.print("bits:");
Serial.println(results.bits);//输出元位数
irrecv.resume();
}
}
void loop()
{
read_key();
if(irrecv.decode(&results)){ //如果接收到信息
switch(results.value){
case 0xFF18E7: //前,对应2
run();
break;
case 0xFF4AB5: //后,对应8
back();
break;
case 0xFF10EF: //左,对应4
left();
break;
case 0xFF5AA5: //右,对应6
right();
break;
case 0xFF38C7: //停止,对应5
brake();
break;
default:
break;
}
irrecv.resume();
}
//蓝牙控制
if(Serial.available()>0){
char ch = Serial.read();
if(ch == '1'){
//前进
run();
Serial.print("前进");
}else if(ch == '2'){
//后退
back();
Serial.print("后退");
}else if(ch == '3'){
//左转
left();
Serial.print("左转");
}else if(ch == '4'){
//右转
right();
Serial.print("右转");
}else if(ch=='0'){
//停车
brake();
Serial.print("停车");
}
}
}
Arduino代码
/*
* 蓝牙串口指令规定
* 改变运行模式:红外:I(默认)、蓝牙:B、openmv:O
* 蓝牙控制参数设置:前进:1、后退:2、左转:3、右转:4、停车:0、油门:5、刹车:6
*/
#include
#include
#define BAUD_RATE 9600
#define CHAR_BUF 128
float left_speed = 1.1;
float right_speed = 1.1;
char buff[CHAR_BUF] = {0};
int RECV_PIN = 11;//红外接收端口
IRrecv irrecv(RECV_PIN);
decode_results results;//结构声明
char mode = 'I'; //设置小车运行模式,默认红外模式
int Left_motor_back=3; //左电机后退(IN1)
int Left_motor_go=4; //左电机前进(IN2)
int Right_motor_go=9; // 右电机前进(IN3)
int Right_motor_back=10; // 右电机后退(IN4)
int ENA = 5; //PWM输入A
int ENB = 6; //PWM输入B
int speed_default = 100; //0-255之间,小车最低速度为70,最佳速度为100
char ch;
bool inverse_left=false;
bool inverse_right=false;
void setup()
{
//初始化电机驱动IO为输出方式
pinMode(Left_motor_go,OUTPUT); // PIN 5 (PWM)
pinMode(Left_motor_back,OUTPUT); // PIN 6 (PWM)
pinMode(Right_motor_go,OUTPUT);// PIN 9 (PWM)
pinMode(Right_motor_back,OUTPUT);// PIN 10 (PWM)
pinMode(ENA,OUTPUT);
pinMode(ENB,OUTPUT);
pinMode(13, OUTPUT);////端口模式,输出
Serial.begin(BAUD_RATE); //波特率9600
irrecv.enableIRIn(); // Start the receiver
Wire.begin();
delay(1000); // 给OpenMV一个启动的时间
}
void run() // 前进
{
digitalWrite(Right_motor_go,HIGH); // 右电机前进
digitalWrite(Right_motor_back,LOW);
digitalWrite(Left_motor_go,HIGH); // 左电机前进
digitalWrite(Left_motor_back,LOW);
analogWrite(ENA,speed_default);
analogWrite(ENB,speed_default);
}
void brake() //刹车,停车
{
digitalWrite(Right_motor_go,LOW);
digitalWrite(Right_motor_back,LOW);
digitalWrite(Left_motor_go,LOW);
digitalWrite(Left_motor_back,LOW);
analogWrite(ENA,speed_default);
analogWrite(ENB,speed_default);
}
void left() //左转(左轮不动,右轮前进)
{
digitalWrite(Right_motor_go,HIGH); // 右电机前进
digitalWrite(Right_motor_back,LOW);
digitalWrite(Left_motor_go,LOW); //左轮不动
digitalWrite(Left_motor_back,LOW);
analogWrite(ENA,speed_default);
analogWrite(ENB,speed_default);
}
void spin_left() //左转(左轮后退,右轮前进)
{
digitalWrite(Right_motor_go,HIGH); // 右电机前进
digitalWrite(Right_motor_back,LOW);
digitalWrite(Left_motor_go,LOW); //左轮后退
digitalWrite(Left_motor_back,HIGH);
analogWrite(ENA,speed_default);
analogWrite(ENB,speed_default);
}
void right() //右转(右轮不动,左轮前进)
{
digitalWrite(Right_motor_go,LOW); //右电机不动
digitalWrite(Right_motor_back,LOW);
digitalWrite(Left_motor_go,HIGH);//左电机前进
digitalWrite(Left_motor_back,LOW);
analogWrite(ENA,speed_default);
analogWrite(ENB,speed_default);
}
void spin_right() //右转(右轮后退,左轮前进)
{
digitalWrite(Right_motor_go,LOW); //右电机后退
digitalWrite(Right_motor_back,HIGH);
digitalWrite(Left_motor_go,HIGH);//左电机前进
digitalWrite(Left_motor_back,LOW);
analogWrite(ENA,speed_default);
analogWrite(ENB,speed_default);
}
void back() //后退
{
digitalWrite(Right_motor_go,LOW); //右轮后退
digitalWrite(Right_motor_back,HIGH);
digitalWrite(Left_motor_go,LOW); //左轮后退
digitalWrite(Left_motor_back,HIGH);
analogWrite(ENA,speed_default);
analogWrite(ENB,speed_default);
}
//=============================================================================
//读取各个按键需要用到这段代码
//=============================================================================
void read_key()
{
if(irrecv.decode(&results)){ //如果接收到信息
Serial.print("code:");
Serial.println(results.value,HEX);//results.value为16进制,unsigned long
Serial.print("bits:");
Serial.println(results.bits);//输出元位数
irrecv.resume();
}
}
//=============================================================================
//处理字符串buff
//============================================================================
void getCode(){ //buff经过传输,尾部有干扰,故用两个空格分割
String temp1,temp2;
String string = String(buff);
int postion = string.indexOf(" ");
temp1 = string.substring(0,postion);
string = string.substring(postion+1,string.length());
postion = postion = string.indexOf(" ");
temp2 = string.substring(0,postion);
left_speed = temp1.toFloat();
right_speed = temp2.toFloat();
}
//=============================================================================
//PWM模式的小车运动
//============================================================================
void openmvrun(){
if(inverse_left)
left_speed=-left_speed;
if(inverse_right)
right_speed=-right_speed;
int l_speed = abs(left_speed);
int r_speed = abs(right_speed);
if(left_speed<0){
digitalWrite(Left_motor_go,LOW); //左轮后退
digitalWrite(Left_motor_back,HIGH);
}else{
digitalWrite(Left_motor_go,HIGH);//左电机前进
digitalWrite(Left_motor_back,LOW);
}
analogWrite(ENA,l_speed);
if(right_speed<0){
digitalWrite(Right_motor_go,LOW); //右轮后退
digitalWrite(Right_motor_back,HIGH);
}else{
digitalWrite(Right_motor_go,HIGH); // 右电机前进
digitalWrite(Right_motor_back,LOW);
}
analogWrite(ENB,r_speed);
Serial.print(l_speed);
Serial.print(" ");
Serial.print(r_speed);
}
void loop()
{
if(Serial.available()>0){
ch = Serial.read();
if(ch == 'I'){
//红外模式
mode = 'I';
}else if(ch == 'B'){
//蓝牙模式
mode = 'B';
}else if(ch == 'O'){
//openmv模式
mode = 'O';
}
}
if(mode == 'I'){ //红外模式控制代码
//Serial.println("红外模式");
read_key();
if(irrecv.decode(&results)){ //如果接收到信息
Serial.println(results.value);
switch(results.value){
case 0xFF18E7: //前,对应2
run();
break;
case 0xFF4AB5: //后,对应8
back();
break;
case 0xFF10EF: //左,对应4
left();
break;
case 0xFF5AA5: //右,对应6
right();
break;
case 0xFF38C7: //停止,对应5
brake();
break;
default:
break;
}
irrecv.resume();
}
}
if(mode == 'B'){ //蓝牙模式控制代码
//Serial.println("蓝牙模式");
char ch1 = '0';
if(ch == '1'){
//前进
run();
Serial.print("前进");
}else if(ch == '2'){
//后退
back();
Serial.print("后退");
}else if(ch == '3'){
//左转
left();
Serial.print("左转");
}else if(ch == '4'){
//右转
right();
Serial.print("右转");
}else if(ch=='0'){
//停车
brake();
Serial.print("停车");
}else if(ch=='5'){
speed_default +=5;
ch = ch1;
}else if(ch=='6'){
speed_default -=5;
ch = ch1;
}
ch1 = ch;
Serial.println(speed_default);
}
if(mode == 'O'){ //openmv模式控制代码
//Serial.println("openmv模式");
int32_t temp = 0;
Wire.requestFrom(0x12, 2);
if (Wire.available() == 2) { // got length?
temp = Wire.read() | (Wire.read() << 8);
delay(1); // Give some setup time...
Wire.requestFrom(0x12, temp);
if (Wire.available() == temp) { // got full message?
temp = 0;
while (Wire.available()) buff[temp++] = Wire.read();
} else {
while (Wire.available()) Wire.read(); // Toss garbage bytes.
}
} else {
while (Wire.available()) Wire.read(); // Toss garbage bytes.
}
//Serial.println(buff);
getCode();
//Serial.println(left_speed+" "+"right_speed="+right_speed);
//Serial.print(left_speed);
//Serial.print(" ");
//Serial.print(right_speed);
openmvrun();
delay(1); // Don't loop to quickly.
}
}
OpenMV代码
#car.py
# Arduino 作为I2C主设备, OpenMV作为I2C从设备。
#
# 请把OpenMV和Arduino按照下面连线:
#
# OpenMV Cam Master I2C Data (P5) - Arduino Uno Data (A4)
# OpenMV Cam Master I2C Clock (P4) - Arduino Uno Clock (A5)
# OpenMV Cam Ground - Arduino Ground
import pyb, ustruct
import ujson
from pyb import Pin, Timer
text = "Hello World!\n"
data = ustruct.pack("<%ds" % len(text), text)
# 使用 "ustruct" 来生成需要发送的数据包
# "<" 把数据以小端序放进struct中
# "%ds" 把字符串放进数据流,比如:"13s" 对应的 "Hello World!\n" (13 chars).
# 详见 https://docs.python.org/3/library/struct.html
# READ ME!!!
#
# 请理解,当您的OpenMV摄像头不是I2C主设备,所以不管是使用中断回调,
# 还是下方的轮循,都可能会错过响应发送数据给主机。当这种情况发生时,
# Arduino会获得NAK,并且不得不从OpenMV再次读数据。请注意,
# OpenMV和Arduino都不擅长解决I2C的错误。在OpenMV和Arduino中,
# 你可以通过释放I2C外设,再重新初始化外设,来恢复功能。
# OpenMV上的硬件I2C总线都是2
bus = pyb.I2C(2, pyb.I2C.SLAVE, addr=0x12)
bus.deinit() # 完全关闭设备
bus = pyb.I2C(2, pyb.I2C.SLAVE, addr=0x12)
print("Waiting for Arduino...")
# 请注意,为了正常同步工作,OpenMV Cam必须 在Arduino轮询数据之前运行此脚本。
# 否则,I2C字节帧会变得乱七八糟。所以,保持Arduino在reset状态,
# 直到OpenMV显示“Waiting for Arduino...”。
def run(left_speed, right_speed):
data = str(left_speed)+" "+str(right_speed)+" "
try:
#print(data)
bus.send(ustruct.pack(", len(data)), timeout=10000) # 首先发送长度 (16-bits).
try:
bus.send(data, timeout=10000) # 然后发送数据
print("Sent Data!") # 没有遇到错误时,会显示
except OSError as err:
pass # 不用担心遇到错误,会跳过
# 请注意,有3个可能的错误。 超时错误(timeout error),
# 通用错误(general purpose error)或繁忙错误
#(busy error)。 “err.arg[0]”的错误代码分别
# 为116,5,16。
except OSError as err:
pass # 不用担心遇到错误,会跳过
# 请注意,有3个可能的错误。 超时错误(timeout error),
# 通用错误(general purpose error)或繁忙错误
#(busy error)。 “err.arg[0]”的错误代码分别
# 为116,5,16。
#pid.py
from pyb import millis
from math import pi, isnan
class PID:
_kp = _ki = _kd = _integrator = _imax = 0
_last_error = _last_derivative = _last_t = 0
_RC = 1/(2 * pi * 20)
def __init__(self, p=0, i=0, d=0, imax=0):
self._kp = float(p)
self._ki = float(i)
self._kd = float(d)
self._imax = abs(imax)
self._last_derivative = float('nan')
def get_pid(self, error, scaler):
tnow = millis()
dt = tnow - self._last_t
output = 0
if self._last_t == 0 or dt > 1000:
dt = 0
self.reset_I()
self._last_t = tnow
delta_time = float(dt) / float(1000)
output += error * self._kp
if abs(self._kd) > 0 and dt > 0:
if isnan(self._last_derivative):
derivative = 0
self._last_derivative = 0
else:
derivative = (error - self._last_error) / delta_time
derivative = self._last_derivative + \
((delta_time / (self._RC + delta_time)) * \
(derivative - self._last_derivative))
self._last_error = error
self._last_derivative = derivative
output += self._kd * derivative
output *= scaler
if abs(self._ki) > 0 and dt > 0:
self._integrator += (error * self._ki) * scaler * delta_time
if self._integrator < -self._imax: self._integrator = -self._imax
elif self._integrator > self._imax: self._integrator = self._imax
output += self._integrator
return output
def reset_I(self):
self._integrator = 0
self._last_derivative = float('nan')
#main.py
# Blob Detection Example
#
# This example shows off how to use the find_blobs function to find color
# blobs in the image. This example in particular looks for dark green objects.
import sensor, image, time
import car
from pid import PID
# You may need to tweak the above settings for tracking green things...
# Select an area in the Framebuffer to copy the color settings.
sensor.reset() # Initialize the camera sensor.
sensor.set_pixformat(sensor.RGB565) # use RGB565.
sensor.set_framesize(sensor.QQVGA) # use QQVGA for speed.
sensor.skip_frames(10) # Let new settings take affect.
sensor.set_auto_whitebal(False) # turn this off.
clock = time.clock() # Tracks FPS.
# For color tracking to work really well you should ideally be in a very, very,
# very, controlled enviroment where the lighting is constant...
green_threshold = (42, 80, 28, 127, -22, 55) # 颜色阈值,不同物体需要修改
size_threshold = 2000 #小球距离
x_pid = PID(p=0.1, i=0.2, imax=30) # 方向参数p
h_pid = PID(p=0.01, i=0.1, imax=100) # 速度参数p
def find_max(blobs): #找到视野中最大的色块,即最大的小球
max_size=0
for blob in blobs:
if blob[2]*blob[3] > max_size:
max_blob=blob
max_size = blob[2]*blob[3]
return max_blob
while(True):
clock.tick() # Track elapsed milliseconds between snapshots().
img = sensor.snapshot() # Take a picture and return the image.
blobs = img.find_blobs([green_threshold])
if blobs:
max_blob = find_max(blobs)
x_error = max_blob[5]-img.width()/2 #色块的外框的中心x坐标blob[5]
h_error = max_blob[2]*max_blob[3]-size_threshold
#色块的外框的宽度blob[2],色块的外框的高度blob[3]
print("x error: ", x_error) #打印 x 轴误差 用于转弯
print("h error: ", h_error) #打印 距离误差 用于速度
'''
for b in blobs:
# Draw a rect around the blob.
img.draw_rectangle(b[0:4]) # rect
img.draw_cross(b[5], b[6]) # cx, cy
'''
img.draw_rectangle(max_blob[0:4]) # rect
img.draw_cross(max_blob[5], max_blob[6]) # cx, cy
x_output=x_pid.get_pid(x_error,1)
h_output=h_pid.get_pid(h_error,1) #h_error调整后的值
print("x_output",x_output)
print("h_output",h_output)
car.run(-h_output-x_output,-h_output+x_output)
print(-h_output-x_output,-h_output+x_output)
else:
car.run(0,0)
此款app是根据@单片机菜鸟(博哥)蓝牙小车项目的app基础上修改。博哥在创客、esp8266、软件编程等领域都是令人钦佩的一位技术大拿,有开源精神,向他学习! ↩︎