YOLOによるカテゴリ認識

目的

Deep Learningベースのリアルタイム物体認識手法であるYOLO(You only look once)を用いた認識を体験します.なお,今回はROSに対応したYOLOのパッケージ(講義ではCPUのみ)を利用します.YOLOのアルゴリズムを知りたい方は,参考文献を参照してください.

YOLOの準備と実行

適当なワークスペース([work_space])のsrcフォルダに移動し,gitによりYOLOのパッケージをダウンロードしてください.

$ cd ~/[work_space]/src/
$ git clone --recursive https://github.com/leggedrobotics/darknet_ros.git

gitがインストールされていないというエラーが発生した場合には,下記のコマンドによりインストールした後,上記のコマンドを実行してください.

$ sudo apt-get update
$ sudo apt-get install git

githubよりダウンロードが完了した後,catkin_makeによりビルド,setup.bashをsourceします.ビルドには数分かかるので注意してください.

$ cd ../
$ catkin_make
$ source devel/setup.bash

launchファイルが用意されていますので,下記によりYOLOを実行します.

$ roslaunch darknet_ros darknet_ros.launch

Waiting for image.という表示が出力されるように,画像データが必要です.カメラから画像を取得するノードを起動して画像データを配信しましょう.必要となるトピック名,メッセージを調べます.まずは,起動しているノードの一覧を取得します.

$ rosnode list 
/darknet_ros
/rosout

YOLOは/darknet_rosという名前のノードで起動していることがわかります.次に,このノードが購読するトピック名とメッセージの型を調べます.

$ rosnode info /darknet_ros 
--------------------------------------------------------------------------------
Node [/darknet_ros]
Publications: 
 * /darknet_ros/bounding_boxes [darknet_ros_msgs/BoundingBoxes]
 * /darknet_ros/check_for_objects/feedback [darknet_ros_msgs/CheckForObjectsActionFeedback]
 * /darknet_ros/check_for_objects/result [darknet_ros_msgs/CheckForObjectsActionResult]
 * /darknet_ros/check_for_objects/status [actionlib_msgs/GoalStatusArray]
 * /darknet_ros/detection_image [sensor_msgs/Image]
 * /darknet_ros/found_object [std_msgs/Int8]
 * /rosout [rosgraph_msgs/Log]

Subscriptions: 
 * /camera/rgb/image_raw [unknown type]
 * /darknet_ros/check_for_objects/cancel [unknown type]
 * /darknet_ros/check_for_objects/goal [unknown type]

Services: 
 * /darknet_ros/get_loggers
 * /darknet_ros/set_logger_level


contacting node http://VB:36948/ ...
Pid: 4120
Connections:
 * topic: /rosout
    * to: /rosout
    * direction: outbound
    * transport: TCPROS

上記の出力より,購読しているトピックは3つ,このうちの一番上に表示されている/camera/rgb/image_rawが画像に関するトピックであることが予想できるので,このトピックの詳細を調べます.

$ rostopic info /camera/rgb/image_raw
Type: sensor_msgs/Image

Publishers: None

Subscribers: 
 * /darknet_ros (http://VB:36409/)

Kinectによる画像処理の講義でも扱ったsensor_msgs/Imageというメッセージ型であることから,/camera/rgb/image_rawというトピック名でカラー画像を配信すれば良いことがわかります.

次に,カメラから画像を取得するノードを起動します.

$ rosrun usb_cam usb_cam_node

立ち上げたノードが配信するトピックを調べます.

$ rosnode info /usb_cam 
--------------------------------------------------------------------------------
Node [/usb_cam]
Publications: 
 * /rosout [rosgraph_msgs/Log]
 * /usb_cam/camera_info [sensor_msgs/CameraInfo]
 * /usb_cam/image_raw [sensor_msgs/Image]
 * /usb_cam/image_raw/compressed [sensor_msgs/CompressedImage]
 * /usb_cam/image_raw/compressed/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
 * /usb_cam/image_raw/compressed/parameter_updates [dynamic_reconfigure/Config]
 * /usb_cam/image_raw/compressedDepth [sensor_msgs/CompressedImage]
 * /usb_cam/image_raw/compressedDepth/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
 * /usb_cam/image_raw/compressedDepth/parameter_updates [dynamic_reconfigure/Config]
 * /usb_cam/image_raw/theora [theora_image_transport/Packet]
 * /usb_cam/image_raw/theora/parameter_descriptions [dynamic_reconfigure/ConfigDescription]
 * /usb_cam/image_raw/theora/parameter_updates [dynamic_reconfigure/Config]

Subscriptions: None

Services: 
 * /usb_cam/get_loggers
 * /usb_cam/image_raw/compressed/set_parameters
 * /usb_cam/image_raw/compressedDepth/set_parameters
 * /usb_cam/image_raw/theora/set_parameters
 * /usb_cam/set_camera_info
 * /usb_cam/set_logger_level
 * /usb_cam/start_capture
 * /usb_cam/stop_capture


contacting node http://VB:33974/ ...
Pid: 6987
Connections:
 * topic: /rosout
    * to: /rosout
    * direction: outbound
    * transport: TCPROS

上記の出力より,メッセージの型が[sensor_msgs/Image]となるトピックを確認します.usb_camノードは,/usb_cam/image_rawというトピック名で画像を配信していることがわかります.YOLOが動作する/darknet_rosという名前のノードは,/camera/rgb/image_rawという名前でトピックを購読するため,トピック名を変えてあげる必要があります.そこで,一旦usb_camノードを終了し,下記のコマンドによりトピック名を変えて改めて起動しましょう.

$ rosrun usb_cam usb_cam_node /usb_cam/image_raw:=/camera/rgb/image_raw

改めてYOLOのノードを起動すると,認識結果と共に下記のような出力が得られます.

$ roslaunch darknet_ros darknet_ros.launch
--------------------省略--------------------

FPS:0.4
Objects:

cup: 93%
teddy bear: 58%
mouse: 65%
cell phone: 70%
laptop: 67%
keyboard: 55%
cup: 37%

様々な物体を認識できていることがわかりますね.なお,認識対象のカテゴリはこちらから確認できます.

最後にdarknet_rosノードが配信しているトピックを確認します.認識結果は下記より確認できます.

$ rostopic echo /darknet_ros/bounding_boxes

このトピックを購読すれば,認識結果に応じてロボットを動かすことができそうです.是非チャレンジしてください.

参考文献
  • YOLO
  • darknet_ros