cv_bridge.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2011, Willow Garage, Inc,
5 * Copyright (c) 2015, Tal Regev.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of the Willow Garage nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *********************************************************************/
35 
36 #ifndef CV_BRIDGE_CV_BRIDGE_H
37 #define CV_BRIDGE_CV_BRIDGE_H
38 
39 #include <sensor_msgs/Image.h>
40 #include <sensor_msgs/CompressedImage.h>
42 #include <ros/static_assert.h>
43 #include <opencv2/core/core.hpp>
44 #include <opencv2/imgproc/imgproc.hpp>
45 #include <opencv2/imgproc/types_c.h>
46 #include <stdexcept>
47 
48 namespace cv_bridge {
49 
50 class Exception : public std::runtime_error
51 {
52 public:
53  Exception(const std::string& description) : std::runtime_error(description) {}
54 };
55 
56 class CvImage;
57 
60 
61 //from: http://docs.opencv.org/modules/highgui/doc/reading_and_writing_images_and_video.html#Mat imread(const string& filename, int flags)
62 typedef enum {
63  BMP, DIB,
65  JP2,
66  PNG,
67  PBM, PGM, PPM,
68  SR, RAS,
70 } Format;
71 
76 class CvImage
77 {
78 public:
79  std_msgs::Header header;
80  std::string encoding;
81  cv::Mat image;
82 
86  CvImage() {}
87 
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)
94  {
95  }
96 
102  sensor_msgs::ImagePtr toImageMsg() const;
103 
111  sensor_msgs::CompressedImagePtr toCompressedImageMsg(const Format dst_format = JPG) const;
112 
119  void toImageMsg(sensor_msgs::Image& ros_image) const;
120 
128  void toCompressedImageMsg(sensor_msgs::CompressedImage& ros_image, const Format dst_format = JPG) const;
129 
130 
133 
134 protected:
136 
138  friend
139  CvImageConstPtr toCvShare(const sensor_msgs::Image& source,
140  const boost::shared_ptr<void const>& tracked_object,
141  const std::string& encoding);
143 };
144 
145 
162 CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr& source,
163  const std::string& encoding = std::string());
164 
165 CvImagePtr toCvCopy(const sensor_msgs::CompressedImageConstPtr& source,
166  const std::string& encoding = std::string());
167 
187 CvImagePtr toCvCopy(const sensor_msgs::Image& source,
188  const std::string& encoding = std::string());
189 
190 CvImagePtr toCvCopy(const sensor_msgs::CompressedImage& source,
191  const std::string& encoding = std::string());
192 
213 CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr& source,
214  const std::string& encoding = std::string());
215 
240 CvImageConstPtr toCvShare(const sensor_msgs::Image& source,
241  const boost::shared_ptr<void const>& tracked_object,
242  const std::string& encoding = std::string());
243 
247 CvImagePtr cvtColor(const CvImageConstPtr& source,
248  const std::string& encoding);
249 
252  do_dynamic_scaling(false),
253  min_image_value(0.0),
254  max_image_value(0.0),
255  colormap(-1),
256  bg_label(-1) {}
260  int colormap;
261  int bg_label;
262 };
263 
264 
296 CvImageConstPtr cvtColorForDisplay(const CvImageConstPtr& source,
297  const std::string& encoding = std::string(),
299 
305 int getCvType(const std::string& encoding);
306 
307 } // namespace cv_bridge
308 
309 
310 // CvImage as a first class message type
311 
312 // The rest of this file hooks into the roscpp serialization API to make CvImage
313 // a first-class message type you can publish and subscribe to directly.
314 // Unfortunately this doesn't yet work with image_transport, so don't rewrite all
315 // your callbacks to use CvImage! It might be useful for specific tasks, like
316 // processing bag files.
317 
319 namespace ros {
320 
321 namespace message_traits {
322 
323 template<> struct MD5Sum<cv_bridge::CvImage>
324 {
325  static const char* value() { return MD5Sum<sensor_msgs::Image>::value(); }
326  static const char* value(const cv_bridge::CvImage&) { return value(); }
327 
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;
330 
331  // If the definition of sensor_msgs/Image changes, we'll get a compile error here.
332  ROS_STATIC_ASSERT(MD5Sum<sensor_msgs::Image>::static_value1 == 0x060021388200f6f0ULL);
333  ROS_STATIC_ASSERT(MD5Sum<sensor_msgs::Image>::static_value2 == 0xf447d0fcd9c64743ULL);
334 };
335 
336 template<> struct DataType<cv_bridge::CvImage>
337 {
338  static const char* value() { return DataType<sensor_msgs::Image>::value(); }
339  static const char* value(const cv_bridge::CvImage&) { return value(); }
340 };
341 
342 template<> struct Definition<cv_bridge::CvImage>
343 {
344  static const char* value() { return Definition<sensor_msgs::Image>::value(); }
345  static const char* value(const cv_bridge::CvImage&) { return value(); }
346 };
347 
348 template<> struct HasHeader<cv_bridge::CvImage> : TrueType {};
349 
350 } // namespace ros::message_traits
351 
352 namespace serialization {
353 
354 template<> struct Serializer<cv_bridge::CvImage>
355 {
357 
358  template<typename Stream>
359  inline static void write(Stream& stream, const cv_bridge::CvImage& m)
360  {
361  stream.next(m.header);
362  stream.next((uint32_t)m.image.rows); // height
363  stream.next((uint32_t)m.image.cols); // width
364  stream.next(m.encoding);
365  uint8_t is_bigendian = 0;
366  stream.next(is_bigendian);
367  stream.next((uint32_t)m.image.step);
368  size_t data_size = m.image.step*m.image.rows;
369  stream.next((uint32_t)data_size);
370  if (data_size > 0)
371  memcpy(stream.advance(data_size), m.image.data, data_size);
372  }
373 
374  template<typename Stream>
375  inline static void read(Stream& stream, cv_bridge::CvImage& m)
376  {
377  stream.next(m.header);
378  uint32_t height, width;
379  stream.next(height);
380  stream.next(width);
381  stream.next(m.encoding);
382  uint8_t is_bigendian;
383  stream.next(is_bigendian);
384  uint32_t step, data_size;
385  stream.next(step);
386  stream.next(data_size);
387  int type = cv_bridge::getCvType(m.encoding);
388  // Construct matrix pointing to the stream data, then copy it to m.image
389  cv::Mat tmp((int)height, (int)width, type, stream.advance(data_size), (size_t)step);
390  tmp.copyTo(m.image);
391  }
392 
393  inline static uint32_t serializedLength(const cv_bridge::CvImage& m)
394  {
395  size_t data_size = m.image.step*m.image.rows;
396  return serializationLength(m.header) + serializationLength(m.encoding) + 17 + data_size;
397  }
398 };
399 
400 } // namespace ros::serialization
401 
402 namespace message_operations {
403 
404 template<> struct Printer<cv_bridge::CvImage>
405 {
406  template<typename Stream>
407  static void stream(Stream&, const std::string&, const cv_bridge::CvImage&)
408  {
410  }
411 };
412 
413 } // namespace ros::message_operations
414 
415 } // namespace ros
416 
417 namespace cv_bridge {
418 
419 inline std::ostream& operator<<(std::ostream& s, const CvImage& m)
420 {
422  return s;
423 }
424 
425 } // namespace cv_bridge
426 
428 
429 #endif
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...
Definition: cv_bridge.cpp:406
boost::shared_ptr< CvImage > Ptr
Definition: cv_bridge.h:131
boost::shared_ptr< CvImage const > ConstPtr
Definition: cv_bridge.h:132
boost::shared_ptr< CvImage > CvImagePtr
Definition: cv_bridge.h:56
boost::shared_ptr< void const > tracked_object_
Definition: cv_bridge.h:135
std::string encoding
Image encoding ("mono8", "bgr8", etc.)
Definition: cv_bridge.h:80
Exception(const std::string &description)
Definition: cv_bridge.h:53
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.
Definition: cv_bridge.cpp:429
Image message class that is interoperable with sensor_msgs/Image but uses a more convenient cv::Mat r...
Definition: cv_bridge.h:76
CvImage(const std_msgs::Header &header, const std::string &encoding, const cv::Mat &image=cv::Mat())
Constructor.
Definition: cv_bridge.h:91
CvImage()
Empty constructor.
Definition: cv_bridge.h:86
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...
Definition: cv_bridge.cpp:392
cv::Mat image
Image data for use with OpenCV.
Definition: cv_bridge.h:81
int getCvType(const std::string &encoding)
Get the OpenCV type enum corresponding to the encoding.
Definition: cv_bridge.cpp:72
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.
Definition: cv_bridge.cpp:538
boost::shared_ptr< CvImage const > CvImageConstPtr
Definition: cv_bridge.h:59
std_msgs::Header header
ROS header.
Definition: cv_bridge.h:79


cv_bridge
Author(s): Patrick Mihelich, James Bowman
autogenerated on Thu Dec 12 2019 03:52:01