00001 """autogenerated by genmsg_py from Marker.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import geometry_msgs.msg
00006 import roslib.rostime
00007 import std_msgs.msg
00008
00009 class Marker(roslib.message.Message):
00010 _md5sum = "bc7602ad2ba78f4cbe1c23250683bdc0"
00011 _type = "visualization_msgs/Marker"
00012 _has_header = True
00013 _full_text = """# 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
00014
00015 byte ARROW=0
00016 byte CUBE=1
00017 byte SPHERE=2
00018 byte CYLINDER=3
00019 byte LINE_STRIP=4
00020 byte LINE_LIST=5
00021 byte CUBE_LIST=6
00022 byte SPHERE_LIST=7
00023 byte POINTS=8
00024 byte TEXT_VIEW_FACING=9
00025 byte MESH_RESOURCE=10
00026 byte TRIANGLE_LIST=11
00027
00028 byte ADD=0
00029 byte MODIFY=0
00030 byte DELETE=2
00031
00032 Header header # header for time/frame information
00033 string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object
00034 int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later
00035 int32 type # Type of object
00036 int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object
00037 geometry_msgs/Pose pose # Pose of the object
00038 geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square)
00039 std_msgs/ColorRGBA color # Color [0.0-1.0]
00040 duration lifetime # How long the object should last before being automatically deleted. 0 means forever
00041 bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep
00042
00043 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)
00044 geometry_msgs/Point[] points
00045 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)
00046 #number of colors must either be 0 or equal to the number of points
00047 #NOTE: alpha is not yet used
00048 std_msgs/ColorRGBA[] colors
00049
00050 # NOTE: only used for text markers
00051 string text
00052
00053 # NOTE: only used for MESH_RESOURCE markers
00054 string mesh_resource
00055 bool mesh_use_embedded_materials
00056
00057 ================================================================================
00058 MSG: std_msgs/Header
00059 # Standard metadata for higher-level stamped data types.
00060 # This is generally used to communicate timestamped data
00061 # in a particular coordinate frame.
00062 #
00063 # sequence ID: consecutively increasing ID
00064 uint32 seq
00065 #Two-integer timestamp that is expressed as:
00066 # * stamp.secs: seconds (stamp_secs) since epoch
00067 # * stamp.nsecs: nanoseconds since stamp_secs
00068 # time-handling sugar is provided by the client library
00069 time stamp
00070 #Frame this data is associated with
00071 # 0: no frame
00072 # 1: global frame
00073 string frame_id
00074
00075 ================================================================================
00076 MSG: geometry_msgs/Pose
00077 # A representation of pose in free space, composed of postion and orientation.
00078 Point position
00079 Quaternion orientation
00080
00081 ================================================================================
00082 MSG: geometry_msgs/Point
00083 # This contains the position of a point in free space
00084 float64 x
00085 float64 y
00086 float64 z
00087
00088 ================================================================================
00089 MSG: geometry_msgs/Quaternion
00090 # This represents an orientation in free space in quaternion form.
00091
00092 float64 x
00093 float64 y
00094 float64 z
00095 float64 w
00096
00097 ================================================================================
00098 MSG: geometry_msgs/Vector3
00099 # This represents a vector in free space.
00100
00101 float64 x
00102 float64 y
00103 float64 z
00104 ================================================================================
00105 MSG: std_msgs/ColorRGBA
00106 float32 r
00107 float32 g
00108 float32 b
00109 float32 a
00110
00111 """
00112
00113 ARROW = 0
00114 CUBE = 1
00115 SPHERE = 2
00116 CYLINDER = 3
00117 LINE_STRIP = 4
00118 LINE_LIST = 5
00119 CUBE_LIST = 6
00120 SPHERE_LIST = 7
00121 POINTS = 8
00122 TEXT_VIEW_FACING = 9
00123 MESH_RESOURCE = 10
00124 TRIANGLE_LIST = 11
00125 ADD = 0
00126 MODIFY = 0
00127 DELETE = 2
00128
00129 __slots__ = ['header','ns','id','type','action','pose','scale','color','lifetime','frame_locked','points','colors','text','mesh_resource','mesh_use_embedded_materials']
00130 _slot_types = ['Header','string','int32','int32','int32','geometry_msgs/Pose','geometry_msgs/Vector3','std_msgs/ColorRGBA','duration','bool','geometry_msgs/Point[]','std_msgs/ColorRGBA[]','string','string','bool']
00131
00132 def __init__(self, *args, **kwds):
00133 """
00134 Constructor. Any message fields that are implicitly/explicitly
00135 set to None will be assigned a default value. The recommend
00136 use is keyword arguments as this is more robust to future message
00137 changes. You cannot mix in-order arguments and keyword arguments.
00138
00139 The available fields are:
00140 header,ns,id,type,action,pose,scale,color,lifetime,frame_locked,points,colors,text,mesh_resource,mesh_use_embedded_materials
00141
00142 @param args: complete set of field values, in .msg order
00143 @param kwds: use keyword arguments corresponding to message field names
00144 to set specific fields.
00145 """
00146 if args or kwds:
00147 super(Marker, self).__init__(*args, **kwds)
00148
00149 if self.header is None:
00150 self.header = std_msgs.msg._Header.Header()
00151 if self.ns is None:
00152 self.ns = ''
00153 if self.id is None:
00154 self.id = 0
00155 if self.type is None:
00156 self.type = 0
00157 if self.action is None:
00158 self.action = 0
00159 if self.pose is None:
00160 self.pose = geometry_msgs.msg.Pose()
00161 if self.scale is None:
00162 self.scale = geometry_msgs.msg.Vector3()
00163 if self.color is None:
00164 self.color = std_msgs.msg.ColorRGBA()
00165 if self.lifetime is None:
00166 self.lifetime = roslib.rostime.Duration()
00167 if self.frame_locked is None:
00168 self.frame_locked = False
00169 if self.points is None:
00170 self.points = []
00171 if self.colors is None:
00172 self.colors = []
00173 if self.text is None:
00174 self.text = ''
00175 if self.mesh_resource is None:
00176 self.mesh_resource = ''
00177 if self.mesh_use_embedded_materials is None:
00178 self.mesh_use_embedded_materials = False
00179 else:
00180 self.header = std_msgs.msg._Header.Header()
00181 self.ns = ''
00182 self.id = 0
00183 self.type = 0
00184 self.action = 0
00185 self.pose = geometry_msgs.msg.Pose()
00186 self.scale = geometry_msgs.msg.Vector3()
00187 self.color = std_msgs.msg.ColorRGBA()
00188 self.lifetime = roslib.rostime.Duration()
00189 self.frame_locked = False
00190 self.points = []
00191 self.colors = []
00192 self.text = ''
00193 self.mesh_resource = ''
00194 self.mesh_use_embedded_materials = False
00195
00196 def _get_types(self):
00197 """
00198 internal API method
00199 """
00200 return self._slot_types
00201
00202 def serialize(self, buff):
00203 """
00204 serialize message into buffer
00205 @param buff: buffer
00206 @type buff: StringIO
00207 """
00208 try:
00209 _x = self
00210 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00211 _x = self.header.frame_id
00212 length = len(_x)
00213 buff.write(struct.pack('<I%ss'%length, length, _x))
00214 _x = self.ns
00215 length = len(_x)
00216 buff.write(struct.pack('<I%ss'%length, length, _x))
00217 _x = self
00218 buff.write(_struct_3i10d4f2iB.pack(_x.id, _x.type, _x.action, _x.pose.position.x, _x.pose.position.y, _x.pose.position.z, _x.pose.orientation.x, _x.pose.orientation.y, _x.pose.orientation.z, _x.pose.orientation.w, _x.scale.x, _x.scale.y, _x.scale.z, _x.color.r, _x.color.g, _x.color.b, _x.color.a, _x.lifetime.secs, _x.lifetime.nsecs, _x.frame_locked))
00219 length = len(self.points)
00220 buff.write(_struct_I.pack(length))
00221 for val1 in self.points:
00222 _x = val1
00223 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00224 length = len(self.colors)
00225 buff.write(_struct_I.pack(length))
00226 for val1 in self.colors:
00227 _x = val1
00228 buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
00229 _x = self.text
00230 length = len(_x)
00231 buff.write(struct.pack('<I%ss'%length, length, _x))
00232 _x = self.mesh_resource
00233 length = len(_x)
00234 buff.write(struct.pack('<I%ss'%length, length, _x))
00235 buff.write(_struct_B.pack(self.mesh_use_embedded_materials))
00236 except struct.error, se: self._check_types(se)
00237 except TypeError, te: self._check_types(te)
00238
00239 def deserialize(self, str):
00240 """
00241 unpack serialized message in str into this message instance
00242 @param str: byte array of serialized message
00243 @type str: str
00244 """
00245 try:
00246 if self.header is None:
00247 self.header = std_msgs.msg._Header.Header()
00248 if self.pose is None:
00249 self.pose = geometry_msgs.msg.Pose()
00250 if self.scale is None:
00251 self.scale = geometry_msgs.msg.Vector3()
00252 if self.color is None:
00253 self.color = std_msgs.msg.ColorRGBA()
00254 if self.lifetime is None:
00255 self.lifetime = roslib.rostime.Duration()
00256 end = 0
00257 _x = self
00258 start = end
00259 end += 12
00260 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00261 start = end
00262 end += 4
00263 (length,) = _struct_I.unpack(str[start:end])
00264 start = end
00265 end += length
00266 self.header.frame_id = str[start:end]
00267 start = end
00268 end += 4
00269 (length,) = _struct_I.unpack(str[start:end])
00270 start = end
00271 end += length
00272 self.ns = str[start:end]
00273 _x = self
00274 start = end
00275 end += 117
00276 (_x.id, _x.type, _x.action, _x.pose.position.x, _x.pose.position.y, _x.pose.position.z, _x.pose.orientation.x, _x.pose.orientation.y, _x.pose.orientation.z, _x.pose.orientation.w, _x.scale.x, _x.scale.y, _x.scale.z, _x.color.r, _x.color.g, _x.color.b, _x.color.a, _x.lifetime.secs, _x.lifetime.nsecs, _x.frame_locked,) = _struct_3i10d4f2iB.unpack(str[start:end])
00277 self.frame_locked = bool(self.frame_locked)
00278 start = end
00279 end += 4
00280 (length,) = _struct_I.unpack(str[start:end])
00281 self.points = []
00282 for i in xrange(0, length):
00283 val1 = geometry_msgs.msg.Point()
00284 _x = val1
00285 start = end
00286 end += 24
00287 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00288 self.points.append(val1)
00289 start = end
00290 end += 4
00291 (length,) = _struct_I.unpack(str[start:end])
00292 self.colors = []
00293 for i in xrange(0, length):
00294 val1 = std_msgs.msg.ColorRGBA()
00295 _x = val1
00296 start = end
00297 end += 16
00298 (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
00299 self.colors.append(val1)
00300 start = end
00301 end += 4
00302 (length,) = _struct_I.unpack(str[start:end])
00303 start = end
00304 end += length
00305 self.text = str[start:end]
00306 start = end
00307 end += 4
00308 (length,) = _struct_I.unpack(str[start:end])
00309 start = end
00310 end += length
00311 self.mesh_resource = str[start:end]
00312 start = end
00313 end += 1
00314 (self.mesh_use_embedded_materials,) = _struct_B.unpack(str[start:end])
00315 self.mesh_use_embedded_materials = bool(self.mesh_use_embedded_materials)
00316 self.lifetime.canon()
00317 return self
00318 except struct.error, e:
00319 raise roslib.message.DeserializationError(e)
00320
00321
00322 def serialize_numpy(self, buff, numpy):
00323 """
00324 serialize message with numpy array types into buffer
00325 @param buff: buffer
00326 @type buff: StringIO
00327 @param numpy: numpy python module
00328 @type numpy module
00329 """
00330 try:
00331 _x = self
00332 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00333 _x = self.header.frame_id
00334 length = len(_x)
00335 buff.write(struct.pack('<I%ss'%length, length, _x))
00336 _x = self.ns
00337 length = len(_x)
00338 buff.write(struct.pack('<I%ss'%length, length, _x))
00339 _x = self
00340 buff.write(_struct_3i10d4f2iB.pack(_x.id, _x.type, _x.action, _x.pose.position.x, _x.pose.position.y, _x.pose.position.z, _x.pose.orientation.x, _x.pose.orientation.y, _x.pose.orientation.z, _x.pose.orientation.w, _x.scale.x, _x.scale.y, _x.scale.z, _x.color.r, _x.color.g, _x.color.b, _x.color.a, _x.lifetime.secs, _x.lifetime.nsecs, _x.frame_locked))
00341 length = len(self.points)
00342 buff.write(_struct_I.pack(length))
00343 for val1 in self.points:
00344 _x = val1
00345 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00346 length = len(self.colors)
00347 buff.write(_struct_I.pack(length))
00348 for val1 in self.colors:
00349 _x = val1
00350 buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
00351 _x = self.text
00352 length = len(_x)
00353 buff.write(struct.pack('<I%ss'%length, length, _x))
00354 _x = self.mesh_resource
00355 length = len(_x)
00356 buff.write(struct.pack('<I%ss'%length, length, _x))
00357 buff.write(_struct_B.pack(self.mesh_use_embedded_materials))
00358 except struct.error, se: self._check_types(se)
00359 except TypeError, te: self._check_types(te)
00360
00361 def deserialize_numpy(self, str, numpy):
00362 """
00363 unpack serialized message in str into this message instance using numpy for array types
00364 @param str: byte array of serialized message
00365 @type str: str
00366 @param numpy: numpy python module
00367 @type numpy: module
00368 """
00369 try:
00370 if self.header is None:
00371 self.header = std_msgs.msg._Header.Header()
00372 if self.pose is None:
00373 self.pose = geometry_msgs.msg.Pose()
00374 if self.scale is None:
00375 self.scale = geometry_msgs.msg.Vector3()
00376 if self.color is None:
00377 self.color = std_msgs.msg.ColorRGBA()
00378 if self.lifetime is None:
00379 self.lifetime = roslib.rostime.Duration()
00380 end = 0
00381 _x = self
00382 start = end
00383 end += 12
00384 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00385 start = end
00386 end += 4
00387 (length,) = _struct_I.unpack(str[start:end])
00388 start = end
00389 end += length
00390 self.header.frame_id = str[start:end]
00391 start = end
00392 end += 4
00393 (length,) = _struct_I.unpack(str[start:end])
00394 start = end
00395 end += length
00396 self.ns = str[start:end]
00397 _x = self
00398 start = end
00399 end += 117
00400 (_x.id, _x.type, _x.action, _x.pose.position.x, _x.pose.position.y, _x.pose.position.z, _x.pose.orientation.x, _x.pose.orientation.y, _x.pose.orientation.z, _x.pose.orientation.w, _x.scale.x, _x.scale.y, _x.scale.z, _x.color.r, _x.color.g, _x.color.b, _x.color.a, _x.lifetime.secs, _x.lifetime.nsecs, _x.frame_locked,) = _struct_3i10d4f2iB.unpack(str[start:end])
00401 self.frame_locked = bool(self.frame_locked)
00402 start = end
00403 end += 4
00404 (length,) = _struct_I.unpack(str[start:end])
00405 self.points = []
00406 for i in xrange(0, length):
00407 val1 = geometry_msgs.msg.Point()
00408 _x = val1
00409 start = end
00410 end += 24
00411 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00412 self.points.append(val1)
00413 start = end
00414 end += 4
00415 (length,) = _struct_I.unpack(str[start:end])
00416 self.colors = []
00417 for i in xrange(0, length):
00418 val1 = std_msgs.msg.ColorRGBA()
00419 _x = val1
00420 start = end
00421 end += 16
00422 (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
00423 self.colors.append(val1)
00424 start = end
00425 end += 4
00426 (length,) = _struct_I.unpack(str[start:end])
00427 start = end
00428 end += length
00429 self.text = str[start:end]
00430 start = end
00431 end += 4
00432 (length,) = _struct_I.unpack(str[start:end])
00433 start = end
00434 end += length
00435 self.mesh_resource = str[start:end]
00436 start = end
00437 end += 1
00438 (self.mesh_use_embedded_materials,) = _struct_B.unpack(str[start:end])
00439 self.mesh_use_embedded_materials = bool(self.mesh_use_embedded_materials)
00440 self.lifetime.canon()
00441 return self
00442 except struct.error, e:
00443 raise roslib.message.DeserializationError(e)
00444
00445 _struct_I = roslib.message.struct_I
00446 _struct_4f = struct.Struct("<4f")
00447 _struct_3I = struct.Struct("<3I")
00448 _struct_B = struct.Struct("<B")
00449 _struct_3i10d4f2iB = struct.Struct("<3i10d4f2iB")
00450 _struct_3d = struct.Struct("<3d")