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