raw_publisher.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2009, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
36 #include <ros/static_assert.h>
37 #include <sensor_msgs/Image.h>
38 
46 {
47 public:
48  sensor_msgs::Image image_;
49  const uint8_t* data_;
50 
55 
59  ImageTransportImage(const sensor_msgs::Image& image, const uint8_t* data)
60  : image_(image), data_(data)
61  {
62  }
63 };
64 
66 namespace ros {
67 
68 namespace message_traits {
69 
70 template<> struct MD5Sum<ImageTransportImage>
71 {
72  static const char* value() { return MD5Sum<sensor_msgs::Image>::value(); }
73  static const char* value(const ImageTransportImage&) { return value(); }
74 
75  static const uint64_t static_value1 = MD5Sum<sensor_msgs::Image>::static_value1;
76  static const uint64_t static_value2 = MD5Sum<sensor_msgs::Image>::static_value2;
77 
78  // If the definition of sensor_msgs/Image changes, we'll get a compile error here.
79  ROS_STATIC_ASSERT(MD5Sum<sensor_msgs::Image>::static_value1 == 0x060021388200f6f0ULL);
80  ROS_STATIC_ASSERT(MD5Sum<sensor_msgs::Image>::static_value2 == 0xf447d0fcd9c64743ULL);
81 };
82 
83 template<> struct DataType<ImageTransportImage>
84 {
85  static const char* value() { return DataType<sensor_msgs::Image>::value(); }
86  static const char* value(const ImageTransportImage&) { return value(); }
87 };
88 
89 template<> struct Definition<ImageTransportImage>
90 {
91  static const char* value() { return Definition<sensor_msgs::Image>::value(); }
92  static const char* value(const ImageTransportImage&) { return value(); }
93 };
94 
95 template<> struct HasHeader<ImageTransportImage> : TrueType {};
96 
97 } // namespace ros::message_traits
98 
99 namespace serialization {
100 
101 template<> struct Serializer<ImageTransportImage>
102 {
104 
105  template<typename Stream>
106  inline static void write(Stream& stream, const ImageTransportImage& m)
107  {
108  stream.next(m.image_.header);
109  stream.next((uint32_t)m.image_.height); // height
110  stream.next((uint32_t)m.image_.width); // width
111  stream.next(m.image_.encoding);
112  uint8_t is_bigendian = 0;
113  stream.next(is_bigendian);
114  stream.next((uint32_t)m.image_.step);
115  size_t data_size = m.image_.step*m.image_.height;
116  stream.next((uint32_t)data_size);
117  if (data_size > 0)
118  memcpy(stream.advance(data_size), m.data_, data_size);
119  }
120 
121  inline static uint32_t serializedLength(const ImageTransportImage& m)
122  {
123  size_t data_size = m.image_.step*m.image_.height;
124  return serializationLength(m.image_.header) + serializationLength(m.image_.encoding) + 17 + data_size;
125  }
126 };
127 
128 } // namespace ros::serialization
129 
130 } // namespace ros
131 
132 
133 namespace image_transport {
134 
135 void RawPublisher::publish(const sensor_msgs::Image& message, const uint8_t* data) const
136 {
137  getPublisher().publish(ImageTransportImage(message, data));
138 }
139 
140 } //namespace image_transport
ros::serialization::Serializer::serializedLength
static uint32_t serializedLength(typename boost::call_traits< T >::param_type t)
ros::serialization::Serializer::write
static void write(Stream &stream, typename boost::call_traits< T >::param_type t)
ros
ros::serialization::serializationLength
uint32_t serializationLength(const boost::array< T, N > &t)
image_transport::SimplePublisherPlugin< sensor_msgs::Image >::getPublisher
const ros::Publisher & getPublisher() const
Returns the internal ros::Publisher.
Definition: simple_publisher_plugin.h:223
ImageTransportImage::data_
const uint8_t * data_
Image data for use with OpenCV.
Definition: raw_publisher.cpp:81
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ImageTransportImage::image_
sensor_msgs::Image image_
ROS header.
Definition: raw_publisher.cpp:80
ImageTransportImage
Definition: raw_publisher.cpp:45
ros::message_traits::DataType::value
static const char * value()
raw_publisher.h
ros::message_traits::MD5Sum::value
static const char * value()
ImageTransportImage::ImageTransportImage
ImageTransportImage()
Empty constructor.
Definition: raw_publisher.cpp:86
image_transport
Definition: camera_common.h:41
ros::message_traits::Definition::value
static const char * value()
ROS_STATIC_ASSERT
#define ROS_STATIC_ASSERT(cond)
static_assert.h
image_transport::RawPublisher::publish
virtual void publish(const sensor_msgs::ImageConstPtr &message) const
Publish an image using the transport associated with this PublisherPlugin.
Definition: raw_publisher.h:124


image_transport
Author(s): Patrick Mihelich
autogenerated on Sat Jan 20 2024 03:14:50