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