_WaypointGoal.py
Go to the documentation of this file.
00001 """autogenerated by genpy from asctec_hl_comm/WaypointGoal.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 std_msgs.msg
00009 
00010 class WaypointGoal(genpy.Message):
00011   _md5sum = "507ec257de0ab6b6c1abb2c69409fbd5"
00012   _type = "asctec_hl_comm/WaypointGoal"
00013   _has_header = True #flag to mark the presence of a Header object
00014   _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00015 #goal
00016 Header header
00017 geometry_msgs/Point32   goal_pos
00018 float32                 goal_yaw
00019 geometry_msgs/Point32   max_speed
00020 float32                                 accuracy_position        # determines the radius around the goal within the goal is considered as reached
00021 float32                 accuracy_orientation     # determines the range within the goal orientation is considered as reached, for the heli only yaw
00022 float32                 timeout                  # timeout in [s] after which flying to the waypoint stops
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: geometry_msgs/Point32
00044 # This contains the position of a point in free space(with 32 bits of precision).
00045 # It is recommeded to use Point wherever possible instead of Point32.  
00046 # 
00047 # This recommendation is to promote interoperability.  
00048 #
00049 # This message is designed to take up less space when sending
00050 # lots of points at once, as in the case of a PointCloud.  
00051 
00052 float32 x
00053 float32 y
00054 float32 z
00055 """
00056   __slots__ = ['header','goal_pos','goal_yaw','max_speed','accuracy_position','accuracy_orientation','timeout']
00057   _slot_types = ['std_msgs/Header','geometry_msgs/Point32','float32','geometry_msgs/Point32','float32','float32','float32']
00058 
00059   def __init__(self, *args, **kwds):
00060     """
00061     Constructor. Any message fields that are implicitly/explicitly
00062     set to None will be assigned a default value. The recommend
00063     use is keyword arguments as this is more robust to future message
00064     changes.  You cannot mix in-order arguments and keyword arguments.
00065 
00066     The available fields are:
00067        header,goal_pos,goal_yaw,max_speed,accuracy_position,accuracy_orientation,timeout
00068 
00069     :param args: complete set of field values, in .msg order
00070     :param kwds: use keyword arguments corresponding to message field names
00071     to set specific fields.
00072     """
00073     if args or kwds:
00074       super(WaypointGoal, self).__init__(*args, **kwds)
00075       #message fields cannot be None, assign default values for those that are
00076       if self.header is None:
00077         self.header = std_msgs.msg.Header()
00078       if self.goal_pos is None:
00079         self.goal_pos = geometry_msgs.msg.Point32()
00080       if self.goal_yaw is None:
00081         self.goal_yaw = 0.
00082       if self.max_speed is None:
00083         self.max_speed = geometry_msgs.msg.Point32()
00084       if self.accuracy_position is None:
00085         self.accuracy_position = 0.
00086       if self.accuracy_orientation is None:
00087         self.accuracy_orientation = 0.
00088       if self.timeout is None:
00089         self.timeout = 0.
00090     else:
00091       self.header = std_msgs.msg.Header()
00092       self.goal_pos = geometry_msgs.msg.Point32()
00093       self.goal_yaw = 0.
00094       self.max_speed = geometry_msgs.msg.Point32()
00095       self.accuracy_position = 0.
00096       self.accuracy_orientation = 0.
00097       self.timeout = 0.
00098 
00099   def _get_types(self):
00100     """
00101     internal API method
00102     """
00103     return self._slot_types
00104 
00105   def serialize(self, buff):
00106     """
00107     serialize message into buffer
00108     :param buff: buffer, ``StringIO``
00109     """
00110     try:
00111       _x = self
00112       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00113       _x = self.header.frame_id
00114       length = len(_x)
00115       if python3 or type(_x) == unicode:
00116         _x = _x.encode('utf-8')
00117         length = len(_x)
00118       buff.write(struct.pack('<I%ss'%length, length, _x))
00119       _x = self
00120       buff.write(_struct_10f.pack(_x.goal_pos.x, _x.goal_pos.y, _x.goal_pos.z, _x.goal_yaw, _x.max_speed.x, _x.max_speed.y, _x.max_speed.z, _x.accuracy_position, _x.accuracy_orientation, _x.timeout))
00121     except struct.error as se: self._check_types(se)
00122     except TypeError as te: self._check_types(te)
00123 
00124   def deserialize(self, str):
00125     """
00126     unpack serialized message in str into this message instance
00127     :param str: byte array of serialized message, ``str``
00128     """
00129     try:
00130       if self.header is None:
00131         self.header = std_msgs.msg.Header()
00132       if self.goal_pos is None:
00133         self.goal_pos = geometry_msgs.msg.Point32()
00134       if self.max_speed is None:
00135         self.max_speed = geometry_msgs.msg.Point32()
00136       end = 0
00137       _x = self
00138       start = end
00139       end += 12
00140       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00141       start = end
00142       end += 4
00143       (length,) = _struct_I.unpack(str[start:end])
00144       start = end
00145       end += length
00146       if python3:
00147         self.header.frame_id = str[start:end].decode('utf-8')
00148       else:
00149         self.header.frame_id = str[start:end]
00150       _x = self
00151       start = end
00152       end += 40
00153       (_x.goal_pos.x, _x.goal_pos.y, _x.goal_pos.z, _x.goal_yaw, _x.max_speed.x, _x.max_speed.y, _x.max_speed.z, _x.accuracy_position, _x.accuracy_orientation, _x.timeout,) = _struct_10f.unpack(str[start:end])
00154       return self
00155     except struct.error as e:
00156       raise genpy.DeserializationError(e) #most likely buffer underfill
00157 
00158 
00159   def serialize_numpy(self, buff, numpy):
00160     """
00161     serialize message with numpy array types into buffer
00162     :param buff: buffer, ``StringIO``
00163     :param numpy: numpy python module
00164     """
00165     try:
00166       _x = self
00167       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00168       _x = self.header.frame_id
00169       length = len(_x)
00170       if python3 or type(_x) == unicode:
00171         _x = _x.encode('utf-8')
00172         length = len(_x)
00173       buff.write(struct.pack('<I%ss'%length, length, _x))
00174       _x = self
00175       buff.write(_struct_10f.pack(_x.goal_pos.x, _x.goal_pos.y, _x.goal_pos.z, _x.goal_yaw, _x.max_speed.x, _x.max_speed.y, _x.max_speed.z, _x.accuracy_position, _x.accuracy_orientation, _x.timeout))
00176     except struct.error as se: self._check_types(se)
00177     except TypeError as te: self._check_types(te)
00178 
00179   def deserialize_numpy(self, str, numpy):
00180     """
00181     unpack serialized message in str into this message instance using numpy for array types
00182     :param str: byte array of serialized message, ``str``
00183     :param numpy: numpy python module
00184     """
00185     try:
00186       if self.header is None:
00187         self.header = std_msgs.msg.Header()
00188       if self.goal_pos is None:
00189         self.goal_pos = geometry_msgs.msg.Point32()
00190       if self.max_speed is None:
00191         self.max_speed = geometry_msgs.msg.Point32()
00192       end = 0
00193       _x = self
00194       start = end
00195       end += 12
00196       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00197       start = end
00198       end += 4
00199       (length,) = _struct_I.unpack(str[start:end])
00200       start = end
00201       end += length
00202       if python3:
00203         self.header.frame_id = str[start:end].decode('utf-8')
00204       else:
00205         self.header.frame_id = str[start:end]
00206       _x = self
00207       start = end
00208       end += 40
00209       (_x.goal_pos.x, _x.goal_pos.y, _x.goal_pos.z, _x.goal_yaw, _x.max_speed.x, _x.max_speed.y, _x.max_speed.z, _x.accuracy_position, _x.accuracy_orientation, _x.timeout,) = _struct_10f.unpack(str[start:end])
00210       return self
00211     except struct.error as e:
00212       raise genpy.DeserializationError(e) #most likely buffer underfill
00213 
00214 _struct_I = genpy.struct_I
00215 _struct_3I = struct.Struct("<3I")
00216 _struct_10f = struct.Struct("<10f")


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