$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-common_msgs/doc_stacks/2013-03-01_14-58-52.505545/common_msgs/visualization_msgs/msg/InteractiveMarkerControl.msg */ 00002 #ifndef VISUALIZATION_MSGS_MESSAGE_INTERACTIVEMARKERCONTROL_H 00003 #define VISUALIZATION_MSGS_MESSAGE_INTERACTIVEMARKERCONTROL_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 "geometry_msgs/Quaternion.h" 00018 #include "visualization_msgs/Marker.h" 00019 00020 namespace visualization_msgs 00021 { 00022 template <class ContainerAllocator> 00023 struct InteractiveMarkerControl_ { 00024 typedef InteractiveMarkerControl_<ContainerAllocator> Type; 00025 00026 InteractiveMarkerControl_() 00027 : name() 00028 , orientation() 00029 , orientation_mode(0) 00030 , interaction_mode(0) 00031 , always_visible(false) 00032 , markers() 00033 , independent_marker_orientation(false) 00034 , description() 00035 { 00036 } 00037 00038 InteractiveMarkerControl_(const ContainerAllocator& _alloc) 00039 : name(_alloc) 00040 , orientation(_alloc) 00041 , orientation_mode(0) 00042 , interaction_mode(0) 00043 , always_visible(false) 00044 , markers(_alloc) 00045 , independent_marker_orientation(false) 00046 , description(_alloc) 00047 { 00048 } 00049 00050 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _name_type; 00051 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > name; 00052 00053 typedef ::geometry_msgs::Quaternion_<ContainerAllocator> _orientation_type; 00054 ::geometry_msgs::Quaternion_<ContainerAllocator> orientation; 00055 00056 typedef uint8_t _orientation_mode_type; 00057 uint8_t orientation_mode; 00058 00059 typedef uint8_t _interaction_mode_type; 00060 uint8_t interaction_mode; 00061 00062 typedef uint8_t _always_visible_type; 00063 uint8_t always_visible; 00064 00065 typedef std::vector< ::visualization_msgs::Marker_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::visualization_msgs::Marker_<ContainerAllocator> >::other > _markers_type; 00066 std::vector< ::visualization_msgs::Marker_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::visualization_msgs::Marker_<ContainerAllocator> >::other > markers; 00067 00068 typedef uint8_t _independent_marker_orientation_type; 00069 uint8_t independent_marker_orientation; 00070 00071 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _description_type; 00072 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > description; 00073 00074 enum { INHERIT = 0 }; 00075 enum { FIXED = 1 }; 00076 enum { VIEW_FACING = 2 }; 00077 enum { NONE = 0 }; 00078 enum { MENU = 1 }; 00079 enum { BUTTON = 2 }; 00080 enum { MOVE_AXIS = 3 }; 00081 enum { MOVE_PLANE = 4 }; 00082 enum { ROTATE_AXIS = 5 }; 00083 enum { MOVE_ROTATE = 6 }; 00084 00085 ROS_DEPRECATED uint32_t get_markers_size() const { return (uint32_t)markers.size(); } 00086 ROS_DEPRECATED void set_markers_size(uint32_t size) { markers.resize((size_t)size); } 00087 ROS_DEPRECATED void get_markers_vec(std::vector< ::visualization_msgs::Marker_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::visualization_msgs::Marker_<ContainerAllocator> >::other > & vec) const { vec = this->markers; } 00088 ROS_DEPRECATED void set_markers_vec(const std::vector< ::visualization_msgs::Marker_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::visualization_msgs::Marker_<ContainerAllocator> >::other > & vec) { this->markers = vec; } 00089 private: 00090 static const char* __s_getDataType_() { return "visualization_msgs/InteractiveMarkerControl"; } 00091 public: 00092 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00093 00094 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00095 00096 private: 00097 static const char* __s_getMD5Sum_() { return "f69c49e4eb251b5b0a89651eebf5a277"; } 00098 public: 00099 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00100 00101 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00102 00103 private: 00104 static const char* __s_getMessageDefinition_() { return "# Represents a control that is to be displayed together with an interactive marker\n\ 00105 \n\ 00106 # Identifying string for this control.\n\ 00107 # You need to assign a unique value to this to receive feedback from the GUI\n\ 00108 # on what actions the user performs on this control (e.g. a button click).\n\ 00109 string name\n\ 00110 \n\ 00111 \n\ 00112 # Defines the local coordinate frame (relative to the pose of the parent\n\ 00113 # interactive marker) in which is being rotated and translated.\n\ 00114 # Default: Identity\n\ 00115 geometry_msgs/Quaternion orientation\n\ 00116 \n\ 00117 \n\ 00118 # Orientation mode: controls how orientation changes.\n\ 00119 # INHERIT: Follow orientation of interactive marker\n\ 00120 # FIXED: Keep orientation fixed at initial state\n\ 00121 # VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up).\n\ 00122 uint8 INHERIT = 0 \n\ 00123 uint8 FIXED = 1\n\ 00124 uint8 VIEW_FACING = 2\n\ 00125 \n\ 00126 uint8 orientation_mode\n\ 00127 \n\ 00128 # Interaction mode for this control\n\ 00129 # \n\ 00130 # NONE: This control is only meant for visualization; no context menu.\n\ 00131 # MENU: Like NONE, but right-click menu is active.\n\ 00132 # BUTTON: Element can be left-clicked.\n\ 00133 # MOVE_AXIS: Translate along local x-axis.\n\ 00134 # MOVE_PLANE: Translate in local y-z plane.\n\ 00135 # ROTATE_AXIS: Rotate around local x-axis.\n\ 00136 # MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS.\n\ 00137 uint8 NONE = 0 \n\ 00138 uint8 MENU = 1\n\ 00139 uint8 BUTTON = 2\n\ 00140 uint8 MOVE_AXIS = 3 \n\ 00141 uint8 MOVE_PLANE = 4\n\ 00142 uint8 ROTATE_AXIS = 5\n\ 00143 uint8 MOVE_ROTATE = 6\n\ 00144 \n\ 00145 uint8 interaction_mode\n\ 00146 \n\ 00147 \n\ 00148 # If true, the contained markers will also be visible\n\ 00149 # when the gui is not in interactive mode.\n\ 00150 bool always_visible\n\ 00151 \n\ 00152 \n\ 00153 # Markers to be displayed as custom visual representation.\n\ 00154 # Leave this empty to use the default control handles.\n\ 00155 #\n\ 00156 # Note: \n\ 00157 # - The markers can be defined in an arbitrary coordinate frame,\n\ 00158 # but will be transformed into the local frame of the interactive marker.\n\ 00159 # - If the header of a marker is empty, its pose will be interpreted as \n\ 00160 # relative to the pose of the parent interactive marker.\n\ 00161 Marker[] markers\n\ 00162 \n\ 00163 \n\ 00164 # In VIEW_FACING mode, set this to true if you don't want the markers\n\ 00165 # to be aligned with the camera view point. The markers will show up\n\ 00166 # as in INHERIT mode.\n\ 00167 bool independent_marker_orientation\n\ 00168 \n\ 00169 \n\ 00170 # Short description (< 40 characters) of what this control does,\n\ 00171 # e.g. \"Move the robot\". \n\ 00172 # Default: A generic description based on the interaction mode\n\ 00173 string description\n\ 00174 \n\ 00175 ================================================================================\n\ 00176 MSG: geometry_msgs/Quaternion\n\ 00177 # This represents an orientation in free space in quaternion form.\n\ 00178 \n\ 00179 float64 x\n\ 00180 float64 y\n\ 00181 float64 z\n\ 00182 float64 w\n\ 00183 \n\ 00184 ================================================================================\n\ 00185 MSG: visualization_msgs/Marker\n\ 00186 # 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\ 00187 \n\ 00188 uint8 ARROW=0\n\ 00189 uint8 CUBE=1\n\ 00190 uint8 SPHERE=2\n\ 00191 uint8 CYLINDER=3\n\ 00192 uint8 LINE_STRIP=4\n\ 00193 uint8 LINE_LIST=5\n\ 00194 uint8 CUBE_LIST=6\n\ 00195 uint8 SPHERE_LIST=7\n\ 00196 uint8 POINTS=8\n\ 00197 uint8 TEXT_VIEW_FACING=9\n\ 00198 uint8 MESH_RESOURCE=10\n\ 00199 uint8 TRIANGLE_LIST=11\n\ 00200 \n\ 00201 uint8 ADD=0\n\ 00202 uint8 MODIFY=0\n\ 00203 uint8 DELETE=2\n\ 00204 \n\ 00205 Header header # header for time/frame information\n\ 00206 string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object\n\ 00207 int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later\n\ 00208 int32 type # Type of object\n\ 00209 int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object\n\ 00210 geometry_msgs/Pose pose # Pose of the object\n\ 00211 geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square)\n\ 00212 std_msgs/ColorRGBA color # Color [0.0-1.0]\n\ 00213 duration lifetime # How long the object should last before being automatically deleted. 0 means forever\n\ 00214 bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep\n\ 00215 \n\ 00216 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\n\ 00217 geometry_msgs/Point[] points\n\ 00218 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\n\ 00219 #number of colors must either be 0 or equal to the number of points\n\ 00220 #NOTE: alpha is not yet used\n\ 00221 std_msgs/ColorRGBA[] colors\n\ 00222 \n\ 00223 # NOTE: only used for text markers\n\ 00224 string text\n\ 00225 \n\ 00226 # NOTE: only used for MESH_RESOURCE markers\n\ 00227 string mesh_resource\n\ 00228 bool mesh_use_embedded_materials\n\ 00229 \n\ 00230 ================================================================================\n\ 00231 MSG: std_msgs/Header\n\ 00232 # Standard metadata for higher-level stamped data types.\n\ 00233 # This is generally used to communicate timestamped data \n\ 00234 # in a particular coordinate frame.\n\ 00235 # \n\ 00236 # sequence ID: consecutively increasing ID \n\ 00237 uint32 seq\n\ 00238 #Two-integer timestamp that is expressed as:\n\ 00239 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00240 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00241 # time-handling sugar is provided by the client library\n\ 00242 time stamp\n\ 00243 #Frame this data is associated with\n\ 00244 # 0: no frame\n\ 00245 # 1: global frame\n\ 00246 string frame_id\n\ 00247 \n\ 00248 ================================================================================\n\ 00249 MSG: geometry_msgs/Pose\n\ 00250 # A representation of pose in free space, composed of postion and orientation. \n\ 00251 Point position\n\ 00252 Quaternion orientation\n\ 00253 \n\ 00254 ================================================================================\n\ 00255 MSG: geometry_msgs/Point\n\ 00256 # This contains the position of a point in free space\n\ 00257 float64 x\n\ 00258 float64 y\n\ 00259 float64 z\n\ 00260 \n\ 00261 ================================================================================\n\ 00262 MSG: geometry_msgs/Vector3\n\ 00263 # This represents a vector in free space. \n\ 00264 \n\ 00265 float64 x\n\ 00266 float64 y\n\ 00267 float64 z\n\ 00268 ================================================================================\n\ 00269 MSG: std_msgs/ColorRGBA\n\ 00270 float32 r\n\ 00271 float32 g\n\ 00272 float32 b\n\ 00273 float32 a\n\ 00274 \n\ 00275 "; } 00276 public: 00277 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00278 00279 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00280 00281 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00282 { 00283 ros::serialization::OStream stream(write_ptr, 1000000000); 00284 ros::serialization::serialize(stream, name); 00285 ros::serialization::serialize(stream, orientation); 00286 ros::serialization::serialize(stream, orientation_mode); 00287 ros::serialization::serialize(stream, interaction_mode); 00288 ros::serialization::serialize(stream, always_visible); 00289 ros::serialization::serialize(stream, markers); 00290 ros::serialization::serialize(stream, independent_marker_orientation); 00291 ros::serialization::serialize(stream, description); 00292 return stream.getData(); 00293 } 00294 00295 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00296 { 00297 ros::serialization::IStream stream(read_ptr, 1000000000); 00298 ros::serialization::deserialize(stream, name); 00299 ros::serialization::deserialize(stream, orientation); 00300 ros::serialization::deserialize(stream, orientation_mode); 00301 ros::serialization::deserialize(stream, interaction_mode); 00302 ros::serialization::deserialize(stream, always_visible); 00303 ros::serialization::deserialize(stream, markers); 00304 ros::serialization::deserialize(stream, independent_marker_orientation); 00305 ros::serialization::deserialize(stream, description); 00306 return stream.getData(); 00307 } 00308 00309 ROS_DEPRECATED virtual uint32_t serializationLength() const 00310 { 00311 uint32_t size = 0; 00312 size += ros::serialization::serializationLength(name); 00313 size += ros::serialization::serializationLength(orientation); 00314 size += ros::serialization::serializationLength(orientation_mode); 00315 size += ros::serialization::serializationLength(interaction_mode); 00316 size += ros::serialization::serializationLength(always_visible); 00317 size += ros::serialization::serializationLength(markers); 00318 size += ros::serialization::serializationLength(independent_marker_orientation); 00319 size += ros::serialization::serializationLength(description); 00320 return size; 00321 } 00322 00323 typedef boost::shared_ptr< ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator> > Ptr; 00324 typedef boost::shared_ptr< ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator> const> ConstPtr; 00325 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00326 }; // struct InteractiveMarkerControl 00327 typedef ::visualization_msgs::InteractiveMarkerControl_<std::allocator<void> > InteractiveMarkerControl; 00328 00329 typedef boost::shared_ptr< ::visualization_msgs::InteractiveMarkerControl> InteractiveMarkerControlPtr; 00330 typedef boost::shared_ptr< ::visualization_msgs::InteractiveMarkerControl const> InteractiveMarkerControlConstPtr; 00331 00332 00333 template<typename ContainerAllocator> 00334 std::ostream& operator<<(std::ostream& s, const ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator> & v) 00335 { 00336 ros::message_operations::Printer< ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator> >::stream(s, "", v); 00337 return s;} 00338 00339 } // namespace visualization_msgs 00340 00341 namespace ros 00342 { 00343 namespace message_traits 00344 { 00345 template<class ContainerAllocator> struct IsMessage< ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator> > : public TrueType {}; 00346 template<class ContainerAllocator> struct IsMessage< ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator> const> : public TrueType {}; 00347 template<class ContainerAllocator> 00348 struct MD5Sum< ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator> > { 00349 static const char* value() 00350 { 00351 return "f69c49e4eb251b5b0a89651eebf5a277"; 00352 } 00353 00354 static const char* value(const ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator> &) { return value(); } 00355 static const uint64_t static_value1 = 0xf69c49e4eb251b5bULL; 00356 static const uint64_t static_value2 = 0x0a89651eebf5a277ULL; 00357 }; 00358 00359 template<class ContainerAllocator> 00360 struct DataType< ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator> > { 00361 static const char* value() 00362 { 00363 return "visualization_msgs/InteractiveMarkerControl"; 00364 } 00365 00366 static const char* value(const ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator> &) { return value(); } 00367 }; 00368 00369 template<class ContainerAllocator> 00370 struct Definition< ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator> > { 00371 static const char* value() 00372 { 00373 return "# Represents a control that is to be displayed together with an interactive marker\n\ 00374 \n\ 00375 # Identifying string for this control.\n\ 00376 # You need to assign a unique value to this to receive feedback from the GUI\n\ 00377 # on what actions the user performs on this control (e.g. a button click).\n\ 00378 string name\n\ 00379 \n\ 00380 \n\ 00381 # Defines the local coordinate frame (relative to the pose of the parent\n\ 00382 # interactive marker) in which is being rotated and translated.\n\ 00383 # Default: Identity\n\ 00384 geometry_msgs/Quaternion orientation\n\ 00385 \n\ 00386 \n\ 00387 # Orientation mode: controls how orientation changes.\n\ 00388 # INHERIT: Follow orientation of interactive marker\n\ 00389 # FIXED: Keep orientation fixed at initial state\n\ 00390 # VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up).\n\ 00391 uint8 INHERIT = 0 \n\ 00392 uint8 FIXED = 1\n\ 00393 uint8 VIEW_FACING = 2\n\ 00394 \n\ 00395 uint8 orientation_mode\n\ 00396 \n\ 00397 # Interaction mode for this control\n\ 00398 # \n\ 00399 # NONE: This control is only meant for visualization; no context menu.\n\ 00400 # MENU: Like NONE, but right-click menu is active.\n\ 00401 # BUTTON: Element can be left-clicked.\n\ 00402 # MOVE_AXIS: Translate along local x-axis.\n\ 00403 # MOVE_PLANE: Translate in local y-z plane.\n\ 00404 # ROTATE_AXIS: Rotate around local x-axis.\n\ 00405 # MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS.\n\ 00406 uint8 NONE = 0 \n\ 00407 uint8 MENU = 1\n\ 00408 uint8 BUTTON = 2\n\ 00409 uint8 MOVE_AXIS = 3 \n\ 00410 uint8 MOVE_PLANE = 4\n\ 00411 uint8 ROTATE_AXIS = 5\n\ 00412 uint8 MOVE_ROTATE = 6\n\ 00413 \n\ 00414 uint8 interaction_mode\n\ 00415 \n\ 00416 \n\ 00417 # If true, the contained markers will also be visible\n\ 00418 # when the gui is not in interactive mode.\n\ 00419 bool always_visible\n\ 00420 \n\ 00421 \n\ 00422 # Markers to be displayed as custom visual representation.\n\ 00423 # Leave this empty to use the default control handles.\n\ 00424 #\n\ 00425 # Note: \n\ 00426 # - The markers can be defined in an arbitrary coordinate frame,\n\ 00427 # but will be transformed into the local frame of the interactive marker.\n\ 00428 # - If the header of a marker is empty, its pose will be interpreted as \n\ 00429 # relative to the pose of the parent interactive marker.\n\ 00430 Marker[] markers\n\ 00431 \n\ 00432 \n\ 00433 # In VIEW_FACING mode, set this to true if you don't want the markers\n\ 00434 # to be aligned with the camera view point. The markers will show up\n\ 00435 # as in INHERIT mode.\n\ 00436 bool independent_marker_orientation\n\ 00437 \n\ 00438 \n\ 00439 # Short description (< 40 characters) of what this control does,\n\ 00440 # e.g. \"Move the robot\". \n\ 00441 # Default: A generic description based on the interaction mode\n\ 00442 string description\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: visualization_msgs/Marker\n\ 00455 # 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\ 00456 \n\ 00457 uint8 ARROW=0\n\ 00458 uint8 CUBE=1\n\ 00459 uint8 SPHERE=2\n\ 00460 uint8 CYLINDER=3\n\ 00461 uint8 LINE_STRIP=4\n\ 00462 uint8 LINE_LIST=5\n\ 00463 uint8 CUBE_LIST=6\n\ 00464 uint8 SPHERE_LIST=7\n\ 00465 uint8 POINTS=8\n\ 00466 uint8 TEXT_VIEW_FACING=9\n\ 00467 uint8 MESH_RESOURCE=10\n\ 00468 uint8 TRIANGLE_LIST=11\n\ 00469 \n\ 00470 uint8 ADD=0\n\ 00471 uint8 MODIFY=0\n\ 00472 uint8 DELETE=2\n\ 00473 \n\ 00474 Header header # header for time/frame information\n\ 00475 string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object\n\ 00476 int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later\n\ 00477 int32 type # Type of object\n\ 00478 int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object\n\ 00479 geometry_msgs/Pose pose # Pose of the object\n\ 00480 geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square)\n\ 00481 std_msgs/ColorRGBA color # Color [0.0-1.0]\n\ 00482 duration lifetime # How long the object should last before being automatically deleted. 0 means forever\n\ 00483 bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep\n\ 00484 \n\ 00485 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\n\ 00486 geometry_msgs/Point[] points\n\ 00487 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\n\ 00488 #number of colors must either be 0 or equal to the number of points\n\ 00489 #NOTE: alpha is not yet used\n\ 00490 std_msgs/ColorRGBA[] colors\n\ 00491 \n\ 00492 # NOTE: only used for text markers\n\ 00493 string text\n\ 00494 \n\ 00495 # NOTE: only used for MESH_RESOURCE markers\n\ 00496 string mesh_resource\n\ 00497 bool mesh_use_embedded_materials\n\ 00498 \n\ 00499 ================================================================================\n\ 00500 MSG: std_msgs/Header\n\ 00501 # Standard metadata for higher-level stamped data types.\n\ 00502 # This is generally used to communicate timestamped data \n\ 00503 # in a particular coordinate frame.\n\ 00504 # \n\ 00505 # sequence ID: consecutively increasing ID \n\ 00506 uint32 seq\n\ 00507 #Two-integer timestamp that is expressed as:\n\ 00508 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00509 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00510 # time-handling sugar is provided by the client library\n\ 00511 time stamp\n\ 00512 #Frame this data is associated with\n\ 00513 # 0: no frame\n\ 00514 # 1: global frame\n\ 00515 string frame_id\n\ 00516 \n\ 00517 ================================================================================\n\ 00518 MSG: geometry_msgs/Pose\n\ 00519 # A representation of pose in free space, composed of postion and orientation. \n\ 00520 Point position\n\ 00521 Quaternion orientation\n\ 00522 \n\ 00523 ================================================================================\n\ 00524 MSG: geometry_msgs/Point\n\ 00525 # This contains the position of a point in free space\n\ 00526 float64 x\n\ 00527 float64 y\n\ 00528 float64 z\n\ 00529 \n\ 00530 ================================================================================\n\ 00531 MSG: geometry_msgs/Vector3\n\ 00532 # This represents a vector in free space. \n\ 00533 \n\ 00534 float64 x\n\ 00535 float64 y\n\ 00536 float64 z\n\ 00537 ================================================================================\n\ 00538 MSG: std_msgs/ColorRGBA\n\ 00539 float32 r\n\ 00540 float32 g\n\ 00541 float32 b\n\ 00542 float32 a\n\ 00543 \n\ 00544 "; 00545 } 00546 00547 static const char* value(const ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator> &) { return value(); } 00548 }; 00549 00550 } // namespace message_traits 00551 } // namespace ros 00552 00553 namespace ros 00554 { 00555 namespace serialization 00556 { 00557 00558 template<class ContainerAllocator> struct Serializer< ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator> > 00559 { 00560 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00561 { 00562 stream.next(m.name); 00563 stream.next(m.orientation); 00564 stream.next(m.orientation_mode); 00565 stream.next(m.interaction_mode); 00566 stream.next(m.always_visible); 00567 stream.next(m.markers); 00568 stream.next(m.independent_marker_orientation); 00569 stream.next(m.description); 00570 } 00571 00572 ROS_DECLARE_ALLINONE_SERIALIZER; 00573 }; // struct InteractiveMarkerControl_ 00574 } // namespace serialization 00575 } // namespace ros 00576 00577 namespace ros 00578 { 00579 namespace message_operations 00580 { 00581 00582 template<class ContainerAllocator> 00583 struct Printer< ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator> > 00584 { 00585 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::visualization_msgs::InteractiveMarkerControl_<ContainerAllocator> & v) 00586 { 00587 s << indent << "name: "; 00588 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.name); 00589 s << indent << "orientation: "; 00590 s << std::endl; 00591 Printer< ::geometry_msgs::Quaternion_<ContainerAllocator> >::stream(s, indent + " ", v.orientation); 00592 s << indent << "orientation_mode: "; 00593 Printer<uint8_t>::stream(s, indent + " ", v.orientation_mode); 00594 s << indent << "interaction_mode: "; 00595 Printer<uint8_t>::stream(s, indent + " ", v.interaction_mode); 00596 s << indent << "always_visible: "; 00597 Printer<uint8_t>::stream(s, indent + " ", v.always_visible); 00598 s << indent << "markers[]" << std::endl; 00599 for (size_t i = 0; i < v.markers.size(); ++i) 00600 { 00601 s << indent << " markers[" << i << "]: "; 00602 s << std::endl; 00603 s << indent; 00604 Printer< ::visualization_msgs::Marker_<ContainerAllocator> >::stream(s, indent + " ", v.markers[i]); 00605 } 00606 s << indent << "independent_marker_orientation: "; 00607 Printer<uint8_t>::stream(s, indent + " ", v.independent_marker_orientation); 00608 s << indent << "description: "; 00609 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.description); 00610 } 00611 }; 00612 00613 00614 } // namespace message_operations 00615 } // namespace ros 00616 00617 #endif // VISUALIZATION_MSGS_MESSAGE_INTERACTIVEMARKERCONTROL_H 00618