00001
00002 #ifndef VISUALIZATION_MSGS_MESSAGE_MARKER_H
00003 #define VISUALIZATION_MSGS_MESSAGE_MARKER_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "std_msgs/Header.h"
00014 #include "geometry_msgs/Pose.h"
00015 #include "geometry_msgs/Vector3.h"
00016 #include "std_msgs/ColorRGBA.h"
00017 #include "geometry_msgs/Point.h"
00018 #include "std_msgs/ColorRGBA.h"
00019
00020 namespace visualization_msgs
00021 {
00022 template <class ContainerAllocator>
00023 struct Marker_ : public ros::Message
00024 {
00025 typedef Marker_<ContainerAllocator> Type;
00026
00027 Marker_()
00028 : header()
00029 , ns()
00030 , id(0)
00031 , type(0)
00032 , action(0)
00033 , pose()
00034 , scale()
00035 , color()
00036 , lifetime()
00037 , frame_locked(false)
00038 , points()
00039 , colors()
00040 , text()
00041 , mesh_resource()
00042 , mesh_use_embedded_materials(false)
00043 {
00044 }
00045
00046 Marker_(const ContainerAllocator& _alloc)
00047 : header(_alloc)
00048 , ns(_alloc)
00049 , id(0)
00050 , type(0)
00051 , action(0)
00052 , pose(_alloc)
00053 , scale(_alloc)
00054 , color(_alloc)
00055 , lifetime()
00056 , frame_locked(false)
00057 , points(_alloc)
00058 , colors(_alloc)
00059 , text(_alloc)
00060 , mesh_resource(_alloc)
00061 , mesh_use_embedded_materials(false)
00062 {
00063 }
00064
00065 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00066 ::std_msgs::Header_<ContainerAllocator> header;
00067
00068 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _ns_type;
00069 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > ns;
00070
00071 typedef int32_t _id_type;
00072 int32_t id;
00073
00074 typedef int32_t _type_type;
00075 int32_t type;
00076
00077 typedef int32_t _action_type;
00078 int32_t action;
00079
00080 typedef ::geometry_msgs::Pose_<ContainerAllocator> _pose_type;
00081 ::geometry_msgs::Pose_<ContainerAllocator> pose;
00082
00083 typedef ::geometry_msgs::Vector3_<ContainerAllocator> _scale_type;
00084 ::geometry_msgs::Vector3_<ContainerAllocator> scale;
00085
00086 typedef ::std_msgs::ColorRGBA_<ContainerAllocator> _color_type;
00087 ::std_msgs::ColorRGBA_<ContainerAllocator> color;
00088
00089 typedef ros::Duration _lifetime_type;
00090 ros::Duration lifetime;
00091
00092 typedef uint8_t _frame_locked_type;
00093 uint8_t frame_locked;
00094
00095 typedef std::vector< ::geometry_msgs::Point_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Point_<ContainerAllocator> >::other > _points_type;
00096 std::vector< ::geometry_msgs::Point_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Point_<ContainerAllocator> >::other > points;
00097
00098 typedef std::vector< ::std_msgs::ColorRGBA_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::std_msgs::ColorRGBA_<ContainerAllocator> >::other > _colors_type;
00099 std::vector< ::std_msgs::ColorRGBA_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::std_msgs::ColorRGBA_<ContainerAllocator> >::other > colors;
00100
00101 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _text_type;
00102 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > text;
00103
00104 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _mesh_resource_type;
00105 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > mesh_resource;
00106
00107 typedef uint8_t _mesh_use_embedded_materials_type;
00108 uint8_t mesh_use_embedded_materials;
00109
00110 enum { ARROW = 0 };
00111 enum { CUBE = 1 };
00112 enum { SPHERE = 2 };
00113 enum { CYLINDER = 3 };
00114 enum { LINE_STRIP = 4 };
00115 enum { LINE_LIST = 5 };
00116 enum { CUBE_LIST = 6 };
00117 enum { SPHERE_LIST = 7 };
00118 enum { POINTS = 8 };
00119 enum { TEXT_VIEW_FACING = 9 };
00120 enum { MESH_RESOURCE = 10 };
00121 enum { TRIANGLE_LIST = 11 };
00122 enum { ADD = 0 };
00123 enum { MODIFY = 0 };
00124 enum { DELETE = 2 };
00125
00126 ROS_DEPRECATED uint32_t get_points_size() const { return (uint32_t)points.size(); }
00127 ROS_DEPRECATED void set_points_size(uint32_t size) { points.resize((size_t)size); }
00128 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; }
00129 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; }
00130 ROS_DEPRECATED uint32_t get_colors_size() const { return (uint32_t)colors.size(); }
00131 ROS_DEPRECATED void set_colors_size(uint32_t size) { colors.resize((size_t)size); }
00132 ROS_DEPRECATED void get_colors_vec(std::vector< ::std_msgs::ColorRGBA_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::std_msgs::ColorRGBA_<ContainerAllocator> >::other > & vec) const { vec = this->colors; }
00133 ROS_DEPRECATED void set_colors_vec(const std::vector< ::std_msgs::ColorRGBA_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::std_msgs::ColorRGBA_<ContainerAllocator> >::other > & vec) { this->colors = vec; }
00134 private:
00135 static const char* __s_getDataType_() { return "visualization_msgs/Marker"; }
00136 public:
00137 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00138
00139 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00140
00141 private:
00142 static const char* __s_getMD5Sum_() { return "bc7602ad2ba78f4cbe1c23250683bdc0"; }
00143 public:
00144 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00145
00146 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00147
00148 private:
00149 static const char* __s_getMessageDefinition_() { 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\
00150 \n\
00151 byte ARROW=0\n\
00152 byte CUBE=1\n\
00153 byte SPHERE=2\n\
00154 byte CYLINDER=3\n\
00155 byte LINE_STRIP=4\n\
00156 byte LINE_LIST=5\n\
00157 byte CUBE_LIST=6\n\
00158 byte SPHERE_LIST=7\n\
00159 byte POINTS=8\n\
00160 byte TEXT_VIEW_FACING=9\n\
00161 byte MESH_RESOURCE=10\n\
00162 byte TRIANGLE_LIST=11\n\
00163 \n\
00164 byte ADD=0\n\
00165 byte MODIFY=0\n\
00166 byte DELETE=2\n\
00167 \n\
00168 Header header # header for time/frame information\n\
00169 string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object\n\
00170 int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later\n\
00171 int32 type # Type of object\n\
00172 int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object\n\
00173 geometry_msgs/Pose pose # Pose of the object\n\
00174 geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square)\n\
00175 std_msgs/ColorRGBA color # Color [0.0-1.0]\n\
00176 duration lifetime # How long the object should last before being automatically deleted. 0 means forever\n\
00177 bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep\n\
00178 \n\
00179 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\n\
00180 geometry_msgs/Point[] points\n\
00181 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\n\
00182 #number of colors must either be 0 or equal to the number of points\n\
00183 #NOTE: alpha is not yet used\n\
00184 std_msgs/ColorRGBA[] colors\n\
00185 \n\
00186 # NOTE: only used for text markers\n\
00187 string text\n\
00188 \n\
00189 # NOTE: only used for MESH_RESOURCE markers\n\
00190 string mesh_resource\n\
00191 bool mesh_use_embedded_materials\n\
00192 \n\
00193 ================================================================================\n\
00194 MSG: std_msgs/Header\n\
00195 # Standard metadata for higher-level stamped data types.\n\
00196 # This is generally used to communicate timestamped data \n\
00197 # in a particular coordinate frame.\n\
00198 # \n\
00199 # sequence ID: consecutively increasing ID \n\
00200 uint32 seq\n\
00201 #Two-integer timestamp that is expressed as:\n\
00202 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00203 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00204 # time-handling sugar is provided by the client library\n\
00205 time stamp\n\
00206 #Frame this data is associated with\n\
00207 # 0: no frame\n\
00208 # 1: global frame\n\
00209 string frame_id\n\
00210 \n\
00211 ================================================================================\n\
00212 MSG: geometry_msgs/Pose\n\
00213 # A representation of pose in free space, composed of postion and orientation. \n\
00214 Point position\n\
00215 Quaternion orientation\n\
00216 \n\
00217 ================================================================================\n\
00218 MSG: geometry_msgs/Point\n\
00219 # This contains the position of a point in free space\n\
00220 float64 x\n\
00221 float64 y\n\
00222 float64 z\n\
00223 \n\
00224 ================================================================================\n\
00225 MSG: geometry_msgs/Quaternion\n\
00226 # This represents an orientation in free space in quaternion form.\n\
00227 \n\
00228 float64 x\n\
00229 float64 y\n\
00230 float64 z\n\
00231 float64 w\n\
00232 \n\
00233 ================================================================================\n\
00234 MSG: geometry_msgs/Vector3\n\
00235 # This represents a vector in free space. \n\
00236 \n\
00237 float64 x\n\
00238 float64 y\n\
00239 float64 z\n\
00240 ================================================================================\n\
00241 MSG: std_msgs/ColorRGBA\n\
00242 float32 r\n\
00243 float32 g\n\
00244 float32 b\n\
00245 float32 a\n\
00246 \n\
00247 "; }
00248 public:
00249 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00250
00251 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00252
00253 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00254 {
00255 ros::serialization::OStream stream(write_ptr, 1000000000);
00256 ros::serialization::serialize(stream, header);
00257 ros::serialization::serialize(stream, ns);
00258 ros::serialization::serialize(stream, id);
00259 ros::serialization::serialize(stream, type);
00260 ros::serialization::serialize(stream, action);
00261 ros::serialization::serialize(stream, pose);
00262 ros::serialization::serialize(stream, scale);
00263 ros::serialization::serialize(stream, color);
00264 ros::serialization::serialize(stream, lifetime);
00265 ros::serialization::serialize(stream, frame_locked);
00266 ros::serialization::serialize(stream, points);
00267 ros::serialization::serialize(stream, colors);
00268 ros::serialization::serialize(stream, text);
00269 ros::serialization::serialize(stream, mesh_resource);
00270 ros::serialization::serialize(stream, mesh_use_embedded_materials);
00271 return stream.getData();
00272 }
00273
00274 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00275 {
00276 ros::serialization::IStream stream(read_ptr, 1000000000);
00277 ros::serialization::deserialize(stream, header);
00278 ros::serialization::deserialize(stream, ns);
00279 ros::serialization::deserialize(stream, id);
00280 ros::serialization::deserialize(stream, type);
00281 ros::serialization::deserialize(stream, action);
00282 ros::serialization::deserialize(stream, pose);
00283 ros::serialization::deserialize(stream, scale);
00284 ros::serialization::deserialize(stream, color);
00285 ros::serialization::deserialize(stream, lifetime);
00286 ros::serialization::deserialize(stream, frame_locked);
00287 ros::serialization::deserialize(stream, points);
00288 ros::serialization::deserialize(stream, colors);
00289 ros::serialization::deserialize(stream, text);
00290 ros::serialization::deserialize(stream, mesh_resource);
00291 ros::serialization::deserialize(stream, mesh_use_embedded_materials);
00292 return stream.getData();
00293 }
00294
00295 ROS_DEPRECATED virtual uint32_t serializationLength() const
00296 {
00297 uint32_t size = 0;
00298 size += ros::serialization::serializationLength(header);
00299 size += ros::serialization::serializationLength(ns);
00300 size += ros::serialization::serializationLength(id);
00301 size += ros::serialization::serializationLength(type);
00302 size += ros::serialization::serializationLength(action);
00303 size += ros::serialization::serializationLength(pose);
00304 size += ros::serialization::serializationLength(scale);
00305 size += ros::serialization::serializationLength(color);
00306 size += ros::serialization::serializationLength(lifetime);
00307 size += ros::serialization::serializationLength(frame_locked);
00308 size += ros::serialization::serializationLength(points);
00309 size += ros::serialization::serializationLength(colors);
00310 size += ros::serialization::serializationLength(text);
00311 size += ros::serialization::serializationLength(mesh_resource);
00312 size += ros::serialization::serializationLength(mesh_use_embedded_materials);
00313 return size;
00314 }
00315
00316 typedef boost::shared_ptr< ::visualization_msgs::Marker_<ContainerAllocator> > Ptr;
00317 typedef boost::shared_ptr< ::visualization_msgs::Marker_<ContainerAllocator> const> ConstPtr;
00318 };
00319 typedef ::visualization_msgs::Marker_<std::allocator<void> > Marker;
00320
00321 typedef boost::shared_ptr< ::visualization_msgs::Marker> MarkerPtr;
00322 typedef boost::shared_ptr< ::visualization_msgs::Marker const> MarkerConstPtr;
00323
00324
00325 template<typename ContainerAllocator>
00326 std::ostream& operator<<(std::ostream& s, const ::visualization_msgs::Marker_<ContainerAllocator> & v)
00327 {
00328 ros::message_operations::Printer< ::visualization_msgs::Marker_<ContainerAllocator> >::stream(s, "", v);
00329 return s;}
00330
00331 }
00332
00333 namespace ros
00334 {
00335 namespace message_traits
00336 {
00337 template<class ContainerAllocator>
00338 struct MD5Sum< ::visualization_msgs::Marker_<ContainerAllocator> > {
00339 static const char* value()
00340 {
00341 return "bc7602ad2ba78f4cbe1c23250683bdc0";
00342 }
00343
00344 static const char* value(const ::visualization_msgs::Marker_<ContainerAllocator> &) { return value(); }
00345 static const uint64_t static_value1 = 0xbc7602ad2ba78f4cULL;
00346 static const uint64_t static_value2 = 0xbe1c23250683bdc0ULL;
00347 };
00348
00349 template<class ContainerAllocator>
00350 struct DataType< ::visualization_msgs::Marker_<ContainerAllocator> > {
00351 static const char* value()
00352 {
00353 return "visualization_msgs/Marker";
00354 }
00355
00356 static const char* value(const ::visualization_msgs::Marker_<ContainerAllocator> &) { return value(); }
00357 };
00358
00359 template<class ContainerAllocator>
00360 struct Definition< ::visualization_msgs::Marker_<ContainerAllocator> > {
00361 static const char* value()
00362 {
00363 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\
00364 \n\
00365 byte ARROW=0\n\
00366 byte CUBE=1\n\
00367 byte SPHERE=2\n\
00368 byte CYLINDER=3\n\
00369 byte LINE_STRIP=4\n\
00370 byte LINE_LIST=5\n\
00371 byte CUBE_LIST=6\n\
00372 byte SPHERE_LIST=7\n\
00373 byte POINTS=8\n\
00374 byte TEXT_VIEW_FACING=9\n\
00375 byte MESH_RESOURCE=10\n\
00376 byte TRIANGLE_LIST=11\n\
00377 \n\
00378 byte ADD=0\n\
00379 byte MODIFY=0\n\
00380 byte DELETE=2\n\
00381 \n\
00382 Header header # header for time/frame information\n\
00383 string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object\n\
00384 int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later\n\
00385 int32 type # Type of object\n\
00386 int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object\n\
00387 geometry_msgs/Pose pose # Pose of the object\n\
00388 geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square)\n\
00389 std_msgs/ColorRGBA color # Color [0.0-1.0]\n\
00390 duration lifetime # How long the object should last before being automatically deleted. 0 means forever\n\
00391 bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep\n\
00392 \n\
00393 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\n\
00394 geometry_msgs/Point[] points\n\
00395 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\n\
00396 #number of colors must either be 0 or equal to the number of points\n\
00397 #NOTE: alpha is not yet used\n\
00398 std_msgs/ColorRGBA[] colors\n\
00399 \n\
00400 # NOTE: only used for text markers\n\
00401 string text\n\
00402 \n\
00403 # NOTE: only used for MESH_RESOURCE markers\n\
00404 string mesh_resource\n\
00405 bool mesh_use_embedded_materials\n\
00406 \n\
00407 ================================================================================\n\
00408 MSG: std_msgs/Header\n\
00409 # Standard metadata for higher-level stamped data types.\n\
00410 # This is generally used to communicate timestamped data \n\
00411 # in a particular coordinate frame.\n\
00412 # \n\
00413 # sequence ID: consecutively increasing ID \n\
00414 uint32 seq\n\
00415 #Two-integer timestamp that is expressed as:\n\
00416 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00417 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00418 # time-handling sugar is provided by the client library\n\
00419 time stamp\n\
00420 #Frame this data is associated with\n\
00421 # 0: no frame\n\
00422 # 1: global frame\n\
00423 string frame_id\n\
00424 \n\
00425 ================================================================================\n\
00426 MSG: geometry_msgs/Pose\n\
00427 # A representation of pose in free space, composed of postion and orientation. \n\
00428 Point position\n\
00429 Quaternion orientation\n\
00430 \n\
00431 ================================================================================\n\
00432 MSG: geometry_msgs/Point\n\
00433 # This contains the position of a point in free space\n\
00434 float64 x\n\
00435 float64 y\n\
00436 float64 z\n\
00437 \n\
00438 ================================================================================\n\
00439 MSG: geometry_msgs/Quaternion\n\
00440 # This represents an orientation in free space in quaternion form.\n\
00441 \n\
00442 float64 x\n\
00443 float64 y\n\
00444 float64 z\n\
00445 float64 w\n\
00446 \n\
00447 ================================================================================\n\
00448 MSG: geometry_msgs/Vector3\n\
00449 # This represents a vector in free space. \n\
00450 \n\
00451 float64 x\n\
00452 float64 y\n\
00453 float64 z\n\
00454 ================================================================================\n\
00455 MSG: std_msgs/ColorRGBA\n\
00456 float32 r\n\
00457 float32 g\n\
00458 float32 b\n\
00459 float32 a\n\
00460 \n\
00461 ";
00462 }
00463
00464 static const char* value(const ::visualization_msgs::Marker_<ContainerAllocator> &) { return value(); }
00465 };
00466
00467 template<class ContainerAllocator> struct HasHeader< ::visualization_msgs::Marker_<ContainerAllocator> > : public TrueType {};
00468 template<class ContainerAllocator> struct HasHeader< const ::visualization_msgs::Marker_<ContainerAllocator> > : public TrueType {};
00469 }
00470 }
00471
00472 namespace ros
00473 {
00474 namespace serialization
00475 {
00476
00477 template<class ContainerAllocator> struct Serializer< ::visualization_msgs::Marker_<ContainerAllocator> >
00478 {
00479 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00480 {
00481 stream.next(m.header);
00482 stream.next(m.ns);
00483 stream.next(m.id);
00484 stream.next(m.type);
00485 stream.next(m.action);
00486 stream.next(m.pose);
00487 stream.next(m.scale);
00488 stream.next(m.color);
00489 stream.next(m.lifetime);
00490 stream.next(m.frame_locked);
00491 stream.next(m.points);
00492 stream.next(m.colors);
00493 stream.next(m.text);
00494 stream.next(m.mesh_resource);
00495 stream.next(m.mesh_use_embedded_materials);
00496 }
00497
00498 ROS_DECLARE_ALLINONE_SERIALIZER;
00499 };
00500 }
00501 }
00502
00503 namespace ros
00504 {
00505 namespace message_operations
00506 {
00507
00508 template<class ContainerAllocator>
00509 struct Printer< ::visualization_msgs::Marker_<ContainerAllocator> >
00510 {
00511 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::visualization_msgs::Marker_<ContainerAllocator> & v)
00512 {
00513 s << indent << "header: ";
00514 s << std::endl;
00515 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00516 s << indent << "ns: ";
00517 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.ns);
00518 s << indent << "id: ";
00519 Printer<int32_t>::stream(s, indent + " ", v.id);
00520 s << indent << "type: ";
00521 Printer<int32_t>::stream(s, indent + " ", v.type);
00522 s << indent << "action: ";
00523 Printer<int32_t>::stream(s, indent + " ", v.action);
00524 s << indent << "pose: ";
00525 s << std::endl;
00526 Printer< ::geometry_msgs::Pose_<ContainerAllocator> >::stream(s, indent + " ", v.pose);
00527 s << indent << "scale: ";
00528 s << std::endl;
00529 Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + " ", v.scale);
00530 s << indent << "color: ";
00531 s << std::endl;
00532 Printer< ::std_msgs::ColorRGBA_<ContainerAllocator> >::stream(s, indent + " ", v.color);
00533 s << indent << "lifetime: ";
00534 Printer<ros::Duration>::stream(s, indent + " ", v.lifetime);
00535 s << indent << "frame_locked: ";
00536 Printer<uint8_t>::stream(s, indent + " ", v.frame_locked);
00537 s << indent << "points[]" << std::endl;
00538 for (size_t i = 0; i < v.points.size(); ++i)
00539 {
00540 s << indent << " points[" << i << "]: ";
00541 s << std::endl;
00542 s << indent;
00543 Printer< ::geometry_msgs::Point_<ContainerAllocator> >::stream(s, indent + " ", v.points[i]);
00544 }
00545 s << indent << "colors[]" << std::endl;
00546 for (size_t i = 0; i < v.colors.size(); ++i)
00547 {
00548 s << indent << " colors[" << i << "]: ";
00549 s << std::endl;
00550 s << indent;
00551 Printer< ::std_msgs::ColorRGBA_<ContainerAllocator> >::stream(s, indent + " ", v.colors[i]);
00552 }
00553 s << indent << "text: ";
00554 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.text);
00555 s << indent << "mesh_resource: ";
00556 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.mesh_resource);
00557 s << indent << "mesh_use_embedded_materials: ";
00558 Printer<uint8_t>::stream(s, indent + " ", v.mesh_use_embedded_materials);
00559 }
00560 };
00561
00562
00563 }
00564 }
00565
00566 #endif // VISUALIZATION_MSGS_MESSAGE_MARKER_H
00567