$search
00001 """autogenerated by genmsg_py from PlanningScene.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 import roslib.rostime 00009 import sensor_msgs.msg 00010 00011 class PlanningScene(roslib.message.Message): 00012 _md5sum = "6d1add8ef6efdd62d194ef430abd4b75" 00013 _type = "arm_navigation_msgs/PlanningScene" 00014 _has_header = False #flag to mark the presence of a Header object 00015 _full_text = """#full robot state 00016 arm_navigation_msgs/RobotState robot_state 00017 00018 #additional frames for duplicating tf 00019 geometry_msgs/TransformStamped[] fixed_frame_transforms 00020 00021 #full allowed collision matrix 00022 AllowedCollisionMatrix allowed_collision_matrix 00023 00024 #allowed contacts 00025 arm_navigation_msgs/AllowedContactSpecification[] allowed_contacts 00026 00027 #all link paddings 00028 arm_navigation_msgs/LinkPadding[] link_padding 00029 00030 #collision objects 00031 arm_navigation_msgs/CollisionObject[] collision_objects 00032 arm_navigation_msgs/AttachedCollisionObject[] attached_collision_objects 00033 00034 #the collision map 00035 arm_navigation_msgs/CollisionMap collision_map 00036 00037 ================================================================================ 00038 MSG: arm_navigation_msgs/RobotState 00039 # This message contains information about the robot state, i.e. the positions of its joints and links 00040 sensor_msgs/JointState joint_state 00041 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state 00042 00043 ================================================================================ 00044 MSG: sensor_msgs/JointState 00045 # This is a message that holds data to describe the state of a set of torque controlled joints. 00046 # 00047 # The state of each joint (revolute or prismatic) is defined by: 00048 # * the position of the joint (rad or m), 00049 # * the velocity of the joint (rad/s or m/s) and 00050 # * the effort that is applied in the joint (Nm or N). 00051 # 00052 # Each joint is uniquely identified by its name 00053 # The header specifies the time at which the joint states were recorded. All the joint states 00054 # in one message have to be recorded at the same time. 00055 # 00056 # This message consists of a multiple arrays, one for each part of the joint state. 00057 # The goal is to make each of the fields optional. When e.g. your joints have no 00058 # effort associated with them, you can leave the effort array empty. 00059 # 00060 # All arrays in this message should have the same size, or be empty. 00061 # This is the only way to uniquely associate the joint name with the correct 00062 # states. 00063 00064 00065 Header header 00066 00067 string[] name 00068 float64[] position 00069 float64[] velocity 00070 float64[] effort 00071 00072 ================================================================================ 00073 MSG: std_msgs/Header 00074 # Standard metadata for higher-level stamped data types. 00075 # This is generally used to communicate timestamped data 00076 # in a particular coordinate frame. 00077 # 00078 # sequence ID: consecutively increasing ID 00079 uint32 seq 00080 #Two-integer timestamp that is expressed as: 00081 # * stamp.secs: seconds (stamp_secs) since epoch 00082 # * stamp.nsecs: nanoseconds since stamp_secs 00083 # time-handling sugar is provided by the client library 00084 time stamp 00085 #Frame this data is associated with 00086 # 0: no frame 00087 # 1: global frame 00088 string frame_id 00089 00090 ================================================================================ 00091 MSG: arm_navigation_msgs/MultiDOFJointState 00092 #A representation of a multi-dof joint state 00093 time stamp 00094 string[] joint_names 00095 string[] frame_ids 00096 string[] child_frame_ids 00097 geometry_msgs/Pose[] poses 00098 00099 ================================================================================ 00100 MSG: geometry_msgs/Pose 00101 # A representation of pose in free space, composed of postion and orientation. 00102 Point position 00103 Quaternion orientation 00104 00105 ================================================================================ 00106 MSG: geometry_msgs/Point 00107 # This contains the position of a point in free space 00108 float64 x 00109 float64 y 00110 float64 z 00111 00112 ================================================================================ 00113 MSG: geometry_msgs/Quaternion 00114 # This represents an orientation in free space in quaternion form. 00115 00116 float64 x 00117 float64 y 00118 float64 z 00119 float64 w 00120 00121 ================================================================================ 00122 MSG: geometry_msgs/TransformStamped 00123 # This expresses a transform from coordinate frame header.frame_id 00124 # to the coordinate frame child_frame_id 00125 # 00126 # This message is mostly used by the 00127 # <a href="http://www.ros.org/wiki/tf">tf</a> package. 00128 # See it's documentation for more information. 00129 00130 Header header 00131 string child_frame_id # the frame id of the child frame 00132 Transform transform 00133 00134 ================================================================================ 00135 MSG: geometry_msgs/Transform 00136 # This represents the transform between two coordinate frames in free space. 00137 00138 Vector3 translation 00139 Quaternion rotation 00140 00141 ================================================================================ 00142 MSG: geometry_msgs/Vector3 00143 # This represents a vector in free space. 00144 00145 float64 x 00146 float64 y 00147 float64 z 00148 ================================================================================ 00149 MSG: arm_navigation_msgs/AllowedCollisionMatrix 00150 # the list of link names in the matrix 00151 string[] link_names 00152 00153 # the individual entries in the allowed collision matrix 00154 # symmetric, with same order as link_names 00155 AllowedCollisionEntry[] entries 00156 00157 ================================================================================ 00158 MSG: arm_navigation_msgs/AllowedCollisionEntry 00159 # whether or not collision checking is enabled 00160 bool[] enabled 00161 00162 ================================================================================ 00163 MSG: arm_navigation_msgs/AllowedContactSpecification 00164 # The names of the regions 00165 string name 00166 00167 # The shape of the region in the environment 00168 arm_navigation_msgs/Shape shape 00169 00170 # The pose of the space defining the region 00171 geometry_msgs/PoseStamped pose_stamped 00172 00173 # The set of links that will be allowed to have penetration contact within this region 00174 string[] link_names 00175 00176 # The maximum penetration depth allowed for every link 00177 float64 penetration_depth 00178 00179 ================================================================================ 00180 MSG: arm_navigation_msgs/Shape 00181 byte SPHERE=0 00182 byte BOX=1 00183 byte CYLINDER=2 00184 byte MESH=3 00185 00186 byte type 00187 00188 00189 #### define sphere, box, cylinder #### 00190 # the origin of each shape is considered at the shape's center 00191 00192 # for sphere 00193 # radius := dimensions[0] 00194 00195 # for cylinder 00196 # radius := dimensions[0] 00197 # length := dimensions[1] 00198 # the length is along the Z axis 00199 00200 # for box 00201 # size_x := dimensions[0] 00202 # size_y := dimensions[1] 00203 # size_z := dimensions[2] 00204 float64[] dimensions 00205 00206 00207 #### define mesh #### 00208 00209 # list of triangles; triangle k is defined by tre vertices located 00210 # at indices triangles[3k], triangles[3k+1], triangles[3k+2] 00211 int32[] triangles 00212 geometry_msgs/Point[] vertices 00213 00214 ================================================================================ 00215 MSG: geometry_msgs/PoseStamped 00216 # A Pose with reference coordinate frame and timestamp 00217 Header header 00218 Pose pose 00219 00220 ================================================================================ 00221 MSG: arm_navigation_msgs/LinkPadding 00222 #name for the link 00223 string link_name 00224 00225 # padding to apply to the link 00226 float64 padding 00227 00228 ================================================================================ 00229 MSG: arm_navigation_msgs/CollisionObject 00230 # a header, used for interpreting the poses 00231 Header header 00232 00233 # the id of the object 00234 string id 00235 00236 # The padding used for filtering points near the object. 00237 # This does not affect collision checking for the object. 00238 # Set to negative to get zero padding. 00239 float32 padding 00240 00241 #This contains what is to be done with the object 00242 CollisionObjectOperation operation 00243 00244 #the shapes associated with the object 00245 arm_navigation_msgs/Shape[] shapes 00246 00247 #the poses associated with the shapes - will be transformed using the header 00248 geometry_msgs/Pose[] poses 00249 00250 ================================================================================ 00251 MSG: arm_navigation_msgs/CollisionObjectOperation 00252 #Puts the object into the environment 00253 #or updates the object if already added 00254 byte ADD=0 00255 00256 #Removes the object from the environment entirely 00257 byte REMOVE=1 00258 00259 #Only valid within the context of a CollisionAttachedObject message 00260 #Will be ignored if sent with an CollisionObject message 00261 #Takes an attached object, detaches from the attached link 00262 #But adds back in as regular object 00263 byte DETACH_AND_ADD_AS_OBJECT=2 00264 00265 #Only valid within the context of a CollisionAttachedObject message 00266 #Will be ignored if sent with an CollisionObject message 00267 #Takes current object in the environment and removes it as 00268 #a regular object 00269 byte ATTACH_AND_REMOVE_AS_OBJECT=3 00270 00271 # Byte code for operation 00272 byte operation 00273 00274 ================================================================================ 00275 MSG: arm_navigation_msgs/AttachedCollisionObject 00276 # The CollisionObject will be attached with a fixed joint to this link 00277 # If link name is set to REMOVE_ALL_ATTACHED_OBJECTS and object.operation 00278 # is set to REMOVE will remove all attached bodies attached to any object 00279 string link_name 00280 00281 #Reserved for indicating that all attached objects should be removed 00282 string REMOVE_ALL_ATTACHED_OBJECTS = "all" 00283 00284 #This contains the actual shapes and poses for the CollisionObject 00285 #to be attached to the link 00286 #If action is remove and no object.id is set, all objects 00287 #attached to the link indicated by link_name will be removed 00288 CollisionObject object 00289 00290 # The set of links that the attached objects are allowed to touch 00291 # by default - the link_name is included by default 00292 string[] touch_links 00293 00294 ================================================================================ 00295 MSG: arm_navigation_msgs/CollisionMap 00296 #header for interpreting box positions 00297 Header header 00298 00299 #boxes for use in collision testing 00300 OrientedBoundingBox[] boxes 00301 00302 ================================================================================ 00303 MSG: arm_navigation_msgs/OrientedBoundingBox 00304 #the center of the box 00305 geometry_msgs/Point32 center 00306 00307 #the extents of the box, assuming the center is at the point 00308 geometry_msgs/Point32 extents 00309 00310 #the axis of the box 00311 geometry_msgs/Point32 axis 00312 00313 #the angle of rotation around the axis 00314 float32 angle 00315 00316 ================================================================================ 00317 MSG: geometry_msgs/Point32 00318 # This contains the position of a point in free space(with 32 bits of precision). 00319 # It is recommeded to use Point wherever possible instead of Point32. 00320 # 00321 # This recommendation is to promote interoperability. 00322 # 00323 # This message is designed to take up less space when sending 00324 # lots of points at once, as in the case of a PointCloud. 00325 00326 float32 x 00327 float32 y 00328 float32 z 00329 """ 00330 __slots__ = ['robot_state','fixed_frame_transforms','allowed_collision_matrix','allowed_contacts','link_padding','collision_objects','attached_collision_objects','collision_map'] 00331 _slot_types = ['arm_navigation_msgs/RobotState','geometry_msgs/TransformStamped[]','arm_navigation_msgs/AllowedCollisionMatrix','arm_navigation_msgs/AllowedContactSpecification[]','arm_navigation_msgs/LinkPadding[]','arm_navigation_msgs/CollisionObject[]','arm_navigation_msgs/AttachedCollisionObject[]','arm_navigation_msgs/CollisionMap'] 00332 00333 def __init__(self, *args, **kwds): 00334 """ 00335 Constructor. Any message fields that are implicitly/explicitly 00336 set to None will be assigned a default value. The recommend 00337 use is keyword arguments as this is more robust to future message 00338 changes. You cannot mix in-order arguments and keyword arguments. 00339 00340 The available fields are: 00341 robot_state,fixed_frame_transforms,allowed_collision_matrix,allowed_contacts,link_padding,collision_objects,attached_collision_objects,collision_map 00342 00343 @param args: complete set of field values, in .msg order 00344 @param kwds: use keyword arguments corresponding to message field names 00345 to set specific fields. 00346 """ 00347 if args or kwds: 00348 super(PlanningScene, self).__init__(*args, **kwds) 00349 #message fields cannot be None, assign default values for those that are 00350 if self.robot_state is None: 00351 self.robot_state = arm_navigation_msgs.msg.RobotState() 00352 if self.fixed_frame_transforms is None: 00353 self.fixed_frame_transforms = [] 00354 if self.allowed_collision_matrix is None: 00355 self.allowed_collision_matrix = arm_navigation_msgs.msg.AllowedCollisionMatrix() 00356 if self.allowed_contacts is None: 00357 self.allowed_contacts = [] 00358 if self.link_padding is None: 00359 self.link_padding = [] 00360 if self.collision_objects is None: 00361 self.collision_objects = [] 00362 if self.attached_collision_objects is None: 00363 self.attached_collision_objects = [] 00364 if self.collision_map is None: 00365 self.collision_map = arm_navigation_msgs.msg.CollisionMap() 00366 else: 00367 self.robot_state = arm_navigation_msgs.msg.RobotState() 00368 self.fixed_frame_transforms = [] 00369 self.allowed_collision_matrix = arm_navigation_msgs.msg.AllowedCollisionMatrix() 00370 self.allowed_contacts = [] 00371 self.link_padding = [] 00372 self.collision_objects = [] 00373 self.attached_collision_objects = [] 00374 self.collision_map = arm_navigation_msgs.msg.CollisionMap() 00375 00376 def _get_types(self): 00377 """ 00378 internal API method 00379 """ 00380 return self._slot_types 00381 00382 def serialize(self, buff): 00383 """ 00384 serialize message into buffer 00385 @param buff: buffer 00386 @type buff: StringIO 00387 """ 00388 try: 00389 _x = self 00390 buff.write(_struct_3I.pack(_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs)) 00391 _x = self.robot_state.joint_state.header.frame_id 00392 length = len(_x) 00393 buff.write(struct.pack('<I%ss'%length, length, _x)) 00394 length = len(self.robot_state.joint_state.name) 00395 buff.write(_struct_I.pack(length)) 00396 for val1 in self.robot_state.joint_state.name: 00397 length = len(val1) 00398 buff.write(struct.pack('<I%ss'%length, length, val1)) 00399 length = len(self.robot_state.joint_state.position) 00400 buff.write(_struct_I.pack(length)) 00401 pattern = '<%sd'%length 00402 buff.write(struct.pack(pattern, *self.robot_state.joint_state.position)) 00403 length = len(self.robot_state.joint_state.velocity) 00404 buff.write(_struct_I.pack(length)) 00405 pattern = '<%sd'%length 00406 buff.write(struct.pack(pattern, *self.robot_state.joint_state.velocity)) 00407 length = len(self.robot_state.joint_state.effort) 00408 buff.write(_struct_I.pack(length)) 00409 pattern = '<%sd'%length 00410 buff.write(struct.pack(pattern, *self.robot_state.joint_state.effort)) 00411 _x = self 00412 buff.write(_struct_2I.pack(_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs)) 00413 length = len(self.robot_state.multi_dof_joint_state.joint_names) 00414 buff.write(_struct_I.pack(length)) 00415 for val1 in self.robot_state.multi_dof_joint_state.joint_names: 00416 length = len(val1) 00417 buff.write(struct.pack('<I%ss'%length, length, val1)) 00418 length = len(self.robot_state.multi_dof_joint_state.frame_ids) 00419 buff.write(_struct_I.pack(length)) 00420 for val1 in self.robot_state.multi_dof_joint_state.frame_ids: 00421 length = len(val1) 00422 buff.write(struct.pack('<I%ss'%length, length, val1)) 00423 length = len(self.robot_state.multi_dof_joint_state.child_frame_ids) 00424 buff.write(_struct_I.pack(length)) 00425 for val1 in self.robot_state.multi_dof_joint_state.child_frame_ids: 00426 length = len(val1) 00427 buff.write(struct.pack('<I%ss'%length, length, val1)) 00428 length = len(self.robot_state.multi_dof_joint_state.poses) 00429 buff.write(_struct_I.pack(length)) 00430 for val1 in self.robot_state.multi_dof_joint_state.poses: 00431 _v1 = val1.position 00432 _x = _v1 00433 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00434 _v2 = val1.orientation 00435 _x = _v2 00436 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00437 length = len(self.fixed_frame_transforms) 00438 buff.write(_struct_I.pack(length)) 00439 for val1 in self.fixed_frame_transforms: 00440 _v3 = val1.header 00441 buff.write(_struct_I.pack(_v3.seq)) 00442 _v4 = _v3.stamp 00443 _x = _v4 00444 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00445 _x = _v3.frame_id 00446 length = len(_x) 00447 buff.write(struct.pack('<I%ss'%length, length, _x)) 00448 _x = val1.child_frame_id 00449 length = len(_x) 00450 buff.write(struct.pack('<I%ss'%length, length, _x)) 00451 _v5 = val1.transform 00452 _v6 = _v5.translation 00453 _x = _v6 00454 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00455 _v7 = _v5.rotation 00456 _x = _v7 00457 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00458 length = len(self.allowed_collision_matrix.link_names) 00459 buff.write(_struct_I.pack(length)) 00460 for val1 in self.allowed_collision_matrix.link_names: 00461 length = len(val1) 00462 buff.write(struct.pack('<I%ss'%length, length, val1)) 00463 length = len(self.allowed_collision_matrix.entries) 00464 buff.write(_struct_I.pack(length)) 00465 for val1 in self.allowed_collision_matrix.entries: 00466 length = len(val1.enabled) 00467 buff.write(_struct_I.pack(length)) 00468 pattern = '<%sB'%length 00469 buff.write(struct.pack(pattern, *val1.enabled)) 00470 length = len(self.allowed_contacts) 00471 buff.write(_struct_I.pack(length)) 00472 for val1 in self.allowed_contacts: 00473 _x = val1.name 00474 length = len(_x) 00475 buff.write(struct.pack('<I%ss'%length, length, _x)) 00476 _v8 = val1.shape 00477 buff.write(_struct_b.pack(_v8.type)) 00478 length = len(_v8.dimensions) 00479 buff.write(_struct_I.pack(length)) 00480 pattern = '<%sd'%length 00481 buff.write(struct.pack(pattern, *_v8.dimensions)) 00482 length = len(_v8.triangles) 00483 buff.write(_struct_I.pack(length)) 00484 pattern = '<%si'%length 00485 buff.write(struct.pack(pattern, *_v8.triangles)) 00486 length = len(_v8.vertices) 00487 buff.write(_struct_I.pack(length)) 00488 for val3 in _v8.vertices: 00489 _x = val3 00490 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00491 _v9 = val1.pose_stamped 00492 _v10 = _v9.header 00493 buff.write(_struct_I.pack(_v10.seq)) 00494 _v11 = _v10.stamp 00495 _x = _v11 00496 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00497 _x = _v10.frame_id 00498 length = len(_x) 00499 buff.write(struct.pack('<I%ss'%length, length, _x)) 00500 _v12 = _v9.pose 00501 _v13 = _v12.position 00502 _x = _v13 00503 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00504 _v14 = _v12.orientation 00505 _x = _v14 00506 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00507 length = len(val1.link_names) 00508 buff.write(_struct_I.pack(length)) 00509 for val2 in val1.link_names: 00510 length = len(val2) 00511 buff.write(struct.pack('<I%ss'%length, length, val2)) 00512 buff.write(_struct_d.pack(val1.penetration_depth)) 00513 length = len(self.link_padding) 00514 buff.write(_struct_I.pack(length)) 00515 for val1 in self.link_padding: 00516 _x = val1.link_name 00517 length = len(_x) 00518 buff.write(struct.pack('<I%ss'%length, length, _x)) 00519 buff.write(_struct_d.pack(val1.padding)) 00520 length = len(self.collision_objects) 00521 buff.write(_struct_I.pack(length)) 00522 for val1 in self.collision_objects: 00523 _v15 = val1.header 00524 buff.write(_struct_I.pack(_v15.seq)) 00525 _v16 = _v15.stamp 00526 _x = _v16 00527 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00528 _x = _v15.frame_id 00529 length = len(_x) 00530 buff.write(struct.pack('<I%ss'%length, length, _x)) 00531 _x = val1.id 00532 length = len(_x) 00533 buff.write(struct.pack('<I%ss'%length, length, _x)) 00534 buff.write(_struct_f.pack(val1.padding)) 00535 _v17 = val1.operation 00536 buff.write(_struct_b.pack(_v17.operation)) 00537 length = len(val1.shapes) 00538 buff.write(_struct_I.pack(length)) 00539 for val2 in val1.shapes: 00540 buff.write(_struct_b.pack(val2.type)) 00541 length = len(val2.dimensions) 00542 buff.write(_struct_I.pack(length)) 00543 pattern = '<%sd'%length 00544 buff.write(struct.pack(pattern, *val2.dimensions)) 00545 length = len(val2.triangles) 00546 buff.write(_struct_I.pack(length)) 00547 pattern = '<%si'%length 00548 buff.write(struct.pack(pattern, *val2.triangles)) 00549 length = len(val2.vertices) 00550 buff.write(_struct_I.pack(length)) 00551 for val3 in val2.vertices: 00552 _x = val3 00553 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00554 length = len(val1.poses) 00555 buff.write(_struct_I.pack(length)) 00556 for val2 in val1.poses: 00557 _v18 = val2.position 00558 _x = _v18 00559 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00560 _v19 = val2.orientation 00561 _x = _v19 00562 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00563 length = len(self.attached_collision_objects) 00564 buff.write(_struct_I.pack(length)) 00565 for val1 in self.attached_collision_objects: 00566 _x = val1.link_name 00567 length = len(_x) 00568 buff.write(struct.pack('<I%ss'%length, length, _x)) 00569 _v20 = val1.object 00570 _v21 = _v20.header 00571 buff.write(_struct_I.pack(_v21.seq)) 00572 _v22 = _v21.stamp 00573 _x = _v22 00574 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 00575 _x = _v21.frame_id 00576 length = len(_x) 00577 buff.write(struct.pack('<I%ss'%length, length, _x)) 00578 _x = _v20.id 00579 length = len(_x) 00580 buff.write(struct.pack('<I%ss'%length, length, _x)) 00581 buff.write(_struct_f.pack(_v20.padding)) 00582 _v23 = _v20.operation 00583 buff.write(_struct_b.pack(_v23.operation)) 00584 length = len(_v20.shapes) 00585 buff.write(_struct_I.pack(length)) 00586 for val3 in _v20.shapes: 00587 buff.write(_struct_b.pack(val3.type)) 00588 length = len(val3.dimensions) 00589 buff.write(_struct_I.pack(length)) 00590 pattern = '<%sd'%length 00591 buff.write(struct.pack(pattern, *val3.dimensions)) 00592 length = len(val3.triangles) 00593 buff.write(_struct_I.pack(length)) 00594 pattern = '<%si'%length 00595 buff.write(struct.pack(pattern, *val3.triangles)) 00596 length = len(val3.vertices) 00597 buff.write(_struct_I.pack(length)) 00598 for val4 in val3.vertices: 00599 _x = val4 00600 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00601 length = len(_v20.poses) 00602 buff.write(_struct_I.pack(length)) 00603 for val3 in _v20.poses: 00604 _v24 = val3.position 00605 _x = _v24 00606 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00607 _v25 = val3.orientation 00608 _x = _v25 00609 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00610 length = len(val1.touch_links) 00611 buff.write(_struct_I.pack(length)) 00612 for val2 in val1.touch_links: 00613 length = len(val2) 00614 buff.write(struct.pack('<I%ss'%length, length, val2)) 00615 _x = self 00616 buff.write(_struct_3I.pack(_x.collision_map.header.seq, _x.collision_map.header.stamp.secs, _x.collision_map.header.stamp.nsecs)) 00617 _x = self.collision_map.header.frame_id 00618 length = len(_x) 00619 buff.write(struct.pack('<I%ss'%length, length, _x)) 00620 length = len(self.collision_map.boxes) 00621 buff.write(_struct_I.pack(length)) 00622 for val1 in self.collision_map.boxes: 00623 _v26 = val1.center 00624 _x = _v26 00625 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z)) 00626 _v27 = val1.extents 00627 _x = _v27 00628 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z)) 00629 _v28 = val1.axis 00630 _x = _v28 00631 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z)) 00632 buff.write(_struct_f.pack(val1.angle)) 00633 except struct.error as se: self._check_types(se) 00634 except TypeError as te: self._check_types(te) 00635 00636 def deserialize(self, str): 00637 """ 00638 unpack serialized message in str into this message instance 00639 @param str: byte array of serialized message 00640 @type str: str 00641 """ 00642 try: 00643 if self.robot_state is None: 00644 self.robot_state = arm_navigation_msgs.msg.RobotState() 00645 if self.allowed_collision_matrix is None: 00646 self.allowed_collision_matrix = arm_navigation_msgs.msg.AllowedCollisionMatrix() 00647 if self.collision_map is None: 00648 self.collision_map = arm_navigation_msgs.msg.CollisionMap() 00649 end = 0 00650 _x = self 00651 start = end 00652 end += 12 00653 (_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00654 start = end 00655 end += 4 00656 (length,) = _struct_I.unpack(str[start:end]) 00657 start = end 00658 end += length 00659 self.robot_state.joint_state.header.frame_id = str[start:end] 00660 start = end 00661 end += 4 00662 (length,) = _struct_I.unpack(str[start:end]) 00663 self.robot_state.joint_state.name = [] 00664 for i in range(0, length): 00665 start = end 00666 end += 4 00667 (length,) = _struct_I.unpack(str[start:end]) 00668 start = end 00669 end += length 00670 val1 = str[start:end] 00671 self.robot_state.joint_state.name.append(val1) 00672 start = end 00673 end += 4 00674 (length,) = _struct_I.unpack(str[start:end]) 00675 pattern = '<%sd'%length 00676 start = end 00677 end += struct.calcsize(pattern) 00678 self.robot_state.joint_state.position = struct.unpack(pattern, str[start:end]) 00679 start = end 00680 end += 4 00681 (length,) = _struct_I.unpack(str[start:end]) 00682 pattern = '<%sd'%length 00683 start = end 00684 end += struct.calcsize(pattern) 00685 self.robot_state.joint_state.velocity = struct.unpack(pattern, str[start:end]) 00686 start = end 00687 end += 4 00688 (length,) = _struct_I.unpack(str[start:end]) 00689 pattern = '<%sd'%length 00690 start = end 00691 end += struct.calcsize(pattern) 00692 self.robot_state.joint_state.effort = struct.unpack(pattern, str[start:end]) 00693 _x = self 00694 start = end 00695 end += 8 00696 (_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00697 start = end 00698 end += 4 00699 (length,) = _struct_I.unpack(str[start:end]) 00700 self.robot_state.multi_dof_joint_state.joint_names = [] 00701 for i in range(0, length): 00702 start = end 00703 end += 4 00704 (length,) = _struct_I.unpack(str[start:end]) 00705 start = end 00706 end += length 00707 val1 = str[start:end] 00708 self.robot_state.multi_dof_joint_state.joint_names.append(val1) 00709 start = end 00710 end += 4 00711 (length,) = _struct_I.unpack(str[start:end]) 00712 self.robot_state.multi_dof_joint_state.frame_ids = [] 00713 for i in range(0, length): 00714 start = end 00715 end += 4 00716 (length,) = _struct_I.unpack(str[start:end]) 00717 start = end 00718 end += length 00719 val1 = str[start:end] 00720 self.robot_state.multi_dof_joint_state.frame_ids.append(val1) 00721 start = end 00722 end += 4 00723 (length,) = _struct_I.unpack(str[start:end]) 00724 self.robot_state.multi_dof_joint_state.child_frame_ids = [] 00725 for i in range(0, length): 00726 start = end 00727 end += 4 00728 (length,) = _struct_I.unpack(str[start:end]) 00729 start = end 00730 end += length 00731 val1 = str[start:end] 00732 self.robot_state.multi_dof_joint_state.child_frame_ids.append(val1) 00733 start = end 00734 end += 4 00735 (length,) = _struct_I.unpack(str[start:end]) 00736 self.robot_state.multi_dof_joint_state.poses = [] 00737 for i in range(0, length): 00738 val1 = geometry_msgs.msg.Pose() 00739 _v29 = val1.position 00740 _x = _v29 00741 start = end 00742 end += 24 00743 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00744 _v30 = val1.orientation 00745 _x = _v30 00746 start = end 00747 end += 32 00748 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00749 self.robot_state.multi_dof_joint_state.poses.append(val1) 00750 start = end 00751 end += 4 00752 (length,) = _struct_I.unpack(str[start:end]) 00753 self.fixed_frame_transforms = [] 00754 for i in range(0, length): 00755 val1 = geometry_msgs.msg.TransformStamped() 00756 _v31 = val1.header 00757 start = end 00758 end += 4 00759 (_v31.seq,) = _struct_I.unpack(str[start:end]) 00760 _v32 = _v31.stamp 00761 _x = _v32 00762 start = end 00763 end += 8 00764 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00765 start = end 00766 end += 4 00767 (length,) = _struct_I.unpack(str[start:end]) 00768 start = end 00769 end += length 00770 _v31.frame_id = str[start:end] 00771 start = end 00772 end += 4 00773 (length,) = _struct_I.unpack(str[start:end]) 00774 start = end 00775 end += length 00776 val1.child_frame_id = str[start:end] 00777 _v33 = val1.transform 00778 _v34 = _v33.translation 00779 _x = _v34 00780 start = end 00781 end += 24 00782 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00783 _v35 = _v33.rotation 00784 _x = _v35 00785 start = end 00786 end += 32 00787 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00788 self.fixed_frame_transforms.append(val1) 00789 start = end 00790 end += 4 00791 (length,) = _struct_I.unpack(str[start:end]) 00792 self.allowed_collision_matrix.link_names = [] 00793 for i in range(0, length): 00794 start = end 00795 end += 4 00796 (length,) = _struct_I.unpack(str[start:end]) 00797 start = end 00798 end += length 00799 val1 = str[start:end] 00800 self.allowed_collision_matrix.link_names.append(val1) 00801 start = end 00802 end += 4 00803 (length,) = _struct_I.unpack(str[start:end]) 00804 self.allowed_collision_matrix.entries = [] 00805 for i in range(0, length): 00806 val1 = arm_navigation_msgs.msg.AllowedCollisionEntry() 00807 start = end 00808 end += 4 00809 (length,) = _struct_I.unpack(str[start:end]) 00810 pattern = '<%sB'%length 00811 start = end 00812 end += struct.calcsize(pattern) 00813 val1.enabled = struct.unpack(pattern, str[start:end]) 00814 val1.enabled = map(bool, val1.enabled) 00815 self.allowed_collision_matrix.entries.append(val1) 00816 start = end 00817 end += 4 00818 (length,) = _struct_I.unpack(str[start:end]) 00819 self.allowed_contacts = [] 00820 for i in range(0, length): 00821 val1 = arm_navigation_msgs.msg.AllowedContactSpecification() 00822 start = end 00823 end += 4 00824 (length,) = _struct_I.unpack(str[start:end]) 00825 start = end 00826 end += length 00827 val1.name = str[start:end] 00828 _v36 = val1.shape 00829 start = end 00830 end += 1 00831 (_v36.type,) = _struct_b.unpack(str[start:end]) 00832 start = end 00833 end += 4 00834 (length,) = _struct_I.unpack(str[start:end]) 00835 pattern = '<%sd'%length 00836 start = end 00837 end += struct.calcsize(pattern) 00838 _v36.dimensions = struct.unpack(pattern, str[start:end]) 00839 start = end 00840 end += 4 00841 (length,) = _struct_I.unpack(str[start:end]) 00842 pattern = '<%si'%length 00843 start = end 00844 end += struct.calcsize(pattern) 00845 _v36.triangles = struct.unpack(pattern, str[start:end]) 00846 start = end 00847 end += 4 00848 (length,) = _struct_I.unpack(str[start:end]) 00849 _v36.vertices = [] 00850 for i in range(0, length): 00851 val3 = geometry_msgs.msg.Point() 00852 _x = val3 00853 start = end 00854 end += 24 00855 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00856 _v36.vertices.append(val3) 00857 _v37 = val1.pose_stamped 00858 _v38 = _v37.header 00859 start = end 00860 end += 4 00861 (_v38.seq,) = _struct_I.unpack(str[start:end]) 00862 _v39 = _v38.stamp 00863 _x = _v39 00864 start = end 00865 end += 8 00866 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00867 start = end 00868 end += 4 00869 (length,) = _struct_I.unpack(str[start:end]) 00870 start = end 00871 end += length 00872 _v38.frame_id = str[start:end] 00873 _v40 = _v37.pose 00874 _v41 = _v40.position 00875 _x = _v41 00876 start = end 00877 end += 24 00878 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00879 _v42 = _v40.orientation 00880 _x = _v42 00881 start = end 00882 end += 32 00883 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00884 start = end 00885 end += 4 00886 (length,) = _struct_I.unpack(str[start:end]) 00887 val1.link_names = [] 00888 for i in range(0, length): 00889 start = end 00890 end += 4 00891 (length,) = _struct_I.unpack(str[start:end]) 00892 start = end 00893 end += length 00894 val2 = str[start:end] 00895 val1.link_names.append(val2) 00896 start = end 00897 end += 8 00898 (val1.penetration_depth,) = _struct_d.unpack(str[start:end]) 00899 self.allowed_contacts.append(val1) 00900 start = end 00901 end += 4 00902 (length,) = _struct_I.unpack(str[start:end]) 00903 self.link_padding = [] 00904 for i in range(0, length): 00905 val1 = arm_navigation_msgs.msg.LinkPadding() 00906 start = end 00907 end += 4 00908 (length,) = _struct_I.unpack(str[start:end]) 00909 start = end 00910 end += length 00911 val1.link_name = str[start:end] 00912 start = end 00913 end += 8 00914 (val1.padding,) = _struct_d.unpack(str[start:end]) 00915 self.link_padding.append(val1) 00916 start = end 00917 end += 4 00918 (length,) = _struct_I.unpack(str[start:end]) 00919 self.collision_objects = [] 00920 for i in range(0, length): 00921 val1 = arm_navigation_msgs.msg.CollisionObject() 00922 _v43 = val1.header 00923 start = end 00924 end += 4 00925 (_v43.seq,) = _struct_I.unpack(str[start:end]) 00926 _v44 = _v43.stamp 00927 _x = _v44 00928 start = end 00929 end += 8 00930 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 00931 start = end 00932 end += 4 00933 (length,) = _struct_I.unpack(str[start:end]) 00934 start = end 00935 end += length 00936 _v43.frame_id = str[start:end] 00937 start = end 00938 end += 4 00939 (length,) = _struct_I.unpack(str[start:end]) 00940 start = end 00941 end += length 00942 val1.id = str[start:end] 00943 start = end 00944 end += 4 00945 (val1.padding,) = _struct_f.unpack(str[start:end]) 00946 _v45 = val1.operation 00947 start = end 00948 end += 1 00949 (_v45.operation,) = _struct_b.unpack(str[start:end]) 00950 start = end 00951 end += 4 00952 (length,) = _struct_I.unpack(str[start:end]) 00953 val1.shapes = [] 00954 for i in range(0, length): 00955 val2 = arm_navigation_msgs.msg.Shape() 00956 start = end 00957 end += 1 00958 (val2.type,) = _struct_b.unpack(str[start:end]) 00959 start = end 00960 end += 4 00961 (length,) = _struct_I.unpack(str[start:end]) 00962 pattern = '<%sd'%length 00963 start = end 00964 end += struct.calcsize(pattern) 00965 val2.dimensions = struct.unpack(pattern, str[start:end]) 00966 start = end 00967 end += 4 00968 (length,) = _struct_I.unpack(str[start:end]) 00969 pattern = '<%si'%length 00970 start = end 00971 end += struct.calcsize(pattern) 00972 val2.triangles = struct.unpack(pattern, str[start:end]) 00973 start = end 00974 end += 4 00975 (length,) = _struct_I.unpack(str[start:end]) 00976 val2.vertices = [] 00977 for i in range(0, length): 00978 val3 = geometry_msgs.msg.Point() 00979 _x = val3 00980 start = end 00981 end += 24 00982 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00983 val2.vertices.append(val3) 00984 val1.shapes.append(val2) 00985 start = end 00986 end += 4 00987 (length,) = _struct_I.unpack(str[start:end]) 00988 val1.poses = [] 00989 for i in range(0, length): 00990 val2 = geometry_msgs.msg.Pose() 00991 _v46 = val2.position 00992 _x = _v46 00993 start = end 00994 end += 24 00995 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00996 _v47 = val2.orientation 00997 _x = _v47 00998 start = end 00999 end += 32 01000 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 01001 val1.poses.append(val2) 01002 self.collision_objects.append(val1) 01003 start = end 01004 end += 4 01005 (length,) = _struct_I.unpack(str[start:end]) 01006 self.attached_collision_objects = [] 01007 for i in range(0, length): 01008 val1 = arm_navigation_msgs.msg.AttachedCollisionObject() 01009 start = end 01010 end += 4 01011 (length,) = _struct_I.unpack(str[start:end]) 01012 start = end 01013 end += length 01014 val1.link_name = str[start:end] 01015 _v48 = val1.object 01016 _v49 = _v48.header 01017 start = end 01018 end += 4 01019 (_v49.seq,) = _struct_I.unpack(str[start:end]) 01020 _v50 = _v49.stamp 01021 _x = _v50 01022 start = end 01023 end += 8 01024 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 01025 start = end 01026 end += 4 01027 (length,) = _struct_I.unpack(str[start:end]) 01028 start = end 01029 end += length 01030 _v49.frame_id = str[start:end] 01031 start = end 01032 end += 4 01033 (length,) = _struct_I.unpack(str[start:end]) 01034 start = end 01035 end += length 01036 _v48.id = str[start:end] 01037 start = end 01038 end += 4 01039 (_v48.padding,) = _struct_f.unpack(str[start:end]) 01040 _v51 = _v48.operation 01041 start = end 01042 end += 1 01043 (_v51.operation,) = _struct_b.unpack(str[start:end]) 01044 start = end 01045 end += 4 01046 (length,) = _struct_I.unpack(str[start:end]) 01047 _v48.shapes = [] 01048 for i in range(0, length): 01049 val3 = arm_navigation_msgs.msg.Shape() 01050 start = end 01051 end += 1 01052 (val3.type,) = _struct_b.unpack(str[start:end]) 01053 start = end 01054 end += 4 01055 (length,) = _struct_I.unpack(str[start:end]) 01056 pattern = '<%sd'%length 01057 start = end 01058 end += struct.calcsize(pattern) 01059 val3.dimensions = struct.unpack(pattern, str[start:end]) 01060 start = end 01061 end += 4 01062 (length,) = _struct_I.unpack(str[start:end]) 01063 pattern = '<%si'%length 01064 start = end 01065 end += struct.calcsize(pattern) 01066 val3.triangles = struct.unpack(pattern, str[start:end]) 01067 start = end 01068 end += 4 01069 (length,) = _struct_I.unpack(str[start:end]) 01070 val3.vertices = [] 01071 for i in range(0, length): 01072 val4 = geometry_msgs.msg.Point() 01073 _x = val4 01074 start = end 01075 end += 24 01076 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 01077 val3.vertices.append(val4) 01078 _v48.shapes.append(val3) 01079 start = end 01080 end += 4 01081 (length,) = _struct_I.unpack(str[start:end]) 01082 _v48.poses = [] 01083 for i in range(0, length): 01084 val3 = geometry_msgs.msg.Pose() 01085 _v52 = val3.position 01086 _x = _v52 01087 start = end 01088 end += 24 01089 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 01090 _v53 = val3.orientation 01091 _x = _v53 01092 start = end 01093 end += 32 01094 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 01095 _v48.poses.append(val3) 01096 start = end 01097 end += 4 01098 (length,) = _struct_I.unpack(str[start:end]) 01099 val1.touch_links = [] 01100 for i in range(0, length): 01101 start = end 01102 end += 4 01103 (length,) = _struct_I.unpack(str[start:end]) 01104 start = end 01105 end += length 01106 val2 = str[start:end] 01107 val1.touch_links.append(val2) 01108 self.attached_collision_objects.append(val1) 01109 _x = self 01110 start = end 01111 end += 12 01112 (_x.collision_map.header.seq, _x.collision_map.header.stamp.secs, _x.collision_map.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 01113 start = end 01114 end += 4 01115 (length,) = _struct_I.unpack(str[start:end]) 01116 start = end 01117 end += length 01118 self.collision_map.header.frame_id = str[start:end] 01119 start = end 01120 end += 4 01121 (length,) = _struct_I.unpack(str[start:end]) 01122 self.collision_map.boxes = [] 01123 for i in range(0, length): 01124 val1 = arm_navigation_msgs.msg.OrientedBoundingBox() 01125 _v54 = val1.center 01126 _x = _v54 01127 start = end 01128 end += 12 01129 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end]) 01130 _v55 = val1.extents 01131 _x = _v55 01132 start = end 01133 end += 12 01134 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end]) 01135 _v56 = val1.axis 01136 _x = _v56 01137 start = end 01138 end += 12 01139 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end]) 01140 start = end 01141 end += 4 01142 (val1.angle,) = _struct_f.unpack(str[start:end]) 01143 self.collision_map.boxes.append(val1) 01144 return self 01145 except struct.error as e: 01146 raise roslib.message.DeserializationError(e) #most likely buffer underfill 01147 01148 01149 def serialize_numpy(self, buff, numpy): 01150 """ 01151 serialize message with numpy array types into buffer 01152 @param buff: buffer 01153 @type buff: StringIO 01154 @param numpy: numpy python module 01155 @type numpy module 01156 """ 01157 try: 01158 _x = self 01159 buff.write(_struct_3I.pack(_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs)) 01160 _x = self.robot_state.joint_state.header.frame_id 01161 length = len(_x) 01162 buff.write(struct.pack('<I%ss'%length, length, _x)) 01163 length = len(self.robot_state.joint_state.name) 01164 buff.write(_struct_I.pack(length)) 01165 for val1 in self.robot_state.joint_state.name: 01166 length = len(val1) 01167 buff.write(struct.pack('<I%ss'%length, length, val1)) 01168 length = len(self.robot_state.joint_state.position) 01169 buff.write(_struct_I.pack(length)) 01170 pattern = '<%sd'%length 01171 buff.write(self.robot_state.joint_state.position.tostring()) 01172 length = len(self.robot_state.joint_state.velocity) 01173 buff.write(_struct_I.pack(length)) 01174 pattern = '<%sd'%length 01175 buff.write(self.robot_state.joint_state.velocity.tostring()) 01176 length = len(self.robot_state.joint_state.effort) 01177 buff.write(_struct_I.pack(length)) 01178 pattern = '<%sd'%length 01179 buff.write(self.robot_state.joint_state.effort.tostring()) 01180 _x = self 01181 buff.write(_struct_2I.pack(_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs)) 01182 length = len(self.robot_state.multi_dof_joint_state.joint_names) 01183 buff.write(_struct_I.pack(length)) 01184 for val1 in self.robot_state.multi_dof_joint_state.joint_names: 01185 length = len(val1) 01186 buff.write(struct.pack('<I%ss'%length, length, val1)) 01187 length = len(self.robot_state.multi_dof_joint_state.frame_ids) 01188 buff.write(_struct_I.pack(length)) 01189 for val1 in self.robot_state.multi_dof_joint_state.frame_ids: 01190 length = len(val1) 01191 buff.write(struct.pack('<I%ss'%length, length, val1)) 01192 length = len(self.robot_state.multi_dof_joint_state.child_frame_ids) 01193 buff.write(_struct_I.pack(length)) 01194 for val1 in self.robot_state.multi_dof_joint_state.child_frame_ids: 01195 length = len(val1) 01196 buff.write(struct.pack('<I%ss'%length, length, val1)) 01197 length = len(self.robot_state.multi_dof_joint_state.poses) 01198 buff.write(_struct_I.pack(length)) 01199 for val1 in self.robot_state.multi_dof_joint_state.poses: 01200 _v57 = val1.position 01201 _x = _v57 01202 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 01203 _v58 = val1.orientation 01204 _x = _v58 01205 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 01206 length = len(self.fixed_frame_transforms) 01207 buff.write(_struct_I.pack(length)) 01208 for val1 in self.fixed_frame_transforms: 01209 _v59 = val1.header 01210 buff.write(_struct_I.pack(_v59.seq)) 01211 _v60 = _v59.stamp 01212 _x = _v60 01213 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 01214 _x = _v59.frame_id 01215 length = len(_x) 01216 buff.write(struct.pack('<I%ss'%length, length, _x)) 01217 _x = val1.child_frame_id 01218 length = len(_x) 01219 buff.write(struct.pack('<I%ss'%length, length, _x)) 01220 _v61 = val1.transform 01221 _v62 = _v61.translation 01222 _x = _v62 01223 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 01224 _v63 = _v61.rotation 01225 _x = _v63 01226 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 01227 length = len(self.allowed_collision_matrix.link_names) 01228 buff.write(_struct_I.pack(length)) 01229 for val1 in self.allowed_collision_matrix.link_names: 01230 length = len(val1) 01231 buff.write(struct.pack('<I%ss'%length, length, val1)) 01232 length = len(self.allowed_collision_matrix.entries) 01233 buff.write(_struct_I.pack(length)) 01234 for val1 in self.allowed_collision_matrix.entries: 01235 length = len(val1.enabled) 01236 buff.write(_struct_I.pack(length)) 01237 pattern = '<%sB'%length 01238 buff.write(val1.enabled.tostring()) 01239 length = len(self.allowed_contacts) 01240 buff.write(_struct_I.pack(length)) 01241 for val1 in self.allowed_contacts: 01242 _x = val1.name 01243 length = len(_x) 01244 buff.write(struct.pack('<I%ss'%length, length, _x)) 01245 _v64 = val1.shape 01246 buff.write(_struct_b.pack(_v64.type)) 01247 length = len(_v64.dimensions) 01248 buff.write(_struct_I.pack(length)) 01249 pattern = '<%sd'%length 01250 buff.write(_v64.dimensions.tostring()) 01251 length = len(_v64.triangles) 01252 buff.write(_struct_I.pack(length)) 01253 pattern = '<%si'%length 01254 buff.write(_v64.triangles.tostring()) 01255 length = len(_v64.vertices) 01256 buff.write(_struct_I.pack(length)) 01257 for val3 in _v64.vertices: 01258 _x = val3 01259 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 01260 _v65 = val1.pose_stamped 01261 _v66 = _v65.header 01262 buff.write(_struct_I.pack(_v66.seq)) 01263 _v67 = _v66.stamp 01264 _x = _v67 01265 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 01266 _x = _v66.frame_id 01267 length = len(_x) 01268 buff.write(struct.pack('<I%ss'%length, length, _x)) 01269 _v68 = _v65.pose 01270 _v69 = _v68.position 01271 _x = _v69 01272 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 01273 _v70 = _v68.orientation 01274 _x = _v70 01275 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 01276 length = len(val1.link_names) 01277 buff.write(_struct_I.pack(length)) 01278 for val2 in val1.link_names: 01279 length = len(val2) 01280 buff.write(struct.pack('<I%ss'%length, length, val2)) 01281 buff.write(_struct_d.pack(val1.penetration_depth)) 01282 length = len(self.link_padding) 01283 buff.write(_struct_I.pack(length)) 01284 for val1 in self.link_padding: 01285 _x = val1.link_name 01286 length = len(_x) 01287 buff.write(struct.pack('<I%ss'%length, length, _x)) 01288 buff.write(_struct_d.pack(val1.padding)) 01289 length = len(self.collision_objects) 01290 buff.write(_struct_I.pack(length)) 01291 for val1 in self.collision_objects: 01292 _v71 = val1.header 01293 buff.write(_struct_I.pack(_v71.seq)) 01294 _v72 = _v71.stamp 01295 _x = _v72 01296 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 01297 _x = _v71.frame_id 01298 length = len(_x) 01299 buff.write(struct.pack('<I%ss'%length, length, _x)) 01300 _x = val1.id 01301 length = len(_x) 01302 buff.write(struct.pack('<I%ss'%length, length, _x)) 01303 buff.write(_struct_f.pack(val1.padding)) 01304 _v73 = val1.operation 01305 buff.write(_struct_b.pack(_v73.operation)) 01306 length = len(val1.shapes) 01307 buff.write(_struct_I.pack(length)) 01308 for val2 in val1.shapes: 01309 buff.write(_struct_b.pack(val2.type)) 01310 length = len(val2.dimensions) 01311 buff.write(_struct_I.pack(length)) 01312 pattern = '<%sd'%length 01313 buff.write(val2.dimensions.tostring()) 01314 length = len(val2.triangles) 01315 buff.write(_struct_I.pack(length)) 01316 pattern = '<%si'%length 01317 buff.write(val2.triangles.tostring()) 01318 length = len(val2.vertices) 01319 buff.write(_struct_I.pack(length)) 01320 for val3 in val2.vertices: 01321 _x = val3 01322 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 01323 length = len(val1.poses) 01324 buff.write(_struct_I.pack(length)) 01325 for val2 in val1.poses: 01326 _v74 = val2.position 01327 _x = _v74 01328 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 01329 _v75 = val2.orientation 01330 _x = _v75 01331 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 01332 length = len(self.attached_collision_objects) 01333 buff.write(_struct_I.pack(length)) 01334 for val1 in self.attached_collision_objects: 01335 _x = val1.link_name 01336 length = len(_x) 01337 buff.write(struct.pack('<I%ss'%length, length, _x)) 01338 _v76 = val1.object 01339 _v77 = _v76.header 01340 buff.write(_struct_I.pack(_v77.seq)) 01341 _v78 = _v77.stamp 01342 _x = _v78 01343 buff.write(_struct_2I.pack(_x.secs, _x.nsecs)) 01344 _x = _v77.frame_id 01345 length = len(_x) 01346 buff.write(struct.pack('<I%ss'%length, length, _x)) 01347 _x = _v76.id 01348 length = len(_x) 01349 buff.write(struct.pack('<I%ss'%length, length, _x)) 01350 buff.write(_struct_f.pack(_v76.padding)) 01351 _v79 = _v76.operation 01352 buff.write(_struct_b.pack(_v79.operation)) 01353 length = len(_v76.shapes) 01354 buff.write(_struct_I.pack(length)) 01355 for val3 in _v76.shapes: 01356 buff.write(_struct_b.pack(val3.type)) 01357 length = len(val3.dimensions) 01358 buff.write(_struct_I.pack(length)) 01359 pattern = '<%sd'%length 01360 buff.write(val3.dimensions.tostring()) 01361 length = len(val3.triangles) 01362 buff.write(_struct_I.pack(length)) 01363 pattern = '<%si'%length 01364 buff.write(val3.triangles.tostring()) 01365 length = len(val3.vertices) 01366 buff.write(_struct_I.pack(length)) 01367 for val4 in val3.vertices: 01368 _x = val4 01369 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 01370 length = len(_v76.poses) 01371 buff.write(_struct_I.pack(length)) 01372 for val3 in _v76.poses: 01373 _v80 = val3.position 01374 _x = _v80 01375 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 01376 _v81 = val3.orientation 01377 _x = _v81 01378 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 01379 length = len(val1.touch_links) 01380 buff.write(_struct_I.pack(length)) 01381 for val2 in val1.touch_links: 01382 length = len(val2) 01383 buff.write(struct.pack('<I%ss'%length, length, val2)) 01384 _x = self 01385 buff.write(_struct_3I.pack(_x.collision_map.header.seq, _x.collision_map.header.stamp.secs, _x.collision_map.header.stamp.nsecs)) 01386 _x = self.collision_map.header.frame_id 01387 length = len(_x) 01388 buff.write(struct.pack('<I%ss'%length, length, _x)) 01389 length = len(self.collision_map.boxes) 01390 buff.write(_struct_I.pack(length)) 01391 for val1 in self.collision_map.boxes: 01392 _v82 = val1.center 01393 _x = _v82 01394 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z)) 01395 _v83 = val1.extents 01396 _x = _v83 01397 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z)) 01398 _v84 = val1.axis 01399 _x = _v84 01400 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z)) 01401 buff.write(_struct_f.pack(val1.angle)) 01402 except struct.error as se: self._check_types(se) 01403 except TypeError as te: self._check_types(te) 01404 01405 def deserialize_numpy(self, str, numpy): 01406 """ 01407 unpack serialized message in str into this message instance using numpy for array types 01408 @param str: byte array of serialized message 01409 @type str: str 01410 @param numpy: numpy python module 01411 @type numpy: module 01412 """ 01413 try: 01414 if self.robot_state is None: 01415 self.robot_state = arm_navigation_msgs.msg.RobotState() 01416 if self.allowed_collision_matrix is None: 01417 self.allowed_collision_matrix = arm_navigation_msgs.msg.AllowedCollisionMatrix() 01418 if self.collision_map is None: 01419 self.collision_map = arm_navigation_msgs.msg.CollisionMap() 01420 end = 0 01421 _x = self 01422 start = end 01423 end += 12 01424 (_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 01425 start = end 01426 end += 4 01427 (length,) = _struct_I.unpack(str[start:end]) 01428 start = end 01429 end += length 01430 self.robot_state.joint_state.header.frame_id = str[start:end] 01431 start = end 01432 end += 4 01433 (length,) = _struct_I.unpack(str[start:end]) 01434 self.robot_state.joint_state.name = [] 01435 for i in range(0, length): 01436 start = end 01437 end += 4 01438 (length,) = _struct_I.unpack(str[start:end]) 01439 start = end 01440 end += length 01441 val1 = str[start:end] 01442 self.robot_state.joint_state.name.append(val1) 01443 start = end 01444 end += 4 01445 (length,) = _struct_I.unpack(str[start:end]) 01446 pattern = '<%sd'%length 01447 start = end 01448 end += struct.calcsize(pattern) 01449 self.robot_state.joint_state.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 01450 start = end 01451 end += 4 01452 (length,) = _struct_I.unpack(str[start:end]) 01453 pattern = '<%sd'%length 01454 start = end 01455 end += struct.calcsize(pattern) 01456 self.robot_state.joint_state.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 01457 start = end 01458 end += 4 01459 (length,) = _struct_I.unpack(str[start:end]) 01460 pattern = '<%sd'%length 01461 start = end 01462 end += struct.calcsize(pattern) 01463 self.robot_state.joint_state.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 01464 _x = self 01465 start = end 01466 end += 8 01467 (_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 01468 start = end 01469 end += 4 01470 (length,) = _struct_I.unpack(str[start:end]) 01471 self.robot_state.multi_dof_joint_state.joint_names = [] 01472 for i in range(0, length): 01473 start = end 01474 end += 4 01475 (length,) = _struct_I.unpack(str[start:end]) 01476 start = end 01477 end += length 01478 val1 = str[start:end] 01479 self.robot_state.multi_dof_joint_state.joint_names.append(val1) 01480 start = end 01481 end += 4 01482 (length,) = _struct_I.unpack(str[start:end]) 01483 self.robot_state.multi_dof_joint_state.frame_ids = [] 01484 for i in range(0, length): 01485 start = end 01486 end += 4 01487 (length,) = _struct_I.unpack(str[start:end]) 01488 start = end 01489 end += length 01490 val1 = str[start:end] 01491 self.robot_state.multi_dof_joint_state.frame_ids.append(val1) 01492 start = end 01493 end += 4 01494 (length,) = _struct_I.unpack(str[start:end]) 01495 self.robot_state.multi_dof_joint_state.child_frame_ids = [] 01496 for i in range(0, length): 01497 start = end 01498 end += 4 01499 (length,) = _struct_I.unpack(str[start:end]) 01500 start = end 01501 end += length 01502 val1 = str[start:end] 01503 self.robot_state.multi_dof_joint_state.child_frame_ids.append(val1) 01504 start = end 01505 end += 4 01506 (length,) = _struct_I.unpack(str[start:end]) 01507 self.robot_state.multi_dof_joint_state.poses = [] 01508 for i in range(0, length): 01509 val1 = geometry_msgs.msg.Pose() 01510 _v85 = val1.position 01511 _x = _v85 01512 start = end 01513 end += 24 01514 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 01515 _v86 = val1.orientation 01516 _x = _v86 01517 start = end 01518 end += 32 01519 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 01520 self.robot_state.multi_dof_joint_state.poses.append(val1) 01521 start = end 01522 end += 4 01523 (length,) = _struct_I.unpack(str[start:end]) 01524 self.fixed_frame_transforms = [] 01525 for i in range(0, length): 01526 val1 = geometry_msgs.msg.TransformStamped() 01527 _v87 = val1.header 01528 start = end 01529 end += 4 01530 (_v87.seq,) = _struct_I.unpack(str[start:end]) 01531 _v88 = _v87.stamp 01532 _x = _v88 01533 start = end 01534 end += 8 01535 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 01536 start = end 01537 end += 4 01538 (length,) = _struct_I.unpack(str[start:end]) 01539 start = end 01540 end += length 01541 _v87.frame_id = str[start:end] 01542 start = end 01543 end += 4 01544 (length,) = _struct_I.unpack(str[start:end]) 01545 start = end 01546 end += length 01547 val1.child_frame_id = str[start:end] 01548 _v89 = val1.transform 01549 _v90 = _v89.translation 01550 _x = _v90 01551 start = end 01552 end += 24 01553 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 01554 _v91 = _v89.rotation 01555 _x = _v91 01556 start = end 01557 end += 32 01558 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 01559 self.fixed_frame_transforms.append(val1) 01560 start = end 01561 end += 4 01562 (length,) = _struct_I.unpack(str[start:end]) 01563 self.allowed_collision_matrix.link_names = [] 01564 for i in range(0, length): 01565 start = end 01566 end += 4 01567 (length,) = _struct_I.unpack(str[start:end]) 01568 start = end 01569 end += length 01570 val1 = str[start:end] 01571 self.allowed_collision_matrix.link_names.append(val1) 01572 start = end 01573 end += 4 01574 (length,) = _struct_I.unpack(str[start:end]) 01575 self.allowed_collision_matrix.entries = [] 01576 for i in range(0, length): 01577 val1 = arm_navigation_msgs.msg.AllowedCollisionEntry() 01578 start = end 01579 end += 4 01580 (length,) = _struct_I.unpack(str[start:end]) 01581 pattern = '<%sB'%length 01582 start = end 01583 end += struct.calcsize(pattern) 01584 val1.enabled = numpy.frombuffer(str[start:end], dtype=numpy.bool, count=length) 01585 val1.enabled = map(bool, val1.enabled) 01586 self.allowed_collision_matrix.entries.append(val1) 01587 start = end 01588 end += 4 01589 (length,) = _struct_I.unpack(str[start:end]) 01590 self.allowed_contacts = [] 01591 for i in range(0, length): 01592 val1 = arm_navigation_msgs.msg.AllowedContactSpecification() 01593 start = end 01594 end += 4 01595 (length,) = _struct_I.unpack(str[start:end]) 01596 start = end 01597 end += length 01598 val1.name = str[start:end] 01599 _v92 = val1.shape 01600 start = end 01601 end += 1 01602 (_v92.type,) = _struct_b.unpack(str[start:end]) 01603 start = end 01604 end += 4 01605 (length,) = _struct_I.unpack(str[start:end]) 01606 pattern = '<%sd'%length 01607 start = end 01608 end += struct.calcsize(pattern) 01609 _v92.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 01610 start = end 01611 end += 4 01612 (length,) = _struct_I.unpack(str[start:end]) 01613 pattern = '<%si'%length 01614 start = end 01615 end += struct.calcsize(pattern) 01616 _v92.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length) 01617 start = end 01618 end += 4 01619 (length,) = _struct_I.unpack(str[start:end]) 01620 _v92.vertices = [] 01621 for i in range(0, length): 01622 val3 = geometry_msgs.msg.Point() 01623 _x = val3 01624 start = end 01625 end += 24 01626 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 01627 _v92.vertices.append(val3) 01628 _v93 = val1.pose_stamped 01629 _v94 = _v93.header 01630 start = end 01631 end += 4 01632 (_v94.seq,) = _struct_I.unpack(str[start:end]) 01633 _v95 = _v94.stamp 01634 _x = _v95 01635 start = end 01636 end += 8 01637 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 01638 start = end 01639 end += 4 01640 (length,) = _struct_I.unpack(str[start:end]) 01641 start = end 01642 end += length 01643 _v94.frame_id = str[start:end] 01644 _v96 = _v93.pose 01645 _v97 = _v96.position 01646 _x = _v97 01647 start = end 01648 end += 24 01649 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 01650 _v98 = _v96.orientation 01651 _x = _v98 01652 start = end 01653 end += 32 01654 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 01655 start = end 01656 end += 4 01657 (length,) = _struct_I.unpack(str[start:end]) 01658 val1.link_names = [] 01659 for i in range(0, length): 01660 start = end 01661 end += 4 01662 (length,) = _struct_I.unpack(str[start:end]) 01663 start = end 01664 end += length 01665 val2 = str[start:end] 01666 val1.link_names.append(val2) 01667 start = end 01668 end += 8 01669 (val1.penetration_depth,) = _struct_d.unpack(str[start:end]) 01670 self.allowed_contacts.append(val1) 01671 start = end 01672 end += 4 01673 (length,) = _struct_I.unpack(str[start:end]) 01674 self.link_padding = [] 01675 for i in range(0, length): 01676 val1 = arm_navigation_msgs.msg.LinkPadding() 01677 start = end 01678 end += 4 01679 (length,) = _struct_I.unpack(str[start:end]) 01680 start = end 01681 end += length 01682 val1.link_name = str[start:end] 01683 start = end 01684 end += 8 01685 (val1.padding,) = _struct_d.unpack(str[start:end]) 01686 self.link_padding.append(val1) 01687 start = end 01688 end += 4 01689 (length,) = _struct_I.unpack(str[start:end]) 01690 self.collision_objects = [] 01691 for i in range(0, length): 01692 val1 = arm_navigation_msgs.msg.CollisionObject() 01693 _v99 = val1.header 01694 start = end 01695 end += 4 01696 (_v99.seq,) = _struct_I.unpack(str[start:end]) 01697 _v100 = _v99.stamp 01698 _x = _v100 01699 start = end 01700 end += 8 01701 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 01702 start = end 01703 end += 4 01704 (length,) = _struct_I.unpack(str[start:end]) 01705 start = end 01706 end += length 01707 _v99.frame_id = str[start:end] 01708 start = end 01709 end += 4 01710 (length,) = _struct_I.unpack(str[start:end]) 01711 start = end 01712 end += length 01713 val1.id = str[start:end] 01714 start = end 01715 end += 4 01716 (val1.padding,) = _struct_f.unpack(str[start:end]) 01717 _v101 = val1.operation 01718 start = end 01719 end += 1 01720 (_v101.operation,) = _struct_b.unpack(str[start:end]) 01721 start = end 01722 end += 4 01723 (length,) = _struct_I.unpack(str[start:end]) 01724 val1.shapes = [] 01725 for i in range(0, length): 01726 val2 = arm_navigation_msgs.msg.Shape() 01727 start = end 01728 end += 1 01729 (val2.type,) = _struct_b.unpack(str[start:end]) 01730 start = end 01731 end += 4 01732 (length,) = _struct_I.unpack(str[start:end]) 01733 pattern = '<%sd'%length 01734 start = end 01735 end += struct.calcsize(pattern) 01736 val2.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 01737 start = end 01738 end += 4 01739 (length,) = _struct_I.unpack(str[start:end]) 01740 pattern = '<%si'%length 01741 start = end 01742 end += struct.calcsize(pattern) 01743 val2.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length) 01744 start = end 01745 end += 4 01746 (length,) = _struct_I.unpack(str[start:end]) 01747 val2.vertices = [] 01748 for i in range(0, length): 01749 val3 = geometry_msgs.msg.Point() 01750 _x = val3 01751 start = end 01752 end += 24 01753 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 01754 val2.vertices.append(val3) 01755 val1.shapes.append(val2) 01756 start = end 01757 end += 4 01758 (length,) = _struct_I.unpack(str[start:end]) 01759 val1.poses = [] 01760 for i in range(0, length): 01761 val2 = geometry_msgs.msg.Pose() 01762 _v102 = val2.position 01763 _x = _v102 01764 start = end 01765 end += 24 01766 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 01767 _v103 = val2.orientation 01768 _x = _v103 01769 start = end 01770 end += 32 01771 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 01772 val1.poses.append(val2) 01773 self.collision_objects.append(val1) 01774 start = end 01775 end += 4 01776 (length,) = _struct_I.unpack(str[start:end]) 01777 self.attached_collision_objects = [] 01778 for i in range(0, length): 01779 val1 = arm_navigation_msgs.msg.AttachedCollisionObject() 01780 start = end 01781 end += 4 01782 (length,) = _struct_I.unpack(str[start:end]) 01783 start = end 01784 end += length 01785 val1.link_name = str[start:end] 01786 _v104 = val1.object 01787 _v105 = _v104.header 01788 start = end 01789 end += 4 01790 (_v105.seq,) = _struct_I.unpack(str[start:end]) 01791 _v106 = _v105.stamp 01792 _x = _v106 01793 start = end 01794 end += 8 01795 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end]) 01796 start = end 01797 end += 4 01798 (length,) = _struct_I.unpack(str[start:end]) 01799 start = end 01800 end += length 01801 _v105.frame_id = str[start:end] 01802 start = end 01803 end += 4 01804 (length,) = _struct_I.unpack(str[start:end]) 01805 start = end 01806 end += length 01807 _v104.id = str[start:end] 01808 start = end 01809 end += 4 01810 (_v104.padding,) = _struct_f.unpack(str[start:end]) 01811 _v107 = _v104.operation 01812 start = end 01813 end += 1 01814 (_v107.operation,) = _struct_b.unpack(str[start:end]) 01815 start = end 01816 end += 4 01817 (length,) = _struct_I.unpack(str[start:end]) 01818 _v104.shapes = [] 01819 for i in range(0, length): 01820 val3 = arm_navigation_msgs.msg.Shape() 01821 start = end 01822 end += 1 01823 (val3.type,) = _struct_b.unpack(str[start:end]) 01824 start = end 01825 end += 4 01826 (length,) = _struct_I.unpack(str[start:end]) 01827 pattern = '<%sd'%length 01828 start = end 01829 end += struct.calcsize(pattern) 01830 val3.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 01831 start = end 01832 end += 4 01833 (length,) = _struct_I.unpack(str[start:end]) 01834 pattern = '<%si'%length 01835 start = end 01836 end += struct.calcsize(pattern) 01837 val3.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length) 01838 start = end 01839 end += 4 01840 (length,) = _struct_I.unpack(str[start:end]) 01841 val3.vertices = [] 01842 for i in range(0, length): 01843 val4 = geometry_msgs.msg.Point() 01844 _x = val4 01845 start = end 01846 end += 24 01847 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 01848 val3.vertices.append(val4) 01849 _v104.shapes.append(val3) 01850 start = end 01851 end += 4 01852 (length,) = _struct_I.unpack(str[start:end]) 01853 _v104.poses = [] 01854 for i in range(0, length): 01855 val3 = geometry_msgs.msg.Pose() 01856 _v108 = val3.position 01857 _x = _v108 01858 start = end 01859 end += 24 01860 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 01861 _v109 = val3.orientation 01862 _x = _v109 01863 start = end 01864 end += 32 01865 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 01866 _v104.poses.append(val3) 01867 start = end 01868 end += 4 01869 (length,) = _struct_I.unpack(str[start:end]) 01870 val1.touch_links = [] 01871 for i in range(0, length): 01872 start = end 01873 end += 4 01874 (length,) = _struct_I.unpack(str[start:end]) 01875 start = end 01876 end += length 01877 val2 = str[start:end] 01878 val1.touch_links.append(val2) 01879 self.attached_collision_objects.append(val1) 01880 _x = self 01881 start = end 01882 end += 12 01883 (_x.collision_map.header.seq, _x.collision_map.header.stamp.secs, _x.collision_map.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 01884 start = end 01885 end += 4 01886 (length,) = _struct_I.unpack(str[start:end]) 01887 start = end 01888 end += length 01889 self.collision_map.header.frame_id = str[start:end] 01890 start = end 01891 end += 4 01892 (length,) = _struct_I.unpack(str[start:end]) 01893 self.collision_map.boxes = [] 01894 for i in range(0, length): 01895 val1 = arm_navigation_msgs.msg.OrientedBoundingBox() 01896 _v110 = val1.center 01897 _x = _v110 01898 start = end 01899 end += 12 01900 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end]) 01901 _v111 = val1.extents 01902 _x = _v111 01903 start = end 01904 end += 12 01905 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end]) 01906 _v112 = val1.axis 01907 _x = _v112 01908 start = end 01909 end += 12 01910 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end]) 01911 start = end 01912 end += 4 01913 (val1.angle,) = _struct_f.unpack(str[start:end]) 01914 self.collision_map.boxes.append(val1) 01915 return self 01916 except struct.error as e: 01917 raise roslib.message.DeserializationError(e) #most likely buffer underfill 01918 01919 _struct_I = roslib.message.struct_I 01920 _struct_b = struct.Struct("<b") 01921 _struct_d = struct.Struct("<d") 01922 _struct_f = struct.Struct("<f") 01923 _struct_3f = struct.Struct("<3f") 01924 _struct_3I = struct.Struct("<3I") 01925 _struct_4d = struct.Struct("<4d") 01926 _struct_2I = struct.Struct("<2I") 01927 _struct_3d = struct.Struct("<3d")