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