Skip to content

2021年春复旦大学大一下电子系统导论大作业——小车避障与绕桩

Notifications You must be signed in to change notification settings

jeekzhang/AGV-mini

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

5 Commits
 
 
 
 
 
 

Repository files navigation

【树莓派小车绕桩实验报告】

电导 没过 树莓 烧过 小车 爱过

一、实验目的:

  1. 综合运用本学期学习的内容,实现小车完整地在“8”字形跑道上巡线行驶
  2. 在保证小车不撞墙、不撞箱、不走错跑道的三大前提下,尽可能地跑出更多的圈数

二、实验原理:

1. PID自动控制:
  • 此部分已在之前的实验报告中详细说明,这里对此做简单描述。

  • PID调节是一种闭环控制的方式,基于反馈调节实现(示意图见下)。在本实验中,使用PID控制的方式,是输⼊偏差量(速度),计算出调整量(占空⽐),实现对速度的控制。在编程实现时,为了方便调整参数,将PID写成一个对象,用两个实例来控制左右轮。通过给左右轮设定对应的数值使之达到相同的速度,使得左右轮速度接近,就可以跑出近似的直线。同时,根据偏差量的大小对“弯”进行判定,再以其偏移量计算出左右轮的调整的占空比,从而实现转弯避障与绕桩。在这里插入图片描述

  • 从实操来讲,对小车的PID控制就是利用三个参数Kp,Ki,Kd,来调整三个对应因素对调整量的影响。

  • 但是在之前的避障实验中,因为线路的简易,我们并未使用严格理论意义上的PID控制。但在此次实验任务中,线路变得较为复杂,转弯幅度陡升,再以此前改变固定的占空比的方法将很难做到转弯和直行的两全。基于此,我们决定保留固定占空比的一部分代码,对某些越界的偏移量进行PID调控,使其沿线行驶。

2. 黑线处理技术(二值化):
  • 每个图像的像素通常对应于二维空间中一个特定的位置,并且有一个或者多个与那个点相关的采样值组成数值。灰度图像,图像中每个像素可以由0(黑)到255(白)的亮度值表示,0-255之间表示不同的灰度级。
  • 二值图像即为每个像素只有两个可能值的数字图像。将大于某个临界灰度值的像素灰度设为灰度极大值(黑),小于这个值的为灰度极小值(白),从而实现二值化。对于小车的摄像头而言,黑线指引应二值化为黑,白毯跑道应二值化为白。
3. 像数转换
  • 对于小车而言,在二值化黑线与地毯后,如何对得到的图像进行处理并最终形成反馈修正小车的轨迹,实现沿线。小车在跑道上时,二值化后黑线产生的黑色像素居中间位置,地毯产生的白色像素居两边位置。当小车发生偏离跑道或弯道出现的情况时,黑色中心像素会偏向小车偏离的反方向或转弯的正方向,恰好这两种情况小车都需要往黑像素偏移方向偏转。根据像素偏移的量,进行一些公式的处理,再通过pid作用于小车左右电机,实现寻线控制。

三、问题分析与方案解决:

1. 对实验目的分析:
  • 任务:小车从赛道起点线出发,通过程序自动驾驶,到达终点线,期间不允许撞到障碍物和跑错跑道。
  • 赛道分析:
  1. 赛道为一条形如“8”字的黑线跑道,在“8”的两“圆”中央位置各有两个纸箱,整体跑道为一张白色的地毯,在跑道两边为两面墙。
  2. 在直行后,共有4个角度相近(120度左右)的弯道,而在过了弯道后,小车将面临“X”分叉路口的选择
2. 可能存在问题及解决方法与思考
1.赛道方面: 在这里插入图片描述
  1. 转弯幅度过大:
  • 最简单的想法就是把占空比调大,来适应转弯幅度。
  • 但需要注意的是,这里的“大”是相对而言的,如果直行速度本身就很快,那么即使转弯的占空比也很大,也很难去纠正小车。
  • 实际情况也是如此,当我们将直行占空比设为40,而转弯占空比设为+-20时,小车能较好的转过弯道;但直行占空比设为60,而转弯占空比设为+-30时,便会出现转弯困难甚至撞墙的情况。
  1. 交叉错道:
  • 与前者思路相同,我们可以把速度加上去,这样其实当小车反应过来时已经过了交叉路口了。同样地,也可以在某个反应函数里加延时。
  • “牵一发而动全生”速度不能无止境大下去,在考虑转弯合理的情况下我们可控的最大占空比是65(+-30),仍然会出现因摆动幅度过大而走错道的情况。
  • 加延时的困难就在于我们只能从数值上去设置调节的范围,但实际情况是在弯处,小车的偏移量都会有差别,且大部分值和弯道时一样,也就是说对其的修正同样作用于弯道,撞墙便在所难免了。
  • 我们的可行做法是占空比修正以减法为主,即当偏移量较大时,一只轮子减占空比实现转弯。这样就保证了转弯时速度较慢,直行时速度较快以冲击交叉口。
2.摄像头被干扰:
  • 对于目标而言,我们当然希望小车可以只看见下方或者说前下方的黑线,但实际情况是,小车还会“看见”箱子、自己的影子甚至是墙上的瓷砖。(注:此处定义的看见是指小车将其或将其部分二值化为黑色)
  • 对于影子这种灰度偏白的情况,我们可以通过调整阈值,将其规避掉。但遗憾的是,由于前二者颜色过深,这一方法对箱子和瓷砖并没有太大的作用。先分析瓷砖,其实瓷砖的位置固定且位于下方,在保证巡线正常的情况下将摄像头的角度调高可以解决这一问题;同时,在小车偏移跑道到看到瓷砖中间会有一段空白期,如果可以加一个search函数让小车处于“空白”的位置时原地转弯去寻找附近黑线的位置,也可以解决这一问题。
  • 再说箱子,其实箱子的存在不一定是坏处,因为其所处的位置恰好与偏转方向相同,如果能合理处理小车行进速度与箱子位置之间的关系,比如我在识别到箱子后进行处理,这之间有一段延时,如果这段延时过去,小车刚好行至转弯处,化危为机,岂不美哉。
  • 在后期的实验中我们发现,其实只要解决严格巡线的问题,这两个问题会迎刃而解。
3.偏移跑道的修正
  • 这一方法思路与前面的search函数相同,但search函数会耽误较多时间,如果可以就当前跑道而言,做具体的修正或许会更有效。
  • 在多次实验中,我们发现偏离跑道的原因主要是小车直行速度过快,当到弯道时由于惯性,即使有减速处理,还是会偏离出跑道。而且我们发现,其实小车在检测到弯道时,就会给出一个修正的偏移量,而当它看不见线时,只要让其contiune,它就会沿着这一弧度画圆,并最终回到另一边的跑道上。

四、实验设计与实操分析:

1. 基于上面的方案分析,给出算法设计:
# coding:utf-8
import RPi.GPIO as GPIO
import time
import cv2
import numpy as np
#前期准备部分

#限制较大值
def sign(x):
    if x > 0:
        return 1.0
    else:
        return -1.0

# 定义引脚
EA, I2, I1, EB, I4, I3 = (13, 19, 26, 16, 20, 21)
FREQUENCY = 50

# 设置GPIO口
GPIO.setmode(GPIO.BCM)

# 设置GPIO口为输出
GPIO.setup([EA, I2, I1, EB, I4, I3], GPIO.OUT)
GPIO.output([EA, I2, EB, I3], GPIO.LOW)
GPIO.output([I1, I4], GPIO.HIGH)

pwma = GPIO.PWM(EA, FREQUENCY)
pwmb = GPIO.PWM(EB, FREQUENCY)

# pwm波初始化
pwma.start(0)
pwmb.start(0)

# center定义
center_now = 320

# 打开摄像头,图像尺寸640*480(长*高),opencv存储值为480*640(行*列)
cap = cv2.VideoCapture(0)

# PID 定义和初始化三个error和adjust数据
error = [0.0] * 3
adjust = [0.0] * 3

# PID 参数配置、目标值、左右轮基准占空比和占空比偏差范围(根据实际情况调整)
kp = 1.3
ki = 0.5
kd = 0.2
target = 320
lspeed = 60
rspeed = 60
control = 35
ret, frame = cap.read()

#前期准备完毕,节省时间
print("准备完毕!按下Enter启动!")
input()

try:
    while True:
        ret, frame = cap.read()
        # 转化为灰度图
        gray = cv2.cvtColor(frame, cv2.COLOR_BGR2GRAY)
        # 大津法二值化
        ret, dst = cv2.threshold(gray, 100, 255, cv2.THRESH_BINARY)
        # 膨胀,白区域变大
        dst = cv2.dilate(dst, None, iterations=2)
        cv2.imshow("镜头画面", dst)

        # 单看第400行的像素值s
        color = dst[400]
        # 找到black色的像素点个数
        black_count = np.sum(color == 0)

        # 防止black_count=0的报错
        if black_count == 0:
            continue
        else:
            black_index = np.where(color == 0)
        # 找到黑色像素的中心点位置
        center_now = (black_index[0][black_count - 1] + black_index[0][0]) / 2

        # 计算出center_now与标准中心点的偏移量
        direction = center_now - 320

        print("偏差值:", direction)

        # 更新PID误差
        error[0] = error[1]
        error[1] = error[2]
        error[2] = center_now - target

        # 更新PID输出(增量式PID表达式)
        adjust[0] = adjust[1]
        adjust[1] = adjust[2]
        adjust[2] = adjust[1] \
                    + kp * (error[2] - error[1]) \
                    + ki * error[2] \
                    + kd * (error[2] - 2 * error[1] + error[0]);
        print(adjust[2])

        # 饱和输出限制在control绝对值之内
        if abs(adjust[2]) > control:
            adjust[2] = sign(adjust[2]) * control
        # print(adjust[2])

        # 执行PID

        # 右转
        if adjust[2] > 20:
            pwma.ChangeDutyCycle(rspeed - adjust[2])
            pwmb.ChangeDutyCycle(lspeed)

        # 左转
        elif adjust[2] < -20:
            pwma.ChangeDutyCycle(rspeed)
            pwmb.ChangeDutyCycle(lspeed + adjust[2])

        else:
            pwma.ChangeDutyCycle(rspeed)
            pwmb.ChangeDutyCycle(lspeed)

        if cv2.waitKey(1) & 0xFF == ord('q'):
            break
except KeyboardInterrupt:
    print("结束!")
    pass
# 释放清理

cap.release()
cv2.destroyAllWindows()
pwma.stop()
pwmb.stop()
GPIO.cleanup()
2.对上面的代码,对其中重点加以分析:
  1. 预加载:
    input()后再try
  • 通过python3的标准输入流函数,需要读取用户的输入指令再进行小车运行的循环操作,从而实现预加载准备事项,降低耗损时间。
  1. 越界情况的处理:
    if black_count == 0:
    continue
  • 在具体实验中,时常会出现跳出黑线的情况,这时在代码层面的表现就是black_count=0。而对于一个固定的跑道而言,我们能否让小车当出现这种情况时,做一些适应性的变化,只要再次”看到“就好办了。
  • 正如之前所提到的那样,如果小车在转弯处出现越界,那么我们其实所做的只是让它沿着之前的弧度画圆,这样又会回到跑道的另一端继续开始寻线。
  1. 防抖:
    if abs(adjust[2]) > control:
  • 当偏移量经过pid处理后,但我们知道速度的调整不可能就是这个值。一来本身占空比最大为100,二来速度变化过大很容易偏转幅度过大而循线不稳。
    if adjust[2] > 20:
  • 同时,我们也并不是所有的偏移量都要去修正。当偏移量控制在某个较小的值时,我们不去修正,保证两轮的速度恒定,使小车前进更加稳定。
3.测试后的想法:
  • 在测试中,最大的问题就是X路口的分叉识别。即使我们将速度加了上去,还是在最后第4圈开始的时候发生了错位。
  • 现在再回头看,可以尝试一下用超声波来对小车所处位置进行分析。小车在转弯和X路口时都会出现较大的偏移量,我们可以单独对这两种情况进行处理。小车在X路口时处于墙的中间,故测距会有较大值;而在8的两端处,小车左右分别是墙和箱子,测距会有一个较小值。所以,当小车发现偏移量较大且测距也较大时,不去pid修正即可。
  • 但还需要注意的是,当时我们之所以在第一次实验就放弃了超声波,是因为小车在获取了速度再进行处理延时会非常糟糕,我也不知道是不是我代码写的非常糟糕。所以还是那句话,理想很丰满,实操很打脸。

五、课程总结与个人思考:

  1. 关于课程
  • 在最后的实际中测试中,第一次跑到了三圈并作为最终成绩进行了记录。但后续两次为了弥补第一次的不足进行了一些参数和处理上的改动,反而效果没有第一次的好。
  • 第二次测试视频链接:https://www.bilibili.com/video/BV18f4y1t7Wr?p=3
  • 当时拿到任务的时候,真的是满脑子的问号,这是我们在两周或是四周里面能完成的吗。最后我们不仅完成了这一任务,甚至可以说是超乎预料的圆满。
  • 根据具体场景来写代码,再在实操中修改参数、增加参数,这都是我们在纯理论课中无法体会到的。
  • 同时也希望来年的电导课可以增加一些测试的跑道,毕竟一堆人挤两个白毯跑道确实体验不太好。对循迹还好,但对选用超声波的同学无疑是一个巨大的挑战。
  1. 一些杂想
  • 最近闹得沸沸扬扬的”特斯拉“事件就牵涉到了图像处理的知识,该车之所以会失灵主要是计算机视觉出处理出现了一些异常,把一些障碍识别错误。最后,特斯拉还是决定采用雷达来经行避障。
  • 这其实和我们的课程非常吻合,分别对应了摄像头和超声波两种避障方案,但在主流选择上却恰好相反,我们大部分同学都是使用的摄像头,而汽车则大量使用的是雷达。其实还是讲到一个应用场景的问题,我们这里的模型很简单,有黑线当然摄像头更佳。
  • 但在实际道路上,是没有黑线的,靠雷达其实对障碍的种类没有那么多的要求,”化繁为简“。而如今机器视觉的火爆,或许在提示我们,可能我们需要将雷达和摄像头结合来增加车的观感,从而实现真正意义上的无人驾驶。

About

2021年春复旦大学大一下电子系统导论大作业——小车避障与绕桩

Resources

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published

Languages