8#ifndef RUSH_ROS_CV_BRIDGE_HPP
9#define RUSH_ROS_CV_BRIDGE_HPP
11#include <cv_bridge/cv_bridge.h>
12#include <opencv2/core/hal/interface.h>
13#include <opencv2/core/mat.hpp>
14#include <opencv2/core/mat.inl.hpp>
15#include <ros/publisher.h>
17#include <sensor_msgs/Image.h>
18#include <sensor_msgs/image_encodings.h>
19#include <std_msgs/Header.h>
22namespace rush::roscv {
28 static inline std::string get(
const cv::Mat &mat,
const bool invert =
true) {
31 return sensor_msgs::image_encodings::MONO8;
33 return invert ? sensor_msgs::image_encodings::BGR8 : sensor_msgs::image_encodings::RGB8;
35 return invert ? sensor_msgs::image_encodings::BGRA8 : sensor_msgs::image_encodings::RGBA8;
37 return sensor_msgs::image_encodings::MONO16;
39 return invert ? sensor_msgs::image_encodings::BGR16 : sensor_msgs::image_encodings::RGB16;
41 return invert ? sensor_msgs::image_encodings::BGRA16 : sensor_msgs::image_encodings::RGBA16;
54inline void cv2ros(
const cv::Mat &cv, sensor_msgs::Image &ros,
const std_msgs::Header &header = std_msgs::Header()) {
55 cv_bridge::CvImage(header, Encoding::get(cv), cv).toImageMsg(ros);
64inline sensor_msgs::ImagePtr
cv2ros(
const cv::Mat &cv,
const std_msgs::Header &header = std_msgs::Header()) {
65 return cv_bridge::CvImage(header, Encoding::get(cv), cv).toImageMsg();
73inline void ros2cv(
const sensor_msgs::Image &ros, cv::Mat &cv) {
74 (cv_bridge::toCvCopy(ros, ros.encoding)->image).copyTo(cv);
82inline cv::Mat &
ros2cv(
const sensor_msgs::Image &ros) {
83 return cv_bridge::toCvCopy(ros, ros.encoding)->image;
92inline void ros2cv(
const sensor_msgs::ImageConstPtr &ros, cv::Mat &cv) {
102inline cv::Mat &
ros2cv(
const sensor_msgs::ImageConstPtr &ros) {
110 using ros::Publisher::Publisher;
113 Publisher &operator=(
const ros::Publisher &x) {
114 ros::Publisher::operator=(x);
124 void publish(
const cv::Mat &img,
const ros::Time &time = ros::Time::now(),
const std::string &frame_id =
"") {
125 std_msgs::Header header;
127 header.frame_id = frame_id;
128 ros::Publisher::publish(
cv2ros(img, header));
Definition ros-cv-bridge.hpp:24
This class extends ros::Publisher to directly publish OpenCV matrices.
Definition ros-cv-bridge.hpp:109
void publish(const cv::Mat &img, const ros::Time &time=ros::Time::now(), const std::string &frame_id="")
Publishes an OpenCV Mat as a ROS Image message.
Definition ros-cv-bridge.hpp:124
void ros2cv(const sensor_msgs::Image &ros, cv::Mat &cv)
Converts a ROS Image message to an OpenCV Mat.
Definition ros-cv-bridge.hpp:73
void cv2ros(const cv::Mat &cv, sensor_msgs::Image &ros, const std_msgs::Header &header=std_msgs::Header())
Converts an OpenCV Mat to a ROS Image message.
Definition ros-cv-bridge.hpp:54