00001 """autogenerated by genpy from head_monitor_msgs/HeadMonitorActionResult.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 arm_navigation_msgs.msg
00009 import actionlib_msgs.msg
00010 import head_monitor_msgs.msg
00011 import genpy
00012 import std_msgs.msg
00013
00014 class HeadMonitorActionResult(genpy.Message):
00015 _md5sum = "b1828954738da404141673c3faf9db0d"
00016 _type = "head_monitor_msgs/HeadMonitorActionResult"
00017 _has_header = True
00018 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00019
00020 Header header
00021 actionlib_msgs/GoalStatus status
00022 HeadMonitorResult result
00023
00024 ================================================================================
00025 MSG: std_msgs/Header
00026 # Standard metadata for higher-level stamped data types.
00027 # This is generally used to communicate timestamped data
00028 # in a particular coordinate frame.
00029 #
00030 # sequence ID: consecutively increasing ID
00031 uint32 seq
00032 #Two-integer timestamp that is expressed as:
00033 # * stamp.secs: seconds (stamp_secs) since epoch
00034 # * stamp.nsecs: nanoseconds since stamp_secs
00035 # time-handling sugar is provided by the client library
00036 time stamp
00037 #Frame this data is associated with
00038 # 0: no frame
00039 # 1: global frame
00040 string frame_id
00041
00042 ================================================================================
00043 MSG: actionlib_msgs/GoalStatus
00044 GoalID goal_id
00045 uint8 status
00046 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00047 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00048 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00049 # and has since completed its execution (Terminal State)
00050 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00051 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00052 # to some failure (Terminal State)
00053 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00054 # because the goal was unattainable or invalid (Terminal State)
00055 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00056 # and has not yet completed execution
00057 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00058 # but the action server has not yet confirmed that the goal is canceled
00059 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00060 # and was successfully cancelled (Terminal State)
00061 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00062 # sent over the wire by an action server
00063
00064 #Allow for the user to associate a string with GoalStatus for debugging
00065 string text
00066
00067
00068 ================================================================================
00069 MSG: actionlib_msgs/GoalID
00070 # The stamp should store the time at which this goal was requested.
00071 # It is used by an action server when it tries to preempt all
00072 # goals that were requested before a certain time
00073 time stamp
00074
00075 # The id provides a way to associate feedback and
00076 # result message with specific goal requests. The id
00077 # specified must be unique.
00078 string id
00079
00080
00081 ================================================================================
00082 MSG: head_monitor_msgs/HeadMonitorResult
00083 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00084 trajectory_msgs/JointTrajectory actual_trajectory
00085 arm_navigation_msgs/ArmNavigationErrorCodes error_code
00086
00087 ================================================================================
00088 MSG: trajectory_msgs/JointTrajectory
00089 Header header
00090 string[] joint_names
00091 JointTrajectoryPoint[] points
00092 ================================================================================
00093 MSG: trajectory_msgs/JointTrajectoryPoint
00094 float64[] positions
00095 float64[] velocities
00096 float64[] accelerations
00097 duration time_from_start
00098 ================================================================================
00099 MSG: arm_navigation_msgs/ArmNavigationErrorCodes
00100 int32 val
00101
00102 # overall behavior
00103 int32 PLANNING_FAILED=-1
00104 int32 SUCCESS=1
00105 int32 TIMED_OUT=-2
00106
00107 # start state errors
00108 int32 START_STATE_IN_COLLISION=-3
00109 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4
00110
00111 # goal errors
00112 int32 GOAL_IN_COLLISION=-5
00113 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6
00114
00115 # robot state
00116 int32 INVALID_ROBOT_STATE=-7
00117 int32 INCOMPLETE_ROBOT_STATE=-8
00118
00119 # planning request errors
00120 int32 INVALID_PLANNER_ID=-9
00121 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10
00122 int32 INVALID_ALLOWED_PLANNING_TIME=-11
00123 int32 INVALID_GROUP_NAME=-12
00124 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13
00125 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14
00126 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15
00127 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16
00128 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17
00129 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18
00130
00131 # state/trajectory monitor errors
00132 int32 INVALID_TRAJECTORY=-19
00133 int32 INVALID_INDEX=-20
00134 int32 JOINT_LIMITS_VIOLATED=-21
00135 int32 PATH_CONSTRAINTS_VIOLATED=-22
00136 int32 COLLISION_CONSTRAINTS_VIOLATED=-23
00137 int32 GOAL_CONSTRAINTS_VIOLATED=-24
00138 int32 JOINTS_NOT_MOVING=-25
00139 int32 TRAJECTORY_CONTROLLER_FAILED=-26
00140
00141 # system errors
00142 int32 FRAME_TRANSFORM_FAILURE=-27
00143 int32 COLLISION_CHECKING_UNAVAILABLE=-28
00144 int32 ROBOT_STATE_STALE=-29
00145 int32 SENSOR_INFO_STALE=-30
00146
00147 # kinematics errors
00148 int32 NO_IK_SOLUTION=-31
00149 int32 INVALID_LINK_NAME=-32
00150 int32 IK_LINK_IN_COLLISION=-33
00151 int32 NO_FK_SOLUTION=-34
00152 int32 KINEMATICS_STATE_IN_COLLISION=-35
00153
00154 # general errors
00155 int32 INVALID_TIMEOUT=-36
00156
00157
00158 """
00159 __slots__ = ['header','status','result']
00160 _slot_types = ['std_msgs/Header','actionlib_msgs/GoalStatus','head_monitor_msgs/HeadMonitorResult']
00161
00162 def __init__(self, *args, **kwds):
00163 """
00164 Constructor. Any message fields that are implicitly/explicitly
00165 set to None will be assigned a default value. The recommend
00166 use is keyword arguments as this is more robust to future message
00167 changes. You cannot mix in-order arguments and keyword arguments.
00168
00169 The available fields are:
00170 header,status,result
00171
00172 :param args: complete set of field values, in .msg order
00173 :param kwds: use keyword arguments corresponding to message field names
00174 to set specific fields.
00175 """
00176 if args or kwds:
00177 super(HeadMonitorActionResult, self).__init__(*args, **kwds)
00178
00179 if self.header is None:
00180 self.header = std_msgs.msg.Header()
00181 if self.status is None:
00182 self.status = actionlib_msgs.msg.GoalStatus()
00183 if self.result is None:
00184 self.result = head_monitor_msgs.msg.HeadMonitorResult()
00185 else:
00186 self.header = std_msgs.msg.Header()
00187 self.status = actionlib_msgs.msg.GoalStatus()
00188 self.result = head_monitor_msgs.msg.HeadMonitorResult()
00189
00190 def _get_types(self):
00191 """
00192 internal API method
00193 """
00194 return self._slot_types
00195
00196 def serialize(self, buff):
00197 """
00198 serialize message into buffer
00199 :param buff: buffer, ``StringIO``
00200 """
00201 try:
00202 _x = self
00203 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00204 _x = self.header.frame_id
00205 length = len(_x)
00206 if python3 or type(_x) == unicode:
00207 _x = _x.encode('utf-8')
00208 length = len(_x)
00209 buff.write(struct.pack('<I%ss'%length, length, _x))
00210 _x = self
00211 buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs))
00212 _x = self.status.goal_id.id
00213 length = len(_x)
00214 if python3 or type(_x) == unicode:
00215 _x = _x.encode('utf-8')
00216 length = len(_x)
00217 buff.write(struct.pack('<I%ss'%length, length, _x))
00218 buff.write(_struct_B.pack(self.status.status))
00219 _x = self.status.text
00220 length = len(_x)
00221 if python3 or type(_x) == unicode:
00222 _x = _x.encode('utf-8')
00223 length = len(_x)
00224 buff.write(struct.pack('<I%ss'%length, length, _x))
00225 _x = self
00226 buff.write(_struct_3I.pack(_x.result.actual_trajectory.header.seq, _x.result.actual_trajectory.header.stamp.secs, _x.result.actual_trajectory.header.stamp.nsecs))
00227 _x = self.result.actual_trajectory.header.frame_id
00228 length = len(_x)
00229 if python3 or type(_x) == unicode:
00230 _x = _x.encode('utf-8')
00231 length = len(_x)
00232 buff.write(struct.pack('<I%ss'%length, length, _x))
00233 length = len(self.result.actual_trajectory.joint_names)
00234 buff.write(_struct_I.pack(length))
00235 for val1 in self.result.actual_trajectory.joint_names:
00236 length = len(val1)
00237 if python3 or type(val1) == unicode:
00238 val1 = val1.encode('utf-8')
00239 length = len(val1)
00240 buff.write(struct.pack('<I%ss'%length, length, val1))
00241 length = len(self.result.actual_trajectory.points)
00242 buff.write(_struct_I.pack(length))
00243 for val1 in self.result.actual_trajectory.points:
00244 length = len(val1.positions)
00245 buff.write(_struct_I.pack(length))
00246 pattern = '<%sd'%length
00247 buff.write(struct.pack(pattern, *val1.positions))
00248 length = len(val1.velocities)
00249 buff.write(_struct_I.pack(length))
00250 pattern = '<%sd'%length
00251 buff.write(struct.pack(pattern, *val1.velocities))
00252 length = len(val1.accelerations)
00253 buff.write(_struct_I.pack(length))
00254 pattern = '<%sd'%length
00255 buff.write(struct.pack(pattern, *val1.accelerations))
00256 _v1 = val1.time_from_start
00257 _x = _v1
00258 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00259 buff.write(_struct_i.pack(self.result.error_code.val))
00260 except struct.error as se: self._check_types(se)
00261 except TypeError as te: self._check_types(te)
00262
00263 def deserialize(self, str):
00264 """
00265 unpack serialized message in str into this message instance
00266 :param str: byte array of serialized message, ``str``
00267 """
00268 try:
00269 if self.header is None:
00270 self.header = std_msgs.msg.Header()
00271 if self.status is None:
00272 self.status = actionlib_msgs.msg.GoalStatus()
00273 if self.result is None:
00274 self.result = head_monitor_msgs.msg.HeadMonitorResult()
00275 end = 0
00276 _x = self
00277 start = end
00278 end += 12
00279 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00280 start = end
00281 end += 4
00282 (length,) = _struct_I.unpack(str[start:end])
00283 start = end
00284 end += length
00285 if python3:
00286 self.header.frame_id = str[start:end].decode('utf-8')
00287 else:
00288 self.header.frame_id = str[start:end]
00289 _x = self
00290 start = end
00291 end += 8
00292 (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00293 start = end
00294 end += 4
00295 (length,) = _struct_I.unpack(str[start:end])
00296 start = end
00297 end += length
00298 if python3:
00299 self.status.goal_id.id = str[start:end].decode('utf-8')
00300 else:
00301 self.status.goal_id.id = str[start:end]
00302 start = end
00303 end += 1
00304 (self.status.status,) = _struct_B.unpack(str[start:end])
00305 start = end
00306 end += 4
00307 (length,) = _struct_I.unpack(str[start:end])
00308 start = end
00309 end += length
00310 if python3:
00311 self.status.text = str[start:end].decode('utf-8')
00312 else:
00313 self.status.text = str[start:end]
00314 _x = self
00315 start = end
00316 end += 12
00317 (_x.result.actual_trajectory.header.seq, _x.result.actual_trajectory.header.stamp.secs, _x.result.actual_trajectory.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00318 start = end
00319 end += 4
00320 (length,) = _struct_I.unpack(str[start:end])
00321 start = end
00322 end += length
00323 if python3:
00324 self.result.actual_trajectory.header.frame_id = str[start:end].decode('utf-8')
00325 else:
00326 self.result.actual_trajectory.header.frame_id = str[start:end]
00327 start = end
00328 end += 4
00329 (length,) = _struct_I.unpack(str[start:end])
00330 self.result.actual_trajectory.joint_names = []
00331 for i in range(0, length):
00332 start = end
00333 end += 4
00334 (length,) = _struct_I.unpack(str[start:end])
00335 start = end
00336 end += length
00337 if python3:
00338 val1 = str[start:end].decode('utf-8')
00339 else:
00340 val1 = str[start:end]
00341 self.result.actual_trajectory.joint_names.append(val1)
00342 start = end
00343 end += 4
00344 (length,) = _struct_I.unpack(str[start:end])
00345 self.result.actual_trajectory.points = []
00346 for i in range(0, length):
00347 val1 = trajectory_msgs.msg.JointTrajectoryPoint()
00348 start = end
00349 end += 4
00350 (length,) = _struct_I.unpack(str[start:end])
00351 pattern = '<%sd'%length
00352 start = end
00353 end += struct.calcsize(pattern)
00354 val1.positions = struct.unpack(pattern, str[start:end])
00355 start = end
00356 end += 4
00357 (length,) = _struct_I.unpack(str[start:end])
00358 pattern = '<%sd'%length
00359 start = end
00360 end += struct.calcsize(pattern)
00361 val1.velocities = struct.unpack(pattern, str[start:end])
00362 start = end
00363 end += 4
00364 (length,) = _struct_I.unpack(str[start:end])
00365 pattern = '<%sd'%length
00366 start = end
00367 end += struct.calcsize(pattern)
00368 val1.accelerations = struct.unpack(pattern, str[start:end])
00369 _v2 = val1.time_from_start
00370 _x = _v2
00371 start = end
00372 end += 8
00373 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00374 self.result.actual_trajectory.points.append(val1)
00375 start = end
00376 end += 4
00377 (self.result.error_code.val,) = _struct_i.unpack(str[start:end])
00378 return self
00379 except struct.error as e:
00380 raise genpy.DeserializationError(e)
00381
00382
00383 def serialize_numpy(self, buff, numpy):
00384 """
00385 serialize message with numpy array types into buffer
00386 :param buff: buffer, ``StringIO``
00387 :param numpy: numpy python module
00388 """
00389 try:
00390 _x = self
00391 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00392 _x = self.header.frame_id
00393 length = len(_x)
00394 if python3 or type(_x) == unicode:
00395 _x = _x.encode('utf-8')
00396 length = len(_x)
00397 buff.write(struct.pack('<I%ss'%length, length, _x))
00398 _x = self
00399 buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs))
00400 _x = self.status.goal_id.id
00401 length = len(_x)
00402 if python3 or type(_x) == unicode:
00403 _x = _x.encode('utf-8')
00404 length = len(_x)
00405 buff.write(struct.pack('<I%ss'%length, length, _x))
00406 buff.write(_struct_B.pack(self.status.status))
00407 _x = self.status.text
00408 length = len(_x)
00409 if python3 or type(_x) == unicode:
00410 _x = _x.encode('utf-8')
00411 length = len(_x)
00412 buff.write(struct.pack('<I%ss'%length, length, _x))
00413 _x = self
00414 buff.write(_struct_3I.pack(_x.result.actual_trajectory.header.seq, _x.result.actual_trajectory.header.stamp.secs, _x.result.actual_trajectory.header.stamp.nsecs))
00415 _x = self.result.actual_trajectory.header.frame_id
00416 length = len(_x)
00417 if python3 or type(_x) == unicode:
00418 _x = _x.encode('utf-8')
00419 length = len(_x)
00420 buff.write(struct.pack('<I%ss'%length, length, _x))
00421 length = len(self.result.actual_trajectory.joint_names)
00422 buff.write(_struct_I.pack(length))
00423 for val1 in self.result.actual_trajectory.joint_names:
00424 length = len(val1)
00425 if python3 or type(val1) == unicode:
00426 val1 = val1.encode('utf-8')
00427 length = len(val1)
00428 buff.write(struct.pack('<I%ss'%length, length, val1))
00429 length = len(self.result.actual_trajectory.points)
00430 buff.write(_struct_I.pack(length))
00431 for val1 in self.result.actual_trajectory.points:
00432 length = len(val1.positions)
00433 buff.write(_struct_I.pack(length))
00434 pattern = '<%sd'%length
00435 buff.write(val1.positions.tostring())
00436 length = len(val1.velocities)
00437 buff.write(_struct_I.pack(length))
00438 pattern = '<%sd'%length
00439 buff.write(val1.velocities.tostring())
00440 length = len(val1.accelerations)
00441 buff.write(_struct_I.pack(length))
00442 pattern = '<%sd'%length
00443 buff.write(val1.accelerations.tostring())
00444 _v3 = val1.time_from_start
00445 _x = _v3
00446 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00447 buff.write(_struct_i.pack(self.result.error_code.val))
00448 except struct.error as se: self._check_types(se)
00449 except TypeError as te: self._check_types(te)
00450
00451 def deserialize_numpy(self, str, numpy):
00452 """
00453 unpack serialized message in str into this message instance using numpy for array types
00454 :param str: byte array of serialized message, ``str``
00455 :param numpy: numpy python module
00456 """
00457 try:
00458 if self.header is None:
00459 self.header = std_msgs.msg.Header()
00460 if self.status is None:
00461 self.status = actionlib_msgs.msg.GoalStatus()
00462 if self.result is None:
00463 self.result = head_monitor_msgs.msg.HeadMonitorResult()
00464 end = 0
00465 _x = self
00466 start = end
00467 end += 12
00468 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00469 start = end
00470 end += 4
00471 (length,) = _struct_I.unpack(str[start:end])
00472 start = end
00473 end += length
00474 if python3:
00475 self.header.frame_id = str[start:end].decode('utf-8')
00476 else:
00477 self.header.frame_id = str[start:end]
00478 _x = self
00479 start = end
00480 end += 8
00481 (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00482 start = end
00483 end += 4
00484 (length,) = _struct_I.unpack(str[start:end])
00485 start = end
00486 end += length
00487 if python3:
00488 self.status.goal_id.id = str[start:end].decode('utf-8')
00489 else:
00490 self.status.goal_id.id = str[start:end]
00491 start = end
00492 end += 1
00493 (self.status.status,) = _struct_B.unpack(str[start:end])
00494 start = end
00495 end += 4
00496 (length,) = _struct_I.unpack(str[start:end])
00497 start = end
00498 end += length
00499 if python3:
00500 self.status.text = str[start:end].decode('utf-8')
00501 else:
00502 self.status.text = str[start:end]
00503 _x = self
00504 start = end
00505 end += 12
00506 (_x.result.actual_trajectory.header.seq, _x.result.actual_trajectory.header.stamp.secs, _x.result.actual_trajectory.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00507 start = end
00508 end += 4
00509 (length,) = _struct_I.unpack(str[start:end])
00510 start = end
00511 end += length
00512 if python3:
00513 self.result.actual_trajectory.header.frame_id = str[start:end].decode('utf-8')
00514 else:
00515 self.result.actual_trajectory.header.frame_id = str[start:end]
00516 start = end
00517 end += 4
00518 (length,) = _struct_I.unpack(str[start:end])
00519 self.result.actual_trajectory.joint_names = []
00520 for i in range(0, length):
00521 start = end
00522 end += 4
00523 (length,) = _struct_I.unpack(str[start:end])
00524 start = end
00525 end += length
00526 if python3:
00527 val1 = str[start:end].decode('utf-8')
00528 else:
00529 val1 = str[start:end]
00530 self.result.actual_trajectory.joint_names.append(val1)
00531 start = end
00532 end += 4
00533 (length,) = _struct_I.unpack(str[start:end])
00534 self.result.actual_trajectory.points = []
00535 for i in range(0, length):
00536 val1 = trajectory_msgs.msg.JointTrajectoryPoint()
00537 start = end
00538 end += 4
00539 (length,) = _struct_I.unpack(str[start:end])
00540 pattern = '<%sd'%length
00541 start = end
00542 end += struct.calcsize(pattern)
00543 val1.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00544 start = end
00545 end += 4
00546 (length,) = _struct_I.unpack(str[start:end])
00547 pattern = '<%sd'%length
00548 start = end
00549 end += struct.calcsize(pattern)
00550 val1.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00551 start = end
00552 end += 4
00553 (length,) = _struct_I.unpack(str[start:end])
00554 pattern = '<%sd'%length
00555 start = end
00556 end += struct.calcsize(pattern)
00557 val1.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00558 _v4 = val1.time_from_start
00559 _x = _v4
00560 start = end
00561 end += 8
00562 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00563 self.result.actual_trajectory.points.append(val1)
00564 start = end
00565 end += 4
00566 (self.result.error_code.val,) = _struct_i.unpack(str[start:end])
00567 return self
00568 except struct.error as e:
00569 raise genpy.DeserializationError(e)
00570
00571 _struct_I = genpy.struct_I
00572 _struct_i = struct.Struct("<i")
00573 _struct_3I = struct.Struct("<3I")
00574 _struct_B = struct.Struct("<B")
00575 _struct_2I = struct.Struct("<2I")
00576 _struct_2i = struct.Struct("<2i")