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