OpenCV调用D435i 并框选目标图像
- 创建一个 Catkin 工作空间:
mkdir -p ~/catkin_ws/src
cd ~/catkin_ws/
catkin_make
source devel/setup.bash
- 在 Catkin 工作空间中创建一个 package:
cd ~/catkin_ws/src
catkin_create_pkg realsense_opencv_detection cv_bridge image_transport roscpp sensor_msgs
-
将以上提供的
main.cpp
代码复制到realsense_opencv_detection/src/main.cpp
文件中,将目标检测模型的路径替换为实际的模型路径。目标检测算法代码(main.cpp):#include <ros/ros.h> #include <cv_bridge/cv_bridge.h> #include <sensor_msgs/Image.h> #include <sensor_msgs/image_encodings.h> #include <opencv2/opencv.hpp> #include <librealsense2/rs.hpp> using namespace cv; class RealsenseOpenCVNode { public: RealsenseOpenCVNode() { image_pub_ = nh_.advertise<sensor_msgs::Image>("realsense_image", 1); // 创建一个名为realsense_image的图像发布器 } void run() { rs2::pipeline pipe; rs2::config cfg; cfg.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_BGR8, 30); // 配置RealSense相机流的参数 pipe.start(cfg); // 开始相机数据流 while (ros::ok()) { rs2::frameset data = pipe.wait_for_frames(); // 等待新的帧数据 rs2::frame color_frame = data.get_color_frame(); // 获取彩色图像帧 const int width = color_frame.as<rs2::video_frame>().get_width(); const int height = color_frame.as<rs2::video_frame>().get_height(); Mat color(Size(width, height), CV_8UC3, (void*)color_frame.get_data(), Mat::AUTO_STEP); // 将彩色图像数据转换为OpenCV的Mat格式 // 检测物体并绘制框 detectAndDrawObjects(color); sensor_msgs::ImagePtr msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", color).toImageMsg(); // 将OpenCV的Mat格式转换为ROS的sensor_msgs::Image消息类型 image_pub_.publish(msg); // 发布图像消息到realsense_image话题 ros::spinOnce(); // 处理ROS的回调函数 } } // 检测物体并绘制框 void detectAndDrawObjects(Mat& image) { // 加载目标检测模型 String modelPath = "path/to/your/model"; // 替换为你的目标检测模型路径 Net net = readNet(modelPath); // 对图像进行目标检测 Mat blob = blobFromImage(image, 1.0, Size(300, 300), Scalar(104.0, 177.0, 123.0), false, false); net.setInput(blob); Mat detection = net.forward(); for (int i = 0; i < detection.size[2]; i++) { float confidence = detection.at<float>(0, 0, i, 2); if (confidence > 0.5) { int x1 = static_cast<int>(detection.at<float>(0, 0, i, 3) * image.cols); int y1 = static_cast<int>(detection.at<float>(0, 0, i, 4) * image.rows); int x2 = static_cast<int>(detection.at<float>(0, 0, i, 5) * image.cols); int y2 = static_cast<int>(detection.at<float>(0, 0, i, 6) * image.rows); rectangle(image, Point(x1, y1), Point(x2, y2), Scalar(0, 255, 0), 2); } } } private: ros::NodeHandle nh_; ros::Publisher image_pub_; }; int main(int argc, char **argv) { ros::init(argc, argv, "realsense_opencv_node"); // 初始化ROS节点 RealsenseOpenCVNode node; node.run(); // 运行节点 return 0; }
请将目标检测模型的路径替换为你实际的模型路径,并确保你的模型与 OpenCV 兼容。这段代码将使用目标检测模型在图像中检测物体并绘制框。你可以根据需要调整模型和参数来实现更精确的目标检测效果。
-
在
realsense_opencv_detection
文件夹中创建一个CMakeLists.txt
文件,将以上提供的CMakeLists.txt
内容复制到其中CMakeLists.txt 文件:
cmake_minimum_required(VERSION 2.8.3) project(realsense_opencv_detection) find_package(catkin REQUIRED COMPONENTS cv_bridge image_transport roscpp sensor_msgs ) find_package(OpenCV REQUIRED) catkin_package() include_directories( ${catkin_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS} ) add_executable(realsense_opencv_node src/main.cpp) target_link_libraries(realsense_opencv_node ${catkin_LIBRARIES} ${OpenCV_LIBS} )
要将目标检测模型的路径替换为实际的模型路径,你可以按照以下步骤在终端中实现:
①打开
main.cpp
文件以编辑目标检测模型的路径:cd ~/catkin_ws/src/realsense_opencv_detection/src gedit main.cpp
②在打开的编辑器中找到以下行:
String modelPath = "path/to/your/model";
③将
"path/to/your/model"
替换为实际的目标检测模型文件的路径。例如,如果你的模型文件名为object_detection_model.pb
,并且放在~/models
目录下,那么路径应该是:String modelPath = "/home/your_username/models/object_detection_model.pb";
- 保存并关闭文件;重新构建你的 Catkin package;运行你的节点:
cd ~/catkin_ws/ catkin_make source ~/catkin_ws/devel/setup.bash rosrun realsense_opencv_detection realsense_opencv_node
现在,你的节点应该能够使用实际的目标检测模型文件进行目标检测。确保模型文件路径正确,并且模型文件与 OpenCV 兼容。
-
在
realsense_opencv_detection
文件夹中创建一个package.xml
文件,可以使用catkin_create_pkg
命令创建时自动生成的package.xml
文件。 -
在
realsense_opencv_detection
文件夹中构建 package:
cd ~/catkin_ws/
catkin_make
- 在一个终端中运行 ROS Master:
roscore
- 在另一个终端中运行 RealSense 相机节点:
roslaunch realsense2_camera rs_camera.launch
- 在另一个终端中运行你的节点:
source ~/catkin_ws/devel/setup.bash
rosrun realsense_opencv_detection realsense_opencv_node
现在,你的节点应该能够订阅 RealSense 相机的图像数据,进行目标检测并在图像中绘制框。请确保你的目标检测模型和参数设置正确,以便实现预期的目标检测效果。