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


arm_navigation_msgs
Author(s): Gil Jones
autogenerated on Mon Dec 2 2013 12:31:50