6 #ifndef VISUALIZATION_MSGS_MESSAGE_MARKER_H
7 #define VISUALIZATION_MSGS_MESSAGE_MARKER_H
14 #include <ros/types.h>
15 #include <ros/serialization.h>
16 #include <ros/builtin_message_traits.h>
17 #include <ros/message_operations.h>
28 template <
class ContainerAllocator>
74 typedef std::basic_string<char, std::char_traits<char>,
typename ContainerAllocator::template rebind<char>::other >
_ns_type;
86 typedef ::geometry_msgs::Pose_<ContainerAllocator>
_pose_type;
89 typedef ::geometry_msgs::Vector3_<ContainerAllocator>
_scale_type;
92 typedef ::std_msgs::ColorRGBA_<ContainerAllocator>
_color_type;
101 typedef std::vector< ::geometry_msgs::Point_<ContainerAllocator> ,
typename ContainerAllocator::template rebind< ::geometry_msgs::Point_<ContainerAllocator> >::other >
_points_type;
104 typedef std::vector< ::std_msgs::ColorRGBA_<ContainerAllocator> ,
typename ContainerAllocator::template rebind< ::std_msgs::ColorRGBA_<ContainerAllocator> >::other >
_colors_type;
107 typedef std::basic_string<char, std::char_traits<char>,
typename ContainerAllocator::template rebind<char>::other >
_text_type;
110 typedef std::basic_string<char, std::char_traits<char>,
typename ContainerAllocator::template rebind<char>::other >
_mesh_resource_type;
119 #if defined(_WIN32) && defined(ARROW)
122 #if defined(_WIN32) && defined(CUBE)
125 #if defined(_WIN32) && defined(SPHERE)
128 #if defined(_WIN32) && defined(CYLINDER)
131 #if defined(_WIN32) && defined(LINE_STRIP)
134 #if defined(_WIN32) && defined(LINE_LIST)
137 #if defined(_WIN32) && defined(CUBE_LIST)
140 #if defined(_WIN32) && defined(SPHERE_LIST)
143 #if defined(_WIN32) && defined(POINTS)
146 #if defined(_WIN32) && defined(TEXT_VIEW_FACING)
147 #undef TEXT_VIEW_FACING
149 #if defined(_WIN32) && defined(MESH_RESOURCE)
152 #if defined(_WIN32) && defined(TRIANGLE_LIST)
155 #if defined(_WIN32) && defined(ADD)
158 #if defined(_WIN32) && defined(MODIFY)
161 #if defined(_WIN32) && defined(DELETE)
164 #if defined(_WIN32) && defined(DELETEALL)
188 typedef std::shared_ptr< ::visualization_msgs::Marker_<ContainerAllocator> >
Ptr;
189 typedef std::shared_ptr< ::visualization_msgs::Marker_<ContainerAllocator>
const>
ConstPtr;
193 typedef ::visualization_msgs::Marker_<std::allocator<void> >
Marker;
195 typedef std::shared_ptr< ::visualization_msgs::Marker >
MarkerPtr;
234 template<
typename ContainerAllocator>
235 std::ostream&
operator<<(std::ostream& s, const ::visualization_msgs::Marker_<ContainerAllocator> & v)
242 template<
typename ContainerAllocator1,
typename ContainerAllocator2>
243 bool operator==(const ::visualization_msgs::Marker_<ContainerAllocator1> & lhs, const ::visualization_msgs::Marker_<ContainerAllocator2> & rhs)
245 return lhs.header == rhs.header &&
248 lhs.type == rhs.type &&
249 lhs.action == rhs.action &&
250 lhs.pose == rhs.pose &&
251 lhs.scale == rhs.scale &&
252 lhs.color == rhs.color &&
253 lhs.lifetime == rhs.lifetime &&
254 lhs.frame_locked == rhs.frame_locked &&
255 lhs.points == rhs.points &&
256 lhs.colors == rhs.colors &&
257 lhs.text == rhs.text &&
258 lhs.mesh_resource == rhs.mesh_resource &&
259 lhs.mesh_use_embedded_materials == rhs.mesh_use_embedded_materials;
262 template<
typename ContainerAllocator1,
typename ContainerAllocator2>
263 bool operator!=(const ::visualization_msgs::Marker_<ContainerAllocator1> & lhs, const ::visualization_msgs::Marker_<ContainerAllocator2> & rhs)
265 return !(lhs == rhs);
273 namespace message_traits
280 template <
class ContainerAllocator>
285 template <
class ContainerAllocator>
290 template <
class ContainerAllocator>
295 template <
class ContainerAllocator>
300 template <
class ContainerAllocator>
305 template <
class ContainerAllocator>
311 template<
class ContainerAllocator>
316 return "4048c9de2a16f4ae8e0538085ebf1b97";
319 static const char*
value(const ::visualization_msgs::Marker_<ContainerAllocator>&) {
return value(); }
320 static const uint64_t static_value1 = 0x4048c9de2a16f4aeULL;
321 static const uint64_t static_value2 = 0x8e0538085ebf1b97ULL;
324 template<
class ContainerAllocator>
329 return "visualization_msgs/Marker";
332 static const char*
value(const ::visualization_msgs::Marker_<ContainerAllocator>&) {
return value(); }
335 template<
class ContainerAllocator>
340 return "# 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"
346 "uint8 LINE_STRIP=4\n"
347 "uint8 LINE_LIST=5\n"
348 "uint8 CUBE_LIST=6\n"
349 "uint8 SPHERE_LIST=7\n"
351 "uint8 TEXT_VIEW_FACING=9\n"
352 "uint8 MESH_RESOURCE=10\n"
353 "uint8 TRIANGLE_LIST=11\n"
358 "uint8 DELETEALL=3\n"
360 "Header header # header for time/frame information\n"
361 "string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object\n"
362 "int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later\n"
363 "int32 type # Type of object\n"
364 "int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects\n"
365 "geometry_msgs/Pose pose # Pose of the object\n"
366 "geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square)\n"
367 "std_msgs/ColorRGBA color # Color [0.0-1.0]\n"
368 "duration lifetime # How long the object should last before being automatically deleted. 0 means forever\n"
369 "bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep\n"
371 "#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\n"
372 "geometry_msgs/Point[] points\n"
373 "#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\n"
374 "#number of colors must either be 0 or equal to the number of points\n"
375 "#NOTE: alpha is not yet used\n"
376 "std_msgs/ColorRGBA[] colors\n"
378 "# NOTE: only used for text markers\n"
381 "# NOTE: only used for MESH_RESOURCE markers\n"
382 "string mesh_resource\n"
383 "bool mesh_use_embedded_materials\n"
385 "================================================================================\n"
386 "MSG: std_msgs/Header\n"
387 "# Standard metadata for higher-level stamped data types.\n"
388 "# This is generally used to communicate timestamped data \n"
389 "# in a particular coordinate frame.\n"
391 "# sequence ID: consecutively increasing ID \n"
393 "#Two-integer timestamp that is expressed as:\n"
394 "# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n"
395 "# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n"
396 "# time-handling sugar is provided by the client library\n"
398 "#Frame this data is associated with\n"
401 "================================================================================\n"
402 "MSG: geometry_msgs/Pose\n"
403 "# A representation of pose in free space, composed of position and orientation. \n"
405 "Quaternion orientation\n"
407 "================================================================================\n"
408 "MSG: geometry_msgs/Point\n"
409 "# This contains the position of a point in free space\n"
414 "================================================================================\n"
415 "MSG: geometry_msgs/Quaternion\n"
416 "# This represents an orientation in free space in quaternion form.\n"
423 "================================================================================\n"
424 "MSG: geometry_msgs/Vector3\n"
425 "# This represents a vector in free space. \n"
426 "# It is only meant to represent a direction. Therefore, it does not\n"
427 "# make sense to apply a translation to it (e.g., when applying a \n"
428 "# generic rigid transformation to a Vector3, tf2 will only apply the\n"
429 "# rotation). If you want your data to be translatable too, use the\n"
430 "# geometry_msgs/Point message instead.\n"
435 "================================================================================\n"
436 "MSG: std_msgs/ColorRGBA\n"
444 static const char*
value(const ::visualization_msgs::Marker_<ContainerAllocator>&) {
return value(); }
452 namespace serialization
457 template<
typename Stream,
typename T>
inline static void allInOne(
Stream& stream, T m)
459 stream.next(m.header);
463 stream.next(m.action);
465 stream.next(m.scale);
466 stream.next(m.color);
467 stream.next(m.lifetime);
468 stream.next(m.frame_locked);
469 stream.next(m.points);
470 stream.next(m.colors);
472 stream.next(m.mesh_resource);
473 stream.next(m.mesh_use_embedded_materials);
484 namespace message_operations
487 template<
class ContainerAllocator>
490 template<
typename Stream>
static void stream(Stream& s,
const std::string&
indent, const ::visualization_msgs::Marker_<ContainerAllocator>& v)
514 s <<
indent <<
"frame_locked: ";
516 s <<
indent <<
"points[]" << std::endl;
517 for (
size_t i = 0; i < v.points.size(); ++i)
519 s <<
indent <<
" points[" << i <<
"]: ";
524 s <<
indent <<
"colors[]" << std::endl;
525 for (
size_t i = 0; i < v.colors.size(); ++i)
527 s <<
indent <<
" colors[" << i <<
"]: ";
534 s <<
indent <<
"mesh_resource: ";
536 s <<
indent <<
"mesh_use_embedded_materials: ";
544 #endif // VISUALIZATION_MSGS_MESSAGE_MARKER_H