-
[Darknet ROS] darknet_ros yolov3 코드 이것 저것 수정Robot, Autonomous Vehicle 2021. 3. 2. 15:30
github.com/leggedrobotics/darknet_ros
1. 여러 머신 또는 한 머신에서 multi object detection 수행하기
-> .launch 파일 수정해야함
-> namespace 추가하기
<?xml version="1.0" encoding="utf-8"?> <launch> <!-- Console launch prefix --> <arg name="launch_prefix" default=""/> <arg name="image" default="/image_raw" /> <!-- 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"/> <!-- Load parameters --> <rosparam command="load" ns="darknet_ros_d/darknet_ros" file="$(find darknet_ros)/config/ros_drone.yaml"/> <rosparam command="load" ns="darknet_ros_d/darknet_ros" file="$(find darknet_ros)/config/yolov3-tiny.yaml"/> <!-- Start darknet and ros wrapper --> <node ns="darknet_ros_d" pkg="darknet_ros" type="darknet_ros" name="darknet_ros" 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="/image_raw" to="$(arg image)" /> </node> <!--<node name="republish" type="republish" pkg="image_transport" output="screen" args="compressed in:=/front_camera/image_raw raw out:=/camera/im$ </launch>
2. darkent_ros object detection 실행 후 detection_image pubilsh 하려면
-> /darknet_ros/config/ros.yaml 파일 수정
-> 맨 아래 enable_opencv 부분 false로
image_view: enable_opencv: false wait_key_delay: 1 enable_console_output: true
3. publish되는 topic 이름들 수정하고 싶을 때
-> /darknet_ros/config/ros.yaml 파일 수정
-> actions, publishers topic 이름 수정
actions: camera_reading: name: /darknet_ros/check_for_objects_d publishers: object_detector: topic: /darknet_ros/found_object_d queue_size: 1 latch: false bounding_boxes: topic: /darknet_ros/bounding_boxes_d queue_size: 1 latch: false detection_image: topic: /darknet_ros/detection_image_d/compressed queue_size: 1 latch: true
4. publish되는 detection_image를 compressed_image로 publish하고 싶을 때
-> /include/darknet_ros/YoloObjectDetector.hpp, /src/YoloObjectDetector.cpp, /config/ros.yaml 3가지 파일 수정
-> YoloObjectDetector.hpp 에 CompressedImage Msg include.
// ROS #include <actionlib/server/simple_action_server.h> #include <geometry_msgs/Point.h> #include <image_transport/image_transport.h> #include <ros/ros.h> #include <sensor_msgs/CompressedImage.h> #include <sensor_msgs/Image.h> #include <sensor_msgs/image_encodings.h> #include <std_msgs/Header.h>
-> YoloObjectDetector.cpp 에 detectionImagePublisher 부분들 수정
-> 여기서 param[1] 부분은 JPEG 압축률, 낮을 수록 압축을 많이 한다 ( == 화질이 낮아진다 ) ==> 전송속도 빨라진다
detectionImagePublisher_ = nodeHandle_.advertise<sensor_msgs::CompressedImage>(detectionImageTopicName, detectionImageQueueSize, detectionImageLatch); // ~~~~ bool YoloObjectDetector::publishDetectionImage(const cv::Mat& detectionImage) { if (detectionImagePublisher_.getNumSubscribers() < 1) return false; std::vector<uchar> buff; std::vector<int> param = std::vector<int>(2); param[0] = CV_IMWRITE_JPEG_QUALITY; param[1] = 10; cv::imencode(".jpg",detectionImage, buff, param); cv::Mat jpegimage = cv::imdecode(buff, CV_LOAD_IMAGE_COLOR); cv_bridge::CvImage cvImage; cvImage.header.stamp = ros::Time::now(); cvImage.header.frame_id = "detection_image"; cvImage.encoding = sensor_msgs::image_encodings::BGR8; //cvImage.image = detectionImage; cvImage.image = jpegimage; detectionImagePublisher_.publish(*cvImage.toCompressedImageMsg()); ROS_DEBUG("Detection image has been published."); return true; }
-> ros.yaml 에서 publihs하는 detection_image topic 이름 뒤에 /compressed 붙이기
detection_image: topic: /darknet_ros/detection_image_d/compressed queue_size: 1 latch: true
'Robot, Autonomous Vehicle' 카테고리의 다른 글
[Python OpenCV ROS] cv.cap으로 딴 이미지 compressedImage msg로 publish하기 (0) 2021.03.02 [ROS USB_CAM] 한 머신에서 multi usb_cam node 켜기 (0) 2021.03.02 [bash file] 이것저것 (0) 2021.02.13 [Jeton Nano] 환경 설정 (0) 2021.02.11 [ROS] Ubuntu 18.04 에 ROS melodic 환경 설정 및 작업 환경 설정 (0) 2021.02.10