_WaypointAction.py
Go to the documentation of this file.
00001 """autogenerated by genpy from asctec_hl_comm/WaypointAction.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 import actionlib_msgs.msg
00010 import asctec_hl_comm.msg
00011 import std_msgs.msg
00012 
00013 class WaypointAction(genpy.Message):
00014   _md5sum = "fafd719c24f92461a507395b00094e42"
00015   _type = "asctec_hl_comm/WaypointAction"
00016   _has_header = False #flag to mark the presence of a Header object
00017   _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00018 
00019 WaypointActionGoal action_goal
00020 WaypointActionResult action_result
00021 WaypointActionFeedback action_feedback
00022 
00023 ================================================================================
00024 MSG: asctec_hl_comm/WaypointActionGoal
00025 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00026 
00027 Header header
00028 actionlib_msgs/GoalID goal_id
00029 WaypointGoal goal
00030 
00031 ================================================================================
00032 MSG: std_msgs/Header
00033 # Standard metadata for higher-level stamped data types.
00034 # This is generally used to communicate timestamped data 
00035 # in a particular coordinate frame.
00036 # 
00037 # sequence ID: consecutively increasing ID 
00038 uint32 seq
00039 #Two-integer timestamp that is expressed as:
00040 # * stamp.secs: seconds (stamp_secs) since epoch
00041 # * stamp.nsecs: nanoseconds since stamp_secs
00042 # time-handling sugar is provided by the client library
00043 time stamp
00044 #Frame this data is associated with
00045 # 0: no frame
00046 # 1: global frame
00047 string frame_id
00048 
00049 ================================================================================
00050 MSG: actionlib_msgs/GoalID
00051 # The stamp should store the time at which this goal was requested.
00052 # It is used by an action server when it tries to preempt all
00053 # goals that were requested before a certain time
00054 time stamp
00055 
00056 # The id provides a way to associate feedback and
00057 # result message with specific goal requests. The id
00058 # specified must be unique.
00059 string id
00060 
00061 
00062 ================================================================================
00063 MSG: asctec_hl_comm/WaypointGoal
00064 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00065 #goal
00066 Header header
00067 geometry_msgs/Point32   goal_pos
00068 float32                 goal_yaw
00069 geometry_msgs/Point32   max_speed
00070 float32                                 accuracy_position        # determines the radius around the goal within the goal is considered as reached
00071 float32                 accuracy_orientation     # determines the range within the goal orientation is considered as reached, for the heli only yaw
00072 float32                 timeout                  # timeout in [s] after which flying to the waypoint stops
00073 
00074 ================================================================================
00075 MSG: geometry_msgs/Point32
00076 # This contains the position of a point in free space(with 32 bits of precision).
00077 # It is recommeded to use Point wherever possible instead of Point32.  
00078 # 
00079 # This recommendation is to promote interoperability.  
00080 #
00081 # This message is designed to take up less space when sending
00082 # lots of points at once, as in the case of a PointCloud.  
00083 
00084 float32 x
00085 float32 y
00086 float32 z
00087 ================================================================================
00088 MSG: asctec_hl_comm/WaypointActionResult
00089 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00090 
00091 Header header
00092 actionlib_msgs/GoalStatus status
00093 WaypointResult result
00094 
00095 ================================================================================
00096 MSG: actionlib_msgs/GoalStatus
00097 GoalID goal_id
00098 uint8 status
00099 uint8 PENDING         = 0   # The goal has yet to be processed by the action server
00100 uint8 ACTIVE          = 1   # The goal is currently being processed by the action server
00101 uint8 PREEMPTED       = 2   # The goal received a cancel request after it started executing
00102                             #   and has since completed its execution (Terminal State)
00103 uint8 SUCCEEDED       = 3   # The goal was achieved successfully by the action server (Terminal State)
00104 uint8 ABORTED         = 4   # The goal was aborted during execution by the action server due
00105                             #    to some failure (Terminal State)
00106 uint8 REJECTED        = 5   # The goal was rejected by the action server without being processed,
00107                             #    because the goal was unattainable or invalid (Terminal State)
00108 uint8 PREEMPTING      = 6   # The goal received a cancel request after it started executing
00109                             #    and has not yet completed execution
00110 uint8 RECALLING       = 7   # The goal received a cancel request before it started executing,
00111                             #    but the action server has not yet confirmed that the goal is canceled
00112 uint8 RECALLED        = 8   # The goal received a cancel request before it started executing
00113                             #    and was successfully cancelled (Terminal State)
00114 uint8 LOST            = 9   # An action client can determine that a goal is LOST. This should not be
00115                             #    sent over the wire by an action server
00116 
00117 #Allow for the user to associate a string with GoalStatus for debugging
00118 string text
00119 
00120 
00121 ================================================================================
00122 MSG: asctec_hl_comm/WaypointResult
00123 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00124 #result
00125 Header header
00126 geometry_msgs/Point32   result_pos
00127 float32                 result_yaw
00128 string                  status
00129 
00130 ================================================================================
00131 MSG: asctec_hl_comm/WaypointActionFeedback
00132 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00133 
00134 Header header
00135 actionlib_msgs/GoalStatus status
00136 WaypointFeedback feedback
00137 
00138 ================================================================================
00139 MSG: asctec_hl_comm/WaypointFeedback
00140 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00141 #feedback
00142 Header header
00143 geometry_msgs/Point32   current_pos
00144 float32                 current_yaw
00145 string                  status
00146 
00147 
00148 """
00149   __slots__ = ['action_goal','action_result','action_feedback']
00150   _slot_types = ['asctec_hl_comm/WaypointActionGoal','asctec_hl_comm/WaypointActionResult','asctec_hl_comm/WaypointActionFeedback']
00151 
00152   def __init__(self, *args, **kwds):
00153     """
00154     Constructor. Any message fields that are implicitly/explicitly
00155     set to None will be assigned a default value. The recommend
00156     use is keyword arguments as this is more robust to future message
00157     changes.  You cannot mix in-order arguments and keyword arguments.
00158 
00159     The available fields are:
00160        action_goal,action_result,action_feedback
00161 
00162     :param args: complete set of field values, in .msg order
00163     :param kwds: use keyword arguments corresponding to message field names
00164     to set specific fields.
00165     """
00166     if args or kwds:
00167       super(WaypointAction, self).__init__(*args, **kwds)
00168       #message fields cannot be None, assign default values for those that are
00169       if self.action_goal is None:
00170         self.action_goal = asctec_hl_comm.msg.WaypointActionGoal()
00171       if self.action_result is None:
00172         self.action_result = asctec_hl_comm.msg.WaypointActionResult()
00173       if self.action_feedback is None:
00174         self.action_feedback = asctec_hl_comm.msg.WaypointActionFeedback()
00175     else:
00176       self.action_goal = asctec_hl_comm.msg.WaypointActionGoal()
00177       self.action_result = asctec_hl_comm.msg.WaypointActionResult()
00178       self.action_feedback = asctec_hl_comm.msg.WaypointActionFeedback()
00179 
00180   def _get_types(self):
00181     """
00182     internal API method
00183     """
00184     return self._slot_types
00185 
00186   def serialize(self, buff):
00187     """
00188     serialize message into buffer
00189     :param buff: buffer, ``StringIO``
00190     """
00191     try:
00192       _x = self
00193       buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00194       _x = self.action_goal.header.frame_id
00195       length = len(_x)
00196       if python3 or type(_x) == unicode:
00197         _x = _x.encode('utf-8')
00198         length = len(_x)
00199       buff.write(struct.pack('<I%ss'%length, length, _x))
00200       _x = self
00201       buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00202       _x = self.action_goal.goal_id.id
00203       length = len(_x)
00204       if python3 or type(_x) == unicode:
00205         _x = _x.encode('utf-8')
00206         length = len(_x)
00207       buff.write(struct.pack('<I%ss'%length, length, _x))
00208       _x = self
00209       buff.write(_struct_3I.pack(_x.action_goal.goal.header.seq, _x.action_goal.goal.header.stamp.secs, _x.action_goal.goal.header.stamp.nsecs))
00210       _x = self.action_goal.goal.header.frame_id
00211       length = len(_x)
00212       if python3 or type(_x) == unicode:
00213         _x = _x.encode('utf-8')
00214         length = len(_x)
00215       buff.write(struct.pack('<I%ss'%length, length, _x))
00216       _x = self
00217       buff.write(_struct_10f3I.pack(_x.action_goal.goal.goal_pos.x, _x.action_goal.goal.goal_pos.y, _x.action_goal.goal.goal_pos.z, _x.action_goal.goal.goal_yaw, _x.action_goal.goal.max_speed.x, _x.action_goal.goal.max_speed.y, _x.action_goal.goal.max_speed.z, _x.action_goal.goal.accuracy_position, _x.action_goal.goal.accuracy_orientation, _x.action_goal.goal.timeout, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00218       _x = self.action_result.header.frame_id
00219       length = len(_x)
00220       if python3 or type(_x) == unicode:
00221         _x = _x.encode('utf-8')
00222         length = len(_x)
00223       buff.write(struct.pack('<I%ss'%length, length, _x))
00224       _x = self
00225       buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00226       _x = self.action_result.status.goal_id.id
00227       length = len(_x)
00228       if python3 or type(_x) == unicode:
00229         _x = _x.encode('utf-8')
00230         length = len(_x)
00231       buff.write(struct.pack('<I%ss'%length, length, _x))
00232       buff.write(_struct_B.pack(self.action_result.status.status))
00233       _x = self.action_result.status.text
00234       length = len(_x)
00235       if python3 or type(_x) == unicode:
00236         _x = _x.encode('utf-8')
00237         length = len(_x)
00238       buff.write(struct.pack('<I%ss'%length, length, _x))
00239       _x = self
00240       buff.write(_struct_3I.pack(_x.action_result.result.header.seq, _x.action_result.result.header.stamp.secs, _x.action_result.result.header.stamp.nsecs))
00241       _x = self.action_result.result.header.frame_id
00242       length = len(_x)
00243       if python3 or type(_x) == unicode:
00244         _x = _x.encode('utf-8')
00245         length = len(_x)
00246       buff.write(struct.pack('<I%ss'%length, length, _x))
00247       _x = self
00248       buff.write(_struct_4f.pack(_x.action_result.result.result_pos.x, _x.action_result.result.result_pos.y, _x.action_result.result.result_pos.z, _x.action_result.result.result_yaw))
00249       _x = self.action_result.result.status
00250       length = len(_x)
00251       if python3 or type(_x) == unicode:
00252         _x = _x.encode('utf-8')
00253         length = len(_x)
00254       buff.write(struct.pack('<I%ss'%length, length, _x))
00255       _x = self
00256       buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00257       _x = self.action_feedback.header.frame_id
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_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00265       _x = self.action_feedback.status.goal_id.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       buff.write(_struct_B.pack(self.action_feedback.status.status))
00272       _x = self.action_feedback.status.text
00273       length = len(_x)
00274       if python3 or type(_x) == unicode:
00275         _x = _x.encode('utf-8')
00276         length = len(_x)
00277       buff.write(struct.pack('<I%ss'%length, length, _x))
00278       _x = self
00279       buff.write(_struct_3I.pack(_x.action_feedback.feedback.header.seq, _x.action_feedback.feedback.header.stamp.secs, _x.action_feedback.feedback.header.stamp.nsecs))
00280       _x = self.action_feedback.feedback.header.frame_id
00281       length = len(_x)
00282       if python3 or type(_x) == unicode:
00283         _x = _x.encode('utf-8')
00284         length = len(_x)
00285       buff.write(struct.pack('<I%ss'%length, length, _x))
00286       _x = self
00287       buff.write(_struct_4f.pack(_x.action_feedback.feedback.current_pos.x, _x.action_feedback.feedback.current_pos.y, _x.action_feedback.feedback.current_pos.z, _x.action_feedback.feedback.current_yaw))
00288       _x = self.action_feedback.feedback.status
00289       length = len(_x)
00290       if python3 or type(_x) == unicode:
00291         _x = _x.encode('utf-8')
00292         length = len(_x)
00293       buff.write(struct.pack('<I%ss'%length, length, _x))
00294     except struct.error as se: self._check_types(se)
00295     except TypeError as te: self._check_types(te)
00296 
00297   def deserialize(self, str):
00298     """
00299     unpack serialized message in str into this message instance
00300     :param str: byte array of serialized message, ``str``
00301     """
00302     try:
00303       if self.action_goal is None:
00304         self.action_goal = asctec_hl_comm.msg.WaypointActionGoal()
00305       if self.action_result is None:
00306         self.action_result = asctec_hl_comm.msg.WaypointActionResult()
00307       if self.action_feedback is None:
00308         self.action_feedback = asctec_hl_comm.msg.WaypointActionFeedback()
00309       end = 0
00310       _x = self
00311       start = end
00312       end += 12
00313       (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00314       start = end
00315       end += 4
00316       (length,) = _struct_I.unpack(str[start:end])
00317       start = end
00318       end += length
00319       if python3:
00320         self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00321       else:
00322         self.action_goal.header.frame_id = str[start:end]
00323       _x = self
00324       start = end
00325       end += 8
00326       (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00327       start = end
00328       end += 4
00329       (length,) = _struct_I.unpack(str[start:end])
00330       start = end
00331       end += length
00332       if python3:
00333         self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00334       else:
00335         self.action_goal.goal_id.id = str[start:end]
00336       _x = self
00337       start = end
00338       end += 12
00339       (_x.action_goal.goal.header.seq, _x.action_goal.goal.header.stamp.secs, _x.action_goal.goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00340       start = end
00341       end += 4
00342       (length,) = _struct_I.unpack(str[start:end])
00343       start = end
00344       end += length
00345       if python3:
00346         self.action_goal.goal.header.frame_id = str[start:end].decode('utf-8')
00347       else:
00348         self.action_goal.goal.header.frame_id = str[start:end]
00349       _x = self
00350       start = end
00351       end += 52
00352       (_x.action_goal.goal.goal_pos.x, _x.action_goal.goal.goal_pos.y, _x.action_goal.goal.goal_pos.z, _x.action_goal.goal.goal_yaw, _x.action_goal.goal.max_speed.x, _x.action_goal.goal.max_speed.y, _x.action_goal.goal.max_speed.z, _x.action_goal.goal.accuracy_position, _x.action_goal.goal.accuracy_orientation, _x.action_goal.goal.timeout, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_10f3I.unpack(str[start:end])
00353       start = end
00354       end += 4
00355       (length,) = _struct_I.unpack(str[start:end])
00356       start = end
00357       end += length
00358       if python3:
00359         self.action_result.header.frame_id = str[start:end].decode('utf-8')
00360       else:
00361         self.action_result.header.frame_id = str[start:end]
00362       _x = self
00363       start = end
00364       end += 8
00365       (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00366       start = end
00367       end += 4
00368       (length,) = _struct_I.unpack(str[start:end])
00369       start = end
00370       end += length
00371       if python3:
00372         self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00373       else:
00374         self.action_result.status.goal_id.id = str[start:end]
00375       start = end
00376       end += 1
00377       (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00378       start = end
00379       end += 4
00380       (length,) = _struct_I.unpack(str[start:end])
00381       start = end
00382       end += length
00383       if python3:
00384         self.action_result.status.text = str[start:end].decode('utf-8')
00385       else:
00386         self.action_result.status.text = str[start:end]
00387       _x = self
00388       start = end
00389       end += 12
00390       (_x.action_result.result.header.seq, _x.action_result.result.header.stamp.secs, _x.action_result.result.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00391       start = end
00392       end += 4
00393       (length,) = _struct_I.unpack(str[start:end])
00394       start = end
00395       end += length
00396       if python3:
00397         self.action_result.result.header.frame_id = str[start:end].decode('utf-8')
00398       else:
00399         self.action_result.result.header.frame_id = str[start:end]
00400       _x = self
00401       start = end
00402       end += 16
00403       (_x.action_result.result.result_pos.x, _x.action_result.result.result_pos.y, _x.action_result.result.result_pos.z, _x.action_result.result.result_yaw,) = _struct_4f.unpack(str[start:end])
00404       start = end
00405       end += 4
00406       (length,) = _struct_I.unpack(str[start:end])
00407       start = end
00408       end += length
00409       if python3:
00410         self.action_result.result.status = str[start:end].decode('utf-8')
00411       else:
00412         self.action_result.result.status = str[start:end]
00413       _x = self
00414       start = end
00415       end += 12
00416       (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00417       start = end
00418       end += 4
00419       (length,) = _struct_I.unpack(str[start:end])
00420       start = end
00421       end += length
00422       if python3:
00423         self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00424       else:
00425         self.action_feedback.header.frame_id = str[start:end]
00426       _x = self
00427       start = end
00428       end += 8
00429       (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00430       start = end
00431       end += 4
00432       (length,) = _struct_I.unpack(str[start:end])
00433       start = end
00434       end += length
00435       if python3:
00436         self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00437       else:
00438         self.action_feedback.status.goal_id.id = str[start:end]
00439       start = end
00440       end += 1
00441       (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00442       start = end
00443       end += 4
00444       (length,) = _struct_I.unpack(str[start:end])
00445       start = end
00446       end += length
00447       if python3:
00448         self.action_feedback.status.text = str[start:end].decode('utf-8')
00449       else:
00450         self.action_feedback.status.text = str[start:end]
00451       _x = self
00452       start = end
00453       end += 12
00454       (_x.action_feedback.feedback.header.seq, _x.action_feedback.feedback.header.stamp.secs, _x.action_feedback.feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00455       start = end
00456       end += 4
00457       (length,) = _struct_I.unpack(str[start:end])
00458       start = end
00459       end += length
00460       if python3:
00461         self.action_feedback.feedback.header.frame_id = str[start:end].decode('utf-8')
00462       else:
00463         self.action_feedback.feedback.header.frame_id = str[start:end]
00464       _x = self
00465       start = end
00466       end += 16
00467       (_x.action_feedback.feedback.current_pos.x, _x.action_feedback.feedback.current_pos.y, _x.action_feedback.feedback.current_pos.z, _x.action_feedback.feedback.current_yaw,) = _struct_4f.unpack(str[start:end])
00468       start = end
00469       end += 4
00470       (length,) = _struct_I.unpack(str[start:end])
00471       start = end
00472       end += length
00473       if python3:
00474         self.action_feedback.feedback.status = str[start:end].decode('utf-8')
00475       else:
00476         self.action_feedback.feedback.status = str[start:end]
00477       return self
00478     except struct.error as e:
00479       raise genpy.DeserializationError(e) #most likely buffer underfill
00480 
00481 
00482   def serialize_numpy(self, buff, numpy):
00483     """
00484     serialize message with numpy array types into buffer
00485     :param buff: buffer, ``StringIO``
00486     :param numpy: numpy python module
00487     """
00488     try:
00489       _x = self
00490       buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00491       _x = self.action_goal.header.frame_id
00492       length = len(_x)
00493       if python3 or type(_x) == unicode:
00494         _x = _x.encode('utf-8')
00495         length = len(_x)
00496       buff.write(struct.pack('<I%ss'%length, length, _x))
00497       _x = self
00498       buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00499       _x = self.action_goal.goal_id.id
00500       length = len(_x)
00501       if python3 or type(_x) == unicode:
00502         _x = _x.encode('utf-8')
00503         length = len(_x)
00504       buff.write(struct.pack('<I%ss'%length, length, _x))
00505       _x = self
00506       buff.write(_struct_3I.pack(_x.action_goal.goal.header.seq, _x.action_goal.goal.header.stamp.secs, _x.action_goal.goal.header.stamp.nsecs))
00507       _x = self.action_goal.goal.header.frame_id
00508       length = len(_x)
00509       if python3 or type(_x) == unicode:
00510         _x = _x.encode('utf-8')
00511         length = len(_x)
00512       buff.write(struct.pack('<I%ss'%length, length, _x))
00513       _x = self
00514       buff.write(_struct_10f3I.pack(_x.action_goal.goal.goal_pos.x, _x.action_goal.goal.goal_pos.y, _x.action_goal.goal.goal_pos.z, _x.action_goal.goal.goal_yaw, _x.action_goal.goal.max_speed.x, _x.action_goal.goal.max_speed.y, _x.action_goal.goal.max_speed.z, _x.action_goal.goal.accuracy_position, _x.action_goal.goal.accuracy_orientation, _x.action_goal.goal.timeout, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00515       _x = self.action_result.header.frame_id
00516       length = len(_x)
00517       if python3 or type(_x) == unicode:
00518         _x = _x.encode('utf-8')
00519         length = len(_x)
00520       buff.write(struct.pack('<I%ss'%length, length, _x))
00521       _x = self
00522       buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00523       _x = self.action_result.status.goal_id.id
00524       length = len(_x)
00525       if python3 or type(_x) == unicode:
00526         _x = _x.encode('utf-8')
00527         length = len(_x)
00528       buff.write(struct.pack('<I%ss'%length, length, _x))
00529       buff.write(_struct_B.pack(self.action_result.status.status))
00530       _x = self.action_result.status.text
00531       length = len(_x)
00532       if python3 or type(_x) == unicode:
00533         _x = _x.encode('utf-8')
00534         length = len(_x)
00535       buff.write(struct.pack('<I%ss'%length, length, _x))
00536       _x = self
00537       buff.write(_struct_3I.pack(_x.action_result.result.header.seq, _x.action_result.result.header.stamp.secs, _x.action_result.result.header.stamp.nsecs))
00538       _x = self.action_result.result.header.frame_id
00539       length = len(_x)
00540       if python3 or type(_x) == unicode:
00541         _x = _x.encode('utf-8')
00542         length = len(_x)
00543       buff.write(struct.pack('<I%ss'%length, length, _x))
00544       _x = self
00545       buff.write(_struct_4f.pack(_x.action_result.result.result_pos.x, _x.action_result.result.result_pos.y, _x.action_result.result.result_pos.z, _x.action_result.result.result_yaw))
00546       _x = self.action_result.result.status
00547       length = len(_x)
00548       if python3 or type(_x) == unicode:
00549         _x = _x.encode('utf-8')
00550         length = len(_x)
00551       buff.write(struct.pack('<I%ss'%length, length, _x))
00552       _x = self
00553       buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00554       _x = self.action_feedback.header.frame_id
00555       length = len(_x)
00556       if python3 or type(_x) == unicode:
00557         _x = _x.encode('utf-8')
00558         length = len(_x)
00559       buff.write(struct.pack('<I%ss'%length, length, _x))
00560       _x = self
00561       buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00562       _x = self.action_feedback.status.goal_id.id
00563       length = len(_x)
00564       if python3 or type(_x) == unicode:
00565         _x = _x.encode('utf-8')
00566         length = len(_x)
00567       buff.write(struct.pack('<I%ss'%length, length, _x))
00568       buff.write(_struct_B.pack(self.action_feedback.status.status))
00569       _x = self.action_feedback.status.text
00570       length = len(_x)
00571       if python3 or type(_x) == unicode:
00572         _x = _x.encode('utf-8')
00573         length = len(_x)
00574       buff.write(struct.pack('<I%ss'%length, length, _x))
00575       _x = self
00576       buff.write(_struct_3I.pack(_x.action_feedback.feedback.header.seq, _x.action_feedback.feedback.header.stamp.secs, _x.action_feedback.feedback.header.stamp.nsecs))
00577       _x = self.action_feedback.feedback.header.frame_id
00578       length = len(_x)
00579       if python3 or type(_x) == unicode:
00580         _x = _x.encode('utf-8')
00581         length = len(_x)
00582       buff.write(struct.pack('<I%ss'%length, length, _x))
00583       _x = self
00584       buff.write(_struct_4f.pack(_x.action_feedback.feedback.current_pos.x, _x.action_feedback.feedback.current_pos.y, _x.action_feedback.feedback.current_pos.z, _x.action_feedback.feedback.current_yaw))
00585       _x = self.action_feedback.feedback.status
00586       length = len(_x)
00587       if python3 or type(_x) == unicode:
00588         _x = _x.encode('utf-8')
00589         length = len(_x)
00590       buff.write(struct.pack('<I%ss'%length, length, _x))
00591     except struct.error as se: self._check_types(se)
00592     except TypeError as te: self._check_types(te)
00593 
00594   def deserialize_numpy(self, str, numpy):
00595     """
00596     unpack serialized message in str into this message instance using numpy for array types
00597     :param str: byte array of serialized message, ``str``
00598     :param numpy: numpy python module
00599     """
00600     try:
00601       if self.action_goal is None:
00602         self.action_goal = asctec_hl_comm.msg.WaypointActionGoal()
00603       if self.action_result is None:
00604         self.action_result = asctec_hl_comm.msg.WaypointActionResult()
00605       if self.action_feedback is None:
00606         self.action_feedback = asctec_hl_comm.msg.WaypointActionFeedback()
00607       end = 0
00608       _x = self
00609       start = end
00610       end += 12
00611       (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00612       start = end
00613       end += 4
00614       (length,) = _struct_I.unpack(str[start:end])
00615       start = end
00616       end += length
00617       if python3:
00618         self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00619       else:
00620         self.action_goal.header.frame_id = str[start:end]
00621       _x = self
00622       start = end
00623       end += 8
00624       (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00625       start = end
00626       end += 4
00627       (length,) = _struct_I.unpack(str[start:end])
00628       start = end
00629       end += length
00630       if python3:
00631         self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00632       else:
00633         self.action_goal.goal_id.id = str[start:end]
00634       _x = self
00635       start = end
00636       end += 12
00637       (_x.action_goal.goal.header.seq, _x.action_goal.goal.header.stamp.secs, _x.action_goal.goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00638       start = end
00639       end += 4
00640       (length,) = _struct_I.unpack(str[start:end])
00641       start = end
00642       end += length
00643       if python3:
00644         self.action_goal.goal.header.frame_id = str[start:end].decode('utf-8')
00645       else:
00646         self.action_goal.goal.header.frame_id = str[start:end]
00647       _x = self
00648       start = end
00649       end += 52
00650       (_x.action_goal.goal.goal_pos.x, _x.action_goal.goal.goal_pos.y, _x.action_goal.goal.goal_pos.z, _x.action_goal.goal.goal_yaw, _x.action_goal.goal.max_speed.x, _x.action_goal.goal.max_speed.y, _x.action_goal.goal.max_speed.z, _x.action_goal.goal.accuracy_position, _x.action_goal.goal.accuracy_orientation, _x.action_goal.goal.timeout, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_10f3I.unpack(str[start:end])
00651       start = end
00652       end += 4
00653       (length,) = _struct_I.unpack(str[start:end])
00654       start = end
00655       end += length
00656       if python3:
00657         self.action_result.header.frame_id = str[start:end].decode('utf-8')
00658       else:
00659         self.action_result.header.frame_id = str[start:end]
00660       _x = self
00661       start = end
00662       end += 8
00663       (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00664       start = end
00665       end += 4
00666       (length,) = _struct_I.unpack(str[start:end])
00667       start = end
00668       end += length
00669       if python3:
00670         self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00671       else:
00672         self.action_result.status.goal_id.id = str[start:end]
00673       start = end
00674       end += 1
00675       (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00676       start = end
00677       end += 4
00678       (length,) = _struct_I.unpack(str[start:end])
00679       start = end
00680       end += length
00681       if python3:
00682         self.action_result.status.text = str[start:end].decode('utf-8')
00683       else:
00684         self.action_result.status.text = str[start:end]
00685       _x = self
00686       start = end
00687       end += 12
00688       (_x.action_result.result.header.seq, _x.action_result.result.header.stamp.secs, _x.action_result.result.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00689       start = end
00690       end += 4
00691       (length,) = _struct_I.unpack(str[start:end])
00692       start = end
00693       end += length
00694       if python3:
00695         self.action_result.result.header.frame_id = str[start:end].decode('utf-8')
00696       else:
00697         self.action_result.result.header.frame_id = str[start:end]
00698       _x = self
00699       start = end
00700       end += 16
00701       (_x.action_result.result.result_pos.x, _x.action_result.result.result_pos.y, _x.action_result.result.result_pos.z, _x.action_result.result.result_yaw,) = _struct_4f.unpack(str[start:end])
00702       start = end
00703       end += 4
00704       (length,) = _struct_I.unpack(str[start:end])
00705       start = end
00706       end += length
00707       if python3:
00708         self.action_result.result.status = str[start:end].decode('utf-8')
00709       else:
00710         self.action_result.result.status = str[start:end]
00711       _x = self
00712       start = end
00713       end += 12
00714       (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00715       start = end
00716       end += 4
00717       (length,) = _struct_I.unpack(str[start:end])
00718       start = end
00719       end += length
00720       if python3:
00721         self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00722       else:
00723         self.action_feedback.header.frame_id = str[start:end]
00724       _x = self
00725       start = end
00726       end += 8
00727       (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00728       start = end
00729       end += 4
00730       (length,) = _struct_I.unpack(str[start:end])
00731       start = end
00732       end += length
00733       if python3:
00734         self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00735       else:
00736         self.action_feedback.status.goal_id.id = str[start:end]
00737       start = end
00738       end += 1
00739       (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00740       start = end
00741       end += 4
00742       (length,) = _struct_I.unpack(str[start:end])
00743       start = end
00744       end += length
00745       if python3:
00746         self.action_feedback.status.text = str[start:end].decode('utf-8')
00747       else:
00748         self.action_feedback.status.text = str[start:end]
00749       _x = self
00750       start = end
00751       end += 12
00752       (_x.action_feedback.feedback.header.seq, _x.action_feedback.feedback.header.stamp.secs, _x.action_feedback.feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00753       start = end
00754       end += 4
00755       (length,) = _struct_I.unpack(str[start:end])
00756       start = end
00757       end += length
00758       if python3:
00759         self.action_feedback.feedback.header.frame_id = str[start:end].decode('utf-8')
00760       else:
00761         self.action_feedback.feedback.header.frame_id = str[start:end]
00762       _x = self
00763       start = end
00764       end += 16
00765       (_x.action_feedback.feedback.current_pos.x, _x.action_feedback.feedback.current_pos.y, _x.action_feedback.feedback.current_pos.z, _x.action_feedback.feedback.current_yaw,) = _struct_4f.unpack(str[start:end])
00766       start = end
00767       end += 4
00768       (length,) = _struct_I.unpack(str[start:end])
00769       start = end
00770       end += length
00771       if python3:
00772         self.action_feedback.feedback.status = str[start:end].decode('utf-8')
00773       else:
00774         self.action_feedback.feedback.status = str[start:end]
00775       return self
00776     except struct.error as e:
00777       raise genpy.DeserializationError(e) #most likely buffer underfill
00778 
00779 _struct_I = genpy.struct_I
00780 _struct_4f = struct.Struct("<4f")
00781 _struct_3I = struct.Struct("<3I")
00782 _struct_B = struct.Struct("<B")
00783 _struct_2I = struct.Struct("<2I")
00784 _struct_10f3I = struct.Struct("<10f3I")


asctec_hl_comm
Author(s): Markus Achtelik, Michael Achtelik, Stephan Weiss, Laurent Kneip
autogenerated on Tue Jan 7 2014 11:05:05