00001
00002 #ifndef VISUALIZATION_MSGS_MESSAGE_IMAGEMARKER_H
00003 #define VISUALIZATION_MSGS_MESSAGE_IMAGEMARKER_H
00004 #include <string>
00005 #include <vector>
00006 #include <map>
00007 #include <ostream>
00008 #include "ros/serialization.h"
00009 #include "ros/builtin_message_traits.h"
00010 #include "ros/message_operations.h"
00011 #include "ros/time.h"
00012
00013 #include "ros/macros.h"
00014
00015 #include "ros/assert.h"
00016
00017 #include "std_msgs/Header.h"
00018 #include "geometry_msgs/Point.h"
00019 #include "std_msgs/ColorRGBA.h"
00020 #include "std_msgs/ColorRGBA.h"
00021 #include "geometry_msgs/Point.h"
00022 #include "std_msgs/ColorRGBA.h"
00023
00024 namespace visualization_msgs
00025 {
00026 template <class ContainerAllocator>
00027 struct ImageMarker_ {
00028 typedef ImageMarker_<ContainerAllocator> Type;
00029
00030 ImageMarker_()
00031 : header()
00032 , ns()
00033 , id(0)
00034 , type(0)
00035 , action(0)
00036 , position()
00037 , scale(0.0)
00038 , outline_color()
00039 , filled(0)
00040 , fill_color()
00041 , lifetime()
00042 , points()
00043 , outline_colors()
00044 {
00045 }
00046
00047 ImageMarker_(const ContainerAllocator& _alloc)
00048 : header(_alloc)
00049 , ns(_alloc)
00050 , id(0)
00051 , type(0)
00052 , action(0)
00053 , position(_alloc)
00054 , scale(0.0)
00055 , outline_color(_alloc)
00056 , filled(0)
00057 , fill_color(_alloc)
00058 , lifetime()
00059 , points(_alloc)
00060 , outline_colors(_alloc)
00061 {
00062 }
00063
00064 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00065 ::std_msgs::Header_<ContainerAllocator> header;
00066
00067 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _ns_type;
00068 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > ns;
00069
00070 typedef int32_t _id_type;
00071 int32_t id;
00072
00073 typedef int32_t _type_type;
00074 int32_t type;
00075
00076 typedef int32_t _action_type;
00077 int32_t action;
00078
00079 typedef ::geometry_msgs::Point_<ContainerAllocator> _position_type;
00080 ::geometry_msgs::Point_<ContainerAllocator> position;
00081
00082 typedef float _scale_type;
00083 float scale;
00084
00085 typedef ::std_msgs::ColorRGBA_<ContainerAllocator> _outline_color_type;
00086 ::std_msgs::ColorRGBA_<ContainerAllocator> outline_color;
00087
00088 typedef uint8_t _filled_type;
00089 uint8_t filled;
00090
00091 typedef ::std_msgs::ColorRGBA_<ContainerAllocator> _fill_color_type;
00092 ::std_msgs::ColorRGBA_<ContainerAllocator> fill_color;
00093
00094 typedef ros::Duration _lifetime_type;
00095 ros::Duration lifetime;
00096
00097 typedef std::vector< ::geometry_msgs::Point_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Point_<ContainerAllocator> >::other > _points_type;
00098 std::vector< ::geometry_msgs::Point_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Point_<ContainerAllocator> >::other > points;
00099
00100 typedef std::vector< ::std_msgs::ColorRGBA_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::std_msgs::ColorRGBA_<ContainerAllocator> >::other > _outline_colors_type;
00101 std::vector< ::std_msgs::ColorRGBA_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::std_msgs::ColorRGBA_<ContainerAllocator> >::other > outline_colors;
00102
00103 enum { CIRCLE = 0 };
00104 enum { LINE_STRIP = 1 };
00105 enum { LINE_LIST = 2 };
00106 enum { POLYGON = 3 };
00107 enum { POINTS = 4 };
00108 enum { ADD = 0 };
00109 enum { REMOVE = 1 };
00110
00111 ROS_DEPRECATED uint32_t get_points_size() const { return (uint32_t)points.size(); }
00112 ROS_DEPRECATED void set_points_size(uint32_t size) { points.resize((size_t)size); }
00113 ROS_DEPRECATED void get_points_vec(std::vector< ::geometry_msgs::Point_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Point_<ContainerAllocator> >::other > & vec) const { vec = this->points; }
00114 ROS_DEPRECATED void set_points_vec(const std::vector< ::geometry_msgs::Point_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Point_<ContainerAllocator> >::other > & vec) { this->points = vec; }
00115 ROS_DEPRECATED uint32_t get_outline_colors_size() const { return (uint32_t)outline_colors.size(); }
00116 ROS_DEPRECATED void set_outline_colors_size(uint32_t size) { outline_colors.resize((size_t)size); }
00117 ROS_DEPRECATED void get_outline_colors_vec(std::vector< ::std_msgs::ColorRGBA_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::std_msgs::ColorRGBA_<ContainerAllocator> >::other > & vec) const { vec = this->outline_colors; }
00118 ROS_DEPRECATED void set_outline_colors_vec(const std::vector< ::std_msgs::ColorRGBA_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::std_msgs::ColorRGBA_<ContainerAllocator> >::other > & vec) { this->outline_colors = vec; }
00119 private:
00120 static const char* __s_getDataType_() { return "visualization_msgs/ImageMarker"; }
00121 public:
00122 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00123
00124 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00125
00126 private:
00127 static const char* __s_getMD5Sum_() { return "1de93c67ec8858b831025a08fbf1b35c"; }
00128 public:
00129 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00130
00131 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00132
00133 private:
00134 static const char* __s_getMessageDefinition_() { return "uint8 CIRCLE=0\n\
00135 uint8 LINE_STRIP=1\n\
00136 uint8 LINE_LIST=2\n\
00137 uint8 POLYGON=3\n\
00138 uint8 POINTS=4\n\
00139 \n\
00140 uint8 ADD=0\n\
00141 uint8 REMOVE=1\n\
00142 \n\
00143 Header header\n\
00144 string ns # namespace, used with id to form a unique id\n\
00145 int32 id # unique id within the namespace\n\
00146 int32 type # CIRCLE/LINE_STRIP/etc.\n\
00147 int32 action # ADD/REMOVE\n\
00148 geometry_msgs/Point position # 2D, in pixel-coords\n\
00149 float32 scale # the diameter for a circle, etc.\n\
00150 std_msgs/ColorRGBA outline_color\n\
00151 uint8 filled # whether to fill in the shape with color\n\
00152 std_msgs/ColorRGBA fill_color # color [0.0-1.0]\n\
00153 duration lifetime # How long the object should last before being automatically deleted. 0 means forever\n\
00154 \n\
00155 \n\
00156 geometry_msgs/Point[] points # used for LINE_STRIP/LINE_LIST/POINTS/etc., 2D in pixel coords\n\
00157 std_msgs/ColorRGBA[] outline_colors # a color for each line, point, etc.\n\
00158 ================================================================================\n\
00159 MSG: std_msgs/Header\n\
00160 # Standard metadata for higher-level stamped data types.\n\
00161 # This is generally used to communicate timestamped data \n\
00162 # in a particular coordinate frame.\n\
00163 # \n\
00164 # sequence ID: consecutively increasing ID \n\
00165 uint32 seq\n\
00166 #Two-integer timestamp that is expressed as:\n\
00167 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00168 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00169 # time-handling sugar is provided by the client library\n\
00170 time stamp\n\
00171 #Frame this data is associated with\n\
00172 # 0: no frame\n\
00173 # 1: global frame\n\
00174 string frame_id\n\
00175 \n\
00176 ================================================================================\n\
00177 MSG: geometry_msgs/Point\n\
00178 # This contains the position of a point in free space\n\
00179 float64 x\n\
00180 float64 y\n\
00181 float64 z\n\
00182 \n\
00183 ================================================================================\n\
00184 MSG: std_msgs/ColorRGBA\n\
00185 float32 r\n\
00186 float32 g\n\
00187 float32 b\n\
00188 float32 a\n\
00189 \n\
00190 "; }
00191 public:
00192 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00193
00194 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00195
00196 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00197 {
00198 ros::serialization::OStream stream(write_ptr, 1000000000);
00199 ros::serialization::serialize(stream, header);
00200 ros::serialization::serialize(stream, ns);
00201 ros::serialization::serialize(stream, id);
00202 ros::serialization::serialize(stream, type);
00203 ros::serialization::serialize(stream, action);
00204 ros::serialization::serialize(stream, position);
00205 ros::serialization::serialize(stream, scale);
00206 ros::serialization::serialize(stream, outline_color);
00207 ros::serialization::serialize(stream, filled);
00208 ros::serialization::serialize(stream, fill_color);
00209 ros::serialization::serialize(stream, lifetime);
00210 ros::serialization::serialize(stream, points);
00211 ros::serialization::serialize(stream, outline_colors);
00212 return stream.getData();
00213 }
00214
00215 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00216 {
00217 ros::serialization::IStream stream(read_ptr, 1000000000);
00218 ros::serialization::deserialize(stream, header);
00219 ros::serialization::deserialize(stream, ns);
00220 ros::serialization::deserialize(stream, id);
00221 ros::serialization::deserialize(stream, type);
00222 ros::serialization::deserialize(stream, action);
00223 ros::serialization::deserialize(stream, position);
00224 ros::serialization::deserialize(stream, scale);
00225 ros::serialization::deserialize(stream, outline_color);
00226 ros::serialization::deserialize(stream, filled);
00227 ros::serialization::deserialize(stream, fill_color);
00228 ros::serialization::deserialize(stream, lifetime);
00229 ros::serialization::deserialize(stream, points);
00230 ros::serialization::deserialize(stream, outline_colors);
00231 return stream.getData();
00232 }
00233
00234 ROS_DEPRECATED virtual uint32_t serializationLength() const
00235 {
00236 uint32_t size = 0;
00237 size += ros::serialization::serializationLength(header);
00238 size += ros::serialization::serializationLength(ns);
00239 size += ros::serialization::serializationLength(id);
00240 size += ros::serialization::serializationLength(type);
00241 size += ros::serialization::serializationLength(action);
00242 size += ros::serialization::serializationLength(position);
00243 size += ros::serialization::serializationLength(scale);
00244 size += ros::serialization::serializationLength(outline_color);
00245 size += ros::serialization::serializationLength(filled);
00246 size += ros::serialization::serializationLength(fill_color);
00247 size += ros::serialization::serializationLength(lifetime);
00248 size += ros::serialization::serializationLength(points);
00249 size += ros::serialization::serializationLength(outline_colors);
00250 return size;
00251 }
00252
00253 typedef boost::shared_ptr< ::visualization_msgs::ImageMarker_<ContainerAllocator> > Ptr;
00254 typedef boost::shared_ptr< ::visualization_msgs::ImageMarker_<ContainerAllocator> const> ConstPtr;
00255 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00256 };
00257 typedef ::visualization_msgs::ImageMarker_<std::allocator<void> > ImageMarker;
00258
00259 typedef boost::shared_ptr< ::visualization_msgs::ImageMarker> ImageMarkerPtr;
00260 typedef boost::shared_ptr< ::visualization_msgs::ImageMarker const> ImageMarkerConstPtr;
00261
00262
00263 template<typename ContainerAllocator>
00264 std::ostream& operator<<(std::ostream& s, const ::visualization_msgs::ImageMarker_<ContainerAllocator> & v)
00265 {
00266 ros::message_operations::Printer< ::visualization_msgs::ImageMarker_<ContainerAllocator> >::stream(s, "", v);
00267 return s;}
00268
00269 }
00270
00271 namespace ros
00272 {
00273 namespace message_traits
00274 {
00275 template<class ContainerAllocator> struct IsMessage< ::visualization_msgs::ImageMarker_<ContainerAllocator> > : public TrueType {};
00276 template<class ContainerAllocator> struct IsMessage< ::visualization_msgs::ImageMarker_<ContainerAllocator> const> : public TrueType {};
00277 template<class ContainerAllocator>
00278 struct MD5Sum< ::visualization_msgs::ImageMarker_<ContainerAllocator> > {
00279 static const char* value()
00280 {
00281 return "1de93c67ec8858b831025a08fbf1b35c";
00282 }
00283
00284 static const char* value(const ::visualization_msgs::ImageMarker_<ContainerAllocator> &) { return value(); }
00285 static const uint64_t static_value1 = 0x1de93c67ec8858b8ULL;
00286 static const uint64_t static_value2 = 0x31025a08fbf1b35cULL;
00287 };
00288
00289 template<class ContainerAllocator>
00290 struct DataType< ::visualization_msgs::ImageMarker_<ContainerAllocator> > {
00291 static const char* value()
00292 {
00293 return "visualization_msgs/ImageMarker";
00294 }
00295
00296 static const char* value(const ::visualization_msgs::ImageMarker_<ContainerAllocator> &) { return value(); }
00297 };
00298
00299 template<class ContainerAllocator>
00300 struct Definition< ::visualization_msgs::ImageMarker_<ContainerAllocator> > {
00301 static const char* value()
00302 {
00303 return "uint8 CIRCLE=0\n\
00304 uint8 LINE_STRIP=1\n\
00305 uint8 LINE_LIST=2\n\
00306 uint8 POLYGON=3\n\
00307 uint8 POINTS=4\n\
00308 \n\
00309 uint8 ADD=0\n\
00310 uint8 REMOVE=1\n\
00311 \n\
00312 Header header\n\
00313 string ns # namespace, used with id to form a unique id\n\
00314 int32 id # unique id within the namespace\n\
00315 int32 type # CIRCLE/LINE_STRIP/etc.\n\
00316 int32 action # ADD/REMOVE\n\
00317 geometry_msgs/Point position # 2D, in pixel-coords\n\
00318 float32 scale # the diameter for a circle, etc.\n\
00319 std_msgs/ColorRGBA outline_color\n\
00320 uint8 filled # whether to fill in the shape with color\n\
00321 std_msgs/ColorRGBA fill_color # color [0.0-1.0]\n\
00322 duration lifetime # How long the object should last before being automatically deleted. 0 means forever\n\
00323 \n\
00324 \n\
00325 geometry_msgs/Point[] points # used for LINE_STRIP/LINE_LIST/POINTS/etc., 2D in pixel coords\n\
00326 std_msgs/ColorRGBA[] outline_colors # a color for each line, point, etc.\n\
00327 ================================================================================\n\
00328 MSG: std_msgs/Header\n\
00329 # Standard metadata for higher-level stamped data types.\n\
00330 # This is generally used to communicate timestamped data \n\
00331 # in a particular coordinate frame.\n\
00332 # \n\
00333 # sequence ID: consecutively increasing ID \n\
00334 uint32 seq\n\
00335 #Two-integer timestamp that is expressed as:\n\
00336 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00337 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00338 # time-handling sugar is provided by the client library\n\
00339 time stamp\n\
00340 #Frame this data is associated with\n\
00341 # 0: no frame\n\
00342 # 1: global frame\n\
00343 string frame_id\n\
00344 \n\
00345 ================================================================================\n\
00346 MSG: geometry_msgs/Point\n\
00347 # This contains the position of a point in free space\n\
00348 float64 x\n\
00349 float64 y\n\
00350 float64 z\n\
00351 \n\
00352 ================================================================================\n\
00353 MSG: std_msgs/ColorRGBA\n\
00354 float32 r\n\
00355 float32 g\n\
00356 float32 b\n\
00357 float32 a\n\
00358 \n\
00359 ";
00360 }
00361
00362 static const char* value(const ::visualization_msgs::ImageMarker_<ContainerAllocator> &) { return value(); }
00363 };
00364
00365 template<class ContainerAllocator> struct HasHeader< ::visualization_msgs::ImageMarker_<ContainerAllocator> > : public TrueType {};
00366 template<class ContainerAllocator> struct HasHeader< const ::visualization_msgs::ImageMarker_<ContainerAllocator> > : public TrueType {};
00367 }
00368 }
00369
00370 namespace ros
00371 {
00372 namespace serialization
00373 {
00374
00375 template<class ContainerAllocator> struct Serializer< ::visualization_msgs::ImageMarker_<ContainerAllocator> >
00376 {
00377 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00378 {
00379 stream.next(m.header);
00380 stream.next(m.ns);
00381 stream.next(m.id);
00382 stream.next(m.type);
00383 stream.next(m.action);
00384 stream.next(m.position);
00385 stream.next(m.scale);
00386 stream.next(m.outline_color);
00387 stream.next(m.filled);
00388 stream.next(m.fill_color);
00389 stream.next(m.lifetime);
00390 stream.next(m.points);
00391 stream.next(m.outline_colors);
00392 }
00393
00394 ROS_DECLARE_ALLINONE_SERIALIZER;
00395 };
00396 }
00397 }
00398
00399 namespace ros
00400 {
00401 namespace message_operations
00402 {
00403
00404 template<class ContainerAllocator>
00405 struct Printer< ::visualization_msgs::ImageMarker_<ContainerAllocator> >
00406 {
00407 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::visualization_msgs::ImageMarker_<ContainerAllocator> & v)
00408 {
00409 s << indent << "header: ";
00410 s << std::endl;
00411 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00412 s << indent << "ns: ";
00413 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.ns);
00414 s << indent << "id: ";
00415 Printer<int32_t>::stream(s, indent + " ", v.id);
00416 s << indent << "type: ";
00417 Printer<int32_t>::stream(s, indent + " ", v.type);
00418 s << indent << "action: ";
00419 Printer<int32_t>::stream(s, indent + " ", v.action);
00420 s << indent << "position: ";
00421 s << std::endl;
00422 Printer< ::geometry_msgs::Point_<ContainerAllocator> >::stream(s, indent + " ", v.position);
00423 s << indent << "scale: ";
00424 Printer<float>::stream(s, indent + " ", v.scale);
00425 s << indent << "outline_color: ";
00426 s << std::endl;
00427 Printer< ::std_msgs::ColorRGBA_<ContainerAllocator> >::stream(s, indent + " ", v.outline_color);
00428 s << indent << "filled: ";
00429 Printer<uint8_t>::stream(s, indent + " ", v.filled);
00430 s << indent << "fill_color: ";
00431 s << std::endl;
00432 Printer< ::std_msgs::ColorRGBA_<ContainerAllocator> >::stream(s, indent + " ", v.fill_color);
00433 s << indent << "lifetime: ";
00434 Printer<ros::Duration>::stream(s, indent + " ", v.lifetime);
00435 s << indent << "points[]" << std::endl;
00436 for (size_t i = 0; i < v.points.size(); ++i)
00437 {
00438 s << indent << " points[" << i << "]: ";
00439 s << std::endl;
00440 s << indent;
00441 Printer< ::geometry_msgs::Point_<ContainerAllocator> >::stream(s, indent + " ", v.points[i]);
00442 }
00443 s << indent << "outline_colors[]" << std::endl;
00444 for (size_t i = 0; i < v.outline_colors.size(); ++i)
00445 {
00446 s << indent << " outline_colors[" << i << "]: ";
00447 s << std::endl;
00448 s << indent;
00449 Printer< ::std_msgs::ColorRGBA_<ContainerAllocator> >::stream(s, indent + " ", v.outline_colors[i]);
00450 }
00451 }
00452 };
00453
00454
00455 }
00456 }
00457
00458 #endif // VISUALIZATION_MSGS_MESSAGE_IMAGEMARKER_H
00459