遇到的坑:
rtsp视频流和转ros2 topic放到一个线程里,频繁提示解码丢帧的情况。
解决这个问题需要将opencv获取rtsp视频流单独开一个线程,不能在里面处理任何多余的代码。
代码如下:
#include <chrono>
#include <cstdio>
#include <rclcpp/rclcpp.hpp>
#include <opencv2/opencv.hpp>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/msg/image.hpp>
#include <std_msgs/msg/string.hpp>
using namespace std::chrono_literals;
class VideoGrab : public rclcpp::Node
{
public:
VideoGrab() : Node("video_grab")
{
// video_publisher_ = this->create_publisher<sensor_msgs::msg::Image>("video", 5);
video_compressed_publisher_ = this->create_publisher<sensor_msgs::msg::CompressedImage>("video/compressed",5);
cap.open("rtsp://admin:user@IP:999/Streaming/Channels/101");
// timer_ = this->create_wall_timer(30ms,std::bind(&VideoGrab::timer_callback,this));
rtsp_th_ = std::make_shared<std::thread>(std::bind(&VideoGrab::run, this));
rtsp_th_->detach();
pub_th_ = std::make_shared<std::thread>(std::bind(&VideoGrab::publish, this));
pub_th_->join();
}
private:
void run()
{
while (rclcpp::ok())
{
cap.read(image);
cv::waitKey(30);
}
}
void publish()
{
while ((rclcpp::ok()))
{
// RCLCPP_INFO(this->get_logger(), "pub image");
try
{
ros_img_ = cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", image).toImageMsg();
if(!image.empty())
{
ros_img_compressed_ = cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", image).toCompressedImageMsg();
video_compressed_publisher_->publish(*ros_img_compressed_);
}
else
RCLCPP_WARN(this->get_logger(), "empty image");
// video_publisher_->publish(*ros_img_);
}
catch (cv_bridge::Exception &e)
{
RCLCPP_ERROR(this->get_logger(),ros_img_->encoding.c_str());
}
cv::waitKey(30);
}
}
private:
cv::VideoCapture cap;
cv::Mat image;
cv_bridge::CvImagePtr cv_ptr;
sensor_msgs::msg::Image::SharedPtr ros_img_;
sensor_msgs::msg::CompressedImage::SharedPtr ros_img_compressed_;
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr video_publisher_;
rclcpp::Publisher<sensor_msgs::msg::CompressedImage>::SharedPtr video_compressed_publisher_;
std::shared_ptr<std::thread> rtsp_th_, pub_th_;
// private:
// void timer_callback()
// {
// // cap.read(image);
// RCLCPP_INFO(this->get_logger(), "pub image");
// ros_img_ = cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", image).toImageMsg();
// video_publisher_->publish(*ros_img_);
// }
};
int main(int argc, char **argv)
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<VideoGrab>());
rclcpp::shutdown();
return 0;
}
本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)