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


arm_navigation_msgs
Author(s): Gil Jones
autogenerated on Thu Dec 12 2013 11:08:10