$search
00001 """autogenerated by genmsg_py from JointTrajectoryWithLimits.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 roslib.rostime 00008 import std_msgs.msg 00009 00010 class JointTrajectoryWithLimits(roslib.message.Message): 00011 _md5sum = "e31e1ba1b3409bbb645c8dfcca5935cd" 00012 _type = "arm_navigation_msgs/JointTrajectoryWithLimits" 00013 _has_header = False #flag to mark the presence of a Header object 00014 _full_text = """# A trajectory message that encodes joint limits within it. 00015 trajectory_msgs/JointTrajectory trajectory 00016 00017 # A vector of JointLimit messages. 00018 # Each message contains the limits for a specific joint 00019 arm_navigation_msgs/JointLimits[] limits 00020 00021 ================================================================================ 00022 MSG: trajectory_msgs/JointTrajectory 00023 Header header 00024 string[] joint_names 00025 JointTrajectoryPoint[] points 00026 ================================================================================ 00027 MSG: std_msgs/Header 00028 # Standard metadata for higher-level stamped data types. 00029 # This is generally used to communicate timestamped data 00030 # in a particular coordinate frame. 00031 # 00032 # sequence ID: consecutively increasing ID 00033 uint32 seq 00034 #Two-integer timestamp that is expressed as: 00035 # * stamp.secs: seconds (stamp_secs) since epoch 00036 # * stamp.nsecs: nanoseconds since stamp_secs 00037 # time-handling sugar is provided by the client library 00038 time stamp 00039 #Frame this data is associated with 00040 # 0: no frame 00041 # 1: global frame 00042 string frame_id 00043 00044 ================================================================================ 00045 MSG: trajectory_msgs/JointTrajectoryPoint 00046 float64[] positions 00047 float64[] velocities 00048 float64[] accelerations 00049 duration time_from_start 00050 ================================================================================ 00051 MSG: arm_navigation_msgs/JointLimits 00052 # This message contains information about limits of a particular joint (or control dimension) 00053 string joint_name 00054 00055 # true if the joint has position limits 00056 bool has_position_limits 00057 00058 # min and max position limits 00059 float64 min_position 00060 float64 max_position 00061 00062 # true if joint has velocity limits 00063 bool has_velocity_limits 00064 00065 # max velocity limit 00066 float64 max_velocity 00067 # min_velocity is assumed to be -max_velocity 00068 00069 # true if joint has acceleration limits 00070 bool has_acceleration_limits 00071 # max acceleration limit 00072 float64 max_acceleration 00073 # min_acceleration is assumed to be -max_acceleration 00074 00075 """ 00076 __slots__ = ['trajectory','limits'] 00077 _slot_types = ['trajectory_msgs/JointTrajectory','arm_navigation_msgs/JointLimits[]'] 00078 00079 def __init__(self, *args, **kwds): 00080 """ 00081 Constructor. Any message fields that are implicitly/explicitly 00082 set to None will be assigned a default value. The recommend 00083 use is keyword arguments as this is more robust to future message 00084 changes. You cannot mix in-order arguments and keyword arguments. 00085 00086 The available fields are: 00087 trajectory,limits 00088 00089 @param args: complete set of field values, in .msg order 00090 @param kwds: use keyword arguments corresponding to message field names 00091 to set specific fields. 00092 """ 00093 if args or kwds: 00094 super(JointTrajectoryWithLimits, self).__init__(*args, **kwds) 00095 #message fields cannot be None, assign default values for those that are 00096 if self.trajectory is None: 00097 self.trajectory = trajectory_msgs.msg.JointTrajectory() 00098 if self.limits is None: 00099 self.limits = [] 00100 else: 00101 self.trajectory = trajectory_msgs.msg.JointTrajectory() 00102 self.limits = [] 00103 00104 def _get_types(self): 00105 """ 00106 internal API method 00107 """ 00108 return self._slot_types 00109 00110 def serialize(self, buff): 00111 """ 00112 serialize message into buffer 00113 @param buff: buffer 00114 @type buff: StringIO 00115 """ 00116 try: 00117 _x = self 00118 buff.write(_struct_3I.pack(_x.trajectory.header.seq, _x.trajectory.header.stamp.secs, _x.trajectory.header.stamp.nsecs)) 00119 _x = self.trajectory.header.frame_id 00120 length = len(_x) 00121 buff.write(struct.pack('<I%ss'%length, length, _x)) 00122 length = len(self.trajectory.joint_names) 00123 buff.write(_struct_I.pack(length)) 00124 for val1 in self.trajectory.joint_names: 00125 length = len(val1) 00126 buff.write(struct.pack('<I%ss'%length, length, val1)) 00127 length = len(self.trajectory.points) 00128 buff.write(_struct_I.pack(length)) 00129 for val1 in self.trajectory.points: 00130 length = len(val1.positions) 00131 buff.write(_struct_I.pack(length)) 00132 pattern = '<%sd'%length 00133 buff.write(struct.pack(pattern, *val1.positions)) 00134 length = len(val1.velocities) 00135 buff.write(_struct_I.pack(length)) 00136 pattern = '<%sd'%length 00137 buff.write(struct.pack(pattern, *val1.velocities)) 00138 length = len(val1.accelerations) 00139 buff.write(_struct_I.pack(length)) 00140 pattern = '<%sd'%length 00141 buff.write(struct.pack(pattern, *val1.accelerations)) 00142 _v1 = val1.time_from_start 00143 _x = _v1 00144 buff.write(_struct_2i.pack(_x.secs, _x.nsecs)) 00145 length = len(self.limits) 00146 buff.write(_struct_I.pack(length)) 00147 for val1 in self.limits: 00148 _x = val1.joint_name 00149 length = len(_x) 00150 buff.write(struct.pack('<I%ss'%length, length, _x)) 00151 _x = val1 00152 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)) 00153 except struct.error as se: self._check_types(se) 00154 except TypeError as te: self._check_types(te) 00155 00156 def deserialize(self, str): 00157 """ 00158 unpack serialized message in str into this message instance 00159 @param str: byte array of serialized message 00160 @type str: str 00161 """ 00162 try: 00163 if self.trajectory is None: 00164 self.trajectory = trajectory_msgs.msg.JointTrajectory() 00165 end = 0 00166 _x = self 00167 start = end 00168 end += 12 00169 (_x.trajectory.header.seq, _x.trajectory.header.stamp.secs, _x.trajectory.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00170 start = end 00171 end += 4 00172 (length,) = _struct_I.unpack(str[start:end]) 00173 start = end 00174 end += length 00175 self.trajectory.header.frame_id = str[start:end] 00176 start = end 00177 end += 4 00178 (length,) = _struct_I.unpack(str[start:end]) 00179 self.trajectory.joint_names = [] 00180 for i in range(0, length): 00181 start = end 00182 end += 4 00183 (length,) = _struct_I.unpack(str[start:end]) 00184 start = end 00185 end += length 00186 val1 = str[start:end] 00187 self.trajectory.joint_names.append(val1) 00188 start = end 00189 end += 4 00190 (length,) = _struct_I.unpack(str[start:end]) 00191 self.trajectory.points = [] 00192 for i in range(0, length): 00193 val1 = trajectory_msgs.msg.JointTrajectoryPoint() 00194 start = end 00195 end += 4 00196 (length,) = _struct_I.unpack(str[start:end]) 00197 pattern = '<%sd'%length 00198 start = end 00199 end += struct.calcsize(pattern) 00200 val1.positions = struct.unpack(pattern, str[start:end]) 00201 start = end 00202 end += 4 00203 (length,) = _struct_I.unpack(str[start:end]) 00204 pattern = '<%sd'%length 00205 start = end 00206 end += struct.calcsize(pattern) 00207 val1.velocities = struct.unpack(pattern, str[start:end]) 00208 start = end 00209 end += 4 00210 (length,) = _struct_I.unpack(str[start:end]) 00211 pattern = '<%sd'%length 00212 start = end 00213 end += struct.calcsize(pattern) 00214 val1.accelerations = struct.unpack(pattern, str[start:end]) 00215 _v2 = val1.time_from_start 00216 _x = _v2 00217 start = end 00218 end += 8 00219 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end]) 00220 self.trajectory.points.append(val1) 00221 start = end 00222 end += 4 00223 (length,) = _struct_I.unpack(str[start:end]) 00224 self.limits = [] 00225 for i in range(0, length): 00226 val1 = arm_navigation_msgs.msg.JointLimits() 00227 start = end 00228 end += 4 00229 (length,) = _struct_I.unpack(str[start:end]) 00230 start = end 00231 end += length 00232 val1.joint_name = str[start:end] 00233 _x = val1 00234 start = end 00235 end += 35 00236 (_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]) 00237 val1.has_position_limits = bool(val1.has_position_limits) 00238 val1.has_velocity_limits = bool(val1.has_velocity_limits) 00239 val1.has_acceleration_limits = bool(val1.has_acceleration_limits) 00240 self.limits.append(val1) 00241 return self 00242 except struct.error as e: 00243 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00244 00245 00246 def serialize_numpy(self, buff, numpy): 00247 """ 00248 serialize message with numpy array types into buffer 00249 @param buff: buffer 00250 @type buff: StringIO 00251 @param numpy: numpy python module 00252 @type numpy module 00253 """ 00254 try: 00255 _x = self 00256 buff.write(_struct_3I.pack(_x.trajectory.header.seq, _x.trajectory.header.stamp.secs, _x.trajectory.header.stamp.nsecs)) 00257 _x = self.trajectory.header.frame_id 00258 length = len(_x) 00259 buff.write(struct.pack('<I%ss'%length, length, _x)) 00260 length = len(self.trajectory.joint_names) 00261 buff.write(_struct_I.pack(length)) 00262 for val1 in self.trajectory.joint_names: 00263 length = len(val1) 00264 buff.write(struct.pack('<I%ss'%length, length, val1)) 00265 length = len(self.trajectory.points) 00266 buff.write(_struct_I.pack(length)) 00267 for val1 in self.trajectory.points: 00268 length = len(val1.positions) 00269 buff.write(_struct_I.pack(length)) 00270 pattern = '<%sd'%length 00271 buff.write(val1.positions.tostring()) 00272 length = len(val1.velocities) 00273 buff.write(_struct_I.pack(length)) 00274 pattern = '<%sd'%length 00275 buff.write(val1.velocities.tostring()) 00276 length = len(val1.accelerations) 00277 buff.write(_struct_I.pack(length)) 00278 pattern = '<%sd'%length 00279 buff.write(val1.accelerations.tostring()) 00280 _v3 = val1.time_from_start 00281 _x = _v3 00282 buff.write(_struct_2i.pack(_x.secs, _x.nsecs)) 00283 length = len(self.limits) 00284 buff.write(_struct_I.pack(length)) 00285 for val1 in self.limits: 00286 _x = val1.joint_name 00287 length = len(_x) 00288 buff.write(struct.pack('<I%ss'%length, length, _x)) 00289 _x = val1 00290 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)) 00291 except struct.error as se: self._check_types(se) 00292 except TypeError as te: self._check_types(te) 00293 00294 def deserialize_numpy(self, str, numpy): 00295 """ 00296 unpack serialized message in str into this message instance using numpy for array types 00297 @param str: byte array of serialized message 00298 @type str: str 00299 @param numpy: numpy python module 00300 @type numpy: module 00301 """ 00302 try: 00303 if self.trajectory is None: 00304 self.trajectory = trajectory_msgs.msg.JointTrajectory() 00305 end = 0 00306 _x = self 00307 start = end 00308 end += 12 00309 (_x.trajectory.header.seq, _x.trajectory.header.stamp.secs, _x.trajectory.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00310 start = end 00311 end += 4 00312 (length,) = _struct_I.unpack(str[start:end]) 00313 start = end 00314 end += length 00315 self.trajectory.header.frame_id = str[start:end] 00316 start = end 00317 end += 4 00318 (length,) = _struct_I.unpack(str[start:end]) 00319 self.trajectory.joint_names = [] 00320 for i in range(0, length): 00321 start = end 00322 end += 4 00323 (length,) = _struct_I.unpack(str[start:end]) 00324 start = end 00325 end += length 00326 val1 = str[start:end] 00327 self.trajectory.joint_names.append(val1) 00328 start = end 00329 end += 4 00330 (length,) = _struct_I.unpack(str[start:end]) 00331 self.trajectory.points = [] 00332 for i in range(0, length): 00333 val1 = trajectory_msgs.msg.JointTrajectoryPoint() 00334 start = end 00335 end += 4 00336 (length,) = _struct_I.unpack(str[start:end]) 00337 pattern = '<%sd'%length 00338 start = end 00339 end += struct.calcsize(pattern) 00340 val1.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 00341 start = end 00342 end += 4 00343 (length,) = _struct_I.unpack(str[start:end]) 00344 pattern = '<%sd'%length 00345 start = end 00346 end += struct.calcsize(pattern) 00347 val1.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 00348 start = end 00349 end += 4 00350 (length,) = _struct_I.unpack(str[start:end]) 00351 pattern = '<%sd'%length 00352 start = end 00353 end += struct.calcsize(pattern) 00354 val1.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 00355 _v4 = val1.time_from_start 00356 _x = _v4 00357 start = end 00358 end += 8 00359 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end]) 00360 self.trajectory.points.append(val1) 00361 start = end 00362 end += 4 00363 (length,) = _struct_I.unpack(str[start:end]) 00364 self.limits = [] 00365 for i in range(0, length): 00366 val1 = arm_navigation_msgs.msg.JointLimits() 00367 start = end 00368 end += 4 00369 (length,) = _struct_I.unpack(str[start:end]) 00370 start = end 00371 end += length 00372 val1.joint_name = str[start:end] 00373 _x = val1 00374 start = end 00375 end += 35 00376 (_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]) 00377 val1.has_position_limits = bool(val1.has_position_limits) 00378 val1.has_velocity_limits = bool(val1.has_velocity_limits) 00379 val1.has_acceleration_limits = bool(val1.has_acceleration_limits) 00380 self.limits.append(val1) 00381 return self 00382 except struct.error as e: 00383 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00384 00385 _struct_I = roslib.message.struct_I 00386 _struct_3I = struct.Struct("<3I") 00387 _struct_2i = struct.Struct("<2i") 00388 _struct_B2dBdBd = struct.Struct("<B2dBdBd")