36 #ifndef CV_BRIDGE_CV_BRIDGE_H 37 #define CV_BRIDGE_CV_BRIDGE_H 39 #include <sensor_msgs/Image.h> 40 #include <sensor_msgs/CompressedImage.h> 43 #include <opencv2/core/core.hpp> 44 #include <opencv2/imgproc/imgproc.hpp> 45 #include <opencv2/imgproc/types_c.h> 53 Exception(
const std::string& description) :
std::runtime_error(description) {}
91 CvImage(
const std_msgs::Header& header,
const std::string& encoding,
92 const cv::Mat& image = cv::Mat())
93 : header(header), encoding(encoding), image(image)
102 sensor_msgs::ImagePtr toImageMsg()
const;
111 sensor_msgs::CompressedImagePtr toCompressedImageMsg(
const Format dst_format =
JPG)
const;
119 void toImageMsg(sensor_msgs::Image& ros_image)
const;
128 void toCompressedImageMsg(sensor_msgs::CompressedImage& ros_image,
const Format dst_format =
JPG)
const;
139 CvImageConstPtr
toCvShare(
const sensor_msgs::Image& source,
141 const std::string& encoding);
162 CvImagePtr
toCvCopy(
const sensor_msgs::ImageConstPtr& source,
163 const std::string& encoding = std::string());
165 CvImagePtr
toCvCopy(
const sensor_msgs::CompressedImageConstPtr& source,
166 const std::string& encoding = std::string());
187 CvImagePtr
toCvCopy(
const sensor_msgs::Image& source,
188 const std::string& encoding = std::string());
190 CvImagePtr
toCvCopy(
const sensor_msgs::CompressedImage& source,
191 const std::string& encoding = std::string());
213 CvImageConstPtr
toCvShare(
const sensor_msgs::ImageConstPtr& source,
214 const std::string& encoding = std::string());
240 CvImageConstPtr
toCvShare(
const sensor_msgs::Image& source,
242 const std::string& encoding = std::string());
247 CvImagePtr
cvtColor(
const CvImageConstPtr& source,
248 const std::string& encoding);
252 do_dynamic_scaling(false),
253 min_image_value(0.0),
254 max_image_value(0.0),
297 const std::string& encoding = std::string(),
305 int getCvType(
const std::string& encoding);
321 namespace message_traits {
325 static const char* value() {
return MD5Sum<sensor_msgs::Image>::value(); }
328 static const uint64_t static_value1 = MD5Sum<sensor_msgs::Image>::static_value1;
329 static const uint64_t static_value2 = MD5Sum<sensor_msgs::Image>::static_value2;
332 ROS_STATIC_ASSERT(MD5Sum<sensor_msgs::Image>::static_value1 == 0x060021388200f6f0ULL);
333 ROS_STATIC_ASSERT(MD5Sum<sensor_msgs::Image>::static_value2 == 0xf447d0fcd9c64743ULL);
338 static const char* value() {
return DataType<sensor_msgs::Image>::value(); }
344 static const char* value() {
return Definition<sensor_msgs::Image>::value(); }
352 namespace serialization {
358 template<
typename Stream>
362 stream.next((uint32_t)m.
image.rows);
363 stream.next((uint32_t)m.
image.cols);
365 uint8_t is_bigendian = 0;
366 stream.next(is_bigendian);
367 stream.next((uint32_t)m.
image.step);
369 stream.next((uint32_t)data_size);
371 memcpy(stream.advance(data_size), m.
image.data, data_size);
374 template<
typename Stream>
378 uint32_t height, width;
382 uint8_t is_bigendian;
383 stream.next(is_bigendian);
384 uint32_t step, data_size;
386 stream.next(data_size);
389 cv::Mat tmp((
int)height, (
int)width, type, stream.advance(data_size), (size_t)step);
402 namespace message_operations {
406 template<
typename Stream>
419 inline std::ostream& operator<<(std::ostream& s,
const CvImage& m)
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
Convert an immutable sensor_msgs::Image message to an OpenCV-compatible CvImage, sharing the image da...
boost::shared_ptr< CvImage > Ptr
boost::shared_ptr< CvImage const > ConstPtr
boost::shared_ptr< CvImage > CvImagePtr
boost::shared_ptr< void const > tracked_object_
CvtColorForDisplayOptions()
std::string encoding
Image encoding ("mono8", "bgr8", etc.)
Exception(const std::string &description)
static void stream(Stream &s, const std::string &indent, const M &value)
#define ROS_STATIC_ASSERT(cond)
CvImagePtr cvtColor(const CvImageConstPtr &source, const std::string &encoding)
Convert a CvImage to another encoding using the same rules as toCvCopy.
Image message class that is interoperable with sensor_msgs/Image but uses a more convenient cv::Mat r...
CvImage(const std_msgs::Header &header, const std::string &encoding, const cv::Mat &image=cv::Mat())
Constructor.
CvImage()
Empty constructor.
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
Convert a sensor_msgs::Image message to an OpenCV-compatible CvImage, copying the image data...
cv::Mat image
Image data for use with OpenCV.
int getCvType(const std::string &encoding)
Get the OpenCV type enum corresponding to the encoding.
uint32_t serializationLength(const T &t)
CvImageConstPtr cvtColorForDisplay(const CvImageConstPtr &source, const std::string &encoding=std::string(), const CvtColorForDisplayOptions options=CvtColorForDisplayOptions())
Converts an immutable sensor_msgs::Image message to another CvImage for display purposes, using practical conversion rules if needed.
boost::shared_ptr< CvImage const > CvImageConstPtr
std_msgs::Header header
ROS header.