玩命加载中 . . .

ROS图像处理


OpenCV 3.3.1

编译

mkdir build && cd build
mkdir installed
cmake -DCMAKE_BUILD_TYPE=RELEASE -DCMAKE_INSTALL_PREFIX=~/Library/opencv-3.3.1/build/installed -DWITH_CUDA=OFF -DBUILD_DOCS=OFF -DBUILD_EXAMPLES=OFF -DBUILD_TESTS=OFF -DBUILD_PERF_TESTS=OFF -DOPENCV_EXTRA_MODULES_PATH=../opencv_contrib/modules ..
make -j4
sudo make install

修改系统默认版本

vim ~/.bashrc
export PKG_CONFIG_PATH=~/Library/opencv-3.3.1/build/installed/lib/pkgconfig
export LD_LIBRARY_PATH=~/Library/opencv-3.3.1/build/installed/lib
source ~/.bashrc

版本确认

pkg-config --modversion opencv
3.3.1

查看头文件位置

pkg-config --cflags opencv
-I/home/kavin/Library/opencv-3.3.1/build/installed/include/opencv
-I/home/kavin/Library/opencv-3.3.1/build/installed/include

查看库文件

pkg-config --libs opencv
-L/home/kavin/Library/opencv-3.3.1/build/installed/lib -lopencv_stitching -lopencv_superres -lopencv_videostab -lopencv_photo -lopencv_aruco 
-lopencv_bgsegm -lopencv_bioinspired -lopencv_ccalib -lopencv_dpm -lopencv_face -lopencv_freetype -lopencv_fuzzy -lopencv_hdf -lopencv_img_hash 
-lopencv_line_descriptor -lopencv_optflow -lopencv_reg -lopencv_rgbd -lopencv_saliency -lopencv_sfm -lopencv_stereo -lopencv_structured_light -lopencv_viz -lopencv_phase_unwrapping 
-lopencv_surface_matching -lopencv_tracking -lopencv_datasets -lopencv_text -lopencv_dnn -lopencv_plot -lopencv_xfeatures2d -lopencv_shape -lopencv_video -lopencv_ml -lopencv_ximgproc 
-lopencv_calib3d -lopencv_features2d -lopencv_highgui -lopencv_videoio -lopencv_flann -lopencv_xobjdetect -lopencv_imgcodecs -lopencv_objdetect 
-lopencv_xphoto -lopencv_imgproc -lopencv_core

CMakeLists指定版本

不修改默认是在/usr查找

set(OpenCV_DIR "~/Library/opencv-3.3.1/build/installed/OpenCV")
find_package(OpenCV REQUIRED)

发布图像

使用image_transport进行图像话题发布订阅

image_transport::ImageTransport it(nh);     //用句柄初始化image_transport
image_transport::Publisher image_pub = it.advertise("image_topic", 10);
//cv::Mat通过cv_bridge::CvImage转换为sensor_msgs::ImagePtr
sensor_msgs::ImagePtr msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image).toImageMsg();

源代码

# include <ros/ros.h>
# include <image_transport/image_transport.h>
# include <opencv2/highgui/highgui.hpp>
# include <opencv2/core/core.hpp>
# include <cv_bridge/cv_bridge.h>
# include <iostream>

using namespace std;
using namespace cv;

int main(int argc, char** argv)
{
    ros::init(argc, argv, "image_pub_node");
    ros::NodeHandle nh;
    image_transport::ImageTransport it(nh);
    image_transport::Publisher image_pub = it.advertise("image_topic", 10);
    Mat image = imread("/home/kavin/Pictures/test.png", IMREAD_COLOR);
    if (image.empty())
    {
        cout << "can't find picture" << endl;
        return -1;
    }
    sensor_msgs::ImagePtr msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image).toImageMsg();
    ros::Rate loop_rate(1);
    while(nh.ok())
    {
        image_pub.publish(msg);
        ROS_INFO("publish an image");
        loop_rate.sleep();
    }
    return 0;
}

接收图像

image_transport::Subscriber image_sub = it.subscribe("/simple_camera/image_raw", 1, image_topic_cb);
//sensor_msgs话题通过cv_bridge::toCvCopy转换为cv::Mat指针
cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
Mat colorImg = cv_ptr->image;

源代码

#include <ros/ros.h>
#include <sensor_msgs/image_encodings.h>
#include <image_transport/image_transport.h>
#include <opencv2/opencv.hpp>
#include <cv_bridge/cv_bridge.h>
#include <iostream>
using namespace std;
using namespace cv;
Mat colorImg;

void image_topic_cb(const sensor_msgs::ImageConstPtr& msg)
{
    try
    {
        ROS_INFO("Receive an image successfully");
        cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
        colorImg = cv_ptr->image;
        imshow("image", colorImg);
        Mat grayImg;
        cvtColor(colorImg, grayImg, COLOR_BGR2GRAY);
        imshow("gray", grayImg);

        // cv::imshow("image", cv_bridge::toCvShare(msg, "bgr8")->image);
        // cv::waitKey(10);
    } catch(cv_bridge::Exception& e) {
        std::cerr << e.what() << std::endl;
    }
}

int main(int argc, char** argv)
{
    ros::init(argc, argv, "image_sub");
    ros::NodeHandle nh;
    image_transport::ImageTransport it(nh);

    namedWindow("image", CV_WINDOW_AUTOSIZE);
    namedWindow("gray", CV_WINDOW_AUTOSIZE);
    startWindowThread();

    image_transport::Subscriber image_sub = it.subscribe("/simple_camera/image_raw", 1, image_topic_cb);
    ros::spin();
    destroyWindow("image");
    destroyWindow("gray");
    return 0;
}

Python

#! /usr/bin/env python
# coding=utf-8

import rospy
from sensor_msgs.msg import Image
import cv2
from cv_bridge import CvBridge


rospy.init_node('py_image_sub', anonymous=True)

def colorCallBack(msg):
    bridge = CvBridge()
    img = bridge.imgmsg_to_cv2(msg, "bgr8")
    cv2.imshow("color", img)
    cv2.waitKey(10)

def listener():
    rospy.Subscriber("image_topic", Image, colorCallBack)
    rospy.spin()


if __name__ == '__main__':
    print(cv2.__version__)
    listener()
    print('done')

文章作者: kunpeng
版权声明: 本博客所有文章除特別声明外,均采用 CC BY 4.0 许可协议。转载请注明来源 kunpeng !
  目录