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