最終課題

自動運転を模した課題に取り組みます.

目的

これまでに学んだ内容を生かし,自動運転にちなんだ課題に取り組みます. 課題を介してROSの仕組みの理解やオープンソースソフトウェアとのインテグレーション,プログラミングの実装力, トライ&エラーによる問題解決,センシング技術など様々なスキルを身につけてください.

課題

自動運転に模した課題に取り組みます. 課題は基本課題と3つの追加課題で構成されています. 最低でも基本課題をクリアしてから追加課題に取り組みましょう. コースは下記の写真の通りです.

最終課題

基本課題

黒色のラインを検知し,ラインに沿ってTurtlebot3を走行させます. スタートからゴールまで黒いラインをトレースして走行させてください. 走行中にTurtlebot3の一部が黒いラインの上にいなければ走行失敗とみなします.

追加課題1

コース上に設置された徐行標識を認識して走行スピードを低下させてください. コース上のどの位置からでも標識を認識して良いこととします. 徐行標識を認識後,1秒間以上走行速度を半分以下に制限してください. 標識認識は1回のみとし,2回以上の認識は追加課題の達成失敗とします.

追加課題2

黒色のライン上に設置された赤色の駐車ラインを認識し,駐車スペースに駐車してください. 駐車動作中はライントレースはしなくても構いません. 駐車スペース用パネルにTurtlebot3の機体半分以上が入り,1秒間以上停止することができれば駐車成功とみなします. 駐車後,黒色のラインに復帰してライントレースを再開してください.

追加課題3

ゴール用パネルの後ろに設置した障害物を認識し,障害物に衝突する前に停止させてください. ただし,ゴール用パネル上で停止させてください. ゴール用パネルにTurtlebot3の機体半分以上が入り,停止することができれば停車成功とみなします.

カメラから得られる画像

ライントレースを行うには黒いラインを検知する必要があります. Turtlebot3に搭載されたカメラは,車体前方の下部に若干下を向くように設置されています. 例えば,下記のようなシーンの場合,黒色のラインが少しだけ観測できます. 最短で約2cm先の黒色のラインを検知できますが,2cm以内のラインは検知できないので注意してください.

turtlebot3_1

image1

追加課題1では標識を認識する必要があります. 下記のようなシーンでは,解像度は低いですが標識を観測することができます.

turtlebot3_2

image2

サンプルプログラム

下記はシンプルなライントレースプログラムです. 黒いラインを検知したら右前に,白いパネルを検知したら左前に進みます. プログラム自体は新しい内容は含まれていません. 既出のプログラムの組み合わせです. まずはプログラムを読み理解することから始めましょう. 分からない場合には過去の講義webページを復習してください.

サンプルプログラムでは,直線を上手くライントレースできますが,カーブは上手く曲がることができません. プログラムを改良して基本課題をクリアしましょう.

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
import rclpy
import cv2
import numpy as np
import time
from rclpy.node import Node
from cv_bridge import CvBridge, CvBridgeError
from sensor_msgs.msg import Image
from geometry_msgs.msg import Twist
from std_msgs.msg import Float32MultiArray
import math

class AutoRun(Node):
    WIDTH = 40
    HEIGHT = 40

    def __init__(self):
        super().__init__('turtlebot_auto_run')

        self.twist_pub = self.create_publisher(Twist, 'cmd_vel', 1)
        self.image_sub = self.create_subscription(Image, "/image_raw", self.image_callback, 1)
        self.bridge = CvBridge()

    def set_move_vector(self, linear_x, angular_z):
        twist = Twist()
        twist.linear.x = linear_x
        twist.angular.z = angular_z

        self.twist_pub.publish(twist)
 
    def image_callback(self, data):
        try:
            color_image = self.bridge.imgmsg_to_cv2(data, "bgr8")
        except CvBridgeError as e:
            self.get_logger().info(e)

        h, w, c = color_image.shape
        x1 = int(w / 2) - self.WIDTH
        x2 = int(w / 2) + self.WIDTH
        y1 = h - (self.HEIGHT * 2)
        y2 = h

        r = g = b = 0
        for i in range(y1, y2):
            for j in range(x1, x2):
                #color_image.itemset((i, j, 0), 0)
                #color_image.itemset((i, j, 1), 0)
                r = r + color_image.item(i, j, 2)
                g = g + color_image.item(i, j, 1)
                b = b + color_image.item(i, j, 0)

        ave_r = r / ((self.WIDTH * 2) * (self.HEIGHT * 2))
        ave_g = g / ((self.WIDTH * 2) * (self.HEIGHT * 2))
        ave_b = b / ((self.WIDTH * 2) * (self.HEIGHT * 2))
        ave = (ave_r + ave_g + ave_b) / 3
       
        if(ave <= 100):
            self.set_move_vector(0.05, -1.2)
        else:
            self.set_move_vector(0.05, 1.2)

def main(args=None):
    rclpy.init(args=args)
    node = AutoRun()
    rclpy.spin(node)

    node.destroy_node()
    rclpy.shutdown()

if __name__ == '__main__':
    main()

参考動画

基本課題と追加課題をクリアした例です. サンプルプログラムでは,ライントレースの際に機体を左右に降るため滑らかなライントレースができません. PID制御を導入することで安定した走行が可能となります. 余力がある人は是非取り組んでみてください.