00001 """autogenerated by genmsg_py from DisplayTrajectory.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import trajectory_msgs.msg
00006 import roslib.rostime
00007 import geometry_msgs.msg
00008 import sensor_msgs.msg
00009 import motion_planning_msgs.msg
00010 import std_msgs.msg
00011
00012 class DisplayTrajectory(roslib.message.Message):
00013 _md5sum = "382f217803665e4718c4edbac445582c"
00014 _type = "motion_planning_msgs/DisplayTrajectory"
00015 _has_header = False
00016 _full_text = """# The model id for which this path has been generated
00017 string model_id
00018 # The representation of the path contains position values for all the joints that are moving along the path
00019 motion_planning_msgs/RobotTrajectory trajectory
00020 # The robot state is used to obtain positions for all/some of the joints of the robot.
00021 # It is used by the path display node to determine the positions of the joints that are not specified in the joint path message above.
00022 # If the robot state message contains joint position information for joints that are also mentioned in the joint path message, the positions in the joint path message will overwrite the positions specified in the robot state message.
00023 RobotState robot_state
00024 ================================================================================
00025 MSG: motion_planning_msgs/RobotTrajectory
00026 trajectory_msgs/JointTrajectory joint_trajectory
00027 motion_planning_msgs/MultiDOFJointTrajectory multi_dof_joint_trajectory
00028 ================================================================================
00029 MSG: trajectory_msgs/JointTrajectory
00030 Header header
00031 string[] joint_names
00032 JointTrajectoryPoint[] points
00033 ================================================================================
00034 MSG: std_msgs/Header
00035 # Standard metadata for higher-level stamped data types.
00036 # This is generally used to communicate timestamped data
00037 # in a particular coordinate frame.
00038 #
00039 # sequence ID: consecutively increasing ID
00040 uint32 seq
00041 #Two-integer timestamp that is expressed as:
00042 # * stamp.secs: seconds (stamp_secs) since epoch
00043 # * stamp.nsecs: nanoseconds since stamp_secs
00044 # time-handling sugar is provided by the client library
00045 time stamp
00046 #Frame this data is associated with
00047 # 0: no frame
00048 # 1: global frame
00049 string frame_id
00050
00051 ================================================================================
00052 MSG: trajectory_msgs/JointTrajectoryPoint
00053 float64[] positions
00054 float64[] velocities
00055 float64[] accelerations
00056 duration time_from_start
00057 ================================================================================
00058 MSG: motion_planning_msgs/MultiDOFJointTrajectory
00059 #A representation of a multi-dof joint trajectory
00060 duration stamp
00061 string[] joint_names
00062 string[] frame_ids
00063 string[] child_frame_ids
00064 MultiDOFJointTrajectoryPoint[] points
00065
00066 ================================================================================
00067 MSG: motion_planning_msgs/MultiDOFJointTrajectoryPoint
00068 geometry_msgs/Pose[] poses
00069 duration time_from_start
00070 ================================================================================
00071 MSG: geometry_msgs/Pose
00072 # A representation of pose in free space, composed of postion and orientation.
00073 Point position
00074 Quaternion orientation
00075
00076 ================================================================================
00077 MSG: geometry_msgs/Point
00078 # This contains the position of a point in free space
00079 float64 x
00080 float64 y
00081 float64 z
00082
00083 ================================================================================
00084 MSG: geometry_msgs/Quaternion
00085 # This represents an orientation in free space in quaternion form.
00086
00087 float64 x
00088 float64 y
00089 float64 z
00090 float64 w
00091
00092 ================================================================================
00093 MSG: motion_planning_msgs/RobotState
00094 # This message contains information about the robot state, i.e. the positions of its joints and links
00095 sensor_msgs/JointState joint_state
00096 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state
00097 ================================================================================
00098 MSG: sensor_msgs/JointState
00099 # This is a message that holds data to describe the state of a set of torque controlled joints.
00100 #
00101 # The state of each joint (revolute or prismatic) is defined by:
00102 # * the position of the joint (rad or m),
00103 # * the velocity of the joint (rad/s or m/s) and
00104 # * the effort that is applied in the joint (Nm or N).
00105 #
00106 # Each joint is uniquely identified by its name
00107 # The header specifies the time at which the joint states were recorded. All the joint states
00108 # in one message have to be recorded at the same time.
00109 #
00110 # This message consists of a multiple arrays, one for each part of the joint state.
00111 # The goal is to make each of the fields optional. When e.g. your joints have no
00112 # effort associated with them, you can leave the effort array empty.
00113 #
00114 # All arrays in this message should have the same size, or be empty.
00115 # This is the only way to uniquely associate the joint name with the correct
00116 # states.
00117
00118
00119 Header header
00120
00121 string[] name
00122 float64[] position
00123 float64[] velocity
00124 float64[] effort
00125
00126 ================================================================================
00127 MSG: motion_planning_msgs/MultiDOFJointState
00128 #A representation of a multi-dof joint state
00129 time stamp
00130 string[] joint_names
00131 string[] frame_ids
00132 string[] child_frame_ids
00133 geometry_msgs/Pose[] poses
00134
00135 """
00136 __slots__ = ['model_id','trajectory','robot_state']
00137 _slot_types = ['string','motion_planning_msgs/RobotTrajectory','motion_planning_msgs/RobotState']
00138
00139 def __init__(self, *args, **kwds):
00140 """
00141 Constructor. Any message fields that are implicitly/explicitly
00142 set to None will be assigned a default value. The recommend
00143 use is keyword arguments as this is more robust to future message
00144 changes. You cannot mix in-order arguments and keyword arguments.
00145
00146 The available fields are:
00147 model_id,trajectory,robot_state
00148
00149 @param args: complete set of field values, in .msg order
00150 @param kwds: use keyword arguments corresponding to message field names
00151 to set specific fields.
00152 """
00153 if args or kwds:
00154 super(DisplayTrajectory, self).__init__(*args, **kwds)
00155
00156 if self.model_id is None:
00157 self.model_id = ''
00158 if self.trajectory is None:
00159 self.trajectory = motion_planning_msgs.msg.RobotTrajectory()
00160 if self.robot_state is None:
00161 self.robot_state = motion_planning_msgs.msg.RobotState()
00162 else:
00163 self.model_id = ''
00164 self.trajectory = motion_planning_msgs.msg.RobotTrajectory()
00165 self.robot_state = motion_planning_msgs.msg.RobotState()
00166
00167 def _get_types(self):
00168 """
00169 internal API method
00170 """
00171 return self._slot_types
00172
00173 def serialize(self, buff):
00174 """
00175 serialize message into buffer
00176 @param buff: buffer
00177 @type buff: StringIO
00178 """
00179 try:
00180 _x = self.model_id
00181 length = len(_x)
00182 buff.write(struct.pack('<I%ss'%length, length, _x))
00183 _x = self
00184 buff.write(_struct_3I.pack(_x.trajectory.joint_trajectory.header.seq, _x.trajectory.joint_trajectory.header.stamp.secs, _x.trajectory.joint_trajectory.header.stamp.nsecs))
00185 _x = self.trajectory.joint_trajectory.header.frame_id
00186 length = len(_x)
00187 buff.write(struct.pack('<I%ss'%length, length, _x))
00188 length = len(self.trajectory.joint_trajectory.joint_names)
00189 buff.write(_struct_I.pack(length))
00190 for val1 in self.trajectory.joint_trajectory.joint_names:
00191 length = len(val1)
00192 buff.write(struct.pack('<I%ss'%length, length, val1))
00193 length = len(self.trajectory.joint_trajectory.points)
00194 buff.write(_struct_I.pack(length))
00195 for val1 in self.trajectory.joint_trajectory.points:
00196 length = len(val1.positions)
00197 buff.write(_struct_I.pack(length))
00198 pattern = '<%sd'%length
00199 buff.write(struct.pack(pattern, *val1.positions))
00200 length = len(val1.velocities)
00201 buff.write(_struct_I.pack(length))
00202 pattern = '<%sd'%length
00203 buff.write(struct.pack(pattern, *val1.velocities))
00204 length = len(val1.accelerations)
00205 buff.write(_struct_I.pack(length))
00206 pattern = '<%sd'%length
00207 buff.write(struct.pack(pattern, *val1.accelerations))
00208 _v1 = val1.time_from_start
00209 _x = _v1
00210 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00211 _x = self
00212 buff.write(_struct_2i.pack(_x.trajectory.multi_dof_joint_trajectory.stamp.secs, _x.trajectory.multi_dof_joint_trajectory.stamp.nsecs))
00213 length = len(self.trajectory.multi_dof_joint_trajectory.joint_names)
00214 buff.write(_struct_I.pack(length))
00215 for val1 in self.trajectory.multi_dof_joint_trajectory.joint_names:
00216 length = len(val1)
00217 buff.write(struct.pack('<I%ss'%length, length, val1))
00218 length = len(self.trajectory.multi_dof_joint_trajectory.frame_ids)
00219 buff.write(_struct_I.pack(length))
00220 for val1 in self.trajectory.multi_dof_joint_trajectory.frame_ids:
00221 length = len(val1)
00222 buff.write(struct.pack('<I%ss'%length, length, val1))
00223 length = len(self.trajectory.multi_dof_joint_trajectory.child_frame_ids)
00224 buff.write(_struct_I.pack(length))
00225 for val1 in self.trajectory.multi_dof_joint_trajectory.child_frame_ids:
00226 length = len(val1)
00227 buff.write(struct.pack('<I%ss'%length, length, val1))
00228 length = len(self.trajectory.multi_dof_joint_trajectory.points)
00229 buff.write(_struct_I.pack(length))
00230 for val1 in self.trajectory.multi_dof_joint_trajectory.points:
00231 length = len(val1.poses)
00232 buff.write(_struct_I.pack(length))
00233 for val2 in val1.poses:
00234 _v2 = val2.position
00235 _x = _v2
00236 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00237 _v3 = val2.orientation
00238 _x = _v3
00239 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00240 _v4 = val1.time_from_start
00241 _x = _v4
00242 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00243 _x = self
00244 buff.write(_struct_3I.pack(_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs))
00245 _x = self.robot_state.joint_state.header.frame_id
00246 length = len(_x)
00247 buff.write(struct.pack('<I%ss'%length, length, _x))
00248 length = len(self.robot_state.joint_state.name)
00249 buff.write(_struct_I.pack(length))
00250 for val1 in self.robot_state.joint_state.name:
00251 length = len(val1)
00252 buff.write(struct.pack('<I%ss'%length, length, val1))
00253 length = len(self.robot_state.joint_state.position)
00254 buff.write(_struct_I.pack(length))
00255 pattern = '<%sd'%length
00256 buff.write(struct.pack(pattern, *self.robot_state.joint_state.position))
00257 length = len(self.robot_state.joint_state.velocity)
00258 buff.write(_struct_I.pack(length))
00259 pattern = '<%sd'%length
00260 buff.write(struct.pack(pattern, *self.robot_state.joint_state.velocity))
00261 length = len(self.robot_state.joint_state.effort)
00262 buff.write(_struct_I.pack(length))
00263 pattern = '<%sd'%length
00264 buff.write(struct.pack(pattern, *self.robot_state.joint_state.effort))
00265 _x = self
00266 buff.write(_struct_2I.pack(_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs))
00267 length = len(self.robot_state.multi_dof_joint_state.joint_names)
00268 buff.write(_struct_I.pack(length))
00269 for val1 in self.robot_state.multi_dof_joint_state.joint_names:
00270 length = len(val1)
00271 buff.write(struct.pack('<I%ss'%length, length, val1))
00272 length = len(self.robot_state.multi_dof_joint_state.frame_ids)
00273 buff.write(_struct_I.pack(length))
00274 for val1 in self.robot_state.multi_dof_joint_state.frame_ids:
00275 length = len(val1)
00276 buff.write(struct.pack('<I%ss'%length, length, val1))
00277 length = len(self.robot_state.multi_dof_joint_state.child_frame_ids)
00278 buff.write(_struct_I.pack(length))
00279 for val1 in self.robot_state.multi_dof_joint_state.child_frame_ids:
00280 length = len(val1)
00281 buff.write(struct.pack('<I%ss'%length, length, val1))
00282 length = len(self.robot_state.multi_dof_joint_state.poses)
00283 buff.write(_struct_I.pack(length))
00284 for val1 in self.robot_state.multi_dof_joint_state.poses:
00285 _v5 = val1.position
00286 _x = _v5
00287 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00288 _v6 = val1.orientation
00289 _x = _v6
00290 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00291 except struct.error, se: self._check_types(se)
00292 except TypeError, te: self._check_types(te)
00293
00294 def deserialize(self, str):
00295 """
00296 unpack serialized message in str into this message instance
00297 @param str: byte array of serialized message
00298 @type str: str
00299 """
00300 try:
00301 if self.trajectory is None:
00302 self.trajectory = motion_planning_msgs.msg.RobotTrajectory()
00303 if self.robot_state is None:
00304 self.robot_state = motion_planning_msgs.msg.RobotState()
00305 end = 0
00306 start = end
00307 end += 4
00308 (length,) = _struct_I.unpack(str[start:end])
00309 start = end
00310 end += length
00311 self.model_id = str[start:end]
00312 _x = self
00313 start = end
00314 end += 12
00315 (_x.trajectory.joint_trajectory.header.seq, _x.trajectory.joint_trajectory.header.stamp.secs, _x.trajectory.joint_trajectory.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00316 start = end
00317 end += 4
00318 (length,) = _struct_I.unpack(str[start:end])
00319 start = end
00320 end += length
00321 self.trajectory.joint_trajectory.header.frame_id = str[start:end]
00322 start = end
00323 end += 4
00324 (length,) = _struct_I.unpack(str[start:end])
00325 self.trajectory.joint_trajectory.joint_names = []
00326 for i in xrange(0, length):
00327 start = end
00328 end += 4
00329 (length,) = _struct_I.unpack(str[start:end])
00330 start = end
00331 end += length
00332 val1 = str[start:end]
00333 self.trajectory.joint_trajectory.joint_names.append(val1)
00334 start = end
00335 end += 4
00336 (length,) = _struct_I.unpack(str[start:end])
00337 self.trajectory.joint_trajectory.points = []
00338 for i in xrange(0, length):
00339 val1 = trajectory_msgs.msg.JointTrajectoryPoint()
00340 start = end
00341 end += 4
00342 (length,) = _struct_I.unpack(str[start:end])
00343 pattern = '<%sd'%length
00344 start = end
00345 end += struct.calcsize(pattern)
00346 val1.positions = struct.unpack(pattern, str[start:end])
00347 start = end
00348 end += 4
00349 (length,) = _struct_I.unpack(str[start:end])
00350 pattern = '<%sd'%length
00351 start = end
00352 end += struct.calcsize(pattern)
00353 val1.velocities = struct.unpack(pattern, str[start:end])
00354 start = end
00355 end += 4
00356 (length,) = _struct_I.unpack(str[start:end])
00357 pattern = '<%sd'%length
00358 start = end
00359 end += struct.calcsize(pattern)
00360 val1.accelerations = struct.unpack(pattern, str[start:end])
00361 _v7 = val1.time_from_start
00362 _x = _v7
00363 start = end
00364 end += 8
00365 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00366 self.trajectory.joint_trajectory.points.append(val1)
00367 _x = self
00368 start = end
00369 end += 8
00370 (_x.trajectory.multi_dof_joint_trajectory.stamp.secs, _x.trajectory.multi_dof_joint_trajectory.stamp.nsecs,) = _struct_2i.unpack(str[start:end])
00371 start = end
00372 end += 4
00373 (length,) = _struct_I.unpack(str[start:end])
00374 self.trajectory.multi_dof_joint_trajectory.joint_names = []
00375 for i in xrange(0, length):
00376 start = end
00377 end += 4
00378 (length,) = _struct_I.unpack(str[start:end])
00379 start = end
00380 end += length
00381 val1 = str[start:end]
00382 self.trajectory.multi_dof_joint_trajectory.joint_names.append(val1)
00383 start = end
00384 end += 4
00385 (length,) = _struct_I.unpack(str[start:end])
00386 self.trajectory.multi_dof_joint_trajectory.frame_ids = []
00387 for i in xrange(0, length):
00388 start = end
00389 end += 4
00390 (length,) = _struct_I.unpack(str[start:end])
00391 start = end
00392 end += length
00393 val1 = str[start:end]
00394 self.trajectory.multi_dof_joint_trajectory.frame_ids.append(val1)
00395 start = end
00396 end += 4
00397 (length,) = _struct_I.unpack(str[start:end])
00398 self.trajectory.multi_dof_joint_trajectory.child_frame_ids = []
00399 for i in xrange(0, length):
00400 start = end
00401 end += 4
00402 (length,) = _struct_I.unpack(str[start:end])
00403 start = end
00404 end += length
00405 val1 = str[start:end]
00406 self.trajectory.multi_dof_joint_trajectory.child_frame_ids.append(val1)
00407 start = end
00408 end += 4
00409 (length,) = _struct_I.unpack(str[start:end])
00410 self.trajectory.multi_dof_joint_trajectory.points = []
00411 for i in xrange(0, length):
00412 val1 = motion_planning_msgs.msg.MultiDOFJointTrajectoryPoint()
00413 start = end
00414 end += 4
00415 (length,) = _struct_I.unpack(str[start:end])
00416 val1.poses = []
00417 for i in xrange(0, length):
00418 val2 = geometry_msgs.msg.Pose()
00419 _v8 = val2.position
00420 _x = _v8
00421 start = end
00422 end += 24
00423 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00424 _v9 = val2.orientation
00425 _x = _v9
00426 start = end
00427 end += 32
00428 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00429 val1.poses.append(val2)
00430 _v10 = val1.time_from_start
00431 _x = _v10
00432 start = end
00433 end += 8
00434 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00435 self.trajectory.multi_dof_joint_trajectory.points.append(val1)
00436 _x = self
00437 start = end
00438 end += 12
00439 (_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00440 start = end
00441 end += 4
00442 (length,) = _struct_I.unpack(str[start:end])
00443 start = end
00444 end += length
00445 self.robot_state.joint_state.header.frame_id = str[start:end]
00446 start = end
00447 end += 4
00448 (length,) = _struct_I.unpack(str[start:end])
00449 self.robot_state.joint_state.name = []
00450 for i in xrange(0, length):
00451 start = end
00452 end += 4
00453 (length,) = _struct_I.unpack(str[start:end])
00454 start = end
00455 end += length
00456 val1 = str[start:end]
00457 self.robot_state.joint_state.name.append(val1)
00458 start = end
00459 end += 4
00460 (length,) = _struct_I.unpack(str[start:end])
00461 pattern = '<%sd'%length
00462 start = end
00463 end += struct.calcsize(pattern)
00464 self.robot_state.joint_state.position = struct.unpack(pattern, str[start:end])
00465 start = end
00466 end += 4
00467 (length,) = _struct_I.unpack(str[start:end])
00468 pattern = '<%sd'%length
00469 start = end
00470 end += struct.calcsize(pattern)
00471 self.robot_state.joint_state.velocity = struct.unpack(pattern, str[start:end])
00472 start = end
00473 end += 4
00474 (length,) = _struct_I.unpack(str[start:end])
00475 pattern = '<%sd'%length
00476 start = end
00477 end += struct.calcsize(pattern)
00478 self.robot_state.joint_state.effort = struct.unpack(pattern, str[start:end])
00479 _x = self
00480 start = end
00481 end += 8
00482 (_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00483 start = end
00484 end += 4
00485 (length,) = _struct_I.unpack(str[start:end])
00486 self.robot_state.multi_dof_joint_state.joint_names = []
00487 for i in xrange(0, length):
00488 start = end
00489 end += 4
00490 (length,) = _struct_I.unpack(str[start:end])
00491 start = end
00492 end += length
00493 val1 = str[start:end]
00494 self.robot_state.multi_dof_joint_state.joint_names.append(val1)
00495 start = end
00496 end += 4
00497 (length,) = _struct_I.unpack(str[start:end])
00498 self.robot_state.multi_dof_joint_state.frame_ids = []
00499 for i in xrange(0, length):
00500 start = end
00501 end += 4
00502 (length,) = _struct_I.unpack(str[start:end])
00503 start = end
00504 end += length
00505 val1 = str[start:end]
00506 self.robot_state.multi_dof_joint_state.frame_ids.append(val1)
00507 start = end
00508 end += 4
00509 (length,) = _struct_I.unpack(str[start:end])
00510 self.robot_state.multi_dof_joint_state.child_frame_ids = []
00511 for i in xrange(0, length):
00512 start = end
00513 end += 4
00514 (length,) = _struct_I.unpack(str[start:end])
00515 start = end
00516 end += length
00517 val1 = str[start:end]
00518 self.robot_state.multi_dof_joint_state.child_frame_ids.append(val1)
00519 start = end
00520 end += 4
00521 (length,) = _struct_I.unpack(str[start:end])
00522 self.robot_state.multi_dof_joint_state.poses = []
00523 for i in xrange(0, length):
00524 val1 = geometry_msgs.msg.Pose()
00525 _v11 = val1.position
00526 _x = _v11
00527 start = end
00528 end += 24
00529 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00530 _v12 = val1.orientation
00531 _x = _v12
00532 start = end
00533 end += 32
00534 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00535 self.robot_state.multi_dof_joint_state.poses.append(val1)
00536 return self
00537 except struct.error, e:
00538 raise roslib.message.DeserializationError(e)
00539
00540
00541 def serialize_numpy(self, buff, numpy):
00542 """
00543 serialize message with numpy array types into buffer
00544 @param buff: buffer
00545 @type buff: StringIO
00546 @param numpy: numpy python module
00547 @type numpy module
00548 """
00549 try:
00550 _x = self.model_id
00551 length = len(_x)
00552 buff.write(struct.pack('<I%ss'%length, length, _x))
00553 _x = self
00554 buff.write(_struct_3I.pack(_x.trajectory.joint_trajectory.header.seq, _x.trajectory.joint_trajectory.header.stamp.secs, _x.trajectory.joint_trajectory.header.stamp.nsecs))
00555 _x = self.trajectory.joint_trajectory.header.frame_id
00556 length = len(_x)
00557 buff.write(struct.pack('<I%ss'%length, length, _x))
00558 length = len(self.trajectory.joint_trajectory.joint_names)
00559 buff.write(_struct_I.pack(length))
00560 for val1 in self.trajectory.joint_trajectory.joint_names:
00561 length = len(val1)
00562 buff.write(struct.pack('<I%ss'%length, length, val1))
00563 length = len(self.trajectory.joint_trajectory.points)
00564 buff.write(_struct_I.pack(length))
00565 for val1 in self.trajectory.joint_trajectory.points:
00566 length = len(val1.positions)
00567 buff.write(_struct_I.pack(length))
00568 pattern = '<%sd'%length
00569 buff.write(val1.positions.tostring())
00570 length = len(val1.velocities)
00571 buff.write(_struct_I.pack(length))
00572 pattern = '<%sd'%length
00573 buff.write(val1.velocities.tostring())
00574 length = len(val1.accelerations)
00575 buff.write(_struct_I.pack(length))
00576 pattern = '<%sd'%length
00577 buff.write(val1.accelerations.tostring())
00578 _v13 = val1.time_from_start
00579 _x = _v13
00580 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00581 _x = self
00582 buff.write(_struct_2i.pack(_x.trajectory.multi_dof_joint_trajectory.stamp.secs, _x.trajectory.multi_dof_joint_trajectory.stamp.nsecs))
00583 length = len(self.trajectory.multi_dof_joint_trajectory.joint_names)
00584 buff.write(_struct_I.pack(length))
00585 for val1 in self.trajectory.multi_dof_joint_trajectory.joint_names:
00586 length = len(val1)
00587 buff.write(struct.pack('<I%ss'%length, length, val1))
00588 length = len(self.trajectory.multi_dof_joint_trajectory.frame_ids)
00589 buff.write(_struct_I.pack(length))
00590 for val1 in self.trajectory.multi_dof_joint_trajectory.frame_ids:
00591 length = len(val1)
00592 buff.write(struct.pack('<I%ss'%length, length, val1))
00593 length = len(self.trajectory.multi_dof_joint_trajectory.child_frame_ids)
00594 buff.write(_struct_I.pack(length))
00595 for val1 in self.trajectory.multi_dof_joint_trajectory.child_frame_ids:
00596 length = len(val1)
00597 buff.write(struct.pack('<I%ss'%length, length, val1))
00598 length = len(self.trajectory.multi_dof_joint_trajectory.points)
00599 buff.write(_struct_I.pack(length))
00600 for val1 in self.trajectory.multi_dof_joint_trajectory.points:
00601 length = len(val1.poses)
00602 buff.write(_struct_I.pack(length))
00603 for val2 in val1.poses:
00604 _v14 = val2.position
00605 _x = _v14
00606 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00607 _v15 = val2.orientation
00608 _x = _v15
00609 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00610 _v16 = val1.time_from_start
00611 _x = _v16
00612 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00613 _x = self
00614 buff.write(_struct_3I.pack(_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs))
00615 _x = self.robot_state.joint_state.header.frame_id
00616 length = len(_x)
00617 buff.write(struct.pack('<I%ss'%length, length, _x))
00618 length = len(self.robot_state.joint_state.name)
00619 buff.write(_struct_I.pack(length))
00620 for val1 in self.robot_state.joint_state.name:
00621 length = len(val1)
00622 buff.write(struct.pack('<I%ss'%length, length, val1))
00623 length = len(self.robot_state.joint_state.position)
00624 buff.write(_struct_I.pack(length))
00625 pattern = '<%sd'%length
00626 buff.write(self.robot_state.joint_state.position.tostring())
00627 length = len(self.robot_state.joint_state.velocity)
00628 buff.write(_struct_I.pack(length))
00629 pattern = '<%sd'%length
00630 buff.write(self.robot_state.joint_state.velocity.tostring())
00631 length = len(self.robot_state.joint_state.effort)
00632 buff.write(_struct_I.pack(length))
00633 pattern = '<%sd'%length
00634 buff.write(self.robot_state.joint_state.effort.tostring())
00635 _x = self
00636 buff.write(_struct_2I.pack(_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs))
00637 length = len(self.robot_state.multi_dof_joint_state.joint_names)
00638 buff.write(_struct_I.pack(length))
00639 for val1 in self.robot_state.multi_dof_joint_state.joint_names:
00640 length = len(val1)
00641 buff.write(struct.pack('<I%ss'%length, length, val1))
00642 length = len(self.robot_state.multi_dof_joint_state.frame_ids)
00643 buff.write(_struct_I.pack(length))
00644 for val1 in self.robot_state.multi_dof_joint_state.frame_ids:
00645 length = len(val1)
00646 buff.write(struct.pack('<I%ss'%length, length, val1))
00647 length = len(self.robot_state.multi_dof_joint_state.child_frame_ids)
00648 buff.write(_struct_I.pack(length))
00649 for val1 in self.robot_state.multi_dof_joint_state.child_frame_ids:
00650 length = len(val1)
00651 buff.write(struct.pack('<I%ss'%length, length, val1))
00652 length = len(self.robot_state.multi_dof_joint_state.poses)
00653 buff.write(_struct_I.pack(length))
00654 for val1 in self.robot_state.multi_dof_joint_state.poses:
00655 _v17 = val1.position
00656 _x = _v17
00657 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00658 _v18 = val1.orientation
00659 _x = _v18
00660 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00661 except struct.error, se: self._check_types(se)
00662 except TypeError, te: self._check_types(te)
00663
00664 def deserialize_numpy(self, str, numpy):
00665 """
00666 unpack serialized message in str into this message instance using numpy for array types
00667 @param str: byte array of serialized message
00668 @type str: str
00669 @param numpy: numpy python module
00670 @type numpy: module
00671 """
00672 try:
00673 if self.trajectory is None:
00674 self.trajectory = motion_planning_msgs.msg.RobotTrajectory()
00675 if self.robot_state is None:
00676 self.robot_state = motion_planning_msgs.msg.RobotState()
00677 end = 0
00678 start = end
00679 end += 4
00680 (length,) = _struct_I.unpack(str[start:end])
00681 start = end
00682 end += length
00683 self.model_id = str[start:end]
00684 _x = self
00685 start = end
00686 end += 12
00687 (_x.trajectory.joint_trajectory.header.seq, _x.trajectory.joint_trajectory.header.stamp.secs, _x.trajectory.joint_trajectory.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00688 start = end
00689 end += 4
00690 (length,) = _struct_I.unpack(str[start:end])
00691 start = end
00692 end += length
00693 self.trajectory.joint_trajectory.header.frame_id = str[start:end]
00694 start = end
00695 end += 4
00696 (length,) = _struct_I.unpack(str[start:end])
00697 self.trajectory.joint_trajectory.joint_names = []
00698 for i in xrange(0, length):
00699 start = end
00700 end += 4
00701 (length,) = _struct_I.unpack(str[start:end])
00702 start = end
00703 end += length
00704 val1 = str[start:end]
00705 self.trajectory.joint_trajectory.joint_names.append(val1)
00706 start = end
00707 end += 4
00708 (length,) = _struct_I.unpack(str[start:end])
00709 self.trajectory.joint_trajectory.points = []
00710 for i in xrange(0, length):
00711 val1 = trajectory_msgs.msg.JointTrajectoryPoint()
00712 start = end
00713 end += 4
00714 (length,) = _struct_I.unpack(str[start:end])
00715 pattern = '<%sd'%length
00716 start = end
00717 end += struct.calcsize(pattern)
00718 val1.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00719 start = end
00720 end += 4
00721 (length,) = _struct_I.unpack(str[start:end])
00722 pattern = '<%sd'%length
00723 start = end
00724 end += struct.calcsize(pattern)
00725 val1.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00726 start = end
00727 end += 4
00728 (length,) = _struct_I.unpack(str[start:end])
00729 pattern = '<%sd'%length
00730 start = end
00731 end += struct.calcsize(pattern)
00732 val1.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00733 _v19 = val1.time_from_start
00734 _x = _v19
00735 start = end
00736 end += 8
00737 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00738 self.trajectory.joint_trajectory.points.append(val1)
00739 _x = self
00740 start = end
00741 end += 8
00742 (_x.trajectory.multi_dof_joint_trajectory.stamp.secs, _x.trajectory.multi_dof_joint_trajectory.stamp.nsecs,) = _struct_2i.unpack(str[start:end])
00743 start = end
00744 end += 4
00745 (length,) = _struct_I.unpack(str[start:end])
00746 self.trajectory.multi_dof_joint_trajectory.joint_names = []
00747 for i in xrange(0, length):
00748 start = end
00749 end += 4
00750 (length,) = _struct_I.unpack(str[start:end])
00751 start = end
00752 end += length
00753 val1 = str[start:end]
00754 self.trajectory.multi_dof_joint_trajectory.joint_names.append(val1)
00755 start = end
00756 end += 4
00757 (length,) = _struct_I.unpack(str[start:end])
00758 self.trajectory.multi_dof_joint_trajectory.frame_ids = []
00759 for i in xrange(0, length):
00760 start = end
00761 end += 4
00762 (length,) = _struct_I.unpack(str[start:end])
00763 start = end
00764 end += length
00765 val1 = str[start:end]
00766 self.trajectory.multi_dof_joint_trajectory.frame_ids.append(val1)
00767 start = end
00768 end += 4
00769 (length,) = _struct_I.unpack(str[start:end])
00770 self.trajectory.multi_dof_joint_trajectory.child_frame_ids = []
00771 for i in xrange(0, length):
00772 start = end
00773 end += 4
00774 (length,) = _struct_I.unpack(str[start:end])
00775 start = end
00776 end += length
00777 val1 = str[start:end]
00778 self.trajectory.multi_dof_joint_trajectory.child_frame_ids.append(val1)
00779 start = end
00780 end += 4
00781 (length,) = _struct_I.unpack(str[start:end])
00782 self.trajectory.multi_dof_joint_trajectory.points = []
00783 for i in xrange(0, length):
00784 val1 = motion_planning_msgs.msg.MultiDOFJointTrajectoryPoint()
00785 start = end
00786 end += 4
00787 (length,) = _struct_I.unpack(str[start:end])
00788 val1.poses = []
00789 for i in xrange(0, length):
00790 val2 = geometry_msgs.msg.Pose()
00791 _v20 = val2.position
00792 _x = _v20
00793 start = end
00794 end += 24
00795 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00796 _v21 = val2.orientation
00797 _x = _v21
00798 start = end
00799 end += 32
00800 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00801 val1.poses.append(val2)
00802 _v22 = val1.time_from_start
00803 _x = _v22
00804 start = end
00805 end += 8
00806 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00807 self.trajectory.multi_dof_joint_trajectory.points.append(val1)
00808 _x = self
00809 start = end
00810 end += 12
00811 (_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00812 start = end
00813 end += 4
00814 (length,) = _struct_I.unpack(str[start:end])
00815 start = end
00816 end += length
00817 self.robot_state.joint_state.header.frame_id = str[start:end]
00818 start = end
00819 end += 4
00820 (length,) = _struct_I.unpack(str[start:end])
00821 self.robot_state.joint_state.name = []
00822 for i in xrange(0, length):
00823 start = end
00824 end += 4
00825 (length,) = _struct_I.unpack(str[start:end])
00826 start = end
00827 end += length
00828 val1 = str[start:end]
00829 self.robot_state.joint_state.name.append(val1)
00830 start = end
00831 end += 4
00832 (length,) = _struct_I.unpack(str[start:end])
00833 pattern = '<%sd'%length
00834 start = end
00835 end += struct.calcsize(pattern)
00836 self.robot_state.joint_state.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00837 start = end
00838 end += 4
00839 (length,) = _struct_I.unpack(str[start:end])
00840 pattern = '<%sd'%length
00841 start = end
00842 end += struct.calcsize(pattern)
00843 self.robot_state.joint_state.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00844 start = end
00845 end += 4
00846 (length,) = _struct_I.unpack(str[start:end])
00847 pattern = '<%sd'%length
00848 start = end
00849 end += struct.calcsize(pattern)
00850 self.robot_state.joint_state.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00851 _x = self
00852 start = end
00853 end += 8
00854 (_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00855 start = end
00856 end += 4
00857 (length,) = _struct_I.unpack(str[start:end])
00858 self.robot_state.multi_dof_joint_state.joint_names = []
00859 for i in xrange(0, length):
00860 start = end
00861 end += 4
00862 (length,) = _struct_I.unpack(str[start:end])
00863 start = end
00864 end += length
00865 val1 = str[start:end]
00866 self.robot_state.multi_dof_joint_state.joint_names.append(val1)
00867 start = end
00868 end += 4
00869 (length,) = _struct_I.unpack(str[start:end])
00870 self.robot_state.multi_dof_joint_state.frame_ids = []
00871 for i in xrange(0, length):
00872 start = end
00873 end += 4
00874 (length,) = _struct_I.unpack(str[start:end])
00875 start = end
00876 end += length
00877 val1 = str[start:end]
00878 self.robot_state.multi_dof_joint_state.frame_ids.append(val1)
00879 start = end
00880 end += 4
00881 (length,) = _struct_I.unpack(str[start:end])
00882 self.robot_state.multi_dof_joint_state.child_frame_ids = []
00883 for i in xrange(0, length):
00884 start = end
00885 end += 4
00886 (length,) = _struct_I.unpack(str[start:end])
00887 start = end
00888 end += length
00889 val1 = str[start:end]
00890 self.robot_state.multi_dof_joint_state.child_frame_ids.append(val1)
00891 start = end
00892 end += 4
00893 (length,) = _struct_I.unpack(str[start:end])
00894 self.robot_state.multi_dof_joint_state.poses = []
00895 for i in xrange(0, length):
00896 val1 = geometry_msgs.msg.Pose()
00897 _v23 = val1.position
00898 _x = _v23
00899 start = end
00900 end += 24
00901 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00902 _v24 = val1.orientation
00903 _x = _v24
00904 start = end
00905 end += 32
00906 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00907 self.robot_state.multi_dof_joint_state.poses.append(val1)
00908 return self
00909 except struct.error, e:
00910 raise roslib.message.DeserializationError(e)
00911
00912 _struct_I = roslib.message.struct_I
00913 _struct_4d = struct.Struct("<4d")
00914 _struct_3I = struct.Struct("<3I")
00915 _struct_2i = struct.Struct("<2i")
00916 _struct_2I = struct.Struct("<2I")
00917 _struct_3d = struct.Struct("<3d")