InteractiveMarkerControl.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/InteractiveMarkerControl.msg
3 // DO NOT EDIT!
4 
5 
6 #ifndef VISUALIZATION_MSGS_MESSAGE_INTERACTIVEMARKERCONTROL_H
7 #define VISUALIZATION_MSGS_MESSAGE_INTERACTIVEMARKERCONTROL_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 
21 
22 namespace visualization_msgs
23 {
24 template <class ContainerAllocator>
26 {
28 
30  : name()
31  , orientation()
32  , orientation_mode(0)
33  , interaction_mode(0)
34  , always_visible(false)
35  , markers()
37  , description() {
38  }
39  InteractiveMarkerControl_(const ContainerAllocator& _alloc)
40  : name(_alloc)
41  , orientation(_alloc)
42  , orientation_mode(0)
43  , interaction_mode(0)
44  , always_visible(false)
45  , markers(_alloc)
47  , description(_alloc) {
48  (void)_alloc;
49  }
50 
51 
52 
53  typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _name_type;
55 
56  typedef ::geometry_msgs::Quaternion_<ContainerAllocator> _orientation_type;
58 
59  typedef uint8_t _orientation_mode_type;
61 
62  typedef uint8_t _interaction_mode_type;
64 
65  typedef uint8_t _always_visible_type;
67 
68  typedef std::vector< ::visualization_msgs::Marker_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::visualization_msgs::Marker_<ContainerAllocator> >::other > _markers_type;
70 
73 
74  typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _description_type;
76 
77 
78 
79 // reducing the odds to have name collisions with Windows.h
80 #if defined(_WIN32) && defined(INHERIT)
81  #undef INHERIT
82 #endif
83 #if defined(_WIN32) && defined(FIXED)
84  #undef FIXED
85 #endif
86 #if defined(_WIN32) && defined(VIEW_FACING)
87  #undef VIEW_FACING
88 #endif
89 #if defined(_WIN32) && defined(NONE)
90  #undef NONE
91 #endif
92 #if defined(_WIN32) && defined(MENU)
93  #undef MENU
94 #endif
95 #if defined(_WIN32) && defined(BUTTON)
96  #undef BUTTON
97 #endif
98 #if defined(_WIN32) && defined(MOVE_AXIS)
99  #undef MOVE_AXIS
100 #endif
101 #if defined(_WIN32) && defined(MOVE_PLANE)
102  #undef MOVE_PLANE
103 #endif
104 #if defined(_WIN32) && defined(ROTATE_AXIS)
105  #undef ROTATE_AXIS
106 #endif
107 #if defined(_WIN32) && defined(MOVE_ROTATE)
108  #undef MOVE_ROTATE
109 #endif
110 #if defined(_WIN32) && defined(MOVE_3D)
111  #undef MOVE_3D
112 #endif
113 #if defined(_WIN32) && defined(ROTATE_3D)
114  #undef ROTATE_3D
115 #endif
116 #if defined(_WIN32) && defined(MOVE_ROTATE_3D)
117  #undef MOVE_ROTATE_3D
118 #endif
119 
120  enum {
121  INHERIT = 0u,
122  FIXED = 1u,
124  NONE = 0u,
125  MENU = 1u,
126  BUTTON = 2u,
127  MOVE_AXIS = 3u,
131  MOVE_3D = 7u,
132  ROTATE_3D = 8u,
134  };
135 
136 
137  typedef std::shared_ptr< ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator> > Ptr;
138  typedef std::shared_ptr< ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator> const> ConstPtr;
139 
140 }; // struct InteractiveMarkerControl_
141 
142 typedef ::visualization_msgs::InteractiveMarkerControl_<std::allocator<void> > InteractiveMarkerControl;
143 
144 typedef std::shared_ptr< ::visualization_msgs::InteractiveMarkerControl > InteractiveMarkerControlPtr;
145 typedef std::shared_ptr< ::visualization_msgs::InteractiveMarkerControl const> InteractiveMarkerControlConstPtr;
146 
147 // constants requiring out of line definition
148 
149 
150 
151 
152 
153 
154 
155 
156 
157 
158 
159 
160 
161 
162 
163 
164 
165 
166 
167 
168 
169 
170 
171 
172 
173 
174 
175 
176 
177 template<typename ContainerAllocator>
178 std::ostream& operator<<(std::ostream& s, const ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator> & v)
179 {
181 return s;
182 }
183 
184 
185 template<typename ContainerAllocator1, typename ContainerAllocator2>
186 bool operator==(const ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator1> & lhs, const ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator2> & rhs)
187 {
188  return lhs.name == rhs.name &&
189  lhs.orientation == rhs.orientation &&
190  lhs.orientation_mode == rhs.orientation_mode &&
191  lhs.interaction_mode == rhs.interaction_mode &&
192  lhs.always_visible == rhs.always_visible &&
193  lhs.markers == rhs.markers &&
194  lhs.independent_marker_orientation == rhs.independent_marker_orientation &&
195  lhs.description == rhs.description;
196 }
197 
198 template<typename ContainerAllocator1, typename ContainerAllocator2>
199 bool operator!=(const ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator1> & lhs, const ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator2> & rhs)
200 {
201  return !(lhs == rhs);
202 }
203 
204 
205 } // namespace visualization_msgs
206 
207 namespace roswrap
208 {
209 namespace message_traits
210 {
211 
212 
213 
214 
215 
216 template <class ContainerAllocator>
218  : FalseType
219  { };
220 
221 template <class ContainerAllocator>
223  : FalseType
224  { };
225 
226 template <class ContainerAllocator>
228  : TrueType
229  { };
230 
231 template <class ContainerAllocator>
233  : TrueType
234  { };
235 
236 template <class ContainerAllocator>
238  : FalseType
239  { };
240 
241 template <class ContainerAllocator>
243  : FalseType
244  { };
245 
246 
247 template<class ContainerAllocator>
249 {
250  static const char* value()
251  {
252  return "b3c81e785788195d1840b86c28da1aac";
253  }
254 
255  static const char* value(const ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator>&) { return value(); }
256  static const uint64_t static_value1 = 0xb3c81e785788195dULL;
257  static const uint64_t static_value2 = 0x1840b86c28da1aacULL;
258 };
259 
260 template<class ContainerAllocator>
262 {
263  static const char* value()
264  {
265  return "visualization_msgs/InteractiveMarkerControl";
266  }
267 
268  static const char* value(const ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator>&) { return value(); }
269 };
270 
271 template<class ContainerAllocator>
273 {
274  static const char* value()
275  {
276  return "# Represents a control that is to be displayed together with an interactive marker\n"
277 "\n"
278 "# Identifying string for this control.\n"
279 "# You need to assign a unique value to this to receive feedback from the GUI\n"
280 "# on what actions the user performs on this control (e.g. a button click).\n"
281 "string name\n"
282 "\n"
283 "\n"
284 "# Defines the local coordinate frame (relative to the pose of the parent\n"
285 "# interactive marker) in which is being rotated and translated.\n"
286 "# Default: Identity\n"
287 "geometry_msgs/Quaternion orientation\n"
288 "\n"
289 "\n"
290 "# Orientation mode: controls how orientation changes.\n"
291 "# INHERIT: Follow orientation of interactive marker\n"
292 "# FIXED: Keep orientation fixed at initial state\n"
293 "# VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up).\n"
294 "uint8 INHERIT = 0 \n"
295 "uint8 FIXED = 1\n"
296 "uint8 VIEW_FACING = 2\n"
297 "\n"
298 "uint8 orientation_mode\n"
299 "\n"
300 "# Interaction mode for this control\n"
301 "# \n"
302 "# NONE: This control is only meant for visualization; no context menu.\n"
303 "# MENU: Like NONE, but right-click menu is active.\n"
304 "# BUTTON: Element can be left-clicked.\n"
305 "# MOVE_AXIS: Translate along local x-axis.\n"
306 "# MOVE_PLANE: Translate in local y-z plane.\n"
307 "# ROTATE_AXIS: Rotate around local x-axis.\n"
308 "# MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS.\n"
309 "uint8 NONE = 0 \n"
310 "uint8 MENU = 1\n"
311 "uint8 BUTTON = 2\n"
312 "uint8 MOVE_AXIS = 3 \n"
313 "uint8 MOVE_PLANE = 4\n"
314 "uint8 ROTATE_AXIS = 5\n"
315 "uint8 MOVE_ROTATE = 6\n"
316 "# \"3D\" interaction modes work with the mouse+SHIFT+CTRL or with 3D cursors.\n"
317 "# MOVE_3D: Translate freely in 3D space.\n"
318 "# ROTATE_3D: Rotate freely in 3D space about the origin of parent frame.\n"
319 "# MOVE_ROTATE_3D: Full 6-DOF freedom of translation and rotation about the cursor origin.\n"
320 "uint8 MOVE_3D = 7\n"
321 "uint8 ROTATE_3D = 8\n"
322 "uint8 MOVE_ROTATE_3D = 9\n"
323 "\n"
324 "uint8 interaction_mode\n"
325 "\n"
326 "\n"
327 "# If true, the contained markers will also be visible\n"
328 "# when the gui is not in interactive mode.\n"
329 "bool always_visible\n"
330 "\n"
331 "\n"
332 "# Markers to be displayed as custom visual representation.\n"
333 "# Leave this empty to use the default control handles.\n"
334 "#\n"
335 "# Note: \n"
336 "# - The markers can be defined in an arbitrary coordinate frame,\n"
337 "# but will be transformed into the local frame of the interactive marker.\n"
338 "# - If the header of a marker is empty, its pose will be interpreted as \n"
339 "# relative to the pose of the parent interactive marker.\n"
340 "Marker[] markers\n"
341 "\n"
342 "\n"
343 "# In VIEW_FACING mode, set this to true if you don't want the markers\n"
344 "# to be aligned with the camera view point. The markers will show up\n"
345 "# as in INHERIT mode.\n"
346 "bool independent_marker_orientation\n"
347 "\n"
348 "\n"
349 "# Short description (< 40 characters) of what this control does,\n"
350 "# e.g. \"Move the robot\". \n"
351 "# Default: A generic description based on the interaction mode\n"
352 "string description\n"
353 "\n"
354 "================================================================================\n"
355 "MSG: geometry_msgs/Quaternion\n"
356 "# This represents an orientation in free space in quaternion form.\n"
357 "\n"
358 "float64 x\n"
359 "float64 y\n"
360 "float64 z\n"
361 "float64 w\n"
362 "\n"
363 "================================================================================\n"
364 "MSG: visualization_msgs/Marker\n"
365 "# See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz\n"
366 "\n"
367 "uint8 ARROW=0\n"
368 "uint8 CUBE=1\n"
369 "uint8 SPHERE=2\n"
370 "uint8 CYLINDER=3\n"
371 "uint8 LINE_STRIP=4\n"
372 "uint8 LINE_LIST=5\n"
373 "uint8 CUBE_LIST=6\n"
374 "uint8 SPHERE_LIST=7\n"
375 "uint8 POINTS=8\n"
376 "uint8 TEXT_VIEW_FACING=9\n"
377 "uint8 MESH_RESOURCE=10\n"
378 "uint8 TRIANGLE_LIST=11\n"
379 "\n"
380 "uint8 ADD=0\n"
381 "uint8 MODIFY=0\n"
382 "uint8 DELETE=2\n"
383 "uint8 DELETEALL=3\n"
384 "\n"
385 "Header header # header for time/frame information\n"
386 "string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object\n"
387 "int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later\n"
388 "int32 type # Type of object\n"
389 "int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects\n"
390 "geometry_msgs/Pose pose # Pose of the object\n"
391 "geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square)\n"
392 "std_msgs/ColorRGBA color # Color [0.0-1.0]\n"
393 "duration lifetime # How long the object should last before being automatically deleted. 0 means forever\n"
394 "bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep\n"
395 "\n"
396 "#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\n"
397 "geometry_msgs/Point[] points\n"
398 "#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\n"
399 "#number of colors must either be 0 or equal to the number of points\n"
400 "#NOTE: alpha is not yet used\n"
401 "std_msgs/ColorRGBA[] colors\n"
402 "\n"
403 "# NOTE: only used for text markers\n"
404 "string text\n"
405 "\n"
406 "# NOTE: only used for MESH_RESOURCE markers\n"
407 "string mesh_resource\n"
408 "bool mesh_use_embedded_materials\n"
409 "\n"
410 "================================================================================\n"
411 "MSG: std_msgs/Header\n"
412 "# Standard metadata for higher-level stamped data types.\n"
413 "# This is generally used to communicate timestamped data \n"
414 "# in a particular coordinate frame.\n"
415 "# \n"
416 "# sequence ID: consecutively increasing ID \n"
417 "uint32 seq\n"
418 "#Two-integer timestamp that is expressed as:\n"
419 "# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n"
420 "# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n"
421 "# time-handling sugar is provided by the client library\n"
422 "time stamp\n"
423 "#Frame this data is associated with\n"
424 "string frame_id\n"
425 "\n"
426 "================================================================================\n"
427 "MSG: geometry_msgs/Pose\n"
428 "# A representation of pose in free space, composed of position and orientation. \n"
429 "Point position\n"
430 "Quaternion orientation\n"
431 "\n"
432 "================================================================================\n"
433 "MSG: geometry_msgs/Point\n"
434 "# This contains the position of a point in free space\n"
435 "float64 x\n"
436 "float64 y\n"
437 "float64 z\n"
438 "\n"
439 "================================================================================\n"
440 "MSG: geometry_msgs/Vector3\n"
441 "# This represents a vector in free space. \n"
442 "# It is only meant to represent a direction. Therefore, it does not\n"
443 "# make sense to apply a translation to it (e.g., when applying a \n"
444 "# generic rigid transformation to a Vector3, tf2 will only apply the\n"
445 "# rotation). If you want your data to be translatable too, use the\n"
446 "# geometry_msgs/Point message instead.\n"
447 "\n"
448 "float64 x\n"
449 "float64 y\n"
450 "float64 z\n"
451 "================================================================================\n"
452 "MSG: std_msgs/ColorRGBA\n"
453 "float32 r\n"
454 "float32 g\n"
455 "float32 b\n"
456 "float32 a\n"
457 ;
458  }
459 
460  static const char* value(const ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator>&) { return value(); }
461 };
462 
463 } // namespace message_traits
464 } // namespace roswrap
465 
466 namespace roswrap
467 {
468 namespace serialization
469 {
470 
471  template<class ContainerAllocator> struct Serializer< ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator> >
472  {
473  template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
474  {
475  stream.next(m.name);
476  stream.next(m.orientation);
477  stream.next(m.orientation_mode);
478  stream.next(m.interaction_mode);
479  stream.next(m.always_visible);
480  stream.next(m.markers);
481  stream.next(m.independent_marker_orientation);
482  stream.next(m.description);
483  }
484 
486  }; // struct InteractiveMarkerControl_
487 
488 } // namespace serialization
489 } // namespace roswrap
490 
491 namespace roswrap
492 {
493 namespace message_operations
494 {
495 
496 template<class ContainerAllocator>
498 {
499  template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator>& v)
500  {
501  s << indent << "name: ";
502  Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.name);
503  s << indent << "orientation: ";
504  s << std::endl;
506  s << indent << "orientation_mode: ";
507  Printer<uint8_t>::stream(s, indent + " ", v.orientation_mode);
508  s << indent << "interaction_mode: ";
509  Printer<uint8_t>::stream(s, indent + " ", v.interaction_mode);
510  s << indent << "always_visible: ";
511  Printer<uint8_t>::stream(s, indent + " ", v.always_visible);
512  s << indent << "markers[]" << std::endl;
513  for (size_t i = 0; i < v.markers.size(); ++i)
514  {
515  s << indent << " markers[" << i << "]: ";
516  s << std::endl;
517  s << indent;
519  }
520  s << indent << "independent_marker_orientation: ";
521  Printer<uint8_t>::stream(s, indent + " ", v.independent_marker_orientation);
522  s << indent << "description: ";
523  Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.description);
524  }
525 };
526 
527 } // namespace message_operations
528 } // namespace roswrap
529 
530 #endif // VISUALIZATION_MSGS_MESSAGE_INTERACTIVEMARKERCONTROL_H
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::InteractiveMarkerControlPtr
std::shared_ptr< ::visualization_msgs::InteractiveMarkerControl > InteractiveMarkerControlPtr
Definition: InteractiveMarkerControl.h:144
visualization_msgs::InteractiveMarkerControl_::_interaction_mode_type
uint8_t _interaction_mode_type
Definition: InteractiveMarkerControl.h:62
roswrap::message_operations::Printer< ::visualization_msgs::InteractiveMarkerControl_< ContainerAllocator > >::stream
static void stream(Stream &s, const std::string &indent, const ::visualization_msgs::InteractiveMarkerControl_< ContainerAllocator > &v)
Definition: InteractiveMarkerControl.h:499
multiscan_pcap_player.indent
indent
Definition: multiscan_pcap_player.py:252
roswrap::serialization::Serializer
Templated serialization class. Default implementation provides backwards compatibility with old messa...
Definition: serialization.h:120
visualization_msgs::InteractiveMarkerControl_::ConstPtr
std::shared_ptr< ::visualization_msgs::InteractiveMarkerControl_< ContainerAllocator > const > ConstPtr
Definition: InteractiveMarkerControl.h:138
visualization_msgs::InteractiveMarkerControl_::Ptr
std::shared_ptr< ::visualization_msgs::InteractiveMarkerControl_< ContainerAllocator > > Ptr
Definition: InteractiveMarkerControl.h:137
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
Quaternion.h
const
#define const
Definition: getopt.c:38
visualization_msgs::InteractiveMarkerControl_::NONE
@ NONE
Definition: InteractiveMarkerControl.h:124
s
XmlRpcServer s
visualization_msgs::InteractiveMarkerControlConstPtr
std::shared_ptr< ::visualization_msgs::InteractiveMarkerControl const > InteractiveMarkerControlConstPtr
Definition: InteractiveMarkerControl.h:145
visualization_msgs::InteractiveMarkerControl_::INHERIT
@ INHERIT
Definition: InteractiveMarkerControl.h:121
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
visualization_msgs::InteractiveMarkerControl_::MOVE_ROTATE_3D
@ MOVE_ROTATE_3D
Definition: InteractiveMarkerControl.h:133
roswrap::message_traits::Definition< ::visualization_msgs::InteractiveMarkerControl_< ContainerAllocator > >::value
static const char * value()
Definition: InteractiveMarkerControl.h:274
roswrap::message_traits::DataType< ::visualization_msgs::InteractiveMarkerControl_< ContainerAllocator > >::value
static const char * value()
Definition: InteractiveMarkerControl.h:263
visualization_msgs::InteractiveMarkerControl_::_orientation_mode_type
uint8_t _orientation_mode_type
Definition: InteractiveMarkerControl.h:59
visualization_msgs::InteractiveMarkerControl_::MOVE_PLANE
@ MOVE_PLANE
Definition: InteractiveMarkerControl.h:128
ros::message_operations::Printer
roswrap::message_traits::DataType< ::visualization_msgs::InteractiveMarkerControl_< ContainerAllocator > >::value
static const char * value(const ::visualization_msgs::InteractiveMarkerControl_< ContainerAllocator > &)
Definition: InteractiveMarkerControl.h:268
roswrap::message_traits::Definition< ::visualization_msgs::InteractiveMarkerControl_< ContainerAllocator > >::value
static const char * value(const ::visualization_msgs::InteractiveMarkerControl_< ContainerAllocator > &)
Definition: InteractiveMarkerControl.h:460
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::InteractiveMarkerControl_::always_visible
_always_visible_type always_visible
Definition: InteractiveMarkerControl.h:66
visualization_msgs::operator==
bool operator==(const ::visualization_msgs::ImageMarker_< ContainerAllocator1 > &lhs, const ::visualization_msgs::ImageMarker_< ContainerAllocator2 > &rhs)
Definition: ImageMarker.h:179
visualization_msgs::InteractiveMarkerControl_::MENU
@ MENU
Definition: InteractiveMarkerControl.h:125
roswrap::message_traits::DataType
Specialize to provide the datatype for a message.
Definition: message_traits.h:135
visualization_msgs::InteractiveMarkerControl_
Definition: InteractiveMarkerControl.h:25
visualization_msgs::InteractiveMarkerControl_::_always_visible_type
uint8_t _always_visible_type
Definition: InteractiveMarkerControl.h:65
roswrap::message_traits::Definition
Specialize to provide the definition for a message.
Definition: message_traits.h:152
visualization_msgs::InteractiveMarkerControl_::VIEW_FACING
@ VIEW_FACING
Definition: InteractiveMarkerControl.h:123
visualization_msgs::InteractiveMarkerControl_::_orientation_type
::geometry_msgs::Quaternion_< ContainerAllocator > _orientation_type
Definition: InteractiveMarkerControl.h:56
visualization_msgs::operator<<
std::ostream & operator<<(std::ostream &s, const ::visualization_msgs::ImageMarker_< ContainerAllocator > &v)
Definition: ImageMarker.h:171
visualization_msgs::InteractiveMarkerControl_::Type
InteractiveMarkerControl_< ContainerAllocator > Type
Definition: InteractiveMarkerControl.h:27
visualization_msgs::InteractiveMarkerControl_::InteractiveMarkerControl_
InteractiveMarkerControl_(const ContainerAllocator &_alloc)
Definition: InteractiveMarkerControl.h:39
visualization_msgs::InteractiveMarkerControl_::orientation
_orientation_type orientation
Definition: InteractiveMarkerControl.h:57
visualization_msgs::InteractiveMarkerControl_::BUTTON
@ BUTTON
Definition: InteractiveMarkerControl.h:126
visualization_msgs::InteractiveMarkerControl_::_description_type
std::basic_string< char, std::char_traits< char >, typename ContainerAllocator::template rebind< char >::other > _description_type
Definition: InteractiveMarkerControl.h:74
visualization_msgs::InteractiveMarkerControl_::InteractiveMarkerControl_
InteractiveMarkerControl_()
Definition: InteractiveMarkerControl.h:29
visualization_msgs::InteractiveMarkerControl_::independent_marker_orientation
_independent_marker_orientation_type independent_marker_orientation
Definition: InteractiveMarkerControl.h:72
roswrap
Definition: param_modi.cpp:41
visualization_msgs::InteractiveMarkerControl_::_name_type
std::basic_string< char, std::char_traits< char >, typename ContainerAllocator::template rebind< char >::other > _name_type
Definition: InteractiveMarkerControl.h:53
visualization_msgs::InteractiveMarkerControl_::MOVE_3D
@ MOVE_3D
Definition: InteractiveMarkerControl.h:131
visualization_msgs::InteractiveMarkerControl_::MOVE_AXIS
@ MOVE_AXIS
Definition: InteractiveMarkerControl.h:127
roswrap::message_operations::Printer
Definition: message_operations.h:40
visualization_msgs::InteractiveMarkerControl_::interaction_mode
_interaction_mode_type interaction_mode
Definition: InteractiveMarkerControl.h:63
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
Marker.h
visualization_msgs
Definition: ImageMarker.h:26
visualization_msgs::InteractiveMarkerControl_::ROTATE_3D
@ ROTATE_3D
Definition: InteractiveMarkerControl.h:132
roswrap::message_traits::IsMessage
Am I message or not.
Definition: message_traits.h:112
visualization_msgs::InteractiveMarkerControl_::markers
_markers_type markers
Definition: InteractiveMarkerControl.h:69
geometry_msgs::Quaternion_
Definition: kinetic/include/geometry_msgs/Quaternion.h:23
roswrap::message_traits::MD5Sum< ::visualization_msgs::InteractiveMarkerControl_< ContainerAllocator > >::value
static const char * value()
Definition: InteractiveMarkerControl.h:250
visualization_msgs::InteractiveMarkerControl_::orientation_mode
_orientation_mode_type orientation_mode
Definition: InteractiveMarkerControl.h:60
sick_scan_base.h
roswrap::serialization::Stream
Stream base-class, provides common functionality for IStream and OStream.
Definition: serialization.h:705
visualization_msgs::InteractiveMarkerControl_::name
_name_type name
Definition: InteractiveMarkerControl.h:54
roswrap::message_traits::MD5Sum< ::visualization_msgs::InteractiveMarkerControl_< ContainerAllocator > >::value
static const char * value(const ::visualization_msgs::InteractiveMarkerControl_< ContainerAllocator > &)
Definition: InteractiveMarkerControl.h:255
visualization_msgs::InteractiveMarkerControl_::_markers_type
std::vector< ::visualization_msgs::Marker_< ContainerAllocator >, typename ContainerAllocator::template rebind< ::visualization_msgs::Marker_< ContainerAllocator > >::other > _markers_type
Definition: InteractiveMarkerControl.h:68
visualization_msgs::InteractiveMarkerControl
::visualization_msgs::InteractiveMarkerControl_< std::allocator< void > > InteractiveMarkerControl
Definition: InteractiveMarkerControl.h:142
visualization_msgs::InteractiveMarkerControl_::description
_description_type description
Definition: InteractiveMarkerControl.h:75
visualization_msgs::InteractiveMarkerControl_::_independent_marker_orientation_type
uint8_t _independent_marker_orientation_type
Definition: InteractiveMarkerControl.h:71
visualization_msgs::InteractiveMarkerControl_::MOVE_ROTATE
@ MOVE_ROTATE
Definition: InteractiveMarkerControl.h:130
visualization_msgs::InteractiveMarkerControl_::ROTATE_AXIS
@ ROTATE_AXIS
Definition: InteractiveMarkerControl.h:129
visualization_msgs::InteractiveMarkerControl_::FIXED
@ FIXED
Definition: InteractiveMarkerControl.h:122
roswrap::serialization::Serializer< ::visualization_msgs::InteractiveMarkerControl_< ContainerAllocator > >::allInOne
static void allInOne(Stream &stream, T m)
Definition: InteractiveMarkerControl.h:473


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