对于熟悉ROS的朋友们来说,图像的topic有了,我们就可以开始自己想干的事情了。这里我创建一个名为hs_image_sub的package来处理角蜂鸟的图像,图像的topic 名字为上一篇提到的:/hs/camera/image_raw. 也是我们打开rqt_image_view窗口看到的东西。

这篇博客主要是利用opencv来获取角蜂鸟图像,然后做一个阈值处理,并且打开窗口显示原图和处理后的图像。有了opencv想做什么处理都可以了,这篇文章主要是教大家在ROS里获取并调用图像。

cd ~/catkin_ws/src

catkin_create_pkg hs_image_sub roscpp sensor_msgs cv_bridge

然后

cd ~/catkin_ws/src/hs_image_sub/src

touch hs_image_sub_node.cpp

gedit hs_image_sub_node.cpp

填入以下代码

#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/image_encodings.h>
#include <image_transport/image_transport.h>
#include <cv_bridge/cv_bridge.h>
 
// OpenCV
#include <opencv2/opencv.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/highgui/highgui.hpp>
 
using namespace std;
using namespace cv;
 
const string Original_winName = "Original Image";
const string Thresh_winName = "Threshed Image";
 
Mat cameraFeed;
Mat HSV;
Mat threshold_ori;
 
void rgbCallback(const sensor_msgs::ImageConstPtr& msg)
{
    cv_bridge::CvImageConstPtr cv_ptr;
    try
    {
        cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8); // Caution the type here.
    }
    catch (cv_bridge::Exception& ex)
    {
        ROS_ERROR("cv_bridge exception in rgbcallback: %s", ex.what());
        exit(-1);
    }
 
 
    cameraFeed = cv_ptr->image.clone();
 
    cvtColor(cameraFeed,HSV,COLOR_BGR2HSV);
    inRange(HSV,Scalar(0,133,0),Scalar(21,256,256),threshold_ori);
    
 
    //show frames
    imshow(Original_winName,cameraFeed);
    imshow(Thresh_winName,threshold_ori);
 
    //delay 10ms so that screen can refresh.
    //image will not appear without this waitKey() command
    waitKey(10);
 
}
 
 
int main(int argc, char *argv[])
{
    ros::init(argc, argv, "HornedSungemGrabber");
 
    ros::NodeHandle n;
 
//    topic name of HornedSungem
    ros::Subscriber rgb_sub = n.subscribe("/hs/camera/image_raw", 1, rgbCallback);
    ROS_INFO("Subscribe to the HS color image topic.");
 
    ros::spin();
    return 0;
}

代码比较简单,主要是订阅图像源,调用回调函数做阈值处理。

注意这里的topic name 和回调函数里的格式:BGR8,只能是这个。

保存,然后

cd ~/catkin_ws/src/hs_image_sub/

gedit CMakeLists.txt

全选,替换为以下内容

cmake_minimum_required(VERSION 2.8.3)
project(hs_image_sub)
 
find_package(OpenCV REQUIRED)
 
find_package(catkin REQUIRED COMPONENTS
  cv_bridge
  roscpp
  sensor_msgs
)
 
 
catkin_package(
#  INCLUDE_DIRS include
#  LIBRARIES hs_image_sub
#  CATKIN_DEPENDS cv_bridge roscpp sensor_msgs
#  DEPENDS system_lib
)
 
 
include_directories(
# include
  ${catkin_INCLUDE_DIRS}
)
 
 add_executable(${PROJECT_NAME}_node src/hs_image_sub_node.cpp)
 
 
 target_link_libraries(${PROJECT_NAME}_node
   ${catkin_LIBRARIES} ${OpenCV_LIBS}
 )

接着编译

cd ~/catkin_ws

catkin_make

看到编译成功,运行角蜂鸟ROS的官方程序,启动相机发布图像源,来供我们这里的程序调用

roslaunch horned_sungem_launch hs_camera.launch cnn_type:=googlenet camera:=hs pixels:=360
 rosrun hs_image_sub hs_image_sub_node 

有了opencv想做什么处理都可以了比如追踪