cv_bridge.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2011, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #ifndef CV_BRIDGE_CV_BRIDGE_H
00036 #define CV_BRIDGE_CV_BRIDGE_H
00037 
00038 #include <sensor_msgs/Image.h>
00039 #include <ros/static_assert.h>
00040 #include <opencv2/core/core.hpp>
00041 #include <stdexcept>
00042 
00043 namespace cv_bridge {
00044 
00045 class Exception : public std::runtime_error
00046 {
00047 public:
00048   Exception(const std::string& description) : std::runtime_error(description) {}
00049 };
00050 
00051 class CvImage;
00052 
00053 typedef boost::shared_ptr<CvImage> CvImagePtr;
00054 typedef boost::shared_ptr<CvImage const> CvImageConstPtr;
00055 
00060 class CvImage
00061 {
00062 public:
00063   std_msgs::Header header; 
00064   std::string encoding;    
00065   cv::Mat image;           
00066 
00070   CvImage() {}
00071 
00075   CvImage(const std_msgs::Header& header, const std::string& encoding,
00076           const cv::Mat& image = cv::Mat())
00077     : header(header), encoding(encoding), image(image)
00078   {
00079   }
00080   
00086   sensor_msgs::ImagePtr toImageMsg() const;
00087 
00094   void toImageMsg(sensor_msgs::Image& ros_image) const;
00095 
00096   typedef boost::shared_ptr<CvImage> Ptr;
00097   typedef boost::shared_ptr<CvImage const> ConstPtr;
00098 
00099 protected:
00100   boost::shared_ptr<void const> tracked_object_; // for sharing ownership
00101 
00103   friend
00104   CvImageConstPtr toCvShare(const sensor_msgs::Image& source,
00105                             const boost::shared_ptr<void const>& tracked_object,
00106                             const std::string& encoding);
00108 };
00109 
00126 CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr& source,
00127                     const std::string& encoding = std::string());
00128 
00148 CvImagePtr toCvCopy(const sensor_msgs::Image& source,
00149                     const std::string& encoding = std::string());
00150 
00171 CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr& source,
00172                           const std::string& encoding = std::string());
00173 
00198 CvImageConstPtr toCvShare(const sensor_msgs::Image& source,
00199                           const boost::shared_ptr<void const>& tracked_object,
00200                           const std::string& encoding = std::string());
00201 
00205 CvImagePtr cvtColor(const CvImageConstPtr& source,
00206                     const std::string& encoding);
00207 
00213 int getCvType(const std::string& encoding);
00214 
00215 } // namespace cv_bridge
00216 
00217 
00218 
00219 // CvImage as a first class message type
00220 
00221 // The rest of this file hooks into the roscpp serialization API to make CvImage
00222 // a first-class message type you can publish and subscribe to directly.
00223 // Unfortunately this doesn't yet work with image_transport, so don't rewrite all
00224 // your callbacks to use CvImage! It might be useful for specific tasks, like
00225 // processing bag files.
00226 
00228 namespace ros {
00229 
00230 namespace message_traits {
00231 
00232 template<> struct MD5Sum<cv_bridge::CvImage>
00233 {
00234   static const char* value() { return MD5Sum<sensor_msgs::Image>::value(); }
00235   static const char* value(const cv_bridge::CvImage&) { return value(); }
00236 
00237   static const uint64_t static_value1 = MD5Sum<sensor_msgs::Image>::static_value1;
00238   static const uint64_t static_value2 = MD5Sum<sensor_msgs::Image>::static_value2;
00239   
00240   // If the definition of sensor_msgs/Image changes, we'll get a compile error here.
00241   ROS_STATIC_ASSERT(MD5Sum<sensor_msgs::Image>::static_value1 == 0x060021388200f6f0ULL);
00242   ROS_STATIC_ASSERT(MD5Sum<sensor_msgs::Image>::static_value2 == 0xf447d0fcd9c64743ULL);
00243 };
00244 
00245 template<> struct DataType<cv_bridge::CvImage>
00246 {
00247   static const char* value() { return DataType<sensor_msgs::Image>::value(); }
00248   static const char* value(const cv_bridge::CvImage&) { return value(); }
00249 };
00250 
00251 template<> struct Definition<cv_bridge::CvImage>
00252 {
00253   static const char* value() { return Definition<sensor_msgs::Image>::value(); }
00254   static const char* value(const cv_bridge::CvImage&) { return value(); }
00255 };
00256 
00257 template<> struct HasHeader<cv_bridge::CvImage> : TrueType {};
00258 
00259 } // namespace ros::message_traits
00260 
00261 namespace serialization {
00262 
00263 template<> struct Serializer<cv_bridge::CvImage>
00264 {
00266   
00267   template<typename Stream>
00268   inline static void write(Stream& stream, const cv_bridge::CvImage& m)
00269   {
00270     stream.next(m.header);
00271     stream.next((uint32_t)m.image.rows); // height
00272     stream.next((uint32_t)m.image.cols); // width
00273     stream.next(m.encoding);
00274     uint8_t is_bigendian = 0;
00275     stream.next(is_bigendian);
00276     stream.next((uint32_t)m.image.step);
00277     size_t data_size = m.image.step*m.image.rows;
00278     stream.next((uint32_t)data_size);
00279     if (data_size > 0)
00280       memcpy(stream.advance(data_size), m.image.data, data_size);
00281   }
00282 
00283   template<typename Stream>
00284   inline static void read(Stream& stream, cv_bridge::CvImage& m)
00285   {
00286     stream.next(m.header);
00287     uint32_t height, width;
00288     stream.next(height);
00289     stream.next(width);
00290     stream.next(m.encoding);
00291     uint8_t is_bigendian;
00292     stream.next(is_bigendian);
00293     uint32_t step, data_size;
00294     stream.next(step);
00295     stream.next(data_size);
00296     int type = cv_bridge::getCvType(m.encoding);
00297     // Construct matrix pointing to the stream data, then copy it to m.image
00298     cv::Mat tmp((int)height, (int)width, type, stream.advance(data_size), (size_t)step);
00299     tmp.copyTo(m.image);
00300   }
00301 
00302   inline static uint32_t serializedLength(const cv_bridge::CvImage& m)
00303   {
00304     size_t data_size = m.image.step*m.image.rows;
00305     return serializationLength(m.header) + serializationLength(m.encoding) + 17 + data_size;
00306   }
00307 };
00308 
00309 } // namespace ros::serialization
00310 
00311 namespace message_operations {
00312 
00313 template<> struct Printer<cv_bridge::CvImage>
00314 {
00315   template<typename Stream>
00316   static void stream(Stream& s, const std::string& indent, const cv_bridge::CvImage& m)
00317   {
00319   }
00320 };
00321 
00322 } // namespace ros::message_operations
00323 
00324 } // namespace ros
00325 
00326 namespace cv_bridge {
00327 
00328 inline std::ostream& operator<<(std::ostream& s, const CvImage& m)
00329 {
00330   ros::message_operations::Printer<CvImage>::stream(s, "", m);
00331   return s;
00332 }
00333 
00334 } // namespace cv_bridge
00335 
00337 
00338 #endif


cv_bridge
Author(s): Patrick Mihelich, James Bowman
autogenerated on Wed Sep 2 2015 12:05:06