卒業研究もラストスパートになり、少し余裕が出てきたので久々に投稿します。
Darknet-rosというパッケージがありますが、そのパッケージ(launchファイル)は1つのノードを立ち上げる前提みたいです。(groupタグで区切れなかった…)
そこで、darknetを複数立ち上げてみたいと思い、darknet_ros.launchに代わるファイルを作りました。具体的には、ネームスペースをdarknet0、darknet1、darknet2…と数字で区切って行く方式で増やしていきます。元の実装は入力のみが変更可能で出力は変更されないみたいなので、これも数字に連動してremapします。
Tossy氏の実装を使用しています。
darknet_ros.launchに代わるdarknet_ros_rename.launchを作成します。
<?xml version="1.0" encoding="utf-8"?> <launch> <!-- Console launch prefix --> <arg name="launch_prefix" default=""/> <arg name="image" default="camera/rgb/image_raw" /> <arg name="num" default="0" /> <arg name="bbox" default="/darknet_ros/bounding_boxes" /> <arg name="obj" default="/darknet_ros/found_object" /> <arg name="detection_img" default="/darknet_ros/detection_image" /> <!-- Config and weights folder. --> <arg name="yolo_weights_path" default="$(find darknet_ros)/yolo_network_config/weights"/> <arg name="yolo_config_path" default="$(find darknet_ros)/yolo_network_config/cfg"/> <!-- ROS and network parameter files --> <arg name="ros_param_file" default="$(find darknet_ros)/config/ros.yaml"/> <arg name="network_param_file" default="$(find darknet_ros)/config/yolov2-tiny.yaml"/> <!-- Load parameters --> <rosparam command="load" ns="darknet_ros$(arg num)" file="$(arg ros_param_file)"/> <rosparam command="load" ns="darknet_ros$(arg num)" file="$(arg network_param_file)"/> <!-- Start darknet and ros wrapper --> <node pkg="darknet_ros" type="darknet_ros" name="darknet_ros$(arg num)" output="screen" launch-prefix="$(arg launch_prefix)"> <param name="weights_path" value="$(arg yolo_weights_path)" /> <param name="config_path" value="$(arg yolo_config_path)" /> <remap from="camera/rgb/image_raw" to="$(arg image)" /> <remap from="darknet_ros/bounding_boxes" to="$(arg bbox)" /> <remap from="darknet_ros/found_object" to="$(arg obj)" /> <remap from="darknet_ros/detection_image" to="$(arg detection_img)" /> </node> <!--<node name="republish" type="republish" pkg="image_transport" output="screen" args="compressed in:=/front_camera/image_raw raw out:=/camera/image_raw" /> --> </launch>
次に、yolo_v4.launchに代わるyolo_v4x2.launchを作ります。uvc_cameraはあらかじめインストールしておきましょう。
<?xml version="1.0" encoding="utf-8"?> <launch> <rosparam> camera0: device: "/dev/video0" </rosparam> <node pkg="rqt_graph" type="rqt_graph" name="rqt"/> <node pkg="uvc_camera" type="uvc_camera_node" name="camera0"> <remap from="/image_raw" to="camera0/image_raw"/> </node> <arg name="camera_num_0" default="0" /> <include file="$(find darknet_ros)/launch/darknet_ros_rename.launch"> <arg name="network_param_file" value="$(find darknet_ros)/config/yolov4.yaml"/> <arg name="num" value="$(arg camera_num_0)" /> <arg name="image" value="camera0/image_raw" /> <arg name="bbox" value="darknet_ros$(arg camera_num_0)/bounding_boxes" /> <arg name="obj" value="darknet_ros$(arg camera_num_0)/found_object" /> <arg name="detection_img" value="darknet_ros$(arg camera_num_0)/detection_image" /> </include> <rosparam> camera1: device: "/dev/video2" </rosparam> <node pkg="uvc_camera" type="uvc_camera_node" name="camera1"> <remap from="/image_raw" to="camera1/image_raw"/> </node> <arg name="camera_num_1" default="1" /> <include file="$(find darknet_ros)/launch/darknet_ros_rename.launch"> <arg name="network_param_file" value="$(find darknet_ros)/config/yolov4.yaml"/> <arg name="num" value="$(arg camera_num_1)" /> <arg name="image" value="camera1/image_raw" /> <arg name="bbox" value="darknet_ros$(arg camera_num_1)/bounding_boxes" /> <arg name="obj" value="darknet_ros$(arg camera_num_1)/found_object" /> <arg name="detection_img" value="darknet_ros$(arg camera_num_1)/detection_image" /> </include> </launch>
ウェブカメラが2台接続された状態で、次のコマンドを実行してプログラムを起動します。$ roslaunch darknet_ros yolo_v4x2.launch
これを実行したデスクトップPC(Ryzen7 2700x + RTX2080Ti)では両ウィンドウが15fpsとかなり重くなってしまったので、相当高性能なPCを使うかYOLOv4-tinyなどの軽量なモデルを使用したほうがいいと思います。
複数のカメラで別の場所を移して物体検出をしたいときや、同じ入力画像に対して2回物体検出をしたいときには使えるかもしれませんね…?