This library provides an easier-to-use ROS-OpenCV bridge.  
More...
#include <cv_bridge/cv_bridge.h>
#include <opencv2/core/hal/interface.h>
#include <opencv2/core/mat.hpp>
#include <opencv2/core/mat.inl.hpp>
#include <ros/publisher.h>
#include <ros/time.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/image_encodings.h>
#include <std_msgs/Header.h>
#include <string>
Go to the source code of this file.
|  | 
| void | rush::roscv::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. 
 | 
|  | 
| sensor_msgs::ImagePtr | rush::roscv::cv2ros (const cv::Mat &cv, const std_msgs::Header &header=std_msgs::Header()) | 
|  | Converts an OpenCV Mat to a ROS Image message. 
 | 
|  | 
| void | rush::roscv::ros2cv (const sensor_msgs::Image &ros, cv::Mat &cv) | 
|  | Converts a ROS Image message to an OpenCV Mat. 
 | 
|  | 
| cv::Mat & | rush::roscv::ros2cv (const sensor_msgs::Image &ros) | 
|  | Converts a ROS Image message to an OpenCV Mat. 
 | 
|  | 
| void | rush::roscv::ros2cv (const sensor_msgs::ImageConstPtr &ros, cv::Mat &cv) | 
|  | Converts a ROS Image message to an OpenCV Mat. 
 | 
|  | 
| cv::Mat & | rush::roscv::ros2cv (const sensor_msgs::ImageConstPtr &ros) | 
|  | Converts a ROS Image message to an OpenCV Mat. 
 | 
|  | 
This library provides an easier-to-use ROS-OpenCV bridge. 
- Author
- Raul Tapia (raultapia.com) 
- Copyright
- GNU General Public License v3.0 
- See also
- https://github.com/raultapia/rush 
◆ cv2ros() [1/2]
  
  | 
        
          | sensor_msgs::ImagePtr rush::roscv::cv2ros | ( | const cv::Mat & | cv, |  
          |  |  | const std_msgs::Header & | header = std_msgs::Header() ) |  | inline | 
 
Converts an OpenCV Mat to a ROS Image message. 
- Parameters
- 
  
    | cv | The input OpenCV Mat. |  | header | The header for the ROS Image message. |  
 
- Returns
- The output ROS Image message. 
 
 
◆ cv2ros() [2/2]
  
  | 
        
          | void rush::roscv::cv2ros | ( | const cv::Mat & | cv, |  
          |  |  | sensor_msgs::Image & | ros, |  
          |  |  | const std_msgs::Header & | header = std_msgs::Header() ) |  | inline | 
 
Converts an OpenCV Mat to a ROS Image message. 
- Parameters
- 
  
    | cv | The input OpenCV Mat. |  | ros | The output ROS Image message. |  | header | The header for the ROS Image message. |  
 
 
 
◆ ros2cv() [1/4]
  
  | 
        
          | cv::Mat & rush::roscv::ros2cv | ( | const sensor_msgs::Image & | ros | ) |  |  | inline | 
 
Converts a ROS Image message to an OpenCV Mat. 
- Parameters
- 
  
    | ros | The input ROS Image message. |  
 
- Returns
- The output OpenCV Mat. 
 
 
◆ ros2cv() [2/4]
  
  | 
        
          | void rush::roscv::ros2cv | ( | const sensor_msgs::Image & | ros, |  
          |  |  | cv::Mat & | cv ) |  | inline | 
 
Converts a ROS Image message to an OpenCV Mat. 
- Parameters
- 
  
    | ros | The input ROS Image message. |  | cv | The output OpenCV Mat. |  
 
 
 
◆ ros2cv() [3/4]
  
  | 
        
          | cv::Mat & rush::roscv::ros2cv | ( | const sensor_msgs::ImageConstPtr & | ros | ) |  |  | inline | 
 
Converts a ROS Image message to an OpenCV Mat. 
- Parameters
- 
  
    | ros | The input ROS Image message. |  
 
- Returns
- The output OpenCV Mat. 
- Note
- This function is provided for convenience when working with ImageConstPtr. 
 
 
◆ ros2cv() [4/4]
  
  | 
        
          | void rush::roscv::ros2cv | ( | const sensor_msgs::ImageConstPtr & | ros, |  
          |  |  | cv::Mat & | cv ) |  | inline | 
 
Converts a ROS Image message to an OpenCV Mat. 
- Parameters
- 
  
    | ros | The input ROS Image message. |  | cv | The output OpenCV Mat. |  
 
- Note
- This function is provided for convenience when working with ImageConstPtr.