OpenCV和ROS Image互转,不依赖cv_bridge

OpenCV和ROS Image互转,不依赖cv_bridge

C++版

#ifndef IMAGE_CONVERTOR_HPP
#define IMAGE_CONVERTOR_HPP

#include "sensor_msgs/Image.h"
#include "opencv2/opencv.hpp"
#include "ros/ros.h"
#include <memory>

int GetType(std::string type);

std::string GetType(int type);

int PixelSize(int type);


std::shared_ptr<sensor_msgs::Image> CvToRos(cv::Mat& img);

std::shared_ptr<cv::Mat> RosToCv(const sensor_msgs::Image::ConstPtr& img);
#endif
#include "image_convertor.hpp"

int GetType(std::string type)
{
    int ret = -1;
    if (!type.compare("mono8")) ret = CV_8UC1;  else
    if (!type.compare("8UC2" )) ret = CV_8UC2;  else
    if (!type.compare("bgr8" )) ret = CV_8UC3;  else
    if (!type.compare("8UC4" )) ret = CV_8UC4;  else
    if (!type.compare("8SC1" )) ret = CV_8SC1;  else
    if (!type.compare("8SC2" )) ret = CV_8SC2;  else
    if (!type.compare("8SC3" )) ret = CV_8SC3;  else
    if (!type.compare("8SC4" )) ret = CV_8SC4;  else
    if (!type.compare("16UC1")) ret = CV_16UC1; else
    if (!type.compare("16UC2")) ret = CV_16UC2; else
    if (!type.compare("16UC3")) ret = CV_16UC3; else
    if (!type.compare("16UC4")) ret = CV_16UC4; else
    if (!type.compare("16SC1")) ret = CV_16SC1; else
    if (!type.compare("16SC2")) ret = CV_16SC2; else
    if (!type.compare("16SC3")) ret = CV_16SC3; else
    if (!type.compare("16SC4")) ret = CV_16SC4; else
    if (!type.compare("32SC1")) ret = CV_32SC1; else
    if (!type.compare("32SC2")) ret = CV_32SC2; else
    if (!type.compare("32SC3")) ret = CV_32SC3; else
    if (!type.compare("32SC4")) ret = CV_32SC4; else
    if (!type.compare("32FC1")) ret = CV_32FC1; else
    if (!type.compare("32FC2")) ret = CV_32FC2; else
    if (!type.compare("32FC3")) ret = CV_32FC3; else
    if (!type.compare("32FC4")) ret = CV_32FC4; else
    if (!type.compare("64FC1")) ret = CV_64FC1; else
    if (!type.compare("64FC2")) ret = CV_64FC2; else
    if (!type.compare("64FC3")) ret = CV_64FC3; else
    if (!type.compare("64FC4")) ret = CV_64FC4; else;
    return ret;
}

std::string GetType(int type)
{
    std::string ret = "";
    if (type == CV_8UC1 ) ret = "mono8"; else
    if (type == CV_8UC2 ) ret = "8UC2" ; else
    if (type == CV_8UC3 ) ret = "bgr8" ; else
    if (type == CV_8UC4 ) ret = "8UC4" ; else
    if (type == CV_8SC1 ) ret = "8SC1" ; else
    if (type == CV_8SC2 ) ret = "8SC2" ; else
    if (type == CV_8SC3 ) ret = "8SC3" ; else
    if (type == CV_8SC4 ) ret = "8SC4" ; else
    if (type == CV_16UC1) ret = "16UC1"; else
    if (type == CV_16UC2) ret = "16UC2"; else
    if (type == CV_16UC3) ret = "16UC3"; else
    if (type == CV_16UC4) ret = "16UC4"; else
    if (type == CV_16SC1) ret = "16SC1"; else
    if (type == CV_16SC2) ret = "16SC2"; else
    if (type == CV_16SC3) ret = "16SC3"; else
    if (type == CV_16SC4) ret = "16SC4"; else
    if (type == CV_32SC1) ret = "32SC1"; else
    if (type == CV_32SC2) ret = "32SC2"; else
    if (type == CV_32SC3) ret = "32SC3"; else
    if (type == CV_32SC4) ret = "32SC4"; else
    if (type == CV_32FC1) ret = "32FC1"; else
    if (type == CV_32FC2) ret = "32FC2"; else
    if (type == CV_32FC3) ret = "32FC3"; else
    if (type == CV_32FC4) ret = "32FC4"; else
    if (type == CV_64FC1) ret = "64FC1"; else
    if (type == CV_64FC2) ret = "64FC2"; else
    if (type == CV_64FC3) ret = "64FC3"; else
    if (type == CV_64FC4) ret = "64FC4"; else;
    return std::move(ret);
}

int PixelSize(int type)
{
    int ret = 0;
    if (type == CV_8UC1 ) ret =  1; else
    if (type == CV_8UC2 ) ret =  2; else
    if (type == CV_8UC3 ) ret =  3; else
    if (type == CV_8UC4 ) ret =  4; else
    if (type == CV_8SC1 ) ret =  1; else
    if (type == CV_8SC2 ) ret =  2; else
    if (type == CV_8SC3 ) ret =  3; else
    if (type == CV_8SC4 ) ret =  4; else
    if (type == CV_16UC1) ret =  2; else
    if (type == CV_16UC2) ret =  4; else
    if (type == CV_16UC3) ret =  6; else
    if (type == CV_16UC4) ret =  8; else
    if (type == CV_16SC1) ret =  2; else
    if (type == CV_16SC2) ret =  4; else
    if (type == CV_16SC3) ret =  6; else
    if (type == CV_16SC4) ret =  8; else
    if (type == CV_32SC1) ret =  4; else
    if (type == CV_32SC2) ret =  8; else
    if (type == CV_32SC3) ret = 12; else
    if (type == CV_32SC4) ret = 16; else
    if (type == CV_32FC1) ret =  4; else
    if (type == CV_32FC2) ret =  8; else
    if (type == CV_32FC3) ret = 12; else
    if (type == CV_32FC4) ret = 16; else
    if (type == CV_64FC1) ret =  8; else
    if (type == CV_64FC2) ret = 16; else
    if (type == CV_64FC3) ret = 24; else
    if (type == CV_64FC4) ret = 32; else;
    return ret;
}

std::shared_ptr<sensor_msgs::Image> CvToRos(cv::Mat& img)
{
    auto ret = std::make_shared<sensor_msgs::Image>();
    ret->header.frame_id = "";
    ret->header.stamp    = ros::Time::now();
    ret->header.seq      = 0;
    ret->height          = img.rows;
    ret->width           = img.cols;
    ret->is_bigendian    = 0;
    ret->encoding        = GetType(img.type());
    ret->step            = img.cols * PixelSize(img.type());
    ret->data.resize(ret->step * img.rows);
    memcpy(ret->data.data(), img.ptr(), ret->data.size());
    return ret;
}

std::shared_ptr<cv::Mat> RosToCv(const sensor_msgs::Image::ConstPtr& img)
{
    auto ret = std::make_shared<cv::Mat>(
        img->height, img->width, GetType(img->encoding));
    memcpy(ret->ptr(), img->data.data(), img->data.size());
    return ret;
}

python版

#-*- coding:utf-8 -*-

import rospy
from sensor_msgs.msg import Image
import numpy as np
import sys
python3 = True if sys.hexversion > 0x03000000 else False
if python3:
    # remove ros python2 library
    ros_cv_path = '/opt/ros/kinetic/lib/python2.7/dist-packages'
    if ros_cv_path in sys.path:
        sys.path.remove(ros_cv_path)
import cv2 as cv

cv_type = dict()

cv_type['mono8'] = (np.uint8  , 1)
cv_type['8UC2']  = (np.uint8  , 2)
cv_type['bgr8']  = (np.uint8  , 3)
cv_type['8UC4']  = (np.uint8  , 4)
cv_type['8SC1']  = (np.int8   , 1)
cv_type['8SC2']  = (np.int8   , 2)
cv_type['8SC3']  = (np.int8   , 3)
cv_type['8SC4']  = (np.int8   , 4)
cv_type['16UC1'] = (np.uint16 , 1)
cv_type['16UC2'] = (np.uint16 , 2)
cv_type['16UC3'] = (np.uint16 , 3)
cv_type['16UC4'] = (np.uint16 , 4)
cv_type['16SC1'] = (np.int16  , 1)
cv_type['16SC2'] = (np.int16  , 2)
cv_type['16SC3'] = (np.int16  , 3)
cv_type['16SC4'] = (np.int16  , 4)
cv_type['32SC1'] = (np.uint32 , 1)
cv_type['32SC2'] = (np.uint32 , 2)
cv_type['32SC3'] = (np.uint32 , 3)
cv_type['32SC4'] = (np.uint32 , 4)
cv_type['32FC1'] = (np.int32  , 1)
cv_type['32FC2'] = (np.int32  , 2)
cv_type['32FC3'] = (np.int32  , 3)
cv_type['32FC4'] = (np.int32  , 4)
cv_type['64FC1'] = (np.float64, 1)
cv_type['64FC2'] = (np.float64, 2)
cv_type['64FC3'] = (np.float64, 3)
cv_type['64FC4'] = (np.float64, 4)

ros_type = dict()

ros_type[('uint8'  , 1)] = ('mono8', 1)
ros_type[('uint8'  , 2)] = ('8UC2' , 2)
ros_type[('uint8'  , 3)] = ('bgr8' , 3)
ros_type[('uint8'  , 4)] = ('8UC4' , 4)
ros_type[('int8'   , 1)] = ('8SC1' , 1)
ros_type[('int8'   , 2)] = ('8SC2' , 2)
ros_type[('int8'   , 3)] = ('8SC3' , 3)
ros_type[('int8'   , 4)] = ('8SC4' , 4)
ros_type[('uint16' , 1)] = ('16UC1', 1)
ros_type[('uint16' , 2)] = ('16UC2', 2)
ros_type[('uint16' , 3)] = ('16UC3', 3)
ros_type[('uint16' , 4)] = ('16UC4', 4)
ros_type[('int16'  , 1)] = ('16SC1', 1)
ros_type[('int16'  , 2)] = ('16SC2', 2)
ros_type[('int16'  , 3)] = ('16SC3', 3)
ros_type[('int16'  , 4)] = ('16SC4', 4)
ros_type[('uint32' , 1)] = ('32SC1', 1)
ros_type[('uint32' , 2)] = ('32SC2', 2)
ros_type[('uint32' , 3)] = ('32SC3', 3)
ros_type[('uint32' , 4)] = ('32SC4', 4)
ros_type[('int32'  , 1)] = ('32FC1', 1)
ros_type[('int32'  , 2)] = ('32FC2', 2)
ros_type[('int32'  , 3)] = ('32FC3', 3)
ros_type[('int32'  , 4)] = ('32FC4', 4)
ros_type[('float64', 1)] = ('64FC1', 1)
ros_type[('float64', 2)] = ('64FC2', 2)
ros_type[('float64', 3)] = ('64FC3', 3)
ros_type[('float64', 4)] = ('64FC4', 4)


def CvToRos(img):
    msg = Image()
    msg.header.stamp = rospy.Time.now()
    msg.width        = img.shape[1]
    msg.height       = img.shape[0]
    channel          = 1
    if len(img.shape) is 3:
    	channel = img.shape[2]
    msg.encoding = ros_type[(str(img.dtype), channel)][0]
    msg.is_bigendian = 0
    msg.step = msg.width * channel
    msg.data = img.tostring()
    return msg

def RosToCv(msg):
    img = np.fromstring(
        msg.data, dtype=cv_type[msg.encoding][0]).reshape(
            msg.height, msg.width, cv_type[msg.encoding][1])
    return img
  • 4
    点赞
  • 8
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值