_GetJointTrajectoryValidity.py
Go to the documentation of this file.
00001 """autogenerated by genpy from arm_navigation_msgs/GetJointTrajectoryValidityRequest.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 trajectory_msgs.msg
00008 import arm_navigation_msgs.msg
00009 import geometry_msgs.msg
00010 import sensor_msgs.msg
00011 import genpy
00012 import std_msgs.msg
00013 
00014 class GetJointTrajectoryValidityRequest(genpy.Message):
00015   _md5sum = "084166b764e3c85269ae9d5ee08f7654"
00016   _type = "arm_navigation_msgs/GetJointTrajectoryValidityRequest"
00017   _has_header = False #flag to mark the presence of a Header object
00018   _full_text = """
00019 trajectory_msgs/JointTrajectory trajectory
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 arm_navigation_msgs/RobotState robot_state
00028 
00029 
00030 bool check_collisions
00031 
00032 
00033 bool check_path_constraints
00034 
00035 
00036 bool check_goal_constraints
00037 
00038 
00039 bool check_joint_limits
00040 
00041 
00042 
00043 
00044 bool check_full_trajectory
00045 
00046 
00047 
00048 
00049 arm_navigation_msgs/Constraints path_constraints
00050 
00051 
00052 
00053 
00054 arm_navigation_msgs/Constraints goal_constraints
00055 
00056 
00057 ================================================================================
00058 MSG: trajectory_msgs/JointTrajectory
00059 Header header
00060 string[] joint_names
00061 JointTrajectoryPoint[] points
00062 ================================================================================
00063 MSG: std_msgs/Header
00064 # Standard metadata for higher-level stamped data types.
00065 # This is generally used to communicate timestamped data 
00066 # in a particular coordinate frame.
00067 # 
00068 # sequence ID: consecutively increasing ID 
00069 uint32 seq
00070 #Two-integer timestamp that is expressed as:
00071 # * stamp.secs: seconds (stamp_secs) since epoch
00072 # * stamp.nsecs: nanoseconds since stamp_secs
00073 # time-handling sugar is provided by the client library
00074 time stamp
00075 #Frame this data is associated with
00076 # 0: no frame
00077 # 1: global frame
00078 string frame_id
00079 
00080 ================================================================================
00081 MSG: trajectory_msgs/JointTrajectoryPoint
00082 float64[] positions
00083 float64[] velocities
00084 float64[] accelerations
00085 duration time_from_start
00086 ================================================================================
00087 MSG: arm_navigation_msgs/RobotState
00088 # This message contains information about the robot state, i.e. the positions of its joints and links
00089 sensor_msgs/JointState joint_state
00090 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state
00091 
00092 ================================================================================
00093 MSG: sensor_msgs/JointState
00094 # This is a message that holds data to describe the state of a set of torque controlled joints. 
00095 #
00096 # The state of each joint (revolute or prismatic) is defined by:
00097 #  * the position of the joint (rad or m),
00098 #  * the velocity of the joint (rad/s or m/s) and 
00099 #  * the effort that is applied in the joint (Nm or N).
00100 #
00101 # Each joint is uniquely identified by its name
00102 # The header specifies the time at which the joint states were recorded. All the joint states
00103 # in one message have to be recorded at the same time.
00104 #
00105 # This message consists of a multiple arrays, one for each part of the joint state. 
00106 # The goal is to make each of the fields optional. When e.g. your joints have no
00107 # effort associated with them, you can leave the effort array empty. 
00108 #
00109 # All arrays in this message should have the same size, or be empty.
00110 # This is the only way to uniquely associate the joint name with the correct
00111 # states.
00112 
00113 
00114 Header header
00115 
00116 string[] name
00117 float64[] position
00118 float64[] velocity
00119 float64[] effort
00120 
00121 ================================================================================
00122 MSG: arm_navigation_msgs/MultiDOFJointState
00123 #A representation of a multi-dof joint state
00124 time stamp
00125 string[] joint_names
00126 string[] frame_ids
00127 string[] child_frame_ids
00128 geometry_msgs/Pose[] poses
00129 
00130 ================================================================================
00131 MSG: geometry_msgs/Pose
00132 # A representation of pose in free space, composed of postion and orientation. 
00133 Point position
00134 Quaternion orientation
00135 
00136 ================================================================================
00137 MSG: geometry_msgs/Point
00138 # This contains the position of a point in free space
00139 float64 x
00140 float64 y
00141 float64 z
00142 
00143 ================================================================================
00144 MSG: geometry_msgs/Quaternion
00145 # This represents an orientation in free space in quaternion form.
00146 
00147 float64 x
00148 float64 y
00149 float64 z
00150 float64 w
00151 
00152 ================================================================================
00153 MSG: arm_navigation_msgs/Constraints
00154 # This message contains a list of motion planning constraints.
00155 
00156 arm_navigation_msgs/JointConstraint[] joint_constraints
00157 arm_navigation_msgs/PositionConstraint[] position_constraints
00158 arm_navigation_msgs/OrientationConstraint[] orientation_constraints
00159 arm_navigation_msgs/VisibilityConstraint[] visibility_constraints
00160 
00161 ================================================================================
00162 MSG: arm_navigation_msgs/JointConstraint
00163 # Constrain the position of a joint to be within a certain bound
00164 string joint_name
00165 
00166 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]
00167 float64 position
00168 float64 tolerance_above
00169 float64 tolerance_below
00170 
00171 # A weighting factor for this constraint
00172 float64 weight
00173 ================================================================================
00174 MSG: arm_navigation_msgs/PositionConstraint
00175 # This message contains the definition of a position constraint.
00176 Header header
00177 
00178 # The robot link this constraint refers to
00179 string link_name
00180 
00181 # The offset (in the link frame) for the target point on the link we are planning for
00182 geometry_msgs/Point target_point_offset
00183 
00184 # The nominal/target position for the point we are planning for
00185 geometry_msgs/Point position
00186 
00187 # The shape of the bounded region that constrains the position of the end-effector
00188 # This region is always centered at the position defined above
00189 arm_navigation_msgs/Shape constraint_region_shape
00190 
00191 # The orientation of the bounded region that constrains the position of the end-effector. 
00192 # This allows the specification of non-axis aligned constraints
00193 geometry_msgs/Quaternion constraint_region_orientation
00194 
00195 # Constraint weighting factor - a weight for this constraint
00196 float64 weight
00197 
00198 ================================================================================
00199 MSG: arm_navigation_msgs/Shape
00200 byte SPHERE=0
00201 byte BOX=1
00202 byte CYLINDER=2
00203 byte MESH=3
00204 
00205 byte type
00206 
00207 
00208 #### define sphere, box, cylinder ####
00209 # the origin of each shape is considered at the shape's center
00210 
00211 # for sphere
00212 # radius := dimensions[0]
00213 
00214 # for cylinder
00215 # radius := dimensions[0]
00216 # length := dimensions[1]
00217 # the length is along the Z axis
00218 
00219 # for box
00220 # size_x := dimensions[0]
00221 # size_y := dimensions[1]
00222 # size_z := dimensions[2]
00223 float64[] dimensions
00224 
00225 
00226 #### define mesh ####
00227 
00228 # list of triangles; triangle k is defined by tre vertices located
00229 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00230 int32[] triangles
00231 geometry_msgs/Point[] vertices
00232 
00233 ================================================================================
00234 MSG: arm_navigation_msgs/OrientationConstraint
00235 # This message contains the definition of an orientation constraint.
00236 Header header
00237 
00238 # The robot link this constraint refers to
00239 string link_name
00240 
00241 # The type of the constraint
00242 int32 type
00243 int32 LINK_FRAME=0
00244 int32 HEADER_FRAME=1
00245 
00246 # The desired orientation of the robot link specified as a quaternion
00247 geometry_msgs/Quaternion orientation
00248 
00249 # optional RPY error tolerances specified if 
00250 float64 absolute_roll_tolerance
00251 float64 absolute_pitch_tolerance
00252 float64 absolute_yaw_tolerance
00253 
00254 # Constraint weighting factor - a weight for this constraint
00255 float64 weight
00256 
00257 ================================================================================
00258 MSG: arm_navigation_msgs/VisibilityConstraint
00259 # This message contains the definition of a visibility constraint.
00260 Header header
00261 
00262 # The point stamped target that needs to be kept within view of the sensor
00263 geometry_msgs/PointStamped target
00264 
00265 # The local pose of the frame in which visibility is to be maintained
00266 # The frame id should represent the robot link to which the sensor is attached
00267 # The visual axis of the sensor is assumed to be along the X axis of this frame
00268 geometry_msgs/PoseStamped sensor_pose
00269 
00270 # The deviation (in radians) that will be tolerated
00271 # Constraint error will be measured as the solid angle between the 
00272 # X axis of the frame defined above and the vector between the origin 
00273 # of the frame defined above and the target location
00274 float64 absolute_tolerance
00275 
00276 
00277 ================================================================================
00278 MSG: geometry_msgs/PointStamped
00279 # This represents a Point with reference coordinate frame and timestamp
00280 Header header
00281 Point point
00282 
00283 ================================================================================
00284 MSG: geometry_msgs/PoseStamped
00285 # A Pose with reference coordinate frame and timestamp
00286 Header header
00287 Pose pose
00288 
00289 """
00290   __slots__ = ['trajectory','robot_state','check_collisions','check_path_constraints','check_goal_constraints','check_joint_limits','check_full_trajectory','path_constraints','goal_constraints']
00291   _slot_types = ['trajectory_msgs/JointTrajectory','arm_navigation_msgs/RobotState','bool','bool','bool','bool','bool','arm_navigation_msgs/Constraints','arm_navigation_msgs/Constraints']
00292 
00293   def __init__(self, *args, **kwds):
00294     """
00295     Constructor. Any message fields that are implicitly/explicitly
00296     set to None will be assigned a default value. The recommend
00297     use is keyword arguments as this is more robust to future message
00298     changes.  You cannot mix in-order arguments and keyword arguments.
00299 
00300     The available fields are:
00301        trajectory,robot_state,check_collisions,check_path_constraints,check_goal_constraints,check_joint_limits,check_full_trajectory,path_constraints,goal_constraints
00302 
00303     :param args: complete set of field values, in .msg order
00304     :param kwds: use keyword arguments corresponding to message field names
00305     to set specific fields.
00306     """
00307     if args or kwds:
00308       super(GetJointTrajectoryValidityRequest, self).__init__(*args, **kwds)
00309       #message fields cannot be None, assign default values for those that are
00310       if self.trajectory is None:
00311         self.trajectory = trajectory_msgs.msg.JointTrajectory()
00312       if self.robot_state is None:
00313         self.robot_state = arm_navigation_msgs.msg.RobotState()
00314       if self.check_collisions is None:
00315         self.check_collisions = False
00316       if self.check_path_constraints is None:
00317         self.check_path_constraints = False
00318       if self.check_goal_constraints is None:
00319         self.check_goal_constraints = False
00320       if self.check_joint_limits is None:
00321         self.check_joint_limits = False
00322       if self.check_full_trajectory is None:
00323         self.check_full_trajectory = False
00324       if self.path_constraints is None:
00325         self.path_constraints = arm_navigation_msgs.msg.Constraints()
00326       if self.goal_constraints is None:
00327         self.goal_constraints = arm_navigation_msgs.msg.Constraints()
00328     else:
00329       self.trajectory = trajectory_msgs.msg.JointTrajectory()
00330       self.robot_state = arm_navigation_msgs.msg.RobotState()
00331       self.check_collisions = False
00332       self.check_path_constraints = False
00333       self.check_goal_constraints = False
00334       self.check_joint_limits = False
00335       self.check_full_trajectory = False
00336       self.path_constraints = arm_navigation_msgs.msg.Constraints()
00337       self.goal_constraints = arm_navigation_msgs.msg.Constraints()
00338 
00339   def _get_types(self):
00340     """
00341     internal API method
00342     """
00343     return self._slot_types
00344 
00345   def serialize(self, buff):
00346     """
00347     serialize message into buffer
00348     :param buff: buffer, ``StringIO``
00349     """
00350     try:
00351       _x = self
00352       buff.write(_struct_3I.pack(_x.trajectory.header.seq, _x.trajectory.header.stamp.secs, _x.trajectory.header.stamp.nsecs))
00353       _x = self.trajectory.header.frame_id
00354       length = len(_x)
00355       if python3 or type(_x) == unicode:
00356         _x = _x.encode('utf-8')
00357         length = len(_x)
00358       buff.write(struct.pack('<I%ss'%length, length, _x))
00359       length = len(self.trajectory.joint_names)
00360       buff.write(_struct_I.pack(length))
00361       for val1 in self.trajectory.joint_names:
00362         length = len(val1)
00363         if python3 or type(val1) == unicode:
00364           val1 = val1.encode('utf-8')
00365           length = len(val1)
00366         buff.write(struct.pack('<I%ss'%length, length, val1))
00367       length = len(self.trajectory.points)
00368       buff.write(_struct_I.pack(length))
00369       for val1 in self.trajectory.points:
00370         length = len(val1.positions)
00371         buff.write(_struct_I.pack(length))
00372         pattern = '<%sd'%length
00373         buff.write(struct.pack(pattern, *val1.positions))
00374         length = len(val1.velocities)
00375         buff.write(_struct_I.pack(length))
00376         pattern = '<%sd'%length
00377         buff.write(struct.pack(pattern, *val1.velocities))
00378         length = len(val1.accelerations)
00379         buff.write(_struct_I.pack(length))
00380         pattern = '<%sd'%length
00381         buff.write(struct.pack(pattern, *val1.accelerations))
00382         _v1 = val1.time_from_start
00383         _x = _v1
00384         buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00385       _x = self
00386       buff.write(_struct_3I.pack(_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs))
00387       _x = self.robot_state.joint_state.header.frame_id
00388       length = len(_x)
00389       if python3 or type(_x) == unicode:
00390         _x = _x.encode('utf-8')
00391         length = len(_x)
00392       buff.write(struct.pack('<I%ss'%length, length, _x))
00393       length = len(self.robot_state.joint_state.name)
00394       buff.write(_struct_I.pack(length))
00395       for val1 in self.robot_state.joint_state.name:
00396         length = len(val1)
00397         if python3 or type(val1) == unicode:
00398           val1 = val1.encode('utf-8')
00399           length = len(val1)
00400         buff.write(struct.pack('<I%ss'%length, length, val1))
00401       length = len(self.robot_state.joint_state.position)
00402       buff.write(_struct_I.pack(length))
00403       pattern = '<%sd'%length
00404       buff.write(struct.pack(pattern, *self.robot_state.joint_state.position))
00405       length = len(self.robot_state.joint_state.velocity)
00406       buff.write(_struct_I.pack(length))
00407       pattern = '<%sd'%length
00408       buff.write(struct.pack(pattern, *self.robot_state.joint_state.velocity))
00409       length = len(self.robot_state.joint_state.effort)
00410       buff.write(_struct_I.pack(length))
00411       pattern = '<%sd'%length
00412       buff.write(struct.pack(pattern, *self.robot_state.joint_state.effort))
00413       _x = self
00414       buff.write(_struct_2I.pack(_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs))
00415       length = len(self.robot_state.multi_dof_joint_state.joint_names)
00416       buff.write(_struct_I.pack(length))
00417       for val1 in self.robot_state.multi_dof_joint_state.joint_names:
00418         length = len(val1)
00419         if python3 or type(val1) == unicode:
00420           val1 = val1.encode('utf-8')
00421           length = len(val1)
00422         buff.write(struct.pack('<I%ss'%length, length, val1))
00423       length = len(self.robot_state.multi_dof_joint_state.frame_ids)
00424       buff.write(_struct_I.pack(length))
00425       for val1 in self.robot_state.multi_dof_joint_state.frame_ids:
00426         length = len(val1)
00427         if python3 or type(val1) == unicode:
00428           val1 = val1.encode('utf-8')
00429           length = len(val1)
00430         buff.write(struct.pack('<I%ss'%length, length, val1))
00431       length = len(self.robot_state.multi_dof_joint_state.child_frame_ids)
00432       buff.write(_struct_I.pack(length))
00433       for val1 in self.robot_state.multi_dof_joint_state.child_frame_ids:
00434         length = len(val1)
00435         if python3 or type(val1) == unicode:
00436           val1 = val1.encode('utf-8')
00437           length = len(val1)
00438         buff.write(struct.pack('<I%ss'%length, length, val1))
00439       length = len(self.robot_state.multi_dof_joint_state.poses)
00440       buff.write(_struct_I.pack(length))
00441       for val1 in self.robot_state.multi_dof_joint_state.poses:
00442         _v2 = val1.position
00443         _x = _v2
00444         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00445         _v3 = val1.orientation
00446         _x = _v3
00447         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00448       _x = self
00449       buff.write(_struct_5B.pack(_x.check_collisions, _x.check_path_constraints, _x.check_goal_constraints, _x.check_joint_limits, _x.check_full_trajectory))
00450       length = len(self.path_constraints.joint_constraints)
00451       buff.write(_struct_I.pack(length))
00452       for val1 in self.path_constraints.joint_constraints:
00453         _x = val1.joint_name
00454         length = len(_x)
00455         if python3 or type(_x) == unicode:
00456           _x = _x.encode('utf-8')
00457           length = len(_x)
00458         buff.write(struct.pack('<I%ss'%length, length, _x))
00459         _x = val1
00460         buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
00461       length = len(self.path_constraints.position_constraints)
00462       buff.write(_struct_I.pack(length))
00463       for val1 in self.path_constraints.position_constraints:
00464         _v4 = val1.header
00465         buff.write(_struct_I.pack(_v4.seq))
00466         _v5 = _v4.stamp
00467         _x = _v5
00468         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00469         _x = _v4.frame_id
00470         length = len(_x)
00471         if python3 or type(_x) == unicode:
00472           _x = _x.encode('utf-8')
00473           length = len(_x)
00474         buff.write(struct.pack('<I%ss'%length, length, _x))
00475         _x = val1.link_name
00476         length = len(_x)
00477         if python3 or type(_x) == unicode:
00478           _x = _x.encode('utf-8')
00479           length = len(_x)
00480         buff.write(struct.pack('<I%ss'%length, length, _x))
00481         _v6 = val1.target_point_offset
00482         _x = _v6
00483         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00484         _v7 = val1.position
00485         _x = _v7
00486         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00487         _v8 = val1.constraint_region_shape
00488         buff.write(_struct_b.pack(_v8.type))
00489         length = len(_v8.dimensions)
00490         buff.write(_struct_I.pack(length))
00491         pattern = '<%sd'%length
00492         buff.write(struct.pack(pattern, *_v8.dimensions))
00493         length = len(_v8.triangles)
00494         buff.write(_struct_I.pack(length))
00495         pattern = '<%si'%length
00496         buff.write(struct.pack(pattern, *_v8.triangles))
00497         length = len(_v8.vertices)
00498         buff.write(_struct_I.pack(length))
00499         for val3 in _v8.vertices:
00500           _x = val3
00501           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00502         _v9 = val1.constraint_region_orientation
00503         _x = _v9
00504         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00505         buff.write(_struct_d.pack(val1.weight))
00506       length = len(self.path_constraints.orientation_constraints)
00507       buff.write(_struct_I.pack(length))
00508       for val1 in self.path_constraints.orientation_constraints:
00509         _v10 = val1.header
00510         buff.write(_struct_I.pack(_v10.seq))
00511         _v11 = _v10.stamp
00512         _x = _v11
00513         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00514         _x = _v10.frame_id
00515         length = len(_x)
00516         if python3 or type(_x) == unicode:
00517           _x = _x.encode('utf-8')
00518           length = len(_x)
00519         buff.write(struct.pack('<I%ss'%length, length, _x))
00520         _x = val1.link_name
00521         length = len(_x)
00522         if python3 or type(_x) == unicode:
00523           _x = _x.encode('utf-8')
00524           length = len(_x)
00525         buff.write(struct.pack('<I%ss'%length, length, _x))
00526         buff.write(_struct_i.pack(val1.type))
00527         _v12 = val1.orientation
00528         _x = _v12
00529         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00530         _x = val1
00531         buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
00532       length = len(self.path_constraints.visibility_constraints)
00533       buff.write(_struct_I.pack(length))
00534       for val1 in self.path_constraints.visibility_constraints:
00535         _v13 = val1.header
00536         buff.write(_struct_I.pack(_v13.seq))
00537         _v14 = _v13.stamp
00538         _x = _v14
00539         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00540         _x = _v13.frame_id
00541         length = len(_x)
00542         if python3 or type(_x) == unicode:
00543           _x = _x.encode('utf-8')
00544           length = len(_x)
00545         buff.write(struct.pack('<I%ss'%length, length, _x))
00546         _v15 = val1.target
00547         _v16 = _v15.header
00548         buff.write(_struct_I.pack(_v16.seq))
00549         _v17 = _v16.stamp
00550         _x = _v17
00551         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00552         _x = _v16.frame_id
00553         length = len(_x)
00554         if python3 or type(_x) == unicode:
00555           _x = _x.encode('utf-8')
00556           length = len(_x)
00557         buff.write(struct.pack('<I%ss'%length, length, _x))
00558         _v18 = _v15.point
00559         _x = _v18
00560         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00561         _v19 = val1.sensor_pose
00562         _v20 = _v19.header
00563         buff.write(_struct_I.pack(_v20.seq))
00564         _v21 = _v20.stamp
00565         _x = _v21
00566         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00567         _x = _v20.frame_id
00568         length = len(_x)
00569         if python3 or type(_x) == unicode:
00570           _x = _x.encode('utf-8')
00571           length = len(_x)
00572         buff.write(struct.pack('<I%ss'%length, length, _x))
00573         _v22 = _v19.pose
00574         _v23 = _v22.position
00575         _x = _v23
00576         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00577         _v24 = _v22.orientation
00578         _x = _v24
00579         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00580         buff.write(_struct_d.pack(val1.absolute_tolerance))
00581       length = len(self.goal_constraints.joint_constraints)
00582       buff.write(_struct_I.pack(length))
00583       for val1 in self.goal_constraints.joint_constraints:
00584         _x = val1.joint_name
00585         length = len(_x)
00586         if python3 or type(_x) == unicode:
00587           _x = _x.encode('utf-8')
00588           length = len(_x)
00589         buff.write(struct.pack('<I%ss'%length, length, _x))
00590         _x = val1
00591         buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
00592       length = len(self.goal_constraints.position_constraints)
00593       buff.write(_struct_I.pack(length))
00594       for val1 in self.goal_constraints.position_constraints:
00595         _v25 = val1.header
00596         buff.write(_struct_I.pack(_v25.seq))
00597         _v26 = _v25.stamp
00598         _x = _v26
00599         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00600         _x = _v25.frame_id
00601         length = len(_x)
00602         if python3 or type(_x) == unicode:
00603           _x = _x.encode('utf-8')
00604           length = len(_x)
00605         buff.write(struct.pack('<I%ss'%length, length, _x))
00606         _x = val1.link_name
00607         length = len(_x)
00608         if python3 or type(_x) == unicode:
00609           _x = _x.encode('utf-8')
00610           length = len(_x)
00611         buff.write(struct.pack('<I%ss'%length, length, _x))
00612         _v27 = val1.target_point_offset
00613         _x = _v27
00614         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00615         _v28 = val1.position
00616         _x = _v28
00617         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00618         _v29 = val1.constraint_region_shape
00619         buff.write(_struct_b.pack(_v29.type))
00620         length = len(_v29.dimensions)
00621         buff.write(_struct_I.pack(length))
00622         pattern = '<%sd'%length
00623         buff.write(struct.pack(pattern, *_v29.dimensions))
00624         length = len(_v29.triangles)
00625         buff.write(_struct_I.pack(length))
00626         pattern = '<%si'%length
00627         buff.write(struct.pack(pattern, *_v29.triangles))
00628         length = len(_v29.vertices)
00629         buff.write(_struct_I.pack(length))
00630         for val3 in _v29.vertices:
00631           _x = val3
00632           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00633         _v30 = val1.constraint_region_orientation
00634         _x = _v30
00635         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00636         buff.write(_struct_d.pack(val1.weight))
00637       length = len(self.goal_constraints.orientation_constraints)
00638       buff.write(_struct_I.pack(length))
00639       for val1 in self.goal_constraints.orientation_constraints:
00640         _v31 = val1.header
00641         buff.write(_struct_I.pack(_v31.seq))
00642         _v32 = _v31.stamp
00643         _x = _v32
00644         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00645         _x = _v31.frame_id
00646         length = len(_x)
00647         if python3 or type(_x) == unicode:
00648           _x = _x.encode('utf-8')
00649           length = len(_x)
00650         buff.write(struct.pack('<I%ss'%length, length, _x))
00651         _x = val1.link_name
00652         length = len(_x)
00653         if python3 or type(_x) == unicode:
00654           _x = _x.encode('utf-8')
00655           length = len(_x)
00656         buff.write(struct.pack('<I%ss'%length, length, _x))
00657         buff.write(_struct_i.pack(val1.type))
00658         _v33 = val1.orientation
00659         _x = _v33
00660         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00661         _x = val1
00662         buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
00663       length = len(self.goal_constraints.visibility_constraints)
00664       buff.write(_struct_I.pack(length))
00665       for val1 in self.goal_constraints.visibility_constraints:
00666         _v34 = val1.header
00667         buff.write(_struct_I.pack(_v34.seq))
00668         _v35 = _v34.stamp
00669         _x = _v35
00670         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00671         _x = _v34.frame_id
00672         length = len(_x)
00673         if python3 or type(_x) == unicode:
00674           _x = _x.encode('utf-8')
00675           length = len(_x)
00676         buff.write(struct.pack('<I%ss'%length, length, _x))
00677         _v36 = val1.target
00678         _v37 = _v36.header
00679         buff.write(_struct_I.pack(_v37.seq))
00680         _v38 = _v37.stamp
00681         _x = _v38
00682         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00683         _x = _v37.frame_id
00684         length = len(_x)
00685         if python3 or type(_x) == unicode:
00686           _x = _x.encode('utf-8')
00687           length = len(_x)
00688         buff.write(struct.pack('<I%ss'%length, length, _x))
00689         _v39 = _v36.point
00690         _x = _v39
00691         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00692         _v40 = val1.sensor_pose
00693         _v41 = _v40.header
00694         buff.write(_struct_I.pack(_v41.seq))
00695         _v42 = _v41.stamp
00696         _x = _v42
00697         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00698         _x = _v41.frame_id
00699         length = len(_x)
00700         if python3 or type(_x) == unicode:
00701           _x = _x.encode('utf-8')
00702           length = len(_x)
00703         buff.write(struct.pack('<I%ss'%length, length, _x))
00704         _v43 = _v40.pose
00705         _v44 = _v43.position
00706         _x = _v44
00707         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00708         _v45 = _v43.orientation
00709         _x = _v45
00710         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00711         buff.write(_struct_d.pack(val1.absolute_tolerance))
00712     except struct.error as se: self._check_types(se)
00713     except TypeError as te: self._check_types(te)
00714 
00715   def deserialize(self, str):
00716     """
00717     unpack serialized message in str into this message instance
00718     :param str: byte array of serialized message, ``str``
00719     """
00720     try:
00721       if self.trajectory is None:
00722         self.trajectory = trajectory_msgs.msg.JointTrajectory()
00723       if self.robot_state is None:
00724         self.robot_state = arm_navigation_msgs.msg.RobotState()
00725       if self.path_constraints is None:
00726         self.path_constraints = arm_navigation_msgs.msg.Constraints()
00727       if self.goal_constraints is None:
00728         self.goal_constraints = arm_navigation_msgs.msg.Constraints()
00729       end = 0
00730       _x = self
00731       start = end
00732       end += 12
00733       (_x.trajectory.header.seq, _x.trajectory.header.stamp.secs, _x.trajectory.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00734       start = end
00735       end += 4
00736       (length,) = _struct_I.unpack(str[start:end])
00737       start = end
00738       end += length
00739       if python3:
00740         self.trajectory.header.frame_id = str[start:end].decode('utf-8')
00741       else:
00742         self.trajectory.header.frame_id = str[start:end]
00743       start = end
00744       end += 4
00745       (length,) = _struct_I.unpack(str[start:end])
00746       self.trajectory.joint_names = []
00747       for i in range(0, length):
00748         start = end
00749         end += 4
00750         (length,) = _struct_I.unpack(str[start:end])
00751         start = end
00752         end += length
00753         if python3:
00754           val1 = str[start:end].decode('utf-8')
00755         else:
00756           val1 = str[start:end]
00757         self.trajectory.joint_names.append(val1)
00758       start = end
00759       end += 4
00760       (length,) = _struct_I.unpack(str[start:end])
00761       self.trajectory.points = []
00762       for i in range(0, length):
00763         val1 = trajectory_msgs.msg.JointTrajectoryPoint()
00764         start = end
00765         end += 4
00766         (length,) = _struct_I.unpack(str[start:end])
00767         pattern = '<%sd'%length
00768         start = end
00769         end += struct.calcsize(pattern)
00770         val1.positions = struct.unpack(pattern, str[start:end])
00771         start = end
00772         end += 4
00773         (length,) = _struct_I.unpack(str[start:end])
00774         pattern = '<%sd'%length
00775         start = end
00776         end += struct.calcsize(pattern)
00777         val1.velocities = struct.unpack(pattern, str[start:end])
00778         start = end
00779         end += 4
00780         (length,) = _struct_I.unpack(str[start:end])
00781         pattern = '<%sd'%length
00782         start = end
00783         end += struct.calcsize(pattern)
00784         val1.accelerations = struct.unpack(pattern, str[start:end])
00785         _v46 = val1.time_from_start
00786         _x = _v46
00787         start = end
00788         end += 8
00789         (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00790         self.trajectory.points.append(val1)
00791       _x = self
00792       start = end
00793       end += 12
00794       (_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00795       start = end
00796       end += 4
00797       (length,) = _struct_I.unpack(str[start:end])
00798       start = end
00799       end += length
00800       if python3:
00801         self.robot_state.joint_state.header.frame_id = str[start:end].decode('utf-8')
00802       else:
00803         self.robot_state.joint_state.header.frame_id = str[start:end]
00804       start = end
00805       end += 4
00806       (length,) = _struct_I.unpack(str[start:end])
00807       self.robot_state.joint_state.name = []
00808       for i in range(0, length):
00809         start = end
00810         end += 4
00811         (length,) = _struct_I.unpack(str[start:end])
00812         start = end
00813         end += length
00814         if python3:
00815           val1 = str[start:end].decode('utf-8')
00816         else:
00817           val1 = str[start:end]
00818         self.robot_state.joint_state.name.append(val1)
00819       start = end
00820       end += 4
00821       (length,) = _struct_I.unpack(str[start:end])
00822       pattern = '<%sd'%length
00823       start = end
00824       end += struct.calcsize(pattern)
00825       self.robot_state.joint_state.position = struct.unpack(pattern, str[start:end])
00826       start = end
00827       end += 4
00828       (length,) = _struct_I.unpack(str[start:end])
00829       pattern = '<%sd'%length
00830       start = end
00831       end += struct.calcsize(pattern)
00832       self.robot_state.joint_state.velocity = struct.unpack(pattern, str[start:end])
00833       start = end
00834       end += 4
00835       (length,) = _struct_I.unpack(str[start:end])
00836       pattern = '<%sd'%length
00837       start = end
00838       end += struct.calcsize(pattern)
00839       self.robot_state.joint_state.effort = struct.unpack(pattern, str[start:end])
00840       _x = self
00841       start = end
00842       end += 8
00843       (_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00844       start = end
00845       end += 4
00846       (length,) = _struct_I.unpack(str[start:end])
00847       self.robot_state.multi_dof_joint_state.joint_names = []
00848       for i in range(0, length):
00849         start = end
00850         end += 4
00851         (length,) = _struct_I.unpack(str[start:end])
00852         start = end
00853         end += length
00854         if python3:
00855           val1 = str[start:end].decode('utf-8')
00856         else:
00857           val1 = str[start:end]
00858         self.robot_state.multi_dof_joint_state.joint_names.append(val1)
00859       start = end
00860       end += 4
00861       (length,) = _struct_I.unpack(str[start:end])
00862       self.robot_state.multi_dof_joint_state.frame_ids = []
00863       for i in range(0, length):
00864         start = end
00865         end += 4
00866         (length,) = _struct_I.unpack(str[start:end])
00867         start = end
00868         end += length
00869         if python3:
00870           val1 = str[start:end].decode('utf-8')
00871         else:
00872           val1 = str[start:end]
00873         self.robot_state.multi_dof_joint_state.frame_ids.append(val1)
00874       start = end
00875       end += 4
00876       (length,) = _struct_I.unpack(str[start:end])
00877       self.robot_state.multi_dof_joint_state.child_frame_ids = []
00878       for i in range(0, length):
00879         start = end
00880         end += 4
00881         (length,) = _struct_I.unpack(str[start:end])
00882         start = end
00883         end += length
00884         if python3:
00885           val1 = str[start:end].decode('utf-8')
00886         else:
00887           val1 = str[start:end]
00888         self.robot_state.multi_dof_joint_state.child_frame_ids.append(val1)
00889       start = end
00890       end += 4
00891       (length,) = _struct_I.unpack(str[start:end])
00892       self.robot_state.multi_dof_joint_state.poses = []
00893       for i in range(0, length):
00894         val1 = geometry_msgs.msg.Pose()
00895         _v47 = val1.position
00896         _x = _v47
00897         start = end
00898         end += 24
00899         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00900         _v48 = val1.orientation
00901         _x = _v48
00902         start = end
00903         end += 32
00904         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00905         self.robot_state.multi_dof_joint_state.poses.append(val1)
00906       _x = self
00907       start = end
00908       end += 5
00909       (_x.check_collisions, _x.check_path_constraints, _x.check_goal_constraints, _x.check_joint_limits, _x.check_full_trajectory,) = _struct_5B.unpack(str[start:end])
00910       self.check_collisions = bool(self.check_collisions)
00911       self.check_path_constraints = bool(self.check_path_constraints)
00912       self.check_goal_constraints = bool(self.check_goal_constraints)
00913       self.check_joint_limits = bool(self.check_joint_limits)
00914       self.check_full_trajectory = bool(self.check_full_trajectory)
00915       start = end
00916       end += 4
00917       (length,) = _struct_I.unpack(str[start:end])
00918       self.path_constraints.joint_constraints = []
00919       for i in range(0, length):
00920         val1 = arm_navigation_msgs.msg.JointConstraint()
00921         start = end
00922         end += 4
00923         (length,) = _struct_I.unpack(str[start:end])
00924         start = end
00925         end += length
00926         if python3:
00927           val1.joint_name = str[start:end].decode('utf-8')
00928         else:
00929           val1.joint_name = str[start:end]
00930         _x = val1
00931         start = end
00932         end += 32
00933         (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
00934         self.path_constraints.joint_constraints.append(val1)
00935       start = end
00936       end += 4
00937       (length,) = _struct_I.unpack(str[start:end])
00938       self.path_constraints.position_constraints = []
00939       for i in range(0, length):
00940         val1 = arm_navigation_msgs.msg.PositionConstraint()
00941         _v49 = val1.header
00942         start = end
00943         end += 4
00944         (_v49.seq,) = _struct_I.unpack(str[start:end])
00945         _v50 = _v49.stamp
00946         _x = _v50
00947         start = end
00948         end += 8
00949         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00950         start = end
00951         end += 4
00952         (length,) = _struct_I.unpack(str[start:end])
00953         start = end
00954         end += length
00955         if python3:
00956           _v49.frame_id = str[start:end].decode('utf-8')
00957         else:
00958           _v49.frame_id = str[start:end]
00959         start = end
00960         end += 4
00961         (length,) = _struct_I.unpack(str[start:end])
00962         start = end
00963         end += length
00964         if python3:
00965           val1.link_name = str[start:end].decode('utf-8')
00966         else:
00967           val1.link_name = str[start:end]
00968         _v51 = val1.target_point_offset
00969         _x = _v51
00970         start = end
00971         end += 24
00972         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00973         _v52 = val1.position
00974         _x = _v52
00975         start = end
00976         end += 24
00977         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00978         _v53 = val1.constraint_region_shape
00979         start = end
00980         end += 1
00981         (_v53.type,) = _struct_b.unpack(str[start:end])
00982         start = end
00983         end += 4
00984         (length,) = _struct_I.unpack(str[start:end])
00985         pattern = '<%sd'%length
00986         start = end
00987         end += struct.calcsize(pattern)
00988         _v53.dimensions = struct.unpack(pattern, str[start:end])
00989         start = end
00990         end += 4
00991         (length,) = _struct_I.unpack(str[start:end])
00992         pattern = '<%si'%length
00993         start = end
00994         end += struct.calcsize(pattern)
00995         _v53.triangles = struct.unpack(pattern, str[start:end])
00996         start = end
00997         end += 4
00998         (length,) = _struct_I.unpack(str[start:end])
00999         _v53.vertices = []
01000         for i in range(0, length):
01001           val3 = geometry_msgs.msg.Point()
01002           _x = val3
01003           start = end
01004           end += 24
01005           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01006           _v53.vertices.append(val3)
01007         _v54 = val1.constraint_region_orientation
01008         _x = _v54
01009         start = end
01010         end += 32
01011         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01012         start = end
01013         end += 8
01014         (val1.weight,) = _struct_d.unpack(str[start:end])
01015         self.path_constraints.position_constraints.append(val1)
01016       start = end
01017       end += 4
01018       (length,) = _struct_I.unpack(str[start:end])
01019       self.path_constraints.orientation_constraints = []
01020       for i in range(0, length):
01021         val1 = arm_navigation_msgs.msg.OrientationConstraint()
01022         _v55 = val1.header
01023         start = end
01024         end += 4
01025         (_v55.seq,) = _struct_I.unpack(str[start:end])
01026         _v56 = _v55.stamp
01027         _x = _v56
01028         start = end
01029         end += 8
01030         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01031         start = end
01032         end += 4
01033         (length,) = _struct_I.unpack(str[start:end])
01034         start = end
01035         end += length
01036         if python3:
01037           _v55.frame_id = str[start:end].decode('utf-8')
01038         else:
01039           _v55.frame_id = str[start:end]
01040         start = end
01041         end += 4
01042         (length,) = _struct_I.unpack(str[start:end])
01043         start = end
01044         end += length
01045         if python3:
01046           val1.link_name = str[start:end].decode('utf-8')
01047         else:
01048           val1.link_name = str[start:end]
01049         start = end
01050         end += 4
01051         (val1.type,) = _struct_i.unpack(str[start:end])
01052         _v57 = val1.orientation
01053         _x = _v57
01054         start = end
01055         end += 32
01056         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01057         _x = val1
01058         start = end
01059         end += 32
01060         (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
01061         self.path_constraints.orientation_constraints.append(val1)
01062       start = end
01063       end += 4
01064       (length,) = _struct_I.unpack(str[start:end])
01065       self.path_constraints.visibility_constraints = []
01066       for i in range(0, length):
01067         val1 = arm_navigation_msgs.msg.VisibilityConstraint()
01068         _v58 = val1.header
01069         start = end
01070         end += 4
01071         (_v58.seq,) = _struct_I.unpack(str[start:end])
01072         _v59 = _v58.stamp
01073         _x = _v59
01074         start = end
01075         end += 8
01076         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01077         start = end
01078         end += 4
01079         (length,) = _struct_I.unpack(str[start:end])
01080         start = end
01081         end += length
01082         if python3:
01083           _v58.frame_id = str[start:end].decode('utf-8')
01084         else:
01085           _v58.frame_id = str[start:end]
01086         _v60 = val1.target
01087         _v61 = _v60.header
01088         start = end
01089         end += 4
01090         (_v61.seq,) = _struct_I.unpack(str[start:end])
01091         _v62 = _v61.stamp
01092         _x = _v62
01093         start = end
01094         end += 8
01095         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01096         start = end
01097         end += 4
01098         (length,) = _struct_I.unpack(str[start:end])
01099         start = end
01100         end += length
01101         if python3:
01102           _v61.frame_id = str[start:end].decode('utf-8')
01103         else:
01104           _v61.frame_id = str[start:end]
01105         _v63 = _v60.point
01106         _x = _v63
01107         start = end
01108         end += 24
01109         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01110         _v64 = val1.sensor_pose
01111         _v65 = _v64.header
01112         start = end
01113         end += 4
01114         (_v65.seq,) = _struct_I.unpack(str[start:end])
01115         _v66 = _v65.stamp
01116         _x = _v66
01117         start = end
01118         end += 8
01119         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01120         start = end
01121         end += 4
01122         (length,) = _struct_I.unpack(str[start:end])
01123         start = end
01124         end += length
01125         if python3:
01126           _v65.frame_id = str[start:end].decode('utf-8')
01127         else:
01128           _v65.frame_id = str[start:end]
01129         _v67 = _v64.pose
01130         _v68 = _v67.position
01131         _x = _v68
01132         start = end
01133         end += 24
01134         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01135         _v69 = _v67.orientation
01136         _x = _v69
01137         start = end
01138         end += 32
01139         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01140         start = end
01141         end += 8
01142         (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
01143         self.path_constraints.visibility_constraints.append(val1)
01144       start = end
01145       end += 4
01146       (length,) = _struct_I.unpack(str[start:end])
01147       self.goal_constraints.joint_constraints = []
01148       for i in range(0, length):
01149         val1 = arm_navigation_msgs.msg.JointConstraint()
01150         start = end
01151         end += 4
01152         (length,) = _struct_I.unpack(str[start:end])
01153         start = end
01154         end += length
01155         if python3:
01156           val1.joint_name = str[start:end].decode('utf-8')
01157         else:
01158           val1.joint_name = str[start:end]
01159         _x = val1
01160         start = end
01161         end += 32
01162         (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
01163         self.goal_constraints.joint_constraints.append(val1)
01164       start = end
01165       end += 4
01166       (length,) = _struct_I.unpack(str[start:end])
01167       self.goal_constraints.position_constraints = []
01168       for i in range(0, length):
01169         val1 = arm_navigation_msgs.msg.PositionConstraint()
01170         _v70 = val1.header
01171         start = end
01172         end += 4
01173         (_v70.seq,) = _struct_I.unpack(str[start:end])
01174         _v71 = _v70.stamp
01175         _x = _v71
01176         start = end
01177         end += 8
01178         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01179         start = end
01180         end += 4
01181         (length,) = _struct_I.unpack(str[start:end])
01182         start = end
01183         end += length
01184         if python3:
01185           _v70.frame_id = str[start:end].decode('utf-8')
01186         else:
01187           _v70.frame_id = str[start:end]
01188         start = end
01189         end += 4
01190         (length,) = _struct_I.unpack(str[start:end])
01191         start = end
01192         end += length
01193         if python3:
01194           val1.link_name = str[start:end].decode('utf-8')
01195         else:
01196           val1.link_name = str[start:end]
01197         _v72 = val1.target_point_offset
01198         _x = _v72
01199         start = end
01200         end += 24
01201         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01202         _v73 = val1.position
01203         _x = _v73
01204         start = end
01205         end += 24
01206         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01207         _v74 = val1.constraint_region_shape
01208         start = end
01209         end += 1
01210         (_v74.type,) = _struct_b.unpack(str[start:end])
01211         start = end
01212         end += 4
01213         (length,) = _struct_I.unpack(str[start:end])
01214         pattern = '<%sd'%length
01215         start = end
01216         end += struct.calcsize(pattern)
01217         _v74.dimensions = struct.unpack(pattern, str[start:end])
01218         start = end
01219         end += 4
01220         (length,) = _struct_I.unpack(str[start:end])
01221         pattern = '<%si'%length
01222         start = end
01223         end += struct.calcsize(pattern)
01224         _v74.triangles = struct.unpack(pattern, str[start:end])
01225         start = end
01226         end += 4
01227         (length,) = _struct_I.unpack(str[start:end])
01228         _v74.vertices = []
01229         for i in range(0, length):
01230           val3 = geometry_msgs.msg.Point()
01231           _x = val3
01232           start = end
01233           end += 24
01234           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01235           _v74.vertices.append(val3)
01236         _v75 = val1.constraint_region_orientation
01237         _x = _v75
01238         start = end
01239         end += 32
01240         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01241         start = end
01242         end += 8
01243         (val1.weight,) = _struct_d.unpack(str[start:end])
01244         self.goal_constraints.position_constraints.append(val1)
01245       start = end
01246       end += 4
01247       (length,) = _struct_I.unpack(str[start:end])
01248       self.goal_constraints.orientation_constraints = []
01249       for i in range(0, length):
01250         val1 = arm_navigation_msgs.msg.OrientationConstraint()
01251         _v76 = val1.header
01252         start = end
01253         end += 4
01254         (_v76.seq,) = _struct_I.unpack(str[start:end])
01255         _v77 = _v76.stamp
01256         _x = _v77
01257         start = end
01258         end += 8
01259         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01260         start = end
01261         end += 4
01262         (length,) = _struct_I.unpack(str[start:end])
01263         start = end
01264         end += length
01265         if python3:
01266           _v76.frame_id = str[start:end].decode('utf-8')
01267         else:
01268           _v76.frame_id = str[start:end]
01269         start = end
01270         end += 4
01271         (length,) = _struct_I.unpack(str[start:end])
01272         start = end
01273         end += length
01274         if python3:
01275           val1.link_name = str[start:end].decode('utf-8')
01276         else:
01277           val1.link_name = str[start:end]
01278         start = end
01279         end += 4
01280         (val1.type,) = _struct_i.unpack(str[start:end])
01281         _v78 = val1.orientation
01282         _x = _v78
01283         start = end
01284         end += 32
01285         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01286         _x = val1
01287         start = end
01288         end += 32
01289         (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
01290         self.goal_constraints.orientation_constraints.append(val1)
01291       start = end
01292       end += 4
01293       (length,) = _struct_I.unpack(str[start:end])
01294       self.goal_constraints.visibility_constraints = []
01295       for i in range(0, length):
01296         val1 = arm_navigation_msgs.msg.VisibilityConstraint()
01297         _v79 = val1.header
01298         start = end
01299         end += 4
01300         (_v79.seq,) = _struct_I.unpack(str[start:end])
01301         _v80 = _v79.stamp
01302         _x = _v80
01303         start = end
01304         end += 8
01305         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01306         start = end
01307         end += 4
01308         (length,) = _struct_I.unpack(str[start:end])
01309         start = end
01310         end += length
01311         if python3:
01312           _v79.frame_id = str[start:end].decode('utf-8')
01313         else:
01314           _v79.frame_id = str[start:end]
01315         _v81 = val1.target
01316         _v82 = _v81.header
01317         start = end
01318         end += 4
01319         (_v82.seq,) = _struct_I.unpack(str[start:end])
01320         _v83 = _v82.stamp
01321         _x = _v83
01322         start = end
01323         end += 8
01324         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01325         start = end
01326         end += 4
01327         (length,) = _struct_I.unpack(str[start:end])
01328         start = end
01329         end += length
01330         if python3:
01331           _v82.frame_id = str[start:end].decode('utf-8')
01332         else:
01333           _v82.frame_id = str[start:end]
01334         _v84 = _v81.point
01335         _x = _v84
01336         start = end
01337         end += 24
01338         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01339         _v85 = val1.sensor_pose
01340         _v86 = _v85.header
01341         start = end
01342         end += 4
01343         (_v86.seq,) = _struct_I.unpack(str[start:end])
01344         _v87 = _v86.stamp
01345         _x = _v87
01346         start = end
01347         end += 8
01348         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01349         start = end
01350         end += 4
01351         (length,) = _struct_I.unpack(str[start:end])
01352         start = end
01353         end += length
01354         if python3:
01355           _v86.frame_id = str[start:end].decode('utf-8')
01356         else:
01357           _v86.frame_id = str[start:end]
01358         _v88 = _v85.pose
01359         _v89 = _v88.position
01360         _x = _v89
01361         start = end
01362         end += 24
01363         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01364         _v90 = _v88.orientation
01365         _x = _v90
01366         start = end
01367         end += 32
01368         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01369         start = end
01370         end += 8
01371         (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
01372         self.goal_constraints.visibility_constraints.append(val1)
01373       return self
01374     except struct.error as e:
01375       raise genpy.DeserializationError(e) #most likely buffer underfill
01376 
01377 
01378   def serialize_numpy(self, buff, numpy):
01379     """
01380     serialize message with numpy array types into buffer
01381     :param buff: buffer, ``StringIO``
01382     :param numpy: numpy python module
01383     """
01384     try:
01385       _x = self
01386       buff.write(_struct_3I.pack(_x.trajectory.header.seq, _x.trajectory.header.stamp.secs, _x.trajectory.header.stamp.nsecs))
01387       _x = self.trajectory.header.frame_id
01388       length = len(_x)
01389       if python3 or type(_x) == unicode:
01390         _x = _x.encode('utf-8')
01391         length = len(_x)
01392       buff.write(struct.pack('<I%ss'%length, length, _x))
01393       length = len(self.trajectory.joint_names)
01394       buff.write(_struct_I.pack(length))
01395       for val1 in self.trajectory.joint_names:
01396         length = len(val1)
01397         if python3 or type(val1) == unicode:
01398           val1 = val1.encode('utf-8')
01399           length = len(val1)
01400         buff.write(struct.pack('<I%ss'%length, length, val1))
01401       length = len(self.trajectory.points)
01402       buff.write(_struct_I.pack(length))
01403       for val1 in self.trajectory.points:
01404         length = len(val1.positions)
01405         buff.write(_struct_I.pack(length))
01406         pattern = '<%sd'%length
01407         buff.write(val1.positions.tostring())
01408         length = len(val1.velocities)
01409         buff.write(_struct_I.pack(length))
01410         pattern = '<%sd'%length
01411         buff.write(val1.velocities.tostring())
01412         length = len(val1.accelerations)
01413         buff.write(_struct_I.pack(length))
01414         pattern = '<%sd'%length
01415         buff.write(val1.accelerations.tostring())
01416         _v91 = val1.time_from_start
01417         _x = _v91
01418         buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
01419       _x = self
01420       buff.write(_struct_3I.pack(_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs))
01421       _x = self.robot_state.joint_state.header.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       length = len(self.robot_state.joint_state.name)
01428       buff.write(_struct_I.pack(length))
01429       for val1 in self.robot_state.joint_state.name:
01430         length = len(val1)
01431         if python3 or type(val1) == unicode:
01432           val1 = val1.encode('utf-8')
01433           length = len(val1)
01434         buff.write(struct.pack('<I%ss'%length, length, val1))
01435       length = len(self.robot_state.joint_state.position)
01436       buff.write(_struct_I.pack(length))
01437       pattern = '<%sd'%length
01438       buff.write(self.robot_state.joint_state.position.tostring())
01439       length = len(self.robot_state.joint_state.velocity)
01440       buff.write(_struct_I.pack(length))
01441       pattern = '<%sd'%length
01442       buff.write(self.robot_state.joint_state.velocity.tostring())
01443       length = len(self.robot_state.joint_state.effort)
01444       buff.write(_struct_I.pack(length))
01445       pattern = '<%sd'%length
01446       buff.write(self.robot_state.joint_state.effort.tostring())
01447       _x = self
01448       buff.write(_struct_2I.pack(_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs))
01449       length = len(self.robot_state.multi_dof_joint_state.joint_names)
01450       buff.write(_struct_I.pack(length))
01451       for val1 in self.robot_state.multi_dof_joint_state.joint_names:
01452         length = len(val1)
01453         if python3 or type(val1) == unicode:
01454           val1 = val1.encode('utf-8')
01455           length = len(val1)
01456         buff.write(struct.pack('<I%ss'%length, length, val1))
01457       length = len(self.robot_state.multi_dof_joint_state.frame_ids)
01458       buff.write(_struct_I.pack(length))
01459       for val1 in self.robot_state.multi_dof_joint_state.frame_ids:
01460         length = len(val1)
01461         if python3 or type(val1) == unicode:
01462           val1 = val1.encode('utf-8')
01463           length = len(val1)
01464         buff.write(struct.pack('<I%ss'%length, length, val1))
01465       length = len(self.robot_state.multi_dof_joint_state.child_frame_ids)
01466       buff.write(_struct_I.pack(length))
01467       for val1 in self.robot_state.multi_dof_joint_state.child_frame_ids:
01468         length = len(val1)
01469         if python3 or type(val1) == unicode:
01470           val1 = val1.encode('utf-8')
01471           length = len(val1)
01472         buff.write(struct.pack('<I%ss'%length, length, val1))
01473       length = len(self.robot_state.multi_dof_joint_state.poses)
01474       buff.write(_struct_I.pack(length))
01475       for val1 in self.robot_state.multi_dof_joint_state.poses:
01476         _v92 = val1.position
01477         _x = _v92
01478         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01479         _v93 = val1.orientation
01480         _x = _v93
01481         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01482       _x = self
01483       buff.write(_struct_5B.pack(_x.check_collisions, _x.check_path_constraints, _x.check_goal_constraints, _x.check_joint_limits, _x.check_full_trajectory))
01484       length = len(self.path_constraints.joint_constraints)
01485       buff.write(_struct_I.pack(length))
01486       for val1 in self.path_constraints.joint_constraints:
01487         _x = val1.joint_name
01488         length = len(_x)
01489         if python3 or type(_x) == unicode:
01490           _x = _x.encode('utf-8')
01491           length = len(_x)
01492         buff.write(struct.pack('<I%ss'%length, length, _x))
01493         _x = val1
01494         buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
01495       length = len(self.path_constraints.position_constraints)
01496       buff.write(_struct_I.pack(length))
01497       for val1 in self.path_constraints.position_constraints:
01498         _v94 = val1.header
01499         buff.write(_struct_I.pack(_v94.seq))
01500         _v95 = _v94.stamp
01501         _x = _v95
01502         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01503         _x = _v94.frame_id
01504         length = len(_x)
01505         if python3 or type(_x) == unicode:
01506           _x = _x.encode('utf-8')
01507           length = len(_x)
01508         buff.write(struct.pack('<I%ss'%length, length, _x))
01509         _x = val1.link_name
01510         length = len(_x)
01511         if python3 or type(_x) == unicode:
01512           _x = _x.encode('utf-8')
01513           length = len(_x)
01514         buff.write(struct.pack('<I%ss'%length, length, _x))
01515         _v96 = val1.target_point_offset
01516         _x = _v96
01517         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01518         _v97 = val1.position
01519         _x = _v97
01520         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01521         _v98 = val1.constraint_region_shape
01522         buff.write(_struct_b.pack(_v98.type))
01523         length = len(_v98.dimensions)
01524         buff.write(_struct_I.pack(length))
01525         pattern = '<%sd'%length
01526         buff.write(_v98.dimensions.tostring())
01527         length = len(_v98.triangles)
01528         buff.write(_struct_I.pack(length))
01529         pattern = '<%si'%length
01530         buff.write(_v98.triangles.tostring())
01531         length = len(_v98.vertices)
01532         buff.write(_struct_I.pack(length))
01533         for val3 in _v98.vertices:
01534           _x = val3
01535           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01536         _v99 = val1.constraint_region_orientation
01537         _x = _v99
01538         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01539         buff.write(_struct_d.pack(val1.weight))
01540       length = len(self.path_constraints.orientation_constraints)
01541       buff.write(_struct_I.pack(length))
01542       for val1 in self.path_constraints.orientation_constraints:
01543         _v100 = val1.header
01544         buff.write(_struct_I.pack(_v100.seq))
01545         _v101 = _v100.stamp
01546         _x = _v101
01547         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01548         _x = _v100.frame_id
01549         length = len(_x)
01550         if python3 or type(_x) == unicode:
01551           _x = _x.encode('utf-8')
01552           length = len(_x)
01553         buff.write(struct.pack('<I%ss'%length, length, _x))
01554         _x = val1.link_name
01555         length = len(_x)
01556         if python3 or type(_x) == unicode:
01557           _x = _x.encode('utf-8')
01558           length = len(_x)
01559         buff.write(struct.pack('<I%ss'%length, length, _x))
01560         buff.write(_struct_i.pack(val1.type))
01561         _v102 = val1.orientation
01562         _x = _v102
01563         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01564         _x = val1
01565         buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
01566       length = len(self.path_constraints.visibility_constraints)
01567       buff.write(_struct_I.pack(length))
01568       for val1 in self.path_constraints.visibility_constraints:
01569         _v103 = val1.header
01570         buff.write(_struct_I.pack(_v103.seq))
01571         _v104 = _v103.stamp
01572         _x = _v104
01573         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01574         _x = _v103.frame_id
01575         length = len(_x)
01576         if python3 or type(_x) == unicode:
01577           _x = _x.encode('utf-8')
01578           length = len(_x)
01579         buff.write(struct.pack('<I%ss'%length, length, _x))
01580         _v105 = val1.target
01581         _v106 = _v105.header
01582         buff.write(_struct_I.pack(_v106.seq))
01583         _v107 = _v106.stamp
01584         _x = _v107
01585         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01586         _x = _v106.frame_id
01587         length = len(_x)
01588         if python3 or type(_x) == unicode:
01589           _x = _x.encode('utf-8')
01590           length = len(_x)
01591         buff.write(struct.pack('<I%ss'%length, length, _x))
01592         _v108 = _v105.point
01593         _x = _v108
01594         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01595         _v109 = val1.sensor_pose
01596         _v110 = _v109.header
01597         buff.write(_struct_I.pack(_v110.seq))
01598         _v111 = _v110.stamp
01599         _x = _v111
01600         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01601         _x = _v110.frame_id
01602         length = len(_x)
01603         if python3 or type(_x) == unicode:
01604           _x = _x.encode('utf-8')
01605           length = len(_x)
01606         buff.write(struct.pack('<I%ss'%length, length, _x))
01607         _v112 = _v109.pose
01608         _v113 = _v112.position
01609         _x = _v113
01610         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01611         _v114 = _v112.orientation
01612         _x = _v114
01613         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01614         buff.write(_struct_d.pack(val1.absolute_tolerance))
01615       length = len(self.goal_constraints.joint_constraints)
01616       buff.write(_struct_I.pack(length))
01617       for val1 in self.goal_constraints.joint_constraints:
01618         _x = val1.joint_name
01619         length = len(_x)
01620         if python3 or type(_x) == unicode:
01621           _x = _x.encode('utf-8')
01622           length = len(_x)
01623         buff.write(struct.pack('<I%ss'%length, length, _x))
01624         _x = val1
01625         buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
01626       length = len(self.goal_constraints.position_constraints)
01627       buff.write(_struct_I.pack(length))
01628       for val1 in self.goal_constraints.position_constraints:
01629         _v115 = val1.header
01630         buff.write(_struct_I.pack(_v115.seq))
01631         _v116 = _v115.stamp
01632         _x = _v116
01633         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01634         _x = _v115.frame_id
01635         length = len(_x)
01636         if python3 or type(_x) == unicode:
01637           _x = _x.encode('utf-8')
01638           length = len(_x)
01639         buff.write(struct.pack('<I%ss'%length, length, _x))
01640         _x = val1.link_name
01641         length = len(_x)
01642         if python3 or type(_x) == unicode:
01643           _x = _x.encode('utf-8')
01644           length = len(_x)
01645         buff.write(struct.pack('<I%ss'%length, length, _x))
01646         _v117 = val1.target_point_offset
01647         _x = _v117
01648         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01649         _v118 = val1.position
01650         _x = _v118
01651         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01652         _v119 = val1.constraint_region_shape
01653         buff.write(_struct_b.pack(_v119.type))
01654         length = len(_v119.dimensions)
01655         buff.write(_struct_I.pack(length))
01656         pattern = '<%sd'%length
01657         buff.write(_v119.dimensions.tostring())
01658         length = len(_v119.triangles)
01659         buff.write(_struct_I.pack(length))
01660         pattern = '<%si'%length
01661         buff.write(_v119.triangles.tostring())
01662         length = len(_v119.vertices)
01663         buff.write(_struct_I.pack(length))
01664         for val3 in _v119.vertices:
01665           _x = val3
01666           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01667         _v120 = val1.constraint_region_orientation
01668         _x = _v120
01669         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01670         buff.write(_struct_d.pack(val1.weight))
01671       length = len(self.goal_constraints.orientation_constraints)
01672       buff.write(_struct_I.pack(length))
01673       for val1 in self.goal_constraints.orientation_constraints:
01674         _v121 = val1.header
01675         buff.write(_struct_I.pack(_v121.seq))
01676         _v122 = _v121.stamp
01677         _x = _v122
01678         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01679         _x = _v121.frame_id
01680         length = len(_x)
01681         if python3 or type(_x) == unicode:
01682           _x = _x.encode('utf-8')
01683           length = len(_x)
01684         buff.write(struct.pack('<I%ss'%length, length, _x))
01685         _x = val1.link_name
01686         length = len(_x)
01687         if python3 or type(_x) == unicode:
01688           _x = _x.encode('utf-8')
01689           length = len(_x)
01690         buff.write(struct.pack('<I%ss'%length, length, _x))
01691         buff.write(_struct_i.pack(val1.type))
01692         _v123 = val1.orientation
01693         _x = _v123
01694         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01695         _x = val1
01696         buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
01697       length = len(self.goal_constraints.visibility_constraints)
01698       buff.write(_struct_I.pack(length))
01699       for val1 in self.goal_constraints.visibility_constraints:
01700         _v124 = val1.header
01701         buff.write(_struct_I.pack(_v124.seq))
01702         _v125 = _v124.stamp
01703         _x = _v125
01704         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01705         _x = _v124.frame_id
01706         length = len(_x)
01707         if python3 or type(_x) == unicode:
01708           _x = _x.encode('utf-8')
01709           length = len(_x)
01710         buff.write(struct.pack('<I%ss'%length, length, _x))
01711         _v126 = val1.target
01712         _v127 = _v126.header
01713         buff.write(_struct_I.pack(_v127.seq))
01714         _v128 = _v127.stamp
01715         _x = _v128
01716         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01717         _x = _v127.frame_id
01718         length = len(_x)
01719         if python3 or type(_x) == unicode:
01720           _x = _x.encode('utf-8')
01721           length = len(_x)
01722         buff.write(struct.pack('<I%ss'%length, length, _x))
01723         _v129 = _v126.point
01724         _x = _v129
01725         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01726         _v130 = val1.sensor_pose
01727         _v131 = _v130.header
01728         buff.write(_struct_I.pack(_v131.seq))
01729         _v132 = _v131.stamp
01730         _x = _v132
01731         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01732         _x = _v131.frame_id
01733         length = len(_x)
01734         if python3 or type(_x) == unicode:
01735           _x = _x.encode('utf-8')
01736           length = len(_x)
01737         buff.write(struct.pack('<I%ss'%length, length, _x))
01738         _v133 = _v130.pose
01739         _v134 = _v133.position
01740         _x = _v134
01741         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01742         _v135 = _v133.orientation
01743         _x = _v135
01744         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01745         buff.write(_struct_d.pack(val1.absolute_tolerance))
01746     except struct.error as se: self._check_types(se)
01747     except TypeError as te: self._check_types(te)
01748 
01749   def deserialize_numpy(self, str, numpy):
01750     """
01751     unpack serialized message in str into this message instance using numpy for array types
01752     :param str: byte array of serialized message, ``str``
01753     :param numpy: numpy python module
01754     """
01755     try:
01756       if self.trajectory is None:
01757         self.trajectory = trajectory_msgs.msg.JointTrajectory()
01758       if self.robot_state is None:
01759         self.robot_state = arm_navigation_msgs.msg.RobotState()
01760       if self.path_constraints is None:
01761         self.path_constraints = arm_navigation_msgs.msg.Constraints()
01762       if self.goal_constraints is None:
01763         self.goal_constraints = arm_navigation_msgs.msg.Constraints()
01764       end = 0
01765       _x = self
01766       start = end
01767       end += 12
01768       (_x.trajectory.header.seq, _x.trajectory.header.stamp.secs, _x.trajectory.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01769       start = end
01770       end += 4
01771       (length,) = _struct_I.unpack(str[start:end])
01772       start = end
01773       end += length
01774       if python3:
01775         self.trajectory.header.frame_id = str[start:end].decode('utf-8')
01776       else:
01777         self.trajectory.header.frame_id = str[start:end]
01778       start = end
01779       end += 4
01780       (length,) = _struct_I.unpack(str[start:end])
01781       self.trajectory.joint_names = []
01782       for i in range(0, length):
01783         start = end
01784         end += 4
01785         (length,) = _struct_I.unpack(str[start:end])
01786         start = end
01787         end += length
01788         if python3:
01789           val1 = str[start:end].decode('utf-8')
01790         else:
01791           val1 = str[start:end]
01792         self.trajectory.joint_names.append(val1)
01793       start = end
01794       end += 4
01795       (length,) = _struct_I.unpack(str[start:end])
01796       self.trajectory.points = []
01797       for i in range(0, length):
01798         val1 = trajectory_msgs.msg.JointTrajectoryPoint()
01799         start = end
01800         end += 4
01801         (length,) = _struct_I.unpack(str[start:end])
01802         pattern = '<%sd'%length
01803         start = end
01804         end += struct.calcsize(pattern)
01805         val1.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01806         start = end
01807         end += 4
01808         (length,) = _struct_I.unpack(str[start:end])
01809         pattern = '<%sd'%length
01810         start = end
01811         end += struct.calcsize(pattern)
01812         val1.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01813         start = end
01814         end += 4
01815         (length,) = _struct_I.unpack(str[start:end])
01816         pattern = '<%sd'%length
01817         start = end
01818         end += struct.calcsize(pattern)
01819         val1.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01820         _v136 = val1.time_from_start
01821         _x = _v136
01822         start = end
01823         end += 8
01824         (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
01825         self.trajectory.points.append(val1)
01826       _x = self
01827       start = end
01828       end += 12
01829       (_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01830       start = end
01831       end += 4
01832       (length,) = _struct_I.unpack(str[start:end])
01833       start = end
01834       end += length
01835       if python3:
01836         self.robot_state.joint_state.header.frame_id = str[start:end].decode('utf-8')
01837       else:
01838         self.robot_state.joint_state.header.frame_id = str[start:end]
01839       start = end
01840       end += 4
01841       (length,) = _struct_I.unpack(str[start:end])
01842       self.robot_state.joint_state.name = []
01843       for i in range(0, length):
01844         start = end
01845         end += 4
01846         (length,) = _struct_I.unpack(str[start:end])
01847         start = end
01848         end += length
01849         if python3:
01850           val1 = str[start:end].decode('utf-8')
01851         else:
01852           val1 = str[start:end]
01853         self.robot_state.joint_state.name.append(val1)
01854       start = end
01855       end += 4
01856       (length,) = _struct_I.unpack(str[start:end])
01857       pattern = '<%sd'%length
01858       start = end
01859       end += struct.calcsize(pattern)
01860       self.robot_state.joint_state.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01861       start = end
01862       end += 4
01863       (length,) = _struct_I.unpack(str[start:end])
01864       pattern = '<%sd'%length
01865       start = end
01866       end += struct.calcsize(pattern)
01867       self.robot_state.joint_state.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01868       start = end
01869       end += 4
01870       (length,) = _struct_I.unpack(str[start:end])
01871       pattern = '<%sd'%length
01872       start = end
01873       end += struct.calcsize(pattern)
01874       self.robot_state.joint_state.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01875       _x = self
01876       start = end
01877       end += 8
01878       (_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01879       start = end
01880       end += 4
01881       (length,) = _struct_I.unpack(str[start:end])
01882       self.robot_state.multi_dof_joint_state.joint_names = []
01883       for i in range(0, length):
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 = str[start:end].decode('utf-8')
01891         else:
01892           val1 = str[start:end]
01893         self.robot_state.multi_dof_joint_state.joint_names.append(val1)
01894       start = end
01895       end += 4
01896       (length,) = _struct_I.unpack(str[start:end])
01897       self.robot_state.multi_dof_joint_state.frame_ids = []
01898       for i in range(0, length):
01899         start = end
01900         end += 4
01901         (length,) = _struct_I.unpack(str[start:end])
01902         start = end
01903         end += length
01904         if python3:
01905           val1 = str[start:end].decode('utf-8')
01906         else:
01907           val1 = str[start:end]
01908         self.robot_state.multi_dof_joint_state.frame_ids.append(val1)
01909       start = end
01910       end += 4
01911       (length,) = _struct_I.unpack(str[start:end])
01912       self.robot_state.multi_dof_joint_state.child_frame_ids = []
01913       for i in range(0, length):
01914         start = end
01915         end += 4
01916         (length,) = _struct_I.unpack(str[start:end])
01917         start = end
01918         end += length
01919         if python3:
01920           val1 = str[start:end].decode('utf-8')
01921         else:
01922           val1 = str[start:end]
01923         self.robot_state.multi_dof_joint_state.child_frame_ids.append(val1)
01924       start = end
01925       end += 4
01926       (length,) = _struct_I.unpack(str[start:end])
01927       self.robot_state.multi_dof_joint_state.poses = []
01928       for i in range(0, length):
01929         val1 = geometry_msgs.msg.Pose()
01930         _v137 = val1.position
01931         _x = _v137
01932         start = end
01933         end += 24
01934         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01935         _v138 = val1.orientation
01936         _x = _v138
01937         start = end
01938         end += 32
01939         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01940         self.robot_state.multi_dof_joint_state.poses.append(val1)
01941       _x = self
01942       start = end
01943       end += 5
01944       (_x.check_collisions, _x.check_path_constraints, _x.check_goal_constraints, _x.check_joint_limits, _x.check_full_trajectory,) = _struct_5B.unpack(str[start:end])
01945       self.check_collisions = bool(self.check_collisions)
01946       self.check_path_constraints = bool(self.check_path_constraints)
01947       self.check_goal_constraints = bool(self.check_goal_constraints)
01948       self.check_joint_limits = bool(self.check_joint_limits)
01949       self.check_full_trajectory = bool(self.check_full_trajectory)
01950       start = end
01951       end += 4
01952       (length,) = _struct_I.unpack(str[start:end])
01953       self.path_constraints.joint_constraints = []
01954       for i in range(0, length):
01955         val1 = arm_navigation_msgs.msg.JointConstraint()
01956         start = end
01957         end += 4
01958         (length,) = _struct_I.unpack(str[start:end])
01959         start = end
01960         end += length
01961         if python3:
01962           val1.joint_name = str[start:end].decode('utf-8')
01963         else:
01964           val1.joint_name = str[start:end]
01965         _x = val1
01966         start = end
01967         end += 32
01968         (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
01969         self.path_constraints.joint_constraints.append(val1)
01970       start = end
01971       end += 4
01972       (length,) = _struct_I.unpack(str[start:end])
01973       self.path_constraints.position_constraints = []
01974       for i in range(0, length):
01975         val1 = arm_navigation_msgs.msg.PositionConstraint()
01976         _v139 = val1.header
01977         start = end
01978         end += 4
01979         (_v139.seq,) = _struct_I.unpack(str[start:end])
01980         _v140 = _v139.stamp
01981         _x = _v140
01982         start = end
01983         end += 8
01984         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01985         start = end
01986         end += 4
01987         (length,) = _struct_I.unpack(str[start:end])
01988         start = end
01989         end += length
01990         if python3:
01991           _v139.frame_id = str[start:end].decode('utf-8')
01992         else:
01993           _v139.frame_id = str[start:end]
01994         start = end
01995         end += 4
01996         (length,) = _struct_I.unpack(str[start:end])
01997         start = end
01998         end += length
01999         if python3:
02000           val1.link_name = str[start:end].decode('utf-8')
02001         else:
02002           val1.link_name = str[start:end]
02003         _v141 = val1.target_point_offset
02004         _x = _v141
02005         start = end
02006         end += 24
02007         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02008         _v142 = val1.position
02009         _x = _v142
02010         start = end
02011         end += 24
02012         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02013         _v143 = val1.constraint_region_shape
02014         start = end
02015         end += 1
02016         (_v143.type,) = _struct_b.unpack(str[start:end])
02017         start = end
02018         end += 4
02019         (length,) = _struct_I.unpack(str[start:end])
02020         pattern = '<%sd'%length
02021         start = end
02022         end += struct.calcsize(pattern)
02023         _v143.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02024         start = end
02025         end += 4
02026         (length,) = _struct_I.unpack(str[start:end])
02027         pattern = '<%si'%length
02028         start = end
02029         end += struct.calcsize(pattern)
02030         _v143.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
02031         start = end
02032         end += 4
02033         (length,) = _struct_I.unpack(str[start:end])
02034         _v143.vertices = []
02035         for i in range(0, length):
02036           val3 = geometry_msgs.msg.Point()
02037           _x = val3
02038           start = end
02039           end += 24
02040           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02041           _v143.vertices.append(val3)
02042         _v144 = val1.constraint_region_orientation
02043         _x = _v144
02044         start = end
02045         end += 32
02046         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02047         start = end
02048         end += 8
02049         (val1.weight,) = _struct_d.unpack(str[start:end])
02050         self.path_constraints.position_constraints.append(val1)
02051       start = end
02052       end += 4
02053       (length,) = _struct_I.unpack(str[start:end])
02054       self.path_constraints.orientation_constraints = []
02055       for i in range(0, length):
02056         val1 = arm_navigation_msgs.msg.OrientationConstraint()
02057         _v145 = val1.header
02058         start = end
02059         end += 4
02060         (_v145.seq,) = _struct_I.unpack(str[start:end])
02061         _v146 = _v145.stamp
02062         _x = _v146
02063         start = end
02064         end += 8
02065         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02066         start = end
02067         end += 4
02068         (length,) = _struct_I.unpack(str[start:end])
02069         start = end
02070         end += length
02071         if python3:
02072           _v145.frame_id = str[start:end].decode('utf-8')
02073         else:
02074           _v145.frame_id = str[start:end]
02075         start = end
02076         end += 4
02077         (length,) = _struct_I.unpack(str[start:end])
02078         start = end
02079         end += length
02080         if python3:
02081           val1.link_name = str[start:end].decode('utf-8')
02082         else:
02083           val1.link_name = str[start:end]
02084         start = end
02085         end += 4
02086         (val1.type,) = _struct_i.unpack(str[start:end])
02087         _v147 = val1.orientation
02088         _x = _v147
02089         start = end
02090         end += 32
02091         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02092         _x = val1
02093         start = end
02094         end += 32
02095         (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
02096         self.path_constraints.orientation_constraints.append(val1)
02097       start = end
02098       end += 4
02099       (length,) = _struct_I.unpack(str[start:end])
02100       self.path_constraints.visibility_constraints = []
02101       for i in range(0, length):
02102         val1 = arm_navigation_msgs.msg.VisibilityConstraint()
02103         _v148 = val1.header
02104         start = end
02105         end += 4
02106         (_v148.seq,) = _struct_I.unpack(str[start:end])
02107         _v149 = _v148.stamp
02108         _x = _v149
02109         start = end
02110         end += 8
02111         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02112         start = end
02113         end += 4
02114         (length,) = _struct_I.unpack(str[start:end])
02115         start = end
02116         end += length
02117         if python3:
02118           _v148.frame_id = str[start:end].decode('utf-8')
02119         else:
02120           _v148.frame_id = str[start:end]
02121         _v150 = val1.target
02122         _v151 = _v150.header
02123         start = end
02124         end += 4
02125         (_v151.seq,) = _struct_I.unpack(str[start:end])
02126         _v152 = _v151.stamp
02127         _x = _v152
02128         start = end
02129         end += 8
02130         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02131         start = end
02132         end += 4
02133         (length,) = _struct_I.unpack(str[start:end])
02134         start = end
02135         end += length
02136         if python3:
02137           _v151.frame_id = str[start:end].decode('utf-8')
02138         else:
02139           _v151.frame_id = str[start:end]
02140         _v153 = _v150.point
02141         _x = _v153
02142         start = end
02143         end += 24
02144         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02145         _v154 = val1.sensor_pose
02146         _v155 = _v154.header
02147         start = end
02148         end += 4
02149         (_v155.seq,) = _struct_I.unpack(str[start:end])
02150         _v156 = _v155.stamp
02151         _x = _v156
02152         start = end
02153         end += 8
02154         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02155         start = end
02156         end += 4
02157         (length,) = _struct_I.unpack(str[start:end])
02158         start = end
02159         end += length
02160         if python3:
02161           _v155.frame_id = str[start:end].decode('utf-8')
02162         else:
02163           _v155.frame_id = str[start:end]
02164         _v157 = _v154.pose
02165         _v158 = _v157.position
02166         _x = _v158
02167         start = end
02168         end += 24
02169         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02170         _v159 = _v157.orientation
02171         _x = _v159
02172         start = end
02173         end += 32
02174         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02175         start = end
02176         end += 8
02177         (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
02178         self.path_constraints.visibility_constraints.append(val1)
02179       start = end
02180       end += 4
02181       (length,) = _struct_I.unpack(str[start:end])
02182       self.goal_constraints.joint_constraints = []
02183       for i in range(0, length):
02184         val1 = arm_navigation_msgs.msg.JointConstraint()
02185         start = end
02186         end += 4
02187         (length,) = _struct_I.unpack(str[start:end])
02188         start = end
02189         end += length
02190         if python3:
02191           val1.joint_name = str[start:end].decode('utf-8')
02192         else:
02193           val1.joint_name = str[start:end]
02194         _x = val1
02195         start = end
02196         end += 32
02197         (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
02198         self.goal_constraints.joint_constraints.append(val1)
02199       start = end
02200       end += 4
02201       (length,) = _struct_I.unpack(str[start:end])
02202       self.goal_constraints.position_constraints = []
02203       for i in range(0, length):
02204         val1 = arm_navigation_msgs.msg.PositionConstraint()
02205         _v160 = val1.header
02206         start = end
02207         end += 4
02208         (_v160.seq,) = _struct_I.unpack(str[start:end])
02209         _v161 = _v160.stamp
02210         _x = _v161
02211         start = end
02212         end += 8
02213         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02214         start = end
02215         end += 4
02216         (length,) = _struct_I.unpack(str[start:end])
02217         start = end
02218         end += length
02219         if python3:
02220           _v160.frame_id = str[start:end].decode('utf-8')
02221         else:
02222           _v160.frame_id = str[start:end]
02223         start = end
02224         end += 4
02225         (length,) = _struct_I.unpack(str[start:end])
02226         start = end
02227         end += length
02228         if python3:
02229           val1.link_name = str[start:end].decode('utf-8')
02230         else:
02231           val1.link_name = str[start:end]
02232         _v162 = val1.target_point_offset
02233         _x = _v162
02234         start = end
02235         end += 24
02236         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02237         _v163 = val1.position
02238         _x = _v163
02239         start = end
02240         end += 24
02241         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02242         _v164 = val1.constraint_region_shape
02243         start = end
02244         end += 1
02245         (_v164.type,) = _struct_b.unpack(str[start:end])
02246         start = end
02247         end += 4
02248         (length,) = _struct_I.unpack(str[start:end])
02249         pattern = '<%sd'%length
02250         start = end
02251         end += struct.calcsize(pattern)
02252         _v164.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02253         start = end
02254         end += 4
02255         (length,) = _struct_I.unpack(str[start:end])
02256         pattern = '<%si'%length
02257         start = end
02258         end += struct.calcsize(pattern)
02259         _v164.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
02260         start = end
02261         end += 4
02262         (length,) = _struct_I.unpack(str[start:end])
02263         _v164.vertices = []
02264         for i in range(0, length):
02265           val3 = geometry_msgs.msg.Point()
02266           _x = val3
02267           start = end
02268           end += 24
02269           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02270           _v164.vertices.append(val3)
02271         _v165 = val1.constraint_region_orientation
02272         _x = _v165
02273         start = end
02274         end += 32
02275         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02276         start = end
02277         end += 8
02278         (val1.weight,) = _struct_d.unpack(str[start:end])
02279         self.goal_constraints.position_constraints.append(val1)
02280       start = end
02281       end += 4
02282       (length,) = _struct_I.unpack(str[start:end])
02283       self.goal_constraints.orientation_constraints = []
02284       for i in range(0, length):
02285         val1 = arm_navigation_msgs.msg.OrientationConstraint()
02286         _v166 = val1.header
02287         start = end
02288         end += 4
02289         (_v166.seq,) = _struct_I.unpack(str[start:end])
02290         _v167 = _v166.stamp
02291         _x = _v167
02292         start = end
02293         end += 8
02294         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02295         start = end
02296         end += 4
02297         (length,) = _struct_I.unpack(str[start:end])
02298         start = end
02299         end += length
02300         if python3:
02301           _v166.frame_id = str[start:end].decode('utf-8')
02302         else:
02303           _v166.frame_id = str[start:end]
02304         start = end
02305         end += 4
02306         (length,) = _struct_I.unpack(str[start:end])
02307         start = end
02308         end += length
02309         if python3:
02310           val1.link_name = str[start:end].decode('utf-8')
02311         else:
02312           val1.link_name = str[start:end]
02313         start = end
02314         end += 4
02315         (val1.type,) = _struct_i.unpack(str[start:end])
02316         _v168 = val1.orientation
02317         _x = _v168
02318         start = end
02319         end += 32
02320         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02321         _x = val1
02322         start = end
02323         end += 32
02324         (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
02325         self.goal_constraints.orientation_constraints.append(val1)
02326       start = end
02327       end += 4
02328       (length,) = _struct_I.unpack(str[start:end])
02329       self.goal_constraints.visibility_constraints = []
02330       for i in range(0, length):
02331         val1 = arm_navigation_msgs.msg.VisibilityConstraint()
02332         _v169 = val1.header
02333         start = end
02334         end += 4
02335         (_v169.seq,) = _struct_I.unpack(str[start:end])
02336         _v170 = _v169.stamp
02337         _x = _v170
02338         start = end
02339         end += 8
02340         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02341         start = end
02342         end += 4
02343         (length,) = _struct_I.unpack(str[start:end])
02344         start = end
02345         end += length
02346         if python3:
02347           _v169.frame_id = str[start:end].decode('utf-8')
02348         else:
02349           _v169.frame_id = str[start:end]
02350         _v171 = val1.target
02351         _v172 = _v171.header
02352         start = end
02353         end += 4
02354         (_v172.seq,) = _struct_I.unpack(str[start:end])
02355         _v173 = _v172.stamp
02356         _x = _v173
02357         start = end
02358         end += 8
02359         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02360         start = end
02361         end += 4
02362         (length,) = _struct_I.unpack(str[start:end])
02363         start = end
02364         end += length
02365         if python3:
02366           _v172.frame_id = str[start:end].decode('utf-8')
02367         else:
02368           _v172.frame_id = str[start:end]
02369         _v174 = _v171.point
02370         _x = _v174
02371         start = end
02372         end += 24
02373         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02374         _v175 = val1.sensor_pose
02375         _v176 = _v175.header
02376         start = end
02377         end += 4
02378         (_v176.seq,) = _struct_I.unpack(str[start:end])
02379         _v177 = _v176.stamp
02380         _x = _v177
02381         start = end
02382         end += 8
02383         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02384         start = end
02385         end += 4
02386         (length,) = _struct_I.unpack(str[start:end])
02387         start = end
02388         end += length
02389         if python3:
02390           _v176.frame_id = str[start:end].decode('utf-8')
02391         else:
02392           _v176.frame_id = str[start:end]
02393         _v178 = _v175.pose
02394         _v179 = _v178.position
02395         _x = _v179
02396         start = end
02397         end += 24
02398         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02399         _v180 = _v178.orientation
02400         _x = _v180
02401         start = end
02402         end += 32
02403         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02404         start = end
02405         end += 8
02406         (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
02407         self.goal_constraints.visibility_constraints.append(val1)
02408       return self
02409     except struct.error as e:
02410       raise genpy.DeserializationError(e) #most likely buffer underfill
02411 
02412 _struct_I = genpy.struct_I
02413 _struct_b = struct.Struct("<b")
02414 _struct_d = struct.Struct("<d")
02415 _struct_2I = struct.Struct("<2I")
02416 _struct_i = struct.Struct("<i")
02417 _struct_3I = struct.Struct("<3I")
02418 _struct_4d = struct.Struct("<4d")
02419 _struct_3d = struct.Struct("<3d")
02420 _struct_2i = struct.Struct("<2i")
02421 _struct_5B = struct.Struct("<5B")
02422 """autogenerated by genpy from arm_navigation_msgs/GetJointTrajectoryValidityResponse.msg. Do not edit."""
02423 import sys
02424 python3 = True if sys.hexversion > 0x03000000 else False
02425 import genpy
02426 import struct
02427 
02428 import arm_navigation_msgs.msg
02429 import geometry_msgs.msg
02430 import std_msgs.msg
02431 
02432 class GetJointTrajectoryValidityResponse(genpy.Message):
02433   _md5sum = "a739823e2969bedb7e3343a4d8c097d4"
02434   _type = "arm_navigation_msgs/GetJointTrajectoryValidityResponse"
02435   _has_header = False #flag to mark the presence of a Header object
02436   _full_text = """
02437 
02438 
02439 
02440 arm_navigation_msgs/ArmNavigationErrorCodes error_code
02441 
02442 
02443 
02444 
02445 arm_navigation_msgs/ArmNavigationErrorCodes[] trajectory_error_codes
02446 
02447 arm_navigation_msgs/ContactInformation[] contacts
02448 
02449 
02450 ================================================================================
02451 MSG: arm_navigation_msgs/ArmNavigationErrorCodes
02452 int32 val
02453 
02454 # overall behavior
02455 int32 PLANNING_FAILED=-1
02456 int32 SUCCESS=1
02457 int32 TIMED_OUT=-2
02458 
02459 # start state errors
02460 int32 START_STATE_IN_COLLISION=-3
02461 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4
02462 
02463 # goal errors
02464 int32 GOAL_IN_COLLISION=-5
02465 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6
02466 
02467 # robot state
02468 int32 INVALID_ROBOT_STATE=-7
02469 int32 INCOMPLETE_ROBOT_STATE=-8
02470 
02471 # planning request errors
02472 int32 INVALID_PLANNER_ID=-9
02473 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10
02474 int32 INVALID_ALLOWED_PLANNING_TIME=-11
02475 int32 INVALID_GROUP_NAME=-12
02476 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13
02477 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14
02478 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15
02479 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16
02480 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17
02481 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18
02482 
02483 # state/trajectory monitor errors
02484 int32 INVALID_TRAJECTORY=-19
02485 int32 INVALID_INDEX=-20
02486 int32 JOINT_LIMITS_VIOLATED=-21
02487 int32 PATH_CONSTRAINTS_VIOLATED=-22
02488 int32 COLLISION_CONSTRAINTS_VIOLATED=-23
02489 int32 GOAL_CONSTRAINTS_VIOLATED=-24
02490 int32 JOINTS_NOT_MOVING=-25
02491 int32 TRAJECTORY_CONTROLLER_FAILED=-26
02492 
02493 # system errors
02494 int32 FRAME_TRANSFORM_FAILURE=-27
02495 int32 COLLISION_CHECKING_UNAVAILABLE=-28
02496 int32 ROBOT_STATE_STALE=-29
02497 int32 SENSOR_INFO_STALE=-30
02498 
02499 # kinematics errors
02500 int32 NO_IK_SOLUTION=-31
02501 int32 INVALID_LINK_NAME=-32
02502 int32 IK_LINK_IN_COLLISION=-33
02503 int32 NO_FK_SOLUTION=-34
02504 int32 KINEMATICS_STATE_IN_COLLISION=-35
02505 
02506 # general errors
02507 int32 INVALID_TIMEOUT=-36
02508 
02509 
02510 ================================================================================
02511 MSG: arm_navigation_msgs/ContactInformation
02512 # Standard ROS header contains information 
02513 # about the frame in which this 
02514 # contact is specified
02515 Header header
02516 
02517 # Position of the contact point
02518 geometry_msgs/Point position
02519 
02520 # Normal corresponding to the contact point
02521 geometry_msgs/Vector3 normal 
02522 
02523 # Depth of contact point
02524 float64 depth
02525 
02526 # Name of the first body that is in contact
02527 # This could be a link or a namespace that represents a body
02528 string contact_body_1
02529 string attached_body_1
02530 uint32 body_type_1
02531 
02532 # Name of the second body that is in contact
02533 # This could be a link or a namespace that represents a body
02534 string contact_body_2
02535 string attached_body_2
02536 uint32 body_type_2
02537 
02538 uint32 ROBOT_LINK=0
02539 uint32 OBJECT=1
02540 uint32 ATTACHED_BODY=2
02541 ================================================================================
02542 MSG: std_msgs/Header
02543 # Standard metadata for higher-level stamped data types.
02544 # This is generally used to communicate timestamped data 
02545 # in a particular coordinate frame.
02546 # 
02547 # sequence ID: consecutively increasing ID 
02548 uint32 seq
02549 #Two-integer timestamp that is expressed as:
02550 # * stamp.secs: seconds (stamp_secs) since epoch
02551 # * stamp.nsecs: nanoseconds since stamp_secs
02552 # time-handling sugar is provided by the client library
02553 time stamp
02554 #Frame this data is associated with
02555 # 0: no frame
02556 # 1: global frame
02557 string frame_id
02558 
02559 ================================================================================
02560 MSG: geometry_msgs/Point
02561 # This contains the position of a point in free space
02562 float64 x
02563 float64 y
02564 float64 z
02565 
02566 ================================================================================
02567 MSG: geometry_msgs/Vector3
02568 # This represents a vector in free space. 
02569 
02570 float64 x
02571 float64 y
02572 float64 z
02573 """
02574   __slots__ = ['error_code','trajectory_error_codes','contacts']
02575   _slot_types = ['arm_navigation_msgs/ArmNavigationErrorCodes','arm_navigation_msgs/ArmNavigationErrorCodes[]','arm_navigation_msgs/ContactInformation[]']
02576 
02577   def __init__(self, *args, **kwds):
02578     """
02579     Constructor. Any message fields that are implicitly/explicitly
02580     set to None will be assigned a default value. The recommend
02581     use is keyword arguments as this is more robust to future message
02582     changes.  You cannot mix in-order arguments and keyword arguments.
02583 
02584     The available fields are:
02585        error_code,trajectory_error_codes,contacts
02586 
02587     :param args: complete set of field values, in .msg order
02588     :param kwds: use keyword arguments corresponding to message field names
02589     to set specific fields.
02590     """
02591     if args or kwds:
02592       super(GetJointTrajectoryValidityResponse, self).__init__(*args, **kwds)
02593       #message fields cannot be None, assign default values for those that are
02594       if self.error_code is None:
02595         self.error_code = arm_navigation_msgs.msg.ArmNavigationErrorCodes()
02596       if self.trajectory_error_codes is None:
02597         self.trajectory_error_codes = []
02598       if self.contacts is None:
02599         self.contacts = []
02600     else:
02601       self.error_code = arm_navigation_msgs.msg.ArmNavigationErrorCodes()
02602       self.trajectory_error_codes = []
02603       self.contacts = []
02604 
02605   def _get_types(self):
02606     """
02607     internal API method
02608     """
02609     return self._slot_types
02610 
02611   def serialize(self, buff):
02612     """
02613     serialize message into buffer
02614     :param buff: buffer, ``StringIO``
02615     """
02616     try:
02617       buff.write(_struct_i.pack(self.error_code.val))
02618       length = len(self.trajectory_error_codes)
02619       buff.write(_struct_I.pack(length))
02620       for val1 in self.trajectory_error_codes:
02621         buff.write(_struct_i.pack(val1.val))
02622       length = len(self.contacts)
02623       buff.write(_struct_I.pack(length))
02624       for val1 in self.contacts:
02625         _v181 = val1.header
02626         buff.write(_struct_I.pack(_v181.seq))
02627         _v182 = _v181.stamp
02628         _x = _v182
02629         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02630         _x = _v181.frame_id
02631         length = len(_x)
02632         if python3 or type(_x) == unicode:
02633           _x = _x.encode('utf-8')
02634           length = len(_x)
02635         buff.write(struct.pack('<I%ss'%length, length, _x))
02636         _v183 = val1.position
02637         _x = _v183
02638         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02639         _v184 = val1.normal
02640         _x = _v184
02641         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02642         buff.write(_struct_d.pack(val1.depth))
02643         _x = val1.contact_body_1
02644         length = len(_x)
02645         if python3 or type(_x) == unicode:
02646           _x = _x.encode('utf-8')
02647           length = len(_x)
02648         buff.write(struct.pack('<I%ss'%length, length, _x))
02649         _x = val1.attached_body_1
02650         length = len(_x)
02651         if python3 or type(_x) == unicode:
02652           _x = _x.encode('utf-8')
02653           length = len(_x)
02654         buff.write(struct.pack('<I%ss'%length, length, _x))
02655         buff.write(_struct_I.pack(val1.body_type_1))
02656         _x = val1.contact_body_2
02657         length = len(_x)
02658         if python3 or type(_x) == unicode:
02659           _x = _x.encode('utf-8')
02660           length = len(_x)
02661         buff.write(struct.pack('<I%ss'%length, length, _x))
02662         _x = val1.attached_body_2
02663         length = len(_x)
02664         if python3 or type(_x) == unicode:
02665           _x = _x.encode('utf-8')
02666           length = len(_x)
02667         buff.write(struct.pack('<I%ss'%length, length, _x))
02668         buff.write(_struct_I.pack(val1.body_type_2))
02669     except struct.error as se: self._check_types(se)
02670     except TypeError as te: self._check_types(te)
02671 
02672   def deserialize(self, str):
02673     """
02674     unpack serialized message in str into this message instance
02675     :param str: byte array of serialized message, ``str``
02676     """
02677     try:
02678       if self.error_code is None:
02679         self.error_code = arm_navigation_msgs.msg.ArmNavigationErrorCodes()
02680       if self.trajectory_error_codes is None:
02681         self.trajectory_error_codes = None
02682       if self.contacts is None:
02683         self.contacts = None
02684       end = 0
02685       start = end
02686       end += 4
02687       (self.error_code.val,) = _struct_i.unpack(str[start:end])
02688       start = end
02689       end += 4
02690       (length,) = _struct_I.unpack(str[start:end])
02691       self.trajectory_error_codes = []
02692       for i in range(0, length):
02693         val1 = arm_navigation_msgs.msg.ArmNavigationErrorCodes()
02694         start = end
02695         end += 4
02696         (val1.val,) = _struct_i.unpack(str[start:end])
02697         self.trajectory_error_codes.append(val1)
02698       start = end
02699       end += 4
02700       (length,) = _struct_I.unpack(str[start:end])
02701       self.contacts = []
02702       for i in range(0, length):
02703         val1 = arm_navigation_msgs.msg.ContactInformation()
02704         _v185 = val1.header
02705         start = end
02706         end += 4
02707         (_v185.seq,) = _struct_I.unpack(str[start:end])
02708         _v186 = _v185.stamp
02709         _x = _v186
02710         start = end
02711         end += 8
02712         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02713         start = end
02714         end += 4
02715         (length,) = _struct_I.unpack(str[start:end])
02716         start = end
02717         end += length
02718         if python3:
02719           _v185.frame_id = str[start:end].decode('utf-8')
02720         else:
02721           _v185.frame_id = str[start:end]
02722         _v187 = val1.position
02723         _x = _v187
02724         start = end
02725         end += 24
02726         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02727         _v188 = val1.normal
02728         _x = _v188
02729         start = end
02730         end += 24
02731         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02732         start = end
02733         end += 8
02734         (val1.depth,) = _struct_d.unpack(str[start:end])
02735         start = end
02736         end += 4
02737         (length,) = _struct_I.unpack(str[start:end])
02738         start = end
02739         end += length
02740         if python3:
02741           val1.contact_body_1 = str[start:end].decode('utf-8')
02742         else:
02743           val1.contact_body_1 = str[start:end]
02744         start = end
02745         end += 4
02746         (length,) = _struct_I.unpack(str[start:end])
02747         start = end
02748         end += length
02749         if python3:
02750           val1.attached_body_1 = str[start:end].decode('utf-8')
02751         else:
02752           val1.attached_body_1 = str[start:end]
02753         start = end
02754         end += 4
02755         (val1.body_type_1,) = _struct_I.unpack(str[start:end])
02756         start = end
02757         end += 4
02758         (length,) = _struct_I.unpack(str[start:end])
02759         start = end
02760         end += length
02761         if python3:
02762           val1.contact_body_2 = str[start:end].decode('utf-8')
02763         else:
02764           val1.contact_body_2 = str[start:end]
02765         start = end
02766         end += 4
02767         (length,) = _struct_I.unpack(str[start:end])
02768         start = end
02769         end += length
02770         if python3:
02771           val1.attached_body_2 = str[start:end].decode('utf-8')
02772         else:
02773           val1.attached_body_2 = str[start:end]
02774         start = end
02775         end += 4
02776         (val1.body_type_2,) = _struct_I.unpack(str[start:end])
02777         self.contacts.append(val1)
02778       return self
02779     except struct.error as e:
02780       raise genpy.DeserializationError(e) #most likely buffer underfill
02781 
02782 
02783   def serialize_numpy(self, buff, numpy):
02784     """
02785     serialize message with numpy array types into buffer
02786     :param buff: buffer, ``StringIO``
02787     :param numpy: numpy python module
02788     """
02789     try:
02790       buff.write(_struct_i.pack(self.error_code.val))
02791       length = len(self.trajectory_error_codes)
02792       buff.write(_struct_I.pack(length))
02793       for val1 in self.trajectory_error_codes:
02794         buff.write(_struct_i.pack(val1.val))
02795       length = len(self.contacts)
02796       buff.write(_struct_I.pack(length))
02797       for val1 in self.contacts:
02798         _v189 = val1.header
02799         buff.write(_struct_I.pack(_v189.seq))
02800         _v190 = _v189.stamp
02801         _x = _v190
02802         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02803         _x = _v189.frame_id
02804         length = len(_x)
02805         if python3 or type(_x) == unicode:
02806           _x = _x.encode('utf-8')
02807           length = len(_x)
02808         buff.write(struct.pack('<I%ss'%length, length, _x))
02809         _v191 = val1.position
02810         _x = _v191
02811         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02812         _v192 = val1.normal
02813         _x = _v192
02814         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02815         buff.write(_struct_d.pack(val1.depth))
02816         _x = val1.contact_body_1
02817         length = len(_x)
02818         if python3 or type(_x) == unicode:
02819           _x = _x.encode('utf-8')
02820           length = len(_x)
02821         buff.write(struct.pack('<I%ss'%length, length, _x))
02822         _x = val1.attached_body_1
02823         length = len(_x)
02824         if python3 or type(_x) == unicode:
02825           _x = _x.encode('utf-8')
02826           length = len(_x)
02827         buff.write(struct.pack('<I%ss'%length, length, _x))
02828         buff.write(_struct_I.pack(val1.body_type_1))
02829         _x = val1.contact_body_2
02830         length = len(_x)
02831         if python3 or type(_x) == unicode:
02832           _x = _x.encode('utf-8')
02833           length = len(_x)
02834         buff.write(struct.pack('<I%ss'%length, length, _x))
02835         _x = val1.attached_body_2
02836         length = len(_x)
02837         if python3 or type(_x) == unicode:
02838           _x = _x.encode('utf-8')
02839           length = len(_x)
02840         buff.write(struct.pack('<I%ss'%length, length, _x))
02841         buff.write(_struct_I.pack(val1.body_type_2))
02842     except struct.error as se: self._check_types(se)
02843     except TypeError as te: self._check_types(te)
02844 
02845   def deserialize_numpy(self, str, numpy):
02846     """
02847     unpack serialized message in str into this message instance using numpy for array types
02848     :param str: byte array of serialized message, ``str``
02849     :param numpy: numpy python module
02850     """
02851     try:
02852       if self.error_code is None:
02853         self.error_code = arm_navigation_msgs.msg.ArmNavigationErrorCodes()
02854       if self.trajectory_error_codes is None:
02855         self.trajectory_error_codes = None
02856       if self.contacts is None:
02857         self.contacts = None
02858       end = 0
02859       start = end
02860       end += 4
02861       (self.error_code.val,) = _struct_i.unpack(str[start:end])
02862       start = end
02863       end += 4
02864       (length,) = _struct_I.unpack(str[start:end])
02865       self.trajectory_error_codes = []
02866       for i in range(0, length):
02867         val1 = arm_navigation_msgs.msg.ArmNavigationErrorCodes()
02868         start = end
02869         end += 4
02870         (val1.val,) = _struct_i.unpack(str[start:end])
02871         self.trajectory_error_codes.append(val1)
02872       start = end
02873       end += 4
02874       (length,) = _struct_I.unpack(str[start:end])
02875       self.contacts = []
02876       for i in range(0, length):
02877         val1 = arm_navigation_msgs.msg.ContactInformation()
02878         _v193 = val1.header
02879         start = end
02880         end += 4
02881         (_v193.seq,) = _struct_I.unpack(str[start:end])
02882         _v194 = _v193.stamp
02883         _x = _v194
02884         start = end
02885         end += 8
02886         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02887         start = end
02888         end += 4
02889         (length,) = _struct_I.unpack(str[start:end])
02890         start = end
02891         end += length
02892         if python3:
02893           _v193.frame_id = str[start:end].decode('utf-8')
02894         else:
02895           _v193.frame_id = str[start:end]
02896         _v195 = val1.position
02897         _x = _v195
02898         start = end
02899         end += 24
02900         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02901         _v196 = val1.normal
02902         _x = _v196
02903         start = end
02904         end += 24
02905         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02906         start = end
02907         end += 8
02908         (val1.depth,) = _struct_d.unpack(str[start:end])
02909         start = end
02910         end += 4
02911         (length,) = _struct_I.unpack(str[start:end])
02912         start = end
02913         end += length
02914         if python3:
02915           val1.contact_body_1 = str[start:end].decode('utf-8')
02916         else:
02917           val1.contact_body_1 = str[start:end]
02918         start = end
02919         end += 4
02920         (length,) = _struct_I.unpack(str[start:end])
02921         start = end
02922         end += length
02923         if python3:
02924           val1.attached_body_1 = str[start:end].decode('utf-8')
02925         else:
02926           val1.attached_body_1 = str[start:end]
02927         start = end
02928         end += 4
02929         (val1.body_type_1,) = _struct_I.unpack(str[start:end])
02930         start = end
02931         end += 4
02932         (length,) = _struct_I.unpack(str[start:end])
02933         start = end
02934         end += length
02935         if python3:
02936           val1.contact_body_2 = str[start:end].decode('utf-8')
02937         else:
02938           val1.contact_body_2 = str[start:end]
02939         start = end
02940         end += 4
02941         (length,) = _struct_I.unpack(str[start:end])
02942         start = end
02943         end += length
02944         if python3:
02945           val1.attached_body_2 = str[start:end].decode('utf-8')
02946         else:
02947           val1.attached_body_2 = str[start:end]
02948         start = end
02949         end += 4
02950         (val1.body_type_2,) = _struct_I.unpack(str[start:end])
02951         self.contacts.append(val1)
02952       return self
02953     except struct.error as e:
02954       raise genpy.DeserializationError(e) #most likely buffer underfill
02955 
02956 _struct_I = genpy.struct_I
02957 _struct_i = struct.Struct("<i")
02958 _struct_2I = struct.Struct("<2I")
02959 _struct_d = struct.Struct("<d")
02960 _struct_3d = struct.Struct("<3d")
02961 class GetJointTrajectoryValidity(object):
02962   _type          = 'arm_navigation_msgs/GetJointTrajectoryValidity'
02963   _md5sum = '4e3f471462093adf968e2e6f6c2b6b2c'
02964   _request_class  = GetJointTrajectoryValidityRequest
02965   _response_class = GetJointTrajectoryValidityResponse


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