ImageMarker.h
Go to the documentation of this file.
1 #include "sick_scan/sick_scan_base.h" /* Base definitions included in all header files, added by add_sick_scan_base_header.py. Do not edit this line. */
2 // Generated by gencpp from file visualization_msgs/ImageMarker.msg
3 // DO NOT EDIT!
4 
5 
6 #ifndef VISUALIZATION_MSGS_MESSAGE_IMAGEMARKER_H
7 #define VISUALIZATION_MSGS_MESSAGE_IMAGEMARKER_H
8 
9 
10 #include <string>
11 #include <vector>
12 #include <map>
13 
14 #include <ros/types.h>
15 #include <ros/serialization.h>
16 #include <ros/builtin_message_traits.h>
17 #include <ros/message_operations.h>
18 
19 #include <std_msgs/Header.h>
20 #include <geometry_msgs/Point.h>
21 #include <std_msgs/ColorRGBA.h>
22 #include <std_msgs/ColorRGBA.h>
23 #include <geometry_msgs/Point.h>
24 #include <std_msgs/ColorRGBA.h>
25 
27 {
28 template <class ContainerAllocator>
30 {
32 
34  : header()
35  , ns()
36  , id(0)
37  , type(0)
38  , action(0)
39  , position()
40  , scale(0.0)
41  , outline_color()
42  , filled(0)
43  , fill_color()
44  , lifetime()
45  , points()
46  , outline_colors() {
47  }
48  ImageMarker_(const ContainerAllocator& _alloc)
49  : header(_alloc)
50  , ns(_alloc)
51  , id(0)
52  , type(0)
53  , action(0)
54  , position(_alloc)
55  , scale(0.0)
56  , outline_color(_alloc)
57  , filled(0)
58  , fill_color(_alloc)
59  , lifetime()
60  , points(_alloc)
61  , outline_colors(_alloc) {
62  (void)_alloc;
63  }
64 
65 
66 
67  typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
69 
70  typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _ns_type;
72 
73  typedef int32_t _id_type;
75 
76  typedef int32_t _type_type;
78 
79  typedef int32_t _action_type;
81 
82  typedef ::geometry_msgs::Point_<ContainerAllocator> _position_type;
84 
85  typedef float _scale_type;
87 
88  typedef ::std_msgs::ColorRGBA_<ContainerAllocator> _outline_color_type;
90 
91  typedef uint8_t _filled_type;
93 
94  typedef ::std_msgs::ColorRGBA_<ContainerAllocator> _fill_color_type;
96 
99 
100  typedef std::vector< ::geometry_msgs::Point_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Point_<ContainerAllocator> >::other > _points_type;
102 
103  typedef std::vector< ::std_msgs::ColorRGBA_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::std_msgs::ColorRGBA_<ContainerAllocator> >::other > _outline_colors_type;
105 
106 
107 
108 // reducing the odds to have name collisions with Windows.h
109 #if defined(_WIN32) && defined(CIRCLE)
110  #undef CIRCLE
111 #endif
112 #if defined(_WIN32) && defined(LINE_STRIP)
113  #undef LINE_STRIP
114 #endif
115 #if defined(_WIN32) && defined(LINE_LIST)
116  #undef LINE_LIST
117 #endif
118 #if defined(_WIN32) && defined(POLYGON)
119  #undef POLYGON
120 #endif
121 #if defined(_WIN32) && defined(POINTS)
122  #undef POINTS
123 #endif
124 #if defined(_WIN32) && defined(ADD)
125  #undef ADD
126 #endif
127 #if defined(_WIN32) && defined(REMOVE)
128  #undef REMOVE
129 #endif
130 
131  enum {
132  CIRCLE = 0u,
134  LINE_LIST = 2u,
135  POLYGON = 3u,
136  POINTS = 4u,
137  ADD = 0u,
138  REMOVE = 1u,
139  };
140 
141 
142  typedef std::shared_ptr< ::visualization_msgs::ImageMarker_<ContainerAllocator> > Ptr;
143  typedef std::shared_ptr< ::visualization_msgs::ImageMarker_<ContainerAllocator> const> ConstPtr;
144 
145 }; // struct ImageMarker_
146 
147 typedef ::visualization_msgs::ImageMarker_<std::allocator<void> > ImageMarker;
148 
149 typedef std::shared_ptr< ::visualization_msgs::ImageMarker > ImageMarkerPtr;
150 typedef std::shared_ptr< ::visualization_msgs::ImageMarker const> ImageMarkerConstPtr;
151 
152 // constants requiring out of line definition
153 
154 
155 
156 
157 
158 
159 
160 
161 
162 
163 
164 
165 
166 
167 
168 
169 
170 template<typename ContainerAllocator>
171 std::ostream& operator<<(std::ostream& s, const ::visualization_msgs::ImageMarker_<ContainerAllocator> & v)
172 {
174 return s;
175 }
176 
177 
178 template<typename ContainerAllocator1, typename ContainerAllocator2>
179 bool operator==(const ::visualization_msgs::ImageMarker_<ContainerAllocator1> & lhs, const ::visualization_msgs::ImageMarker_<ContainerAllocator2> & rhs)
180 {
181  return lhs.header == rhs.header &&
182  lhs.ns == rhs.ns &&
183  lhs.id == rhs.id &&
184  lhs.type == rhs.type &&
185  lhs.action == rhs.action &&
186  lhs.position == rhs.position &&
187  lhs.scale == rhs.scale &&
188  lhs.outline_color == rhs.outline_color &&
189  lhs.filled == rhs.filled &&
190  lhs.fill_color == rhs.fill_color &&
191  lhs.lifetime == rhs.lifetime &&
192  lhs.points == rhs.points &&
193  lhs.outline_colors == rhs.outline_colors;
194 }
195 
196 template<typename ContainerAllocator1, typename ContainerAllocator2>
197 bool operator!=(const ::visualization_msgs::ImageMarker_<ContainerAllocator1> & lhs, const ::visualization_msgs::ImageMarker_<ContainerAllocator2> & rhs)
198 {
199  return !(lhs == rhs);
200 }
201 
202 
203 } // namespace visualization_msgs
204 
205 namespace roswrap
206 {
207 namespace message_traits
208 {
209 
210 
211 
212 
213 
214 template <class ContainerAllocator>
215 struct IsFixedSize< ::visualization_msgs::ImageMarker_<ContainerAllocator> >
216  : FalseType
217  { };
218 
219 template <class ContainerAllocator>
220 struct IsFixedSize< ::visualization_msgs::ImageMarker_<ContainerAllocator> const>
221  : FalseType
222  { };
223 
224 template <class ContainerAllocator>
225 struct IsMessage< ::visualization_msgs::ImageMarker_<ContainerAllocator> >
226  : TrueType
227  { };
228 
229 template <class ContainerAllocator>
230 struct IsMessage< ::visualization_msgs::ImageMarker_<ContainerAllocator> const>
231  : TrueType
232  { };
233 
234 template <class ContainerAllocator>
235 struct HasHeader< ::visualization_msgs::ImageMarker_<ContainerAllocator> >
236  : TrueType
237  { };
238 
239 template <class ContainerAllocator>
240 struct HasHeader< ::visualization_msgs::ImageMarker_<ContainerAllocator> const>
241  : TrueType
242  { };
243 
244 
245 template<class ContainerAllocator>
246 struct MD5Sum< ::visualization_msgs::ImageMarker_<ContainerAllocator> >
247 {
248  static const char* value()
249  {
250  return "1de93c67ec8858b831025a08fbf1b35c";
251  }
252 
253  static const char* value(const ::visualization_msgs::ImageMarker_<ContainerAllocator>&) { return value(); }
254  static const uint64_t static_value1 = 0x1de93c67ec8858b8ULL;
255  static const uint64_t static_value2 = 0x31025a08fbf1b35cULL;
256 };
257 
258 template<class ContainerAllocator>
259 struct DataType< ::visualization_msgs::ImageMarker_<ContainerAllocator> >
260 {
261  static const char* value()
262  {
263  return "visualization_msgs/ImageMarker";
264  }
265 
266  static const char* value(const ::visualization_msgs::ImageMarker_<ContainerAllocator>&) { return value(); }
267 };
268 
269 template<class ContainerAllocator>
270 struct Definition< ::visualization_msgs::ImageMarker_<ContainerAllocator> >
271 {
272  static const char* value()
273  {
274  return "uint8 CIRCLE=0\n"
275 "uint8 LINE_STRIP=1\n"
276 "uint8 LINE_LIST=2\n"
277 "uint8 POLYGON=3\n"
278 "uint8 POINTS=4\n"
279 "\n"
280 "uint8 ADD=0\n"
281 "uint8 REMOVE=1\n"
282 "\n"
283 "Header header\n"
284 "string ns # namespace, used with id to form a unique id\n"
285 "int32 id # unique id within the namespace\n"
286 "int32 type # CIRCLE/LINE_STRIP/etc.\n"
287 "int32 action # ADD/REMOVE\n"
288 "geometry_msgs/Point position # 2D, in pixel-coords\n"
289 "float32 scale # the diameter for a circle, etc.\n"
290 "std_msgs/ColorRGBA outline_color\n"
291 "uint8 filled # whether to fill in the shape with color\n"
292 "std_msgs/ColorRGBA fill_color # color [0.0-1.0]\n"
293 "duration lifetime # How long the object should last before being automatically deleted. 0 means forever\n"
294 "\n"
295 "\n"
296 "geometry_msgs/Point[] points # used for LINE_STRIP/LINE_LIST/POINTS/etc., 2D in pixel coords\n"
297 "std_msgs/ColorRGBA[] outline_colors # a color for each line, point, etc.\n"
298 "================================================================================\n"
299 "MSG: std_msgs/Header\n"
300 "# Standard metadata for higher-level stamped data types.\n"
301 "# This is generally used to communicate timestamped data \n"
302 "# in a particular coordinate frame.\n"
303 "# \n"
304 "# sequence ID: consecutively increasing ID \n"
305 "uint32 seq\n"
306 "#Two-integer timestamp that is expressed as:\n"
307 "# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n"
308 "# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n"
309 "# time-handling sugar is provided by the client library\n"
310 "time stamp\n"
311 "#Frame this data is associated with\n"
312 "string frame_id\n"
313 "\n"
314 "================================================================================\n"
315 "MSG: geometry_msgs/Point\n"
316 "# This contains the position of a point in free space\n"
317 "float64 x\n"
318 "float64 y\n"
319 "float64 z\n"
320 "\n"
321 "================================================================================\n"
322 "MSG: std_msgs/ColorRGBA\n"
323 "float32 r\n"
324 "float32 g\n"
325 "float32 b\n"
326 "float32 a\n"
327 ;
328  }
329 
330  static const char* value(const ::visualization_msgs::ImageMarker_<ContainerAllocator>&) { return value(); }
331 };
332 
333 } // namespace message_traits
334 } // namespace roswrap
335 
336 namespace roswrap
337 {
338 namespace serialization
339 {
340 
341  template<class ContainerAllocator> struct Serializer< ::visualization_msgs::ImageMarker_<ContainerAllocator> >
342  {
343  template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
344  {
345  stream.next(m.header);
346  stream.next(m.ns);
347  stream.next(m.id);
348  stream.next(m.type);
349  stream.next(m.action);
350  stream.next(m.position);
351  stream.next(m.scale);
352  stream.next(m.outline_color);
353  stream.next(m.filled);
354  stream.next(m.fill_color);
355  stream.next(m.lifetime);
356  stream.next(m.points);
357  stream.next(m.outline_colors);
358  }
359 
361  }; // struct ImageMarker_
362 
363 } // namespace serialization
364 } // namespace roswrap
365 
366 namespace roswrap
367 {
368 namespace message_operations
369 {
370 
371 template<class ContainerAllocator>
372 struct Printer< ::visualization_msgs::ImageMarker_<ContainerAllocator> >
373 {
374  template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::visualization_msgs::ImageMarker_<ContainerAllocator>& v)
375  {
376  s << indent << "header: ";
377  s << std::endl;
379  s << indent << "ns: ";
380  Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.ns);
381  s << indent << "id: ";
382  Printer<int32_t>::stream(s, indent + " ", v.id);
383  s << indent << "type: ";
384  Printer<int32_t>::stream(s, indent + " ", v.type);
385  s << indent << "action: ";
386  Printer<int32_t>::stream(s, indent + " ", v.action);
387  s << indent << "position: ";
388  s << std::endl;
390  s << indent << "scale: ";
391  Printer<float>::stream(s, indent + " ", v.scale);
392  s << indent << "outline_color: ";
393  s << std::endl;
395  s << indent << "filled: ";
396  Printer<uint8_t>::stream(s, indent + " ", v.filled);
397  s << indent << "fill_color: ";
398  s << std::endl;
400  s << indent << "lifetime: ";
401  Printer<ros::Duration>::stream(s, indent + " ", v.lifetime);
402  s << indent << "points[]" << std::endl;
403  for (size_t i = 0; i < v.points.size(); ++i)
404  {
405  s << indent << " points[" << i << "]: ";
406  s << std::endl;
407  s << indent;
409  }
410  s << indent << "outline_colors[]" << std::endl;
411  for (size_t i = 0; i < v.outline_colors.size(); ++i)
412  {
413  s << indent << " outline_colors[" << i << "]: ";
414  s << std::endl;
415  s << indent;
417  }
418  }
419 };
420 
421 } // namespace message_operations
422 } // namespace roswrap
423 
424 #endif // VISUALIZATION_MSGS_MESSAGE_IMAGEMARKER_H
roswrap::message_traits::Definition< ::visualization_msgs::ImageMarker_< ContainerAllocator > >::value
static const char * value(const ::visualization_msgs::ImageMarker_< ContainerAllocator > &)
Definition: ImageMarker.h:330
visualization_msgs::ImageMarker_::action
_action_type action
Definition: ImageMarker.h:80
roswrap::message_traits::FalseType
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
Definition: message_traits.h:89
visualization_msgs::operator!=
bool operator!=(const ::visualization_msgs::ImageMarker_< ContainerAllocator1 > &lhs, const ::visualization_msgs::ImageMarker_< ContainerAllocator2 > &rhs)
Definition: ImageMarker.h:197
visualization_msgs::ImageMarker_::outline_colors
_outline_colors_type outline_colors
Definition: ImageMarker.h:104
visualization_msgs::ImageMarker_::ImageMarker_
ImageMarker_()
Definition: ImageMarker.h:33
Point.h
multiscan_pcap_player.indent
indent
Definition: multiscan_pcap_player.py:252
std_msgs::ColorRGBA_
Definition: ColorRGBA.h:23
roswrap::serialization::Serializer
Templated serialization class. Default implementation provides backwards compatibility with old messa...
Definition: serialization.h:120
visualization_msgs::ImageMarker_
Definition: ImageMarker.h:29
roswrap::message_traits::Definition< ::visualization_msgs::ImageMarker_< ContainerAllocator > >::value
static const char * value()
Definition: ImageMarker.h:272
roswrap::message_traits::HasHeader
HasHeader informs whether or not there is a header that gets serialized as the first thing in the mes...
Definition: message_traits.h:107
roswrap::serialization::Serializer< ::visualization_msgs::ImageMarker_< ContainerAllocator > >::allInOne
static void allInOne(Stream &stream, T m)
Definition: ImageMarker.h:343
visualization_msgs::ImageMarker_::CIRCLE
@ CIRCLE
Definition: ImageMarker.h:132
const
#define const
Definition: getopt.c:38
visualization_msgs::ImageMarker_::Ptr
std::shared_ptr< ::visualization_msgs::ImageMarker_< ContainerAllocator > > Ptr
Definition: ImageMarker.h:142
s
XmlRpcServer s
visualization_msgs::ImageMarker_::_fill_color_type
::std_msgs::ColorRGBA_< ContainerAllocator > _fill_color_type
Definition: ImageMarker.h:94
visualization_msgs::ImageMarker_::_position_type
::geometry_msgs::Point_< ContainerAllocator > _position_type
Definition: ImageMarker.h:82
visualization_msgs::ImageMarker_::_ns_type
std::basic_string< char, std::char_traits< char >, typename ContainerAllocator::template rebind< char >::other > _ns_type
Definition: ImageMarker.h:70
roswrap::message_operations::Printer::stream
static void stream(Stream &s, const std::string &indent, const M &value)
Definition: message_operations.h:43
roswrap::message_traits::IsFixedSize
A fixed-size datatype is one whose size is constant, i.e. it has no variable-length arrays or strings...
Definition: message_traits.h:103
roswrap::message_traits::DataType< ::visualization_msgs::ImageMarker_< ContainerAllocator > >::value
static const char * value()
Definition: ImageMarker.h:261
ros::message_operations::Printer
ROS_DECLARE_ALLINONE_SERIALIZER
#define ROS_DECLARE_ALLINONE_SERIALIZER
Declare your serializer to use an allInOne member instead of requiring 3 different serialization func...
Definition: serialization.h:74
visualization_msgs::ImageMarker_::outline_color
_outline_color_type outline_color
Definition: ImageMarker.h:89
visualization_msgs::operator==
bool operator==(const ::visualization_msgs::ImageMarker_< ContainerAllocator1 > &lhs, const ::visualization_msgs::ImageMarker_< ContainerAllocator2 > &rhs)
Definition: ImageMarker.h:179
visualization_msgs::ImageMarker_::_outline_colors_type
std::vector< ::std_msgs::ColorRGBA_< ContainerAllocator >, typename ContainerAllocator::template rebind< ::std_msgs::ColorRGBA_< ContainerAllocator > >::other > _outline_colors_type
Definition: ImageMarker.h:103
visualization_msgs::ImageMarker_::ADD
@ ADD
Definition: ImageMarker.h:137
roswrap::message_traits::DataType
Specialize to provide the datatype for a message.
Definition: message_traits.h:135
visualization_msgs::ImageMarker_::_header_type
::std_msgs::Header_< ContainerAllocator > _header_type
Definition: ImageMarker.h:67
roswrap::message_operations::Printer< ::visualization_msgs::ImageMarker_< ContainerAllocator > >::stream
static void stream(Stream &s, const std::string &indent, const ::visualization_msgs::ImageMarker_< ContainerAllocator > &v)
Definition: ImageMarker.h:374
visualization_msgs::ImageMarker_::_points_type
std::vector< ::geometry_msgs::Point_< ContainerAllocator >, typename ContainerAllocator::template rebind< ::geometry_msgs::Point_< ContainerAllocator > >::other > _points_type
Definition: ImageMarker.h:100
roswrap::message_traits::Definition
Specialize to provide the definition for a message.
Definition: message_traits.h:152
visualization_msgs::ImageMarker_::_action_type
int32_t _action_type
Definition: ImageMarker.h:79
visualization_msgs::ImageMarker_::header
_header_type header
Definition: ImageMarker.h:68
visualization_msgs::operator<<
std::ostream & operator<<(std::ostream &s, const ::visualization_msgs::ImageMarker_< ContainerAllocator > &v)
Definition: ImageMarker.h:171
visualization_msgs::ImageMarker_::scale
_scale_type scale
Definition: ImageMarker.h:86
visualization_msgs::ImageMarker_::position
_position_type position
Definition: ImageMarker.h:83
visualization_msgs::ImageMarker_::LINE_LIST
@ LINE_LIST
Definition: ImageMarker.h:134
visualization_msgs::ImageMarker_::fill_color
_fill_color_type fill_color
Definition: ImageMarker.h:95
visualization_msgs::ImageMarker_::_filled_type
uint8_t _filled_type
Definition: ImageMarker.h:91
visualization_msgs::ImageMarker_::type
_type_type type
Definition: ImageMarker.h:77
roswrap::message_traits::MD5Sum< ::visualization_msgs::ImageMarker_< ContainerAllocator > >::value
static const char * value(const ::visualization_msgs::ImageMarker_< ContainerAllocator > &)
Definition: ImageMarker.h:253
roswrap
Definition: param_modi.cpp:41
roswrap::message_operations::Printer
Definition: message_operations.h:40
visualization_msgs::ImageMarker_::id
_id_type id
Definition: ImageMarker.h:74
std_msgs::Header_
Definition: Header.h:23
visualization_msgs::ImageMarker_::LINE_STRIP
@ LINE_STRIP
Definition: ImageMarker.h:133
visualization_msgs::ImageMarker_::_id_type
int32_t _id_type
Definition: ImageMarker.h:73
ColorRGBA.h
visualization_msgs::ImageMarker_::ImageMarker_
ImageMarker_(const ContainerAllocator &_alloc)
Definition: ImageMarker.h:48
visualization_msgs::ImageMarker_::lifetime
_lifetime_type lifetime
Definition: ImageMarker.h:98
roswrap::message_traits::TrueType
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
Definition: message_traits.h:79
roswrap::message_traits::MD5Sum
Specialize to provide the md5sum for a message.
Definition: message_traits.h:118
visualization_msgs::ImageMarkerConstPtr
std::shared_ptr< ::visualization_msgs::ImageMarker const > ImageMarkerConstPtr
Definition: ImageMarker.h:150
visualization_msgs
Definition: ImageMarker.h:26
visualization_msgs::ImageMarkerPtr
std::shared_ptr< ::visualization_msgs::ImageMarker > ImageMarkerPtr
Definition: ImageMarker.h:149
visualization_msgs::ImageMarker_::ns
_ns_type ns
Definition: ImageMarker.h:71
visualization_msgs::ImageMarker_::_lifetime_type
ros::Duration _lifetime_type
Definition: ImageMarker.h:97
roswrap::message_traits::DataType< ::visualization_msgs::ImageMarker_< ContainerAllocator > >::value
static const char * value(const ::visualization_msgs::ImageMarker_< ContainerAllocator > &)
Definition: ImageMarker.h:266
roswrap::message_traits::IsMessage
Am I message or not.
Definition: message_traits.h:112
visualization_msgs::ImageMarker_::_type_type
int32_t _type_type
Definition: ImageMarker.h:76
visualization_msgs::ImageMarker_::points
_points_type points
Definition: ImageMarker.h:101
visualization_msgs::ImageMarker_::REMOVE
@ REMOVE
Definition: ImageMarker.h:138
sick_scan_base.h
roswrap::serialization::Stream
Stream base-class, provides common functionality for IStream and OStream.
Definition: serialization.h:705
visualization_msgs::ImageMarker_::_scale_type
float _scale_type
Definition: ImageMarker.h:85
geometry_msgs::Point_
Definition: Point.h:23
roswrap::message_traits::MD5Sum< ::visualization_msgs::ImageMarker_< ContainerAllocator > >::value
static const char * value()
Definition: ImageMarker.h:248
visualization_msgs::ImageMarker_::POINTS
@ POINTS
Definition: ImageMarker.h:136
visualization_msgs::ImageMarker_::filled
_filled_type filled
Definition: ImageMarker.h:92
ros::Duration
visualization_msgs::ImageMarker_::Type
ImageMarker_< ContainerAllocator > Type
Definition: ImageMarker.h:31
Header.h
visualization_msgs::ImageMarker_::_outline_color_type
::std_msgs::ColorRGBA_< ContainerAllocator > _outline_color_type
Definition: ImageMarker.h:88
visualization_msgs::ImageMarker
::visualization_msgs::ImageMarker_< std::allocator< void > > ImageMarker
Definition: ImageMarker.h:147
visualization_msgs::ImageMarker_::ConstPtr
std::shared_ptr< ::visualization_msgs::ImageMarker_< ContainerAllocator > const > ConstPtr
Definition: ImageMarker.h:143
visualization_msgs::ImageMarker_::POLYGON
@ POLYGON
Definition: ImageMarker.h:135


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:08