rtsp_topic

1.打开推流服务器

2.接收ros图像

3.ffmpeg命令推流

pushflow.cpp

 

// 1.包含头文件;
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include <iostream>
#include <csignal>
#include <opencv4/opencv2/opencv.hpp>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/msg/image.hpp>
using namespace std::chrono_literals;
using std::placeholders::_1;

FILE *fp = nullptr;
 
// 3.定义节点类;
class MinimalSubscriber : public rclcpp::Node
{
  public:
    MinimalSubscriber(std::string name)
    : Node(name)
    {
      // 3-1.创建订阅方;
      //subscription_ = this->create_subscription<std_msgs::msg::String>("rtsptopic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));
      
      std::string rtspUrl = "rtsp://127.0.0.1:8554/test";
      std::stringstream command;
      command << "ffmpeg "
              << "-re "
              << "-f rawvideo "
              << "-vcodec rawvideo "
              << "-pix_fmt bgr24 "
              << "-s 1080x720 "
              << "-r 19 "
              << "-i - "
              << "-an "
              << "-q:v 1 "
              //<<"-c:v libx264 "
              << "-f rtsp "
              << rtspUrl;//<<" "
              //<< "-c copy";

      fp = popen(command.str().c_str(),"w");
     
      

      //if(fp!= nullptr){
      subscription_ = this->create_subscription<sensor_msgs::msg::CompressedImage>("detectResultMatTopic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));
      //subscription_ = this->create_subscription<sensor_msgs::msg::CompressedImage>("pubImageTopic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));
      //pclose(fp);
       // }

    }

  private:
    
    rclcpp::Subscription<sensor_msgs::msg::CompressedImage>::SharedPtr subscription_;
    // 3-2.处理订阅到的消息;

    void topic_callback(const sensor_msgs::msg::CompressedImage::ConstPtr  msg) const
    {
      cv_bridge::CvImagePtr cv_ptr_compressed = cv_bridge::toCvCopy(msg,sensor_msgs::image_encodings::BGR8);
      cv::Mat imgCallback = cv_ptr_compressed->image;

      cv::Mat des1080;

      cv::resize(imgCallback, des1080, cv::Size(1080, 720), 0, 0, cv::INTER_NEAREST);
      //cv::imshow("imgCallbackrtsp",des1080);
      //cv::waitKey(1);

      fwrite(des1080.data,sizeof(char),des1080.total()*des1080.elemSize(),fp);
    }
    
};


 
int main(int argc, char * argv[])
{
  // 2.初始化 ROS2 客户端;
  rclcpp::init(argc, argv);
  // 4.调用spin函数,并传入节点对象指针。
  auto node = std::make_shared<MinimalSubscriber>("rtsp");
  rclcpp::spin(node);

  //rclcpp::init(argc, argv);
  // 4.调用spin函数,并传入节点对象指针。
  //auto node = std::make_shared<MinimalSubscriber>("detect");
  //rclcpp::spin(node);
  //rclcpp::spin(std::make_shared<MinimalSubscriber>());
  // 5.释放资源;
  //rclcpp::shutdown();
  // 5.释放资源;
  rclcpp::shutdown();
  return 0;
}

CMakeLists.txt

cmake_minimum_required(VERSION 3.5)
project(rtsp_topic)

# Default to C99
if(NOT CMAKE_C_STANDARD)
  set(CMAKE_C_STANDARD 99)
endif()

# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
  set(CMAKE_CXX_STANDARD 14)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
  add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)

find_package(cv_bridge REQUIRED)
find_package(image_transport)
find_package(sensor_msgs REQUIRED)

find_package(OpenCV REQUIRED)
include_directories( ${OpenCV_INCLUDE_DIRS})

add_executable(rtsp
  src/pushflow.cpp
)

target_link_libraries(rtsp ${OpenCV_LIBS})




# ros
target_link_libraries(rtsp
  ${rclcpp_LIBRARIES} 
)

ament_target_dependencies(rtsp
  rclcpp
  std_msgs
  sensor_msgs 
  cv_bridge 
  OpenCV
  image_transport
)
 


# 安装可执行文件
install(TARGETS rtsp
  DESTINATION lib/${PROJECT_NAME}
)

ament_package()

package.xml

<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
  <name>rtsp_topic</name>
  <version>0.0.0</version>
  <description>TODO: Package description</description>
  <maintainer email="jetson@todo.todo">jetson</maintainer>
  <license>TODO: License declaration</license>

  <buildtool_depend>ament_cmake</buildtool_depend>

  <depend>rclcpp</depend>
  <depend>std_msgs</depend>

  <test_depend>ament_lint_auto</test_depend>
  <test_depend>ament_lint_common</test_depend>

  <export>
    <build_type>ament_cmake</build_type>
  </export>
</package>

评论 2
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值