$search
00001 """autogenerated by genmsg_py from RobotTrajectory.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import trajectory_msgs.msg 00006 import arm_navigation_msgs.msg 00007 import geometry_msgs.msg 00008 import roslib.rostime 00009 import std_msgs.msg 00010 00011 class RobotTrajectory(roslib.message.Message): 00012 _md5sum = "5bc8324620001e5c07a09d0bbfaaf093" 00013 _type = "arm_navigation_msgs/RobotTrajectory" 00014 _has_header = False #flag to mark the presence of a Header object 00015 _full_text = """trajectory_msgs/JointTrajectory joint_trajectory 00016 arm_navigation_msgs/MultiDOFJointTrajectory multi_dof_joint_trajectory 00017 00018 ================================================================================ 00019 MSG: trajectory_msgs/JointTrajectory 00020 Header header 00021 string[] joint_names 00022 JointTrajectoryPoint[] points 00023 ================================================================================ 00024 MSG: std_msgs/Header 00025 # Standard metadata for higher-level stamped data types. 00026 # This is generally used to communicate timestamped data 00027 # in a particular coordinate frame. 00028 # 00029 # sequence ID: consecutively increasing ID 00030 uint32 seq 00031 #Two-integer timestamp that is expressed as: 00032 # * stamp.secs: seconds (stamp_secs) since epoch 00033 # * stamp.nsecs: nanoseconds since stamp_secs 00034 # time-handling sugar is provided by the client library 00035 time stamp 00036 #Frame this data is associated with 00037 # 0: no frame 00038 # 1: global frame 00039 string frame_id 00040 00041 ================================================================================ 00042 MSG: trajectory_msgs/JointTrajectoryPoint 00043 float64[] positions 00044 float64[] velocities 00045 float64[] accelerations 00046 duration time_from_start 00047 ================================================================================ 00048 MSG: arm_navigation_msgs/MultiDOFJointTrajectory 00049 #A representation of a multi-dof joint trajectory 00050 duration stamp 00051 string[] joint_names 00052 string[] frame_ids 00053 string[] child_frame_ids 00054 MultiDOFJointTrajectoryPoint[] points 00055 00056 ================================================================================ 00057 MSG: arm_navigation_msgs/MultiDOFJointTrajectoryPoint 00058 geometry_msgs/Pose[] poses 00059 duration time_from_start 00060 ================================================================================ 00061 MSG: geometry_msgs/Pose 00062 # A representation of pose in free space, composed of postion and orientation. 00063 Point position 00064 Quaternion orientation 00065 00066 ================================================================================ 00067 MSG: geometry_msgs/Point 00068 # This contains the position of a point in free space 00069 float64 x 00070 float64 y 00071 float64 z 00072 00073 ================================================================================ 00074 MSG: geometry_msgs/Quaternion 00075 # This represents an orientation in free space in quaternion form. 00076 00077 float64 x 00078 float64 y 00079 float64 z 00080 float64 w 00081 00082 """ 00083 __slots__ = ['joint_trajectory','multi_dof_joint_trajectory'] 00084 _slot_types = ['trajectory_msgs/JointTrajectory','arm_navigation_msgs/MultiDOFJointTrajectory'] 00085 00086 def __init__(self, *args, **kwds): 00087 """ 00088 Constructor. Any message fields that are implicitly/explicitly 00089 set to None will be assigned a default value. The recommend 00090 use is keyword arguments as this is more robust to future message 00091 changes. You cannot mix in-order arguments and keyword arguments. 00092 00093 The available fields are: 00094 joint_trajectory,multi_dof_joint_trajectory 00095 00096 @param args: complete set of field values, in .msg order 00097 @param kwds: use keyword arguments corresponding to message field names 00098 to set specific fields. 00099 """ 00100 if args or kwds: 00101 super(RobotTrajectory, self).__init__(*args, **kwds) 00102 #message fields cannot be None, assign default values for those that are 00103 if self.joint_trajectory is None: 00104 self.joint_trajectory = trajectory_msgs.msg.JointTrajectory() 00105 if self.multi_dof_joint_trajectory is None: 00106 self.multi_dof_joint_trajectory = arm_navigation_msgs.msg.MultiDOFJointTrajectory() 00107 else: 00108 self.joint_trajectory = trajectory_msgs.msg.JointTrajectory() 00109 self.multi_dof_joint_trajectory = arm_navigation_msgs.msg.MultiDOFJointTrajectory() 00110 00111 def _get_types(self): 00112 """ 00113 internal API method 00114 """ 00115 return self._slot_types 00116 00117 def serialize(self, buff): 00118 """ 00119 serialize message into buffer 00120 @param buff: buffer 00121 @type buff: StringIO 00122 """ 00123 try: 00124 _x = self 00125 buff.write(_struct_3I.pack(_x.joint_trajectory.header.seq, _x.joint_trajectory.header.stamp.secs, _x.joint_trajectory.header.stamp.nsecs)) 00126 _x = self.joint_trajectory.header.frame_id 00127 length = len(_x) 00128 buff.write(struct.pack('<I%ss'%length, length, _x)) 00129 length = len(self.joint_trajectory.joint_names) 00130 buff.write(_struct_I.pack(length)) 00131 for val1 in self.joint_trajectory.joint_names: 00132 length = len(val1) 00133 buff.write(struct.pack('<I%ss'%length, length, val1)) 00134 length = len(self.joint_trajectory.points) 00135 buff.write(_struct_I.pack(length)) 00136 for val1 in self.joint_trajectory.points: 00137 length = len(val1.positions) 00138 buff.write(_struct_I.pack(length)) 00139 pattern = '<%sd'%length 00140 buff.write(struct.pack(pattern, *val1.positions)) 00141 length = len(val1.velocities) 00142 buff.write(_struct_I.pack(length)) 00143 pattern = '<%sd'%length 00144 buff.write(struct.pack(pattern, *val1.velocities)) 00145 length = len(val1.accelerations) 00146 buff.write(_struct_I.pack(length)) 00147 pattern = '<%sd'%length 00148 buff.write(struct.pack(pattern, *val1.accelerations)) 00149 _v1 = val1.time_from_start 00150 _x = _v1 00151 buff.write(_struct_2i.pack(_x.secs, _x.nsecs)) 00152 _x = self 00153 buff.write(_struct_2i.pack(_x.multi_dof_joint_trajectory.stamp.secs, _x.multi_dof_joint_trajectory.stamp.nsecs)) 00154 length = len(self.multi_dof_joint_trajectory.joint_names) 00155 buff.write(_struct_I.pack(length)) 00156 for val1 in self.multi_dof_joint_trajectory.joint_names: 00157 length = len(val1) 00158 buff.write(struct.pack('<I%ss'%length, length, val1)) 00159 length = len(self.multi_dof_joint_trajectory.frame_ids) 00160 buff.write(_struct_I.pack(length)) 00161 for val1 in self.multi_dof_joint_trajectory.frame_ids: 00162 length = len(val1) 00163 buff.write(struct.pack('<I%ss'%length, length, val1)) 00164 length = len(self.multi_dof_joint_trajectory.child_frame_ids) 00165 buff.write(_struct_I.pack(length)) 00166 for val1 in self.multi_dof_joint_trajectory.child_frame_ids: 00167 length = len(val1) 00168 buff.write(struct.pack('<I%ss'%length, length, val1)) 00169 length = len(self.multi_dof_joint_trajectory.points) 00170 buff.write(_struct_I.pack(length)) 00171 for val1 in self.multi_dof_joint_trajectory.points: 00172 length = len(val1.poses) 00173 buff.write(_struct_I.pack(length)) 00174 for val2 in val1.poses: 00175 _v2 = val2.position 00176 _x = _v2 00177 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00178 _v3 = val2.orientation 00179 _x = _v3 00180 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00181 _v4 = val1.time_from_start 00182 _x = _v4 00183 buff.write(_struct_2i.pack(_x.secs, _x.nsecs)) 00184 except struct.error as se: self._check_types(se) 00185 except TypeError as te: self._check_types(te) 00186 00187 def deserialize(self, str): 00188 """ 00189 unpack serialized message in str into this message instance 00190 @param str: byte array of serialized message 00191 @type str: str 00192 """ 00193 try: 00194 if self.joint_trajectory is None: 00195 self.joint_trajectory = trajectory_msgs.msg.JointTrajectory() 00196 if self.multi_dof_joint_trajectory is None: 00197 self.multi_dof_joint_trajectory = arm_navigation_msgs.msg.MultiDOFJointTrajectory() 00198 end = 0 00199 _x = self 00200 start = end 00201 end += 12 00202 (_x.joint_trajectory.header.seq, _x.joint_trajectory.header.stamp.secs, _x.joint_trajectory.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00203 start = end 00204 end += 4 00205 (length,) = _struct_I.unpack(str[start:end]) 00206 start = end 00207 end += length 00208 self.joint_trajectory.header.frame_id = str[start:end] 00209 start = end 00210 end += 4 00211 (length,) = _struct_I.unpack(str[start:end]) 00212 self.joint_trajectory.joint_names = [] 00213 for i in range(0, length): 00214 start = end 00215 end += 4 00216 (length,) = _struct_I.unpack(str[start:end]) 00217 start = end 00218 end += length 00219 val1 = str[start:end] 00220 self.joint_trajectory.joint_names.append(val1) 00221 start = end 00222 end += 4 00223 (length,) = _struct_I.unpack(str[start:end]) 00224 self.joint_trajectory.points = [] 00225 for i in range(0, length): 00226 val1 = trajectory_msgs.msg.JointTrajectoryPoint() 00227 start = end 00228 end += 4 00229 (length,) = _struct_I.unpack(str[start:end]) 00230 pattern = '<%sd'%length 00231 start = end 00232 end += struct.calcsize(pattern) 00233 val1.positions = struct.unpack(pattern, str[start:end]) 00234 start = end 00235 end += 4 00236 (length,) = _struct_I.unpack(str[start:end]) 00237 pattern = '<%sd'%length 00238 start = end 00239 end += struct.calcsize(pattern) 00240 val1.velocities = struct.unpack(pattern, str[start:end]) 00241 start = end 00242 end += 4 00243 (length,) = _struct_I.unpack(str[start:end]) 00244 pattern = '<%sd'%length 00245 start = end 00246 end += struct.calcsize(pattern) 00247 val1.accelerations = struct.unpack(pattern, str[start:end]) 00248 _v5 = val1.time_from_start 00249 _x = _v5 00250 start = end 00251 end += 8 00252 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end]) 00253 self.joint_trajectory.points.append(val1) 00254 _x = self 00255 start = end 00256 end += 8 00257 (_x.multi_dof_joint_trajectory.stamp.secs, _x.multi_dof_joint_trajectory.stamp.nsecs,) = _struct_2i.unpack(str[start:end]) 00258 start = end 00259 end += 4 00260 (length,) = _struct_I.unpack(str[start:end]) 00261 self.multi_dof_joint_trajectory.joint_names = [] 00262 for i in range(0, length): 00263 start = end 00264 end += 4 00265 (length,) = _struct_I.unpack(str[start:end]) 00266 start = end 00267 end += length 00268 val1 = str[start:end] 00269 self.multi_dof_joint_trajectory.joint_names.append(val1) 00270 start = end 00271 end += 4 00272 (length,) = _struct_I.unpack(str[start:end]) 00273 self.multi_dof_joint_trajectory.frame_ids = [] 00274 for i in range(0, length): 00275 start = end 00276 end += 4 00277 (length,) = _struct_I.unpack(str[start:end]) 00278 start = end 00279 end += length 00280 val1 = str[start:end] 00281 self.multi_dof_joint_trajectory.frame_ids.append(val1) 00282 start = end 00283 end += 4 00284 (length,) = _struct_I.unpack(str[start:end]) 00285 self.multi_dof_joint_trajectory.child_frame_ids = [] 00286 for i in range(0, length): 00287 start = end 00288 end += 4 00289 (length,) = _struct_I.unpack(str[start:end]) 00290 start = end 00291 end += length 00292 val1 = str[start:end] 00293 self.multi_dof_joint_trajectory.child_frame_ids.append(val1) 00294 start = end 00295 end += 4 00296 (length,) = _struct_I.unpack(str[start:end]) 00297 self.multi_dof_joint_trajectory.points = [] 00298 for i in range(0, length): 00299 val1 = arm_navigation_msgs.msg.MultiDOFJointTrajectoryPoint() 00300 start = end 00301 end += 4 00302 (length,) = _struct_I.unpack(str[start:end]) 00303 val1.poses = [] 00304 for i in range(0, length): 00305 val2 = geometry_msgs.msg.Pose() 00306 _v6 = val2.position 00307 _x = _v6 00308 start = end 00309 end += 24 00310 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00311 _v7 = val2.orientation 00312 _x = _v7 00313 start = end 00314 end += 32 00315 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00316 val1.poses.append(val2) 00317 _v8 = val1.time_from_start 00318 _x = _v8 00319 start = end 00320 end += 8 00321 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end]) 00322 self.multi_dof_joint_trajectory.points.append(val1) 00323 return self 00324 except struct.error as e: 00325 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00326 00327 00328 def serialize_numpy(self, buff, numpy): 00329 """ 00330 serialize message with numpy array types into buffer 00331 @param buff: buffer 00332 @type buff: StringIO 00333 @param numpy: numpy python module 00334 @type numpy module 00335 """ 00336 try: 00337 _x = self 00338 buff.write(_struct_3I.pack(_x.joint_trajectory.header.seq, _x.joint_trajectory.header.stamp.secs, _x.joint_trajectory.header.stamp.nsecs)) 00339 _x = self.joint_trajectory.header.frame_id 00340 length = len(_x) 00341 buff.write(struct.pack('<I%ss'%length, length, _x)) 00342 length = len(self.joint_trajectory.joint_names) 00343 buff.write(_struct_I.pack(length)) 00344 for val1 in self.joint_trajectory.joint_names: 00345 length = len(val1) 00346 buff.write(struct.pack('<I%ss'%length, length, val1)) 00347 length = len(self.joint_trajectory.points) 00348 buff.write(_struct_I.pack(length)) 00349 for val1 in self.joint_trajectory.points: 00350 length = len(val1.positions) 00351 buff.write(_struct_I.pack(length)) 00352 pattern = '<%sd'%length 00353 buff.write(val1.positions.tostring()) 00354 length = len(val1.velocities) 00355 buff.write(_struct_I.pack(length)) 00356 pattern = '<%sd'%length 00357 buff.write(val1.velocities.tostring()) 00358 length = len(val1.accelerations) 00359 buff.write(_struct_I.pack(length)) 00360 pattern = '<%sd'%length 00361 buff.write(val1.accelerations.tostring()) 00362 _v9 = val1.time_from_start 00363 _x = _v9 00364 buff.write(_struct_2i.pack(_x.secs, _x.nsecs)) 00365 _x = self 00366 buff.write(_struct_2i.pack(_x.multi_dof_joint_trajectory.stamp.secs, _x.multi_dof_joint_trajectory.stamp.nsecs)) 00367 length = len(self.multi_dof_joint_trajectory.joint_names) 00368 buff.write(_struct_I.pack(length)) 00369 for val1 in self.multi_dof_joint_trajectory.joint_names: 00370 length = len(val1) 00371 buff.write(struct.pack('<I%ss'%length, length, val1)) 00372 length = len(self.multi_dof_joint_trajectory.frame_ids) 00373 buff.write(_struct_I.pack(length)) 00374 for val1 in self.multi_dof_joint_trajectory.frame_ids: 00375 length = len(val1) 00376 buff.write(struct.pack('<I%ss'%length, length, val1)) 00377 length = len(self.multi_dof_joint_trajectory.child_frame_ids) 00378 buff.write(_struct_I.pack(length)) 00379 for val1 in self.multi_dof_joint_trajectory.child_frame_ids: 00380 length = len(val1) 00381 buff.write(struct.pack('<I%ss'%length, length, val1)) 00382 length = len(self.multi_dof_joint_trajectory.points) 00383 buff.write(_struct_I.pack(length)) 00384 for val1 in self.multi_dof_joint_trajectory.points: 00385 length = len(val1.poses) 00386 buff.write(_struct_I.pack(length)) 00387 for val2 in val1.poses: 00388 _v10 = val2.position 00389 _x = _v10 00390 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00391 _v11 = val2.orientation 00392 _x = _v11 00393 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w)) 00394 _v12 = val1.time_from_start 00395 _x = _v12 00396 buff.write(_struct_2i.pack(_x.secs, _x.nsecs)) 00397 except struct.error as se: self._check_types(se) 00398 except TypeError as te: self._check_types(te) 00399 00400 def deserialize_numpy(self, str, numpy): 00401 """ 00402 unpack serialized message in str into this message instance using numpy for array types 00403 @param str: byte array of serialized message 00404 @type str: str 00405 @param numpy: numpy python module 00406 @type numpy: module 00407 """ 00408 try: 00409 if self.joint_trajectory is None: 00410 self.joint_trajectory = trajectory_msgs.msg.JointTrajectory() 00411 if self.multi_dof_joint_trajectory is None: 00412 self.multi_dof_joint_trajectory = arm_navigation_msgs.msg.MultiDOFJointTrajectory() 00413 end = 0 00414 _x = self 00415 start = end 00416 end += 12 00417 (_x.joint_trajectory.header.seq, _x.joint_trajectory.header.stamp.secs, _x.joint_trajectory.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00418 start = end 00419 end += 4 00420 (length,) = _struct_I.unpack(str[start:end]) 00421 start = end 00422 end += length 00423 self.joint_trajectory.header.frame_id = str[start:end] 00424 start = end 00425 end += 4 00426 (length,) = _struct_I.unpack(str[start:end]) 00427 self.joint_trajectory.joint_names = [] 00428 for i in range(0, length): 00429 start = end 00430 end += 4 00431 (length,) = _struct_I.unpack(str[start:end]) 00432 start = end 00433 end += length 00434 val1 = str[start:end] 00435 self.joint_trajectory.joint_names.append(val1) 00436 start = end 00437 end += 4 00438 (length,) = _struct_I.unpack(str[start:end]) 00439 self.joint_trajectory.points = [] 00440 for i in range(0, length): 00441 val1 = trajectory_msgs.msg.JointTrajectoryPoint() 00442 start = end 00443 end += 4 00444 (length,) = _struct_I.unpack(str[start:end]) 00445 pattern = '<%sd'%length 00446 start = end 00447 end += struct.calcsize(pattern) 00448 val1.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 00449 start = end 00450 end += 4 00451 (length,) = _struct_I.unpack(str[start:end]) 00452 pattern = '<%sd'%length 00453 start = end 00454 end += struct.calcsize(pattern) 00455 val1.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 00456 start = end 00457 end += 4 00458 (length,) = _struct_I.unpack(str[start:end]) 00459 pattern = '<%sd'%length 00460 start = end 00461 end += struct.calcsize(pattern) 00462 val1.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 00463 _v13 = val1.time_from_start 00464 _x = _v13 00465 start = end 00466 end += 8 00467 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end]) 00468 self.joint_trajectory.points.append(val1) 00469 _x = self 00470 start = end 00471 end += 8 00472 (_x.multi_dof_joint_trajectory.stamp.secs, _x.multi_dof_joint_trajectory.stamp.nsecs,) = _struct_2i.unpack(str[start:end]) 00473 start = end 00474 end += 4 00475 (length,) = _struct_I.unpack(str[start:end]) 00476 self.multi_dof_joint_trajectory.joint_names = [] 00477 for i in range(0, length): 00478 start = end 00479 end += 4 00480 (length,) = _struct_I.unpack(str[start:end]) 00481 start = end 00482 end += length 00483 val1 = str[start:end] 00484 self.multi_dof_joint_trajectory.joint_names.append(val1) 00485 start = end 00486 end += 4 00487 (length,) = _struct_I.unpack(str[start:end]) 00488 self.multi_dof_joint_trajectory.frame_ids = [] 00489 for i in range(0, length): 00490 start = end 00491 end += 4 00492 (length,) = _struct_I.unpack(str[start:end]) 00493 start = end 00494 end += length 00495 val1 = str[start:end] 00496 self.multi_dof_joint_trajectory.frame_ids.append(val1) 00497 start = end 00498 end += 4 00499 (length,) = _struct_I.unpack(str[start:end]) 00500 self.multi_dof_joint_trajectory.child_frame_ids = [] 00501 for i in range(0, length): 00502 start = end 00503 end += 4 00504 (length,) = _struct_I.unpack(str[start:end]) 00505 start = end 00506 end += length 00507 val1 = str[start:end] 00508 self.multi_dof_joint_trajectory.child_frame_ids.append(val1) 00509 start = end 00510 end += 4 00511 (length,) = _struct_I.unpack(str[start:end]) 00512 self.multi_dof_joint_trajectory.points = [] 00513 for i in range(0, length): 00514 val1 = arm_navigation_msgs.msg.MultiDOFJointTrajectoryPoint() 00515 start = end 00516 end += 4 00517 (length,) = _struct_I.unpack(str[start:end]) 00518 val1.poses = [] 00519 for i in range(0, length): 00520 val2 = geometry_msgs.msg.Pose() 00521 _v14 = val2.position 00522 _x = _v14 00523 start = end 00524 end += 24 00525 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00526 _v15 = val2.orientation 00527 _x = _v15 00528 start = end 00529 end += 32 00530 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end]) 00531 val1.poses.append(val2) 00532 _v16 = val1.time_from_start 00533 _x = _v16 00534 start = end 00535 end += 8 00536 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end]) 00537 self.multi_dof_joint_trajectory.points.append(val1) 00538 return self 00539 except struct.error as e: 00540 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00541 00542 _struct_I = roslib.message.struct_I 00543 _struct_4d = struct.Struct("<4d") 00544 _struct_3I = struct.Struct("<3I") 00545 _struct_2i = struct.Struct("<2i") 00546 _struct_3d = struct.Struct("<3d")