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