00001 """autogenerated by genpy from nasa_r2_common_msgs/PoseTrajectoryPoint.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 geometry_msgs.msg
00008 import genpy
00009
00010 class PoseTrajectoryPoint(genpy.Message):
00011 _md5sum = "29009f42fa3cbc3a6154994f31b2db03"
00012 _type = "nasa_r2_common_msgs/PoseTrajectoryPoint"
00013 _has_header = False
00014 _full_text = """# currently, position only but could add velocity and acceleration later
00015 geometry_msgs/Pose[] positions
00016 geometry_msgs/Twist[] velocities
00017 geometry_msgs/Twist[] accelerations
00018 duration time_from_start
00019
00020 ================================================================================
00021 MSG: geometry_msgs/Pose
00022 # A representation of pose in free space, composed of postion and orientation.
00023 Point position
00024 Quaternion orientation
00025
00026 ================================================================================
00027 MSG: geometry_msgs/Point
00028 # This contains the position of a point in free space
00029 float64 x
00030 float64 y
00031 float64 z
00032
00033 ================================================================================
00034 MSG: geometry_msgs/Quaternion
00035 # This represents an orientation in free space in quaternion form.
00036
00037 float64 x
00038 float64 y
00039 float64 z
00040 float64 w
00041
00042 ================================================================================
00043 MSG: geometry_msgs/Twist
00044 # This expresses velocity in free space broken into its linear and angular parts.
00045 Vector3 linear
00046 Vector3 angular
00047
00048 ================================================================================
00049 MSG: geometry_msgs/Vector3
00050 # This represents a vector in free space.
00051
00052 float64 x
00053 float64 y
00054 float64 z
00055 """
00056 __slots__ = ['positions','velocities','accelerations','time_from_start']
00057 _slot_types = ['geometry_msgs/Pose[]','geometry_msgs/Twist[]','geometry_msgs/Twist[]','duration']
00058
00059 def __init__(self, *args, **kwds):
00060 """
00061 Constructor. Any message fields that are implicitly/explicitly
00062 set to None will be assigned a default value. The recommend
00063 use is keyword arguments as this is more robust to future message
00064 changes. You cannot mix in-order arguments and keyword arguments.
00065
00066 The available fields are:
00067 positions,velocities,accelerations,time_from_start
00068
00069 :param args: complete set of field values, in .msg order
00070 :param kwds: use keyword arguments corresponding to message field names
00071 to set specific fields.
00072 """
00073 if args or kwds:
00074 super(PoseTrajectoryPoint, self).__init__(*args, **kwds)
00075
00076 if self.positions is None:
00077 self.positions = []
00078 if self.velocities is None:
00079 self.velocities = []
00080 if self.accelerations is None:
00081 self.accelerations = []
00082 if self.time_from_start is None:
00083 self.time_from_start = genpy.Duration()
00084 else:
00085 self.positions = []
00086 self.velocities = []
00087 self.accelerations = []
00088 self.time_from_start = genpy.Duration()
00089
00090 def _get_types(self):
00091 """
00092 internal API method
00093 """
00094 return self._slot_types
00095
00096 def serialize(self, buff):
00097 """
00098 serialize message into buffer
00099 :param buff: buffer, ``StringIO``
00100 """
00101 try:
00102 length = len(self.positions)
00103 buff.write(_struct_I.pack(length))
00104 for val1 in self.positions:
00105 _v1 = val1.position
00106 _x = _v1
00107 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00108 _v2 = val1.orientation
00109 _x = _v2
00110 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00111 length = len(self.velocities)
00112 buff.write(_struct_I.pack(length))
00113 for val1 in self.velocities:
00114 _v3 = val1.linear
00115 _x = _v3
00116 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00117 _v4 = val1.angular
00118 _x = _v4
00119 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00120 length = len(self.accelerations)
00121 buff.write(_struct_I.pack(length))
00122 for val1 in self.accelerations:
00123 _v5 = val1.linear
00124 _x = _v5
00125 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00126 _v6 = val1.angular
00127 _x = _v6
00128 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00129 _x = self
00130 buff.write(_struct_2i.pack(_x.time_from_start.secs, _x.time_from_start.nsecs))
00131 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00132 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00133
00134 def deserialize(self, str):
00135 """
00136 unpack serialized message in str into this message instance
00137 :param str: byte array of serialized message, ``str``
00138 """
00139 try:
00140 if self.positions is None:
00141 self.positions = None
00142 if self.velocities is None:
00143 self.velocities = None
00144 if self.accelerations is None:
00145 self.accelerations = None
00146 if self.time_from_start is None:
00147 self.time_from_start = genpy.Duration()
00148 end = 0
00149 start = end
00150 end += 4
00151 (length,) = _struct_I.unpack(str[start:end])
00152 self.positions = []
00153 for i in range(0, length):
00154 val1 = geometry_msgs.msg.Pose()
00155 _v7 = val1.position
00156 _x = _v7
00157 start = end
00158 end += 24
00159 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00160 _v8 = val1.orientation
00161 _x = _v8
00162 start = end
00163 end += 32
00164 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00165 self.positions.append(val1)
00166 start = end
00167 end += 4
00168 (length,) = _struct_I.unpack(str[start:end])
00169 self.velocities = []
00170 for i in range(0, length):
00171 val1 = geometry_msgs.msg.Twist()
00172 _v9 = val1.linear
00173 _x = _v9
00174 start = end
00175 end += 24
00176 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00177 _v10 = val1.angular
00178 _x = _v10
00179 start = end
00180 end += 24
00181 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00182 self.velocities.append(val1)
00183 start = end
00184 end += 4
00185 (length,) = _struct_I.unpack(str[start:end])
00186 self.accelerations = []
00187 for i in range(0, length):
00188 val1 = geometry_msgs.msg.Twist()
00189 _v11 = val1.linear
00190 _x = _v11
00191 start = end
00192 end += 24
00193 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00194 _v12 = val1.angular
00195 _x = _v12
00196 start = end
00197 end += 24
00198 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00199 self.accelerations.append(val1)
00200 _x = self
00201 start = end
00202 end += 8
00203 (_x.time_from_start.secs, _x.time_from_start.nsecs,) = _struct_2i.unpack(str[start:end])
00204 self.time_from_start.canon()
00205 return self
00206 except struct.error as e:
00207 raise genpy.DeserializationError(e)
00208
00209
00210 def serialize_numpy(self, buff, numpy):
00211 """
00212 serialize message with numpy array types into buffer
00213 :param buff: buffer, ``StringIO``
00214 :param numpy: numpy python module
00215 """
00216 try:
00217 length = len(self.positions)
00218 buff.write(_struct_I.pack(length))
00219 for val1 in self.positions:
00220 _v13 = val1.position
00221 _x = _v13
00222 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00223 _v14 = val1.orientation
00224 _x = _v14
00225 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00226 length = len(self.velocities)
00227 buff.write(_struct_I.pack(length))
00228 for val1 in self.velocities:
00229 _v15 = val1.linear
00230 _x = _v15
00231 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00232 _v16 = val1.angular
00233 _x = _v16
00234 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00235 length = len(self.accelerations)
00236 buff.write(_struct_I.pack(length))
00237 for val1 in self.accelerations:
00238 _v17 = val1.linear
00239 _x = _v17
00240 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00241 _v18 = val1.angular
00242 _x = _v18
00243 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00244 _x = self
00245 buff.write(_struct_2i.pack(_x.time_from_start.secs, _x.time_from_start.nsecs))
00246 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00247 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00248
00249 def deserialize_numpy(self, str, numpy):
00250 """
00251 unpack serialized message in str into this message instance using numpy for array types
00252 :param str: byte array of serialized message, ``str``
00253 :param numpy: numpy python module
00254 """
00255 try:
00256 if self.positions is None:
00257 self.positions = None
00258 if self.velocities is None:
00259 self.velocities = None
00260 if self.accelerations is None:
00261 self.accelerations = None
00262 if self.time_from_start is None:
00263 self.time_from_start = genpy.Duration()
00264 end = 0
00265 start = end
00266 end += 4
00267 (length,) = _struct_I.unpack(str[start:end])
00268 self.positions = []
00269 for i in range(0, length):
00270 val1 = geometry_msgs.msg.Pose()
00271 _v19 = val1.position
00272 _x = _v19
00273 start = end
00274 end += 24
00275 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00276 _v20 = val1.orientation
00277 _x = _v20
00278 start = end
00279 end += 32
00280 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00281 self.positions.append(val1)
00282 start = end
00283 end += 4
00284 (length,) = _struct_I.unpack(str[start:end])
00285 self.velocities = []
00286 for i in range(0, length):
00287 val1 = geometry_msgs.msg.Twist()
00288 _v21 = val1.linear
00289 _x = _v21
00290 start = end
00291 end += 24
00292 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00293 _v22 = val1.angular
00294 _x = _v22
00295 start = end
00296 end += 24
00297 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00298 self.velocities.append(val1)
00299 start = end
00300 end += 4
00301 (length,) = _struct_I.unpack(str[start:end])
00302 self.accelerations = []
00303 for i in range(0, length):
00304 val1 = geometry_msgs.msg.Twist()
00305 _v23 = val1.linear
00306 _x = _v23
00307 start = end
00308 end += 24
00309 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00310 _v24 = val1.angular
00311 _x = _v24
00312 start = end
00313 end += 24
00314 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00315 self.accelerations.append(val1)
00316 _x = self
00317 start = end
00318 end += 8
00319 (_x.time_from_start.secs, _x.time_from_start.nsecs,) = _struct_2i.unpack(str[start:end])
00320 self.time_from_start.canon()
00321 return self
00322 except struct.error as e:
00323 raise genpy.DeserializationError(e)
00324
00325 _struct_I = genpy.struct_I
00326 _struct_4d = struct.Struct("<4d")
00327 _struct_2i = struct.Struct("<2i")
00328 _struct_3d = struct.Struct("<3d")