00001
00002
00003
00004
00005 #ifndef RVIZ_TEXTURED_QUADS_MESSAGE_TEXTUREDQUAD_H
00006 #define RVIZ_TEXTURED_QUADS_MESSAGE_TEXTUREDQUAD_H
00007
00008
00009 #include <string>
00010 #include <vector>
00011 #include <map>
00012
00013 #include <ros/types.h>
00014 #include <ros/serialization.h>
00015 #include <ros/builtin_message_traits.h>
00016 #include <ros/message_operations.h>
00017
00018 #include <sensor_msgs/Image.h>
00019 #include <geometry_msgs/Pose.h>
00020
00021 namespace rviz_textured_quads
00022 {
00023 template <class ContainerAllocator>
00024 struct TexturedQuad_
00025 {
00026 typedef TexturedQuad_<ContainerAllocator> Type;
00027
00028 TexturedQuad_()
00029 : image()
00030 , pose()
00031 , width(0.0)
00032 , height(0.0)
00033 , caption()
00034 , border_size(0.0)
00035 , border_color() {
00036 }
00037 TexturedQuad_(const ContainerAllocator& _alloc)
00038 : image(_alloc)
00039 , pose(_alloc)
00040 , width(0.0)
00041 , height(0.0)
00042 , caption(_alloc)
00043 , border_size(0.0)
00044 , border_color(_alloc) {
00045 (void)_alloc;
00046 }
00047
00048
00049
00050 typedef ::sensor_msgs::Image_<ContainerAllocator> _image_type;
00051 _image_type image;
00052
00053 typedef ::geometry_msgs::Pose_<ContainerAllocator> _pose_type;
00054 _pose_type pose;
00055
00056 typedef float _width_type;
00057 _width_type width;
00058
00059 typedef float _height_type;
00060 _height_type height;
00061
00062 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _caption_type;
00063 _caption_type caption;
00064
00065 typedef float _border_size_type;
00066 _border_size_type border_size;
00067
00068 typedef std::vector<float, typename ContainerAllocator::template rebind<float>::other > _border_color_type;
00069 _border_color_type border_color;
00070
00071
00072
00073
00074 typedef boost::shared_ptr< ::rviz_textured_quads::TexturedQuad_<ContainerAllocator> > Ptr;
00075 typedef boost::shared_ptr< ::rviz_textured_quads::TexturedQuad_<ContainerAllocator> const> ConstPtr;
00076
00077 };
00078
00079 typedef ::rviz_textured_quads::TexturedQuad_<std::allocator<void> > TexturedQuad;
00080
00081 typedef boost::shared_ptr< ::rviz_textured_quads::TexturedQuad > TexturedQuadPtr;
00082 typedef boost::shared_ptr< ::rviz_textured_quads::TexturedQuad const> TexturedQuadConstPtr;
00083
00084
00085
00086
00087
00088 template<typename ContainerAllocator>
00089 std::ostream& operator<<(std::ostream& s, const ::rviz_textured_quads::TexturedQuad_<ContainerAllocator> & v)
00090 {
00091 ros::message_operations::Printer< ::rviz_textured_quads::TexturedQuad_<ContainerAllocator> >::stream(s, "", v);
00092 return s;
00093 }
00094
00095 }
00096
00097 namespace ros
00098 {
00099 namespace message_traits
00100 {
00101
00102
00103
00104
00105
00106
00107
00108
00109
00110
00111
00112 template <class ContainerAllocator>
00113 struct IsFixedSize< ::rviz_textured_quads::TexturedQuad_<ContainerAllocator> >
00114 : FalseType
00115 { };
00116
00117 template <class ContainerAllocator>
00118 struct IsFixedSize< ::rviz_textured_quads::TexturedQuad_<ContainerAllocator> const>
00119 : FalseType
00120 { };
00121
00122 template <class ContainerAllocator>
00123 struct IsMessage< ::rviz_textured_quads::TexturedQuad_<ContainerAllocator> >
00124 : TrueType
00125 { };
00126
00127 template <class ContainerAllocator>
00128 struct IsMessage< ::rviz_textured_quads::TexturedQuad_<ContainerAllocator> const>
00129 : TrueType
00130 { };
00131
00132 template <class ContainerAllocator>
00133 struct HasHeader< ::rviz_textured_quads::TexturedQuad_<ContainerAllocator> >
00134 : FalseType
00135 { };
00136
00137 template <class ContainerAllocator>
00138 struct HasHeader< ::rviz_textured_quads::TexturedQuad_<ContainerAllocator> const>
00139 : FalseType
00140 { };
00141
00142
00143 template<class ContainerAllocator>
00144 struct MD5Sum< ::rviz_textured_quads::TexturedQuad_<ContainerAllocator> >
00145 {
00146 static const char* value()
00147 {
00148 return "ca357eef48c96ef31533ee760ce93902";
00149 }
00150
00151 static const char* value(const ::rviz_textured_quads::TexturedQuad_<ContainerAllocator>&) { return value(); }
00152 static const uint64_t static_value1 = 0xca357eef48c96ef3ULL;
00153 static const uint64_t static_value2 = 0x1533ee760ce93902ULL;
00154 };
00155
00156 template<class ContainerAllocator>
00157 struct DataType< ::rviz_textured_quads::TexturedQuad_<ContainerAllocator> >
00158 {
00159 static const char* value()
00160 {
00161 return "rviz_textured_quads/TexturedQuad";
00162 }
00163
00164 static const char* value(const ::rviz_textured_quads::TexturedQuad_<ContainerAllocator>&) { return value(); }
00165 };
00166
00167 template<class ContainerAllocator>
00168 struct Definition< ::rviz_textured_quads::TexturedQuad_<ContainerAllocator> >
00169 {
00170 static const char* value()
00171 {
00172 return "sensor_msgs/Image image # texture \n\
00173 geometry_msgs/Pose pose # 6DOF pose of the center of the quad to be displayed\n\
00174 float32 width # physical width of the quad in Rviz unit (usually meters) \n\
00175 float32 height # physical height of the quad in Rviz unit (usually meters) \n\
00176 string caption # [OPTIONAL] text description to appear below the quad\n\
00177 float32 border_size # [OPTIONAL] size of the quad border\n\
00178 float32[] border_color # [OPTIONAL] (r,g,b,a) color value of the quad border (Size = 4) \n\
00179 ================================================================================\n\
00180 MSG: sensor_msgs/Image\n\
00181 # This message contains an uncompressed image\n\
00182 # (0, 0) is at top-left corner of image\n\
00183 #\n\
00184 \n\
00185 Header header # Header timestamp should be acquisition time of image\n\
00186 # Header frame_id should be optical frame of camera\n\
00187 # origin of frame should be optical center of cameara\n\
00188 # +x should point to the right in the image\n\
00189 # +y should point down in the image\n\
00190 # +z should point into to plane of the image\n\
00191 # If the frame_id here and the frame_id of the CameraInfo\n\
00192 # message associated with the image conflict\n\
00193 # the behavior is undefined\n\
00194 \n\
00195 uint32 height # image height, that is, number of rows\n\
00196 uint32 width # image width, that is, number of columns\n\
00197 \n\
00198 # The legal values for encoding are in file src/image_encodings.cpp\n\
00199 # If you want to standardize a new string format, join\n\
00200 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.\n\
00201 \n\
00202 string encoding # Encoding of pixels -- channel meaning, ordering, size\n\
00203 # taken from the list of strings in include/sensor_msgs/image_encodings.h\n\
00204 \n\
00205 uint8 is_bigendian # is this data bigendian?\n\
00206 uint32 step # Full row length in bytes\n\
00207 uint8[] data # actual matrix data, size is (step * rows)\n\
00208 \n\
00209 ================================================================================\n\
00210 MSG: std_msgs/Header\n\
00211 # Standard metadata for higher-level stamped data types.\n\
00212 # This is generally used to communicate timestamped data \n\
00213 # in a particular coordinate frame.\n\
00214 # \n\
00215 # sequence ID: consecutively increasing ID \n\
00216 uint32 seq\n\
00217 #Two-integer timestamp that is expressed as:\n\
00218 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
00219 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
00220 # time-handling sugar is provided by the client library\n\
00221 time stamp\n\
00222 #Frame this data is associated with\n\
00223 # 0: no frame\n\
00224 # 1: global frame\n\
00225 string frame_id\n\
00226 \n\
00227 ================================================================================\n\
00228 MSG: geometry_msgs/Pose\n\
00229 # A representation of pose in free space, composed of postion and orientation. \n\
00230 Point position\n\
00231 Quaternion orientation\n\
00232 \n\
00233 ================================================================================\n\
00234 MSG: geometry_msgs/Point\n\
00235 # This contains the position of a point in free space\n\
00236 float64 x\n\
00237 float64 y\n\
00238 float64 z\n\
00239 \n\
00240 ================================================================================\n\
00241 MSG: geometry_msgs/Quaternion\n\
00242 # This represents an orientation in free space in quaternion form.\n\
00243 \n\
00244 float64 x\n\
00245 float64 y\n\
00246 float64 z\n\
00247 float64 w\n\
00248 ";
00249 }
00250
00251 static const char* value(const ::rviz_textured_quads::TexturedQuad_<ContainerAllocator>&) { return value(); }
00252 };
00253
00254 }
00255 }
00256
00257 namespace ros
00258 {
00259 namespace serialization
00260 {
00261
00262 template<class ContainerAllocator> struct Serializer< ::rviz_textured_quads::TexturedQuad_<ContainerAllocator> >
00263 {
00264 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00265 {
00266 stream.next(m.image);
00267 stream.next(m.pose);
00268 stream.next(m.width);
00269 stream.next(m.height);
00270 stream.next(m.caption);
00271 stream.next(m.border_size);
00272 stream.next(m.border_color);
00273 }
00274
00275 ROS_DECLARE_ALLINONE_SERIALIZER
00276 };
00277
00278 }
00279 }
00280
00281 namespace ros
00282 {
00283 namespace message_operations
00284 {
00285
00286 template<class ContainerAllocator>
00287 struct Printer< ::rviz_textured_quads::TexturedQuad_<ContainerAllocator> >
00288 {
00289 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::rviz_textured_quads::TexturedQuad_<ContainerAllocator>& v)
00290 {
00291 s << indent << "image: ";
00292 s << std::endl;
00293 Printer< ::sensor_msgs::Image_<ContainerAllocator> >::stream(s, indent + " ", v.image);
00294 s << indent << "pose: ";
00295 s << std::endl;
00296 Printer< ::geometry_msgs::Pose_<ContainerAllocator> >::stream(s, indent + " ", v.pose);
00297 s << indent << "width: ";
00298 Printer<float>::stream(s, indent + " ", v.width);
00299 s << indent << "height: ";
00300 Printer<float>::stream(s, indent + " ", v.height);
00301 s << indent << "caption: ";
00302 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.caption);
00303 s << indent << "border_size: ";
00304 Printer<float>::stream(s, indent + " ", v.border_size);
00305 s << indent << "border_color[]" << std::endl;
00306 for (size_t i = 0; i < v.border_color.size(); ++i)
00307 {
00308 s << indent << " border_color[" << i << "]: ";
00309 Printer<float>::stream(s, indent + " ", v.border_color[i]);
00310 }
00311 }
00312 };
00313
00314 }
00315 }
00316
00317 #endif // RVIZ_TEXTURED_QUADS_MESSAGE_TEXTUREDQUAD_H