視覚距離計学習(一)ROSリアルタイムでカメラ画像を読み取り表示


タスクの説明

  • test_image_publisher.cpp:コンピュータカメラから画像を読み取り、画像情報を公開する「camera/image」
  • test_image_subscriber.cpp:publisherが発行する画像情報
  • を読み出す

    test_image_publisher.cpp


    一.コード構造解析

  • 初期化
  • ros::init(argc, argv, "image_publisher");
    ros::NodeHandle nh;
    image_transport::ImageTransport it(nh);
    image_transport::Publisher pub = it.advertise("camera/image", 1);
    
     , . "camera/image" ("\" )
  • カメラから画像を読み出す
  • .
    cv::VideoCapture cap(0);

    カメラハンドルをもらい、次に
    cap >> frame;

    直接画像を得る3.パブリックスペースへの画像メッセージの公開
    pub.publish(msg);  

    二.完全なコード

    #include 
    #include 
    #include 
    #include 
    #include 
    
    int main(int argc, char** argv) {
    
    
        ros::init(argc, argv, "image_publisher");
        ros::NodeHandle nh;
        image_transport::ImageTransport it(nh);
        image_transport::Publisher pub = it.advertise("camera/image", 1);
    
        cv::VideoCapture cap(0);
        if (!cap.isOpened()) {
        ROS_INFO("cannot open video device
    "
    ); return 1; } cv::Mat frame; sensor_msgs::ImagePtr msg; ros::Rate loop_rate(10);// 10ms while (nh.ok()) { cap >> frame; if (!frame.empty()) { msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", frame).toImageMsg(); pub.publish(msg); } ROS_INFO("runnning!"); ros::spinOnce(); loop_rate.sleep();// ros::Rate loop_rate , 10ms } }

    test_image_subscriber.cpp


    一.コード構造解析

  • メインプログラム初期化
  • ros::init(argc, argv, "image_subscriber");  
    ros::NodeHandle nh;  
    //ros::NodeHandle nh_private("~");  
    cv::namedWindow("view", CV_WINDOW_NORMAL);   
    cv::startWindowThread();  

    rosシステムを初期化し、nodeノードを作成し、名前を設定します.次に、画像表示ウィンドウを開き、スレッド表示画像2を個別に配置する.リスナーsubscriberを設定し、対応する名前のmessageを受信すると応答関数imageCallbackに直接ジャンプします.
    image_transport::ImageTransport it(nh);  
    image_transport::Subscriber sub = it.subscribe("camera/image", 1, imageCallback);

    nodeハンドルnhによりリスナーを作成する.nhは共通ノードであるため、同じ共通ノードで発行する情報(空間範囲が"/")をすべて受信する.nh_に気づくprivateはプライベートノードであるため、特定の空間範囲で発行する情報しか受信できない("/image_subscriber").プライベートノードと共有ノードについての具体的な議論は、この記事[[ROS学習](七)ROSパラメータサービス(1)]を参照することができる.(http://blog.csdn.net/wengge987/article/details/50620121)
  • messageの到来を待つ
  • ros::spin();  

    この時から、プログラムはずっと画像情報の到来を待っている.

    二.完全プログラム(cpp,launch,CMakeLists.txt)

    //test_image_subscriber.cpp
    #include <ros/ros.h>  
    #include <image_transport/image_transport.h>  
    #include <opencv2/highgui/highgui.hpp>  
    #include <cv_bridge/cv_bridge.h>  
    
    void imageCallback(const sensor_msgs::ImageConstPtr& msg)  
    {  
    
      cv_bridge::CvImagePtr cv_ptr;  
      try  
      {  
         cv_ptr = cv_bridge::toCvCopy(msg, "mono8");  
      }  
      catch (cv_bridge::Exception& e)  
      {  
         ROS_ERROR("cv_bridge exception: %s", e.what());  
         return;  
      }  
    
      cv::Mat img_rgb;  
      img_rgb = cv_ptr->image;  
    
      cv::imshow("view", img_rgb);  
      // fail if don't have waitKey(3).
      cv::waitKey(3);
    }  
    
    int main(int argc, char **argv)  
    {  
      ros::init(argc, argv, "image_subscriber");  
      ros::NodeHandle nh;  
      cv::namedWindow("view", CV_WINDOW_NORMAL);   
      cv::startWindowThread();  
      image_transport::ImageTransport it(nh);  
      image_transport::Subscriber sub = it.subscribe("camera/image", 1, imageCallback);
      ros::spin();  
      cv::destroyWindow("view");  
      return 0;
    } 

    CMakeListsキー
    cmake_minimum_required(VERSION 2.8.3)
    project(my_vio)
    
    set(CMAKE_BUILD_TYPE "Release")
    set(CMAKE_CXX_FLAGS "-std=c++11")
    
    find_package(catkin REQUIRED COMPONENTS
      roscpp
      rospy
      sensor_msgs
      image_transport 
      cv_bridge
    )
    
    find_package(OpenCV REQUIRED)
    
    include_directories(
      include
      include/my_vio
      ${catkin_INCLUDE_DIRS}
     # "/usr/include/eigen3"
    )
    
    catkin_package()
    
    # add the publisher example  
    
    add_executable(test_image_subscriber src/test_image_subscriber.cpp)  
    target_link_libraries(test_image_subscriber ${catkin_LIBRARIES} ${OpenCV_LIBRARIES})  
    
    add_executable(test_image_publisher src/test_image_publisher.cpp)  
    target_link_libraries(test_image_publisher ${catkin_LIBRARIES} ${OpenCV_LIBRARIES})  

    launchファイル
    <launch>
        <node name="image_publisher" pkg="my_vio" type="test_image_publisher" output="screen"/>
        <node name="image_subscriber" pkg="my_vio" type="test_image_subscriber" output="screen"/>
    launch>

    小結調通後、画像情報をスムーズに入手でき、その後のすべての視覚距離計がこの基礎の上で開発される.