00001 """autogenerated by genpy from spline_smoother/SplineTrajectory.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 genpy
00008 import spline_smoother.msg
00009 import std_msgs.msg
00010
00011 class SplineTrajectory(genpy.Message):
00012 _md5sum = "45d783dc5c58ac7ae093c93ba1b8d451"
00013 _type = "spline_smoother/SplineTrajectory"
00014 _has_header = True
00015 _full_text = """Header header
00016 string[] names
00017 SplineTrajectorySegment[] segments
00018
00019 ================================================================================
00020 MSG: std_msgs/Header
00021 # Standard metadata for higher-level stamped data types.
00022 # This is generally used to communicate timestamped data
00023 # in a particular coordinate frame.
00024 #
00025 # sequence ID: consecutively increasing ID
00026 uint32 seq
00027 #Two-integer timestamp that is expressed as:
00028 # * stamp.secs: seconds (stamp_secs) since epoch
00029 # * stamp.nsecs: nanoseconds since stamp_secs
00030 # time-handling sugar is provided by the client library
00031 time stamp
00032 #Frame this data is associated with
00033 # 0: no frame
00034 # 1: global frame
00035 string frame_id
00036
00037 ================================================================================
00038 MSG: spline_smoother/SplineTrajectorySegment
00039 duration duration
00040 SplineCoefficients[] joints
00041
00042 ================================================================================
00043 MSG: spline_smoother/SplineCoefficients
00044 float64[] coefficients
00045
00046 """
00047 __slots__ = ['header','names','segments']
00048 _slot_types = ['std_msgs/Header','string[]','spline_smoother/SplineTrajectorySegment[]']
00049
00050 def __init__(self, *args, **kwds):
00051 """
00052 Constructor. Any message fields that are implicitly/explicitly
00053 set to None will be assigned a default value. The recommend
00054 use is keyword arguments as this is more robust to future message
00055 changes. You cannot mix in-order arguments and keyword arguments.
00056
00057 The available fields are:
00058 header,names,segments
00059
00060 :param args: complete set of field values, in .msg order
00061 :param kwds: use keyword arguments corresponding to message field names
00062 to set specific fields.
00063 """
00064 if args or kwds:
00065 super(SplineTrajectory, self).__init__(*args, **kwds)
00066
00067 if self.header is None:
00068 self.header = std_msgs.msg.Header()
00069 if self.names is None:
00070 self.names = []
00071 if self.segments is None:
00072 self.segments = []
00073 else:
00074 self.header = std_msgs.msg.Header()
00075 self.names = []
00076 self.segments = []
00077
00078 def _get_types(self):
00079 """
00080 internal API method
00081 """
00082 return self._slot_types
00083
00084 def serialize(self, buff):
00085 """
00086 serialize message into buffer
00087 :param buff: buffer, ``StringIO``
00088 """
00089 try:
00090 _x = self
00091 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00092 _x = self.header.frame_id
00093 length = len(_x)
00094 if python3 or type(_x) == unicode:
00095 _x = _x.encode('utf-8')
00096 length = len(_x)
00097 buff.write(struct.pack('<I%ss'%length, length, _x))
00098 length = len(self.names)
00099 buff.write(_struct_I.pack(length))
00100 for val1 in self.names:
00101 length = len(val1)
00102 if python3 or type(val1) == unicode:
00103 val1 = val1.encode('utf-8')
00104 length = len(val1)
00105 buff.write(struct.pack('<I%ss'%length, length, val1))
00106 length = len(self.segments)
00107 buff.write(_struct_I.pack(length))
00108 for val1 in self.segments:
00109 _v1 = val1.duration
00110 _x = _v1
00111 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00112 length = len(val1.joints)
00113 buff.write(_struct_I.pack(length))
00114 for val2 in val1.joints:
00115 length = len(val2.coefficients)
00116 buff.write(_struct_I.pack(length))
00117 pattern = '<%sd'%length
00118 buff.write(struct.pack(pattern, *val2.coefficients))
00119 except struct.error as se: self._check_types(se)
00120 except TypeError as te: self._check_types(te)
00121
00122 def deserialize(self, str):
00123 """
00124 unpack serialized message in str into this message instance
00125 :param str: byte array of serialized message, ``str``
00126 """
00127 try:
00128 if self.header is None:
00129 self.header = std_msgs.msg.Header()
00130 if self.segments is None:
00131 self.segments = None
00132 end = 0
00133 _x = self
00134 start = end
00135 end += 12
00136 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00137 start = end
00138 end += 4
00139 (length,) = _struct_I.unpack(str[start:end])
00140 start = end
00141 end += length
00142 if python3:
00143 self.header.frame_id = str[start:end].decode('utf-8')
00144 else:
00145 self.header.frame_id = str[start:end]
00146 start = end
00147 end += 4
00148 (length,) = _struct_I.unpack(str[start:end])
00149 self.names = []
00150 for i in range(0, length):
00151 start = end
00152 end += 4
00153 (length,) = _struct_I.unpack(str[start:end])
00154 start = end
00155 end += length
00156 if python3:
00157 val1 = str[start:end].decode('utf-8')
00158 else:
00159 val1 = str[start:end]
00160 self.names.append(val1)
00161 start = end
00162 end += 4
00163 (length,) = _struct_I.unpack(str[start:end])
00164 self.segments = []
00165 for i in range(0, length):
00166 val1 = spline_smoother.msg.SplineTrajectorySegment()
00167 _v2 = val1.duration
00168 _x = _v2
00169 start = end
00170 end += 8
00171 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00172 start = end
00173 end += 4
00174 (length,) = _struct_I.unpack(str[start:end])
00175 val1.joints = []
00176 for i in range(0, length):
00177 val2 = spline_smoother.msg.SplineCoefficients()
00178 start = end
00179 end += 4
00180 (length,) = _struct_I.unpack(str[start:end])
00181 pattern = '<%sd'%length
00182 start = end
00183 end += struct.calcsize(pattern)
00184 val2.coefficients = struct.unpack(pattern, str[start:end])
00185 val1.joints.append(val2)
00186 self.segments.append(val1)
00187 return self
00188 except struct.error as e:
00189 raise genpy.DeserializationError(e)
00190
00191
00192 def serialize_numpy(self, buff, numpy):
00193 """
00194 serialize message with numpy array types into buffer
00195 :param buff: buffer, ``StringIO``
00196 :param numpy: numpy python module
00197 """
00198 try:
00199 _x = self
00200 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00201 _x = self.header.frame_id
00202 length = len(_x)
00203 if python3 or type(_x) == unicode:
00204 _x = _x.encode('utf-8')
00205 length = len(_x)
00206 buff.write(struct.pack('<I%ss'%length, length, _x))
00207 length = len(self.names)
00208 buff.write(_struct_I.pack(length))
00209 for val1 in self.names:
00210 length = len(val1)
00211 if python3 or type(val1) == unicode:
00212 val1 = val1.encode('utf-8')
00213 length = len(val1)
00214 buff.write(struct.pack('<I%ss'%length, length, val1))
00215 length = len(self.segments)
00216 buff.write(_struct_I.pack(length))
00217 for val1 in self.segments:
00218 _v3 = val1.duration
00219 _x = _v3
00220 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00221 length = len(val1.joints)
00222 buff.write(_struct_I.pack(length))
00223 for val2 in val1.joints:
00224 length = len(val2.coefficients)
00225 buff.write(_struct_I.pack(length))
00226 pattern = '<%sd'%length
00227 buff.write(val2.coefficients.tostring())
00228 except struct.error as se: self._check_types(se)
00229 except TypeError as te: self._check_types(te)
00230
00231 def deserialize_numpy(self, str, numpy):
00232 """
00233 unpack serialized message in str into this message instance using numpy for array types
00234 :param str: byte array of serialized message, ``str``
00235 :param numpy: numpy python module
00236 """
00237 try:
00238 if self.header is None:
00239 self.header = std_msgs.msg.Header()
00240 if self.segments is None:
00241 self.segments = None
00242 end = 0
00243 _x = self
00244 start = end
00245 end += 12
00246 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00247 start = end
00248 end += 4
00249 (length,) = _struct_I.unpack(str[start:end])
00250 start = end
00251 end += length
00252 if python3:
00253 self.header.frame_id = str[start:end].decode('utf-8')
00254 else:
00255 self.header.frame_id = str[start:end]
00256 start = end
00257 end += 4
00258 (length,) = _struct_I.unpack(str[start:end])
00259 self.names = []
00260 for i in range(0, length):
00261 start = end
00262 end += 4
00263 (length,) = _struct_I.unpack(str[start:end])
00264 start = end
00265 end += length
00266 if python3:
00267 val1 = str[start:end].decode('utf-8')
00268 else:
00269 val1 = str[start:end]
00270 self.names.append(val1)
00271 start = end
00272 end += 4
00273 (length,) = _struct_I.unpack(str[start:end])
00274 self.segments = []
00275 for i in range(0, length):
00276 val1 = spline_smoother.msg.SplineTrajectorySegment()
00277 _v4 = val1.duration
00278 _x = _v4
00279 start = end
00280 end += 8
00281 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00282 start = end
00283 end += 4
00284 (length,) = _struct_I.unpack(str[start:end])
00285 val1.joints = []
00286 for i in range(0, length):
00287 val2 = spline_smoother.msg.SplineCoefficients()
00288 start = end
00289 end += 4
00290 (length,) = _struct_I.unpack(str[start:end])
00291 pattern = '<%sd'%length
00292 start = end
00293 end += struct.calcsize(pattern)
00294 val2.coefficients = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00295 val1.joints.append(val2)
00296 self.segments.append(val1)
00297 return self
00298 except struct.error as e:
00299 raise genpy.DeserializationError(e)
00300
00301 _struct_I = genpy.struct_I
00302 _struct_3I = struct.Struct("<3I")
00303 _struct_2i = struct.Struct("<2i")