00001 """autogenerated by genmsg_py from AttachedCollisionObject.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import mapping_msgs.msg
00006 import geometry_msgs.msg
00007 import geometric_shapes_msgs.msg
00008 import std_msgs.msg
00009
00010 class AttachedCollisionObject(roslib.message.Message):
00011 _md5sum = "58c7f119e35988da1dbd450c682308ed"
00012 _type = "mapping_msgs/AttachedCollisionObject"
00013 _has_header = False
00014 _full_text = """# The CollisionObject will be attached with a fixed joint to this link
00015 # If link name is set to REMOVE_ALL_ATTACHED_OBJECTS and object.operation
00016 # is set to REMOVE will remove all attached bodies attached to any object
00017 string link_name
00018
00019 #Reserved for indicating that all attached objects should be removed
00020 string REMOVE_ALL_ATTACHED_OBJECTS = "all"
00021
00022 #This contains the actual shapes and poses for the CollisionObject
00023 #to be attached to the link
00024 #If action is remove and no object.id is set, all objects
00025 #attached to the link indicated by link_name will be removed
00026 CollisionObject object
00027
00028 # The set of links that the attached objects are allowed to touch
00029 # by default - the link_name is included by default
00030 string[] touch_links
00031
00032 ================================================================================
00033 MSG: mapping_msgs/CollisionObject
00034 # a header, used for interpreting the poses
00035 Header header
00036
00037 # the id of the object
00038 string id
00039
00040 #This contains what is to be done with the object
00041 CollisionObjectOperation operation
00042
00043 #the shapes associated with the object
00044 geometric_shapes_msgs/Shape[] shapes
00045
00046 #the poses associated with the shapes - will be transformed using the header
00047 geometry_msgs/Pose[] poses
00048
00049 ================================================================================
00050 MSG: std_msgs/Header
00051 # Standard metadata for higher-level stamped data types.
00052 # This is generally used to communicate timestamped data
00053 # in a particular coordinate frame.
00054 #
00055 # sequence ID: consecutively increasing ID
00056 uint32 seq
00057 #Two-integer timestamp that is expressed as:
00058 # * stamp.secs: seconds (stamp_secs) since epoch
00059 # * stamp.nsecs: nanoseconds since stamp_secs
00060 # time-handling sugar is provided by the client library
00061 time stamp
00062 #Frame this data is associated with
00063 # 0: no frame
00064 # 1: global frame
00065 string frame_id
00066
00067 ================================================================================
00068 MSG: mapping_msgs/CollisionObjectOperation
00069 #Puts the object into the environment
00070 #or updates the object if already added
00071 byte ADD=0
00072
00073 #Removes the object from the environment entirely
00074 byte REMOVE=1
00075
00076 #Only valid within the context of a CollisionAttachedObject message
00077 #Will be ignored if sent with an CollisionObject message
00078 #Takes an attached object, detaches from the attached link
00079 #But adds back in as regular object
00080 byte DETACH_AND_ADD_AS_OBJECT=2
00081
00082 #Only valid within the context of a CollisionAttachedObject message
00083 #Will be ignored if sent with an CollisionObject message
00084 #Takes current object in the environment and removes it as
00085 #a regular object
00086 byte ATTACH_AND_REMOVE_AS_OBJECT=3
00087
00088 # Byte code for operation
00089 byte operation
00090
00091 ================================================================================
00092 MSG: geometric_shapes_msgs/Shape
00093 byte SPHERE=0
00094 byte BOX=1
00095 byte CYLINDER=2
00096 byte MESH=3
00097
00098 byte type
00099
00100
00101 #### define sphere, box, cylinder ####
00102 # the origin of each shape is considered at the shape's center
00103
00104 # for sphere
00105 # radius := dimensions[0]
00106
00107 # for cylinder
00108 # radius := dimensions[0]
00109 # length := dimensions[1]
00110 # the length is along the Z axis
00111
00112 # for box
00113 # size_x := dimensions[0]
00114 # size_y := dimensions[1]
00115 # size_z := dimensions[2]
00116 float64[] dimensions
00117
00118
00119 #### define mesh ####
00120
00121 # list of triangles; triangle k is defined by tre vertices located
00122 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00123 int32[] triangles
00124 geometry_msgs/Point[] vertices
00125
00126 ================================================================================
00127 MSG: geometry_msgs/Point
00128 # This contains the position of a point in free space
00129 float64 x
00130 float64 y
00131 float64 z
00132
00133 ================================================================================
00134 MSG: geometry_msgs/Pose
00135 # A representation of pose in free space, composed of postion and orientation.
00136 Point position
00137 Quaternion orientation
00138
00139 ================================================================================
00140 MSG: geometry_msgs/Quaternion
00141 # This represents an orientation in free space in quaternion form.
00142
00143 float64 x
00144 float64 y
00145 float64 z
00146 float64 w
00147
00148 """
00149
00150 REMOVE_ALL_ATTACHED_OBJECTS = r'"all"'
00151
00152 __slots__ = ['link_name','object','touch_links']
00153 _slot_types = ['string','mapping_msgs/CollisionObject','string[]']
00154
00155 def __init__(self, *args, **kwds):
00156 """
00157 Constructor. Any message fields that are implicitly/explicitly
00158 set to None will be assigned a default value. The recommend
00159 use is keyword arguments as this is more robust to future message
00160 changes. You cannot mix in-order arguments and keyword arguments.
00161
00162 The available fields are:
00163 link_name,object,touch_links
00164
00165 @param args: complete set of field values, in .msg order
00166 @param kwds: use keyword arguments corresponding to message field names
00167 to set specific fields.
00168 """
00169 if args or kwds:
00170 super(AttachedCollisionObject, self).__init__(*args, **kwds)
00171
00172 if self.link_name is None:
00173 self.link_name = ''
00174 if self.object is None:
00175 self.object = mapping_msgs.msg.CollisionObject()
00176 if self.touch_links is None:
00177 self.touch_links = []
00178 else:
00179 self.link_name = ''
00180 self.object = mapping_msgs.msg.CollisionObject()
00181 self.touch_links = []
00182
00183 def _get_types(self):
00184 """
00185 internal API method
00186 """
00187 return self._slot_types
00188
00189 def serialize(self, buff):
00190 """
00191 serialize message into buffer
00192 @param buff: buffer
00193 @type buff: StringIO
00194 """
00195 try:
00196 _x = self.link_name
00197 length = len(_x)
00198 buff.write(struct.pack('<I%ss'%length, length, _x))
00199 _x = self
00200 buff.write(_struct_3I.pack(_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs))
00201 _x = self.object.header.frame_id
00202 length = len(_x)
00203 buff.write(struct.pack('<I%ss'%length, length, _x))
00204 _x = self.object.id
00205 length = len(_x)
00206 buff.write(struct.pack('<I%ss'%length, length, _x))
00207 buff.write(_struct_b.pack(self.object.operation.operation))
00208 length = len(self.object.shapes)
00209 buff.write(_struct_I.pack(length))
00210 for val1 in self.object.shapes:
00211 buff.write(_struct_b.pack(val1.type))
00212 length = len(val1.dimensions)
00213 buff.write(_struct_I.pack(length))
00214 pattern = '<%sd'%length
00215 buff.write(struct.pack(pattern, *val1.dimensions))
00216 length = len(val1.triangles)
00217 buff.write(_struct_I.pack(length))
00218 pattern = '<%si'%length
00219 buff.write(struct.pack(pattern, *val1.triangles))
00220 length = len(val1.vertices)
00221 buff.write(_struct_I.pack(length))
00222 for val2 in val1.vertices:
00223 _x = val2
00224 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00225 length = len(self.object.poses)
00226 buff.write(_struct_I.pack(length))
00227 for val1 in self.object.poses:
00228 _v1 = val1.position
00229 _x = _v1
00230 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00231 _v2 = val1.orientation
00232 _x = _v2
00233 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00234 length = len(self.touch_links)
00235 buff.write(_struct_I.pack(length))
00236 for val1 in self.touch_links:
00237 length = len(val1)
00238 buff.write(struct.pack('<I%ss'%length, length, val1))
00239 except struct.error, se: self._check_types(se)
00240 except TypeError, te: self._check_types(te)
00241
00242 def deserialize(self, str):
00243 """
00244 unpack serialized message in str into this message instance
00245 @param str: byte array of serialized message
00246 @type str: str
00247 """
00248 try:
00249 if self.object is None:
00250 self.object = mapping_msgs.msg.CollisionObject()
00251 end = 0
00252 start = end
00253 end += 4
00254 (length,) = _struct_I.unpack(str[start:end])
00255 start = end
00256 end += length
00257 self.link_name = str[start:end]
00258 _x = self
00259 start = end
00260 end += 12
00261 (_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00262 start = end
00263 end += 4
00264 (length,) = _struct_I.unpack(str[start:end])
00265 start = end
00266 end += length
00267 self.object.header.frame_id = str[start:end]
00268 start = end
00269 end += 4
00270 (length,) = _struct_I.unpack(str[start:end])
00271 start = end
00272 end += length
00273 self.object.id = str[start:end]
00274 start = end
00275 end += 1
00276 (self.object.operation.operation,) = _struct_b.unpack(str[start:end])
00277 start = end
00278 end += 4
00279 (length,) = _struct_I.unpack(str[start:end])
00280 self.object.shapes = []
00281 for i in xrange(0, length):
00282 val1 = geometric_shapes_msgs.msg.Shape()
00283 start = end
00284 end += 1
00285 (val1.type,) = _struct_b.unpack(str[start:end])
00286 start = end
00287 end += 4
00288 (length,) = _struct_I.unpack(str[start:end])
00289 pattern = '<%sd'%length
00290 start = end
00291 end += struct.calcsize(pattern)
00292 val1.dimensions = struct.unpack(pattern, str[start:end])
00293 start = end
00294 end += 4
00295 (length,) = _struct_I.unpack(str[start:end])
00296 pattern = '<%si'%length
00297 start = end
00298 end += struct.calcsize(pattern)
00299 val1.triangles = struct.unpack(pattern, str[start:end])
00300 start = end
00301 end += 4
00302 (length,) = _struct_I.unpack(str[start:end])
00303 val1.vertices = []
00304 for i in xrange(0, length):
00305 val2 = geometry_msgs.msg.Point()
00306 _x = val2
00307 start = end
00308 end += 24
00309 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00310 val1.vertices.append(val2)
00311 self.object.shapes.append(val1)
00312 start = end
00313 end += 4
00314 (length,) = _struct_I.unpack(str[start:end])
00315 self.object.poses = []
00316 for i in xrange(0, length):
00317 val1 = geometry_msgs.msg.Pose()
00318 _v3 = val1.position
00319 _x = _v3
00320 start = end
00321 end += 24
00322 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00323 _v4 = val1.orientation
00324 _x = _v4
00325 start = end
00326 end += 32
00327 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00328 self.object.poses.append(val1)
00329 start = end
00330 end += 4
00331 (length,) = _struct_I.unpack(str[start:end])
00332 self.touch_links = []
00333 for i in xrange(0, length):
00334 start = end
00335 end += 4
00336 (length,) = _struct_I.unpack(str[start:end])
00337 start = end
00338 end += length
00339 val1 = str[start:end]
00340 self.touch_links.append(val1)
00341 return self
00342 except struct.error, e:
00343 raise roslib.message.DeserializationError(e)
00344
00345
00346 def serialize_numpy(self, buff, numpy):
00347 """
00348 serialize message with numpy array types into buffer
00349 @param buff: buffer
00350 @type buff: StringIO
00351 @param numpy: numpy python module
00352 @type numpy module
00353 """
00354 try:
00355 _x = self.link_name
00356 length = len(_x)
00357 buff.write(struct.pack('<I%ss'%length, length, _x))
00358 _x = self
00359 buff.write(_struct_3I.pack(_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs))
00360 _x = self.object.header.frame_id
00361 length = len(_x)
00362 buff.write(struct.pack('<I%ss'%length, length, _x))
00363 _x = self.object.id
00364 length = len(_x)
00365 buff.write(struct.pack('<I%ss'%length, length, _x))
00366 buff.write(_struct_b.pack(self.object.operation.operation))
00367 length = len(self.object.shapes)
00368 buff.write(_struct_I.pack(length))
00369 for val1 in self.object.shapes:
00370 buff.write(_struct_b.pack(val1.type))
00371 length = len(val1.dimensions)
00372 buff.write(_struct_I.pack(length))
00373 pattern = '<%sd'%length
00374 buff.write(val1.dimensions.tostring())
00375 length = len(val1.triangles)
00376 buff.write(_struct_I.pack(length))
00377 pattern = '<%si'%length
00378 buff.write(val1.triangles.tostring())
00379 length = len(val1.vertices)
00380 buff.write(_struct_I.pack(length))
00381 for val2 in val1.vertices:
00382 _x = val2
00383 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00384 length = len(self.object.poses)
00385 buff.write(_struct_I.pack(length))
00386 for val1 in self.object.poses:
00387 _v5 = val1.position
00388 _x = _v5
00389 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00390 _v6 = val1.orientation
00391 _x = _v6
00392 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00393 length = len(self.touch_links)
00394 buff.write(_struct_I.pack(length))
00395 for val1 in self.touch_links:
00396 length = len(val1)
00397 buff.write(struct.pack('<I%ss'%length, length, val1))
00398 except struct.error, se: self._check_types(se)
00399 except TypeError, te: self._check_types(te)
00400
00401 def deserialize_numpy(self, str, numpy):
00402 """
00403 unpack serialized message in str into this message instance using numpy for array types
00404 @param str: byte array of serialized message
00405 @type str: str
00406 @param numpy: numpy python module
00407 @type numpy: module
00408 """
00409 try:
00410 if self.object is None:
00411 self.object = mapping_msgs.msg.CollisionObject()
00412 end = 0
00413 start = end
00414 end += 4
00415 (length,) = _struct_I.unpack(str[start:end])
00416 start = end
00417 end += length
00418 self.link_name = str[start:end]
00419 _x = self
00420 start = end
00421 end += 12
00422 (_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00423 start = end
00424 end += 4
00425 (length,) = _struct_I.unpack(str[start:end])
00426 start = end
00427 end += length
00428 self.object.header.frame_id = str[start:end]
00429 start = end
00430 end += 4
00431 (length,) = _struct_I.unpack(str[start:end])
00432 start = end
00433 end += length
00434 self.object.id = str[start:end]
00435 start = end
00436 end += 1
00437 (self.object.operation.operation,) = _struct_b.unpack(str[start:end])
00438 start = end
00439 end += 4
00440 (length,) = _struct_I.unpack(str[start:end])
00441 self.object.shapes = []
00442 for i in xrange(0, length):
00443 val1 = geometric_shapes_msgs.msg.Shape()
00444 start = end
00445 end += 1
00446 (val1.type,) = _struct_b.unpack(str[start:end])
00447 start = end
00448 end += 4
00449 (length,) = _struct_I.unpack(str[start:end])
00450 pattern = '<%sd'%length
00451 start = end
00452 end += struct.calcsize(pattern)
00453 val1.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00454 start = end
00455 end += 4
00456 (length,) = _struct_I.unpack(str[start:end])
00457 pattern = '<%si'%length
00458 start = end
00459 end += struct.calcsize(pattern)
00460 val1.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00461 start = end
00462 end += 4
00463 (length,) = _struct_I.unpack(str[start:end])
00464 val1.vertices = []
00465 for i in xrange(0, length):
00466 val2 = geometry_msgs.msg.Point()
00467 _x = val2
00468 start = end
00469 end += 24
00470 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00471 val1.vertices.append(val2)
00472 self.object.shapes.append(val1)
00473 start = end
00474 end += 4
00475 (length,) = _struct_I.unpack(str[start:end])
00476 self.object.poses = []
00477 for i in xrange(0, length):
00478 val1 = geometry_msgs.msg.Pose()
00479 _v7 = val1.position
00480 _x = _v7
00481 start = end
00482 end += 24
00483 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00484 _v8 = val1.orientation
00485 _x = _v8
00486 start = end
00487 end += 32
00488 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00489 self.object.poses.append(val1)
00490 start = end
00491 end += 4
00492 (length,) = _struct_I.unpack(str[start:end])
00493 self.touch_links = []
00494 for i in xrange(0, length):
00495 start = end
00496 end += 4
00497 (length,) = _struct_I.unpack(str[start:end])
00498 start = end
00499 end += length
00500 val1 = str[start:end]
00501 self.touch_links.append(val1)
00502 return self
00503 except struct.error, e:
00504 raise roslib.message.DeserializationError(e)
00505
00506 _struct_I = roslib.message.struct_I
00507 _struct_3I = struct.Struct("<3I")
00508 _struct_b = struct.Struct("<b")
00509 _struct_4d = struct.Struct("<4d")
00510 _struct_3d = struct.Struct("<3d")