一、创建模拟相机图像话题发布功能
通过对一个现有的车位图像集进行模拟相机ros2图像话题发布功能
1.创建图像发布工作空间
mkdir -p SimImage/src
2.创建simimage功能包
从SimImage/src中进入终端,创建simimage ros2功能包。
所以依赖项要有rclpy、sensor_msgs、cv_bridge、std_msgs:
ros2 pkg create --build-type ament_python simimage --dependencies rclpy sensor_msgs cv_bridge std_msgs
3.编写ros2图像发布话题
在SimImage/src/simimage/simimage中创建imagetopic.py
内容如下:
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
import os
import cv2
class ImagePublisher(Node):
def __init__(self, folder_path):
super().__init__('image_publisher')
self.folder_path = folder_path
self.publisher_ = self.create_publisher(Image, 'image_topic', 10) #注意你的话题名称
self.timer = self.create_timer(0.5, self.publish_image)
self.bridge = CvBridge()
self.image_count = 0
# 获取文件夹中所有图像的列表
self.image_files = [os.path.join(self.folder_path, f) for f in os.listdir(self.folder_path) if f.endswith('.jpg') or f.endswith('.png')]
def publish_image(self):
if self.image_count < len(self.image_files):
image_path = self.image_files[self.image_count]
self.get_logger().info(f'Publishing image: {image_path}')
image = cv2.imread(image_path)
message = self.bridge.cv2_to_imgmsg(image, 'bgr8')
self.publisher_.publish(message)
self.image_count += 1
else:
self.get_logger().info('All images published. Restarting from the beginning.')
self.image_count = 0
def main(args=None):
rclpy.init(args=args)
folder_path = '/home/stk/cardatas/image' #替换为你自己的图像集路径
publisher = ImagePublisher(folder_path)
rclpy.spin(publisher)
rclpy.shutdown()
if __name__ == '__main__':
main()
4.修改setup.py
在SimImage/src/simimage/setup.py文件中添加入口点,如下内容:
'imagetopic = simimage.imagetopic:main'
5.编译运行
从SimImage或者SimImage/src/simimage路径进入终端编译(从哪个路径编译的,就从哪个路径进入终端运行),这里从SimImage进入:
colcon build
6.运行
第一个终端,从SimImage进入:
. install/setup.bash
ros2 run simimage imagetopic
第二个终端,查看话题是否发布及其内容:
ros2 topic list
ros2 topic echo /image_topic
也可以通过image_view查看话题发布的图像
安装:
sudo apt install ros-foxy-image-view
运行:
ros2 run image_view image_view image:=/image_topic
二、修改ros2 yolov4dm检测功能
在上一篇文章中已经详细描述了创建ros2 yolov4dm检测功能包过程,这里在之前创建的基础上进行修改
1.修改package.xml
因为这里将输入单个图片的检测方式改为通过话题接受图像的检测方式,所以要添加sensor_msgs依赖项。(图片中多添加的std_msgs不用在意,反正没用到)
<depend>sensor_msgs</depend>
2.修改predict.py
主要创建图像话题接受和检测结果发布节点
内容:
import sys
sys.path.append('/home/stk/ros2work/ORB_SLAM3_Grid_Mapping/Examples/YOLOV4DM/src/yolov4dm/yolov4dm')
import rclpy
import time
import cv2
import numpy as np
from matplotlib import pyplot as plt
from PIL import Image as Images
from cv_bridge import CvBridge
from yolo import YOLO
from rclpy.node import Node
from geometry_msgs.msg import Point
from sensor_msgs.msg import Image
from std_msgs.msg import Int32
class ImageSubscriber(Node):
def __init__(self):
super().__init__('image_subscriber')
super().__init__('point_publisher')
self.subscription = self.create_subscription(
Image,
'/image_topic',
self.image_callback,
10)
self.cv_bridge = CvBridge()
self.publisher_ = self.create_publisher(Point, 'point_topic', 10)
def image_callback(self, msg):
cv2_img = self.cv_bridge.imgmsg_to_cv2(msg,'bgr8')
self.get_logger().info('Received image with dimensions: %s' % str(cv2_img.shape))
msgss = Point()
yolo = YOLO()
mode = "predict"
if mode == "predict":
try:
image = Images.fromarray(cv2.cvtColor(cv2_img,cv2.COLOR_BGR2RGB))
img_read = cv2_img
except:
print('Open Error! Try again!')
else:
#print('1212!')
r_image,label1,top1,left1,bottom1,right1 = yolo.detect_image(image,img_read, crop = False, count=False)
if not label1:
top1=10
bottom1=20
right1=30
#top1=10
#bottom1=20
#right1=30
else:
top1=1
bottom1=2
right1=3
msgss.x = float(top1)
msgss.y = float(bottom1)
msgss.z = float(right1)
self.publisher_.publish(msgss)
def main(args=None):
rclpy.init(args=args)
image_subscriber = ImageSubscriber()
#point_publisher = PointPublisher()
rclpy.spin(image_subscriber)
#rclpy.spin(point_publisher)
rclpy.shutdown()
if __name__ == '__main__':
main()
3.编译
在YOLOV4DM中进入终端: colcon build
4.运行
第一个终端:
在SimImage中进入终端运行图像发布功能:
. install/setup.bash
ros2 run simimage imagetopic
第二个终端:
在YOLOV4DM中进入终端:
. install/setup.bash
ros2 run yolov4dm predict
第三个终端:
随便哪里进入终端,查看发布的检测结果:
ros2 topic echo /point_topic