行空板视觉循迹车
【项目背景】之前,有个网友咨询用行空板做视觉循迹车,我做了一个,给这个网友参考。之后这个车就被再“利用”了,今天再重新做一个。
【项目设计】
在佳立创重新打板,实现固定电机及电机驱动板。这个板子是为给Micro:bit设计的小车底板,因行空行板也可使用这个电机驱动板,并且Mind+中Python模式下已有这个电机驱动板的扩展。
【佳立创打板】
电路比较简单,设置好布局和尺寸。
【组装小车】
电机驱动板使用3.7V锂电池供电。
【程序编写】
Mind+ Python模式下连接行空板编写程序。
1.测试驱动电机使用pinpong库加载“DFMotor”驱动电机。
#-*- coding: UTF-8 -*-
# MindPlus
# Python
import time
from pinpong.board import Board
from pinpong.libs.microbit_motor import DFMotor
Board().begin()
p_dfr0548_motor_M1 = DFMotor(1)
p_dfr0548_motor_M2 = DFMotor(2)
p_dfr0548_motor_M3 = DFMotor(3)
p_dfr0548_motor_M4 = DFMotor(4)
p_dfr0548_motor_ALL = DFMotor(5)
while True:
p_dfr0548_motor_M1.speed(200)
p_dfr0548_motor_M1.run(p_dfr0548_motor_M1.CCW)
p_dfr0548_motor_M2.speed(200)
p_dfr0548_motor_M2.run(p_dfr0548_motor_M2.CCW)
p_dfr0548_motor_M3.speed(200)
p_dfr0548_motor_M3.run(p_dfr0548_motor_M3.CCW)
p_dfr0548_motor_M4.speed(200)
p_dfr0548_motor_M4.run(p_dfr0548_motor_M4.CCW)
time.sleep(2)
p_dfr0548_motor_ALL.stop()
time.sleep(2)
2.行空板 Opencv 视频 识线加载opencv 库函数头文件”cv2“,开启USB摄像头采集图像,通过图像处理,获取目标颜色,进而识别目标”线“所在区域。
import cv2 # opencv 库函数头文件引用
import numpy as np # python 库引用
import math # python 库引用
import sys
class Twist:
x = 0
z = 0
linear=0
angular=0
# 利用opencv 库函数,从摄像头采集一帧图像
cap = cv2.VideoCapture(0)
ret, cv_image = cap.read()
while ret:
ret, cv_image = cap.read()
# 对图像进行裁剪
height, width, channels = cv_image.shape
descentre = 50
rows_to_watch = 100
crop_img = cv_image[(int((height)/4) + descentre):(int((height)/4)+ (descentre+rows_to_watch))]
#将图像从RGB转换成HSV色彩空间
hsv = cv2.cvtColor(crop_img,cv2.COLOR_RGB2HSV)
# 设置需要提取的颜色的是绿色,然后确认其HSV空间下的范围
lower = np.array()
upper = np.array()
#制作模板,绿色部分和其他颜色二值化后变为白色和黑色
mask = cv2.inRange(hsv,lower ,upper)
#将模板图像和原始图像按照 像素 位相与,提取出目标颜色
res = cv2.bitwise_and(crop_img,crop_img,mask = mask)
m = cv2.moments(mask,False)
try:
cx, cy = m['m10']/m['m00'], m['m01']/m['m00']
except ZeroDivisionError:
cx, cy = height/2, width/2
height, width, channels = cv_image.shape
error_x = cx - width / 2
twist_object = Twist()
# 设置固定的线速度值,单位 m/s
twist_object.linear = 0.05
# 将横向像素的偏差除以一个系数,该系数决定角速度值的大小,需要根据线速度和图像总宽度进行调节,才能达到比较好的循迹效果
twist_object.angular = error_x / 80
# 二值化图像的像素统计,即统计目标颜色区域所占的像素个数
no_red = cv2.countNonZero(mask)
# 添加角速度和目标颜色像素判别,避免过大的角速度出现,防止车疯狂旋转
if ((math.fabs(twist_object.angular)) < 10 and (no_red > 20000)):
print(twist_object.angular)
else:
twist_object.linear = 0
print("out of range")
twist_object.angular = 0
cv2.imshow("dst",mask)
if cv2.waitKey(1) & 0xff== 27:
break
3.完整程序
import cv2 # opencv 库函数头文件引用
import numpy as np # python 库引用
import math # python 库引用
import sys
import time
from pinpong.board import Board
from pinpong.libs.microbit_motor import DFMotor
Board().begin()
p_dfr0548_motor_M1 = DFMotor(1)
p_dfr0548_motor_M2 = DFMotor(2)
p_dfr0548_motor_M3 = DFMotor(3)
p_dfr0548_motor_M4 = DFMotor(4)
p_dfr0548_motor_ALL = DFMotor(5)
def speed(left,right):
p_dfr0548_motor_M1.speed(left)
p_dfr0548_motor_M1.run(p_dfr0548_motor_M1.CW)
p_dfr0548_motor_M2.speed(left)
p_dfr0548_motor_M2.run(p_dfr0548_motor_M2.CW)
p_dfr0548_motor_M3.speed(right)
p_dfr0548_motor_M3.run(p_dfr0548_motor_M3.CW)
p_dfr0548_motor_M4.speed(right)
p_dfr0548_motor_M4.run(p_dfr0548_motor_M4.CW)
def numberMap(x, in_min, in_max, out_min, out_max):
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min
num=30#电机启动基数
num2=100#电机调整范围
class Twist:
x = 0
z = 0
linear=0
angular=0
# 利用opencv 库函数,从摄像头采集一帧图像
cap = cv2.VideoCapture(0)
ret, cv_image = cap.read()
while ret:
ret, cv_image = cap.read()
# 对图像进行裁剪
height, width, channels = cv_image.shape
descentre = 50
rows_to_watch = 100
crop_img = cv_image[(int((height)/4) + descentre):(int((height)/4)+ (descentre+rows_to_watch))]
#将图像从RGB转换成HSV色彩空间
hsv = cv2.cvtColor(crop_img,cv2.COLOR_RGB2HSV)
# 设置需要提取的颜色的是绿色,然后确认其HSV空间下的范围
lower = np.array()
upper = np.array()
#制作模板,绿色部分和其他颜色二值化后变为白色和黑色
mask = cv2.inRange(hsv,lower ,upper)
#将模板图像和原始图像按照 像素 位相与,提取出目标颜色
res = cv2.bitwise_and(crop_img,crop_img,mask = mask)
m = cv2.moments(mask,False)
try:
cx, cy = m['m10']/m['m00'], m['m01']/m['m00']
except ZeroDivisionError:
cx, cy = height/2, width/2
height, width, channels = cv_image.shape
error_x = cx - width / 2
twist_object = Twist()
# 设置固定的线速度值,单位 m/s
twist_object.linear = 0.05
# 将横向像素的偏差除以一个系数,该系数决定角速度值的大小,需要根据线速度和图像总宽度进行调节,才能达到比较好的循迹效果
twist_object.angular = error_x / 80
# 二值化图像的像素统计,即统计目标颜色区域所占的像素个数
no_red = cv2.countNonZero(mask)
# 添加角速度和目标颜色像素判别,避免过大的角速度出现,防止车疯狂旋转
if ((math.fabs(twist_object.angular)) < 10 and (no_red > 20000)):
print(twist_object.angular)
if(twist_object.angular>0):
left=int(numberMap(int(twist_object.angular*100),0,300,0,num2))
print("left:"+str(left))
speed(num-left,num+left)
if(twist_object.angular<0):
right=int(numberMap(int(abs(twist_object.angular)*100),0,300,0,num2))
print("right:"+str(right))
speed(num+right,num-right)
else:
twist_object.linear = 0
print("out of range")
twist_object.angular = 0
#cv2.imshow("dst",mask)
#if cv2.waitKey(1) & 0xff== 27:
#break
【演示视频】
https://www.bilibili.com/video/BV1EE421g7bC/?share_source=copy_web
页:
[1]