_WayPoint.py
Go to the documentation of this file.
00001 """autogenerated by genpy from art_msgs/WayPoint.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 art_msgs.msg
00009 
00010 class WayPoint(genpy.Message):
00011   _md5sum = "93d7bd4ade2e33f8e836f5cd46c71e50"
00012   _type = "art_msgs/WayPoint"
00013   _has_header = False #flag to mark the presence of a Header object
00014   _full_text = """# Way-point attributes
00015 # $Id: WayPoint.msg 614 2010-09-24 15:08:46Z jack.oquin $
00016 
00017 float64 latitude                        # latitude in degrees
00018 float64 longitude                       # longitude in degrees
00019 geometry_msgs/Point32 mapxy             # MapXY position
00020 MapID id                                # way-point ID
00021 uint16 index                            # parser index of waypoint
00022 
00023 # way-point flags
00024 bool is_entry                           # lane or zone exit point
00025 bool is_exit                            # lane or zone entry point
00026 bool is_goal                            # this is a goal checkpoint
00027 bool is_lane_change                     # change lanes after here
00028 bool is_spot                            # parking spot
00029 bool is_stop                            # stop line here
00030 bool is_perimeter                       # zone perimeter point
00031 int32 checkpoint_id                     # checkpoint ID or zero
00032 float32 lane_width
00033 
00034 ================================================================================
00035 MSG: geometry_msgs/Point32
00036 # This contains the position of a point in free space(with 32 bits of precision).
00037 # It is recommeded to use Point wherever possible instead of Point32.  
00038 # 
00039 # This recommendation is to promote interoperability.  
00040 #
00041 # This message is designed to take up less space when sending
00042 # lots of points at once, as in the case of a PointCloud.  
00043 
00044 float32 x
00045 float32 y
00046 float32 z
00047 ================================================================================
00048 MSG: art_msgs/MapID
00049 # Road map identifier for segments, lanes and way-points.
00050 # $Id: MapID.msg 614 2010-09-24 15:08:46Z jack.oquin $
00051 
00052 uint16 NULL_ID = 65535
00053 
00054 uint16 seg      # segment ID
00055 uint16 lane     # lane ID
00056 uint16 pt       # way-point ID
00057 
00058 """
00059   __slots__ = ['latitude','longitude','mapxy','id','index','is_entry','is_exit','is_goal','is_lane_change','is_spot','is_stop','is_perimeter','checkpoint_id','lane_width']
00060   _slot_types = ['float64','float64','geometry_msgs/Point32','art_msgs/MapID','uint16','bool','bool','bool','bool','bool','bool','bool','int32','float32']
00061 
00062   def __init__(self, *args, **kwds):
00063     """
00064     Constructor. Any message fields that are implicitly/explicitly
00065     set to None will be assigned a default value. The recommend
00066     use is keyword arguments as this is more robust to future message
00067     changes.  You cannot mix in-order arguments and keyword arguments.
00068 
00069     The available fields are:
00070        latitude,longitude,mapxy,id,index,is_entry,is_exit,is_goal,is_lane_change,is_spot,is_stop,is_perimeter,checkpoint_id,lane_width
00071 
00072     :param args: complete set of field values, in .msg order
00073     :param kwds: use keyword arguments corresponding to message field names
00074     to set specific fields.
00075     """
00076     if args or kwds:
00077       super(WayPoint, self).__init__(*args, **kwds)
00078       #message fields cannot be None, assign default values for those that are
00079       if self.latitude is None:
00080         self.latitude = 0.
00081       if self.longitude is None:
00082         self.longitude = 0.
00083       if self.mapxy is None:
00084         self.mapxy = geometry_msgs.msg.Point32()
00085       if self.id is None:
00086         self.id = art_msgs.msg.MapID()
00087       if self.index is None:
00088         self.index = 0
00089       if self.is_entry is None:
00090         self.is_entry = False
00091       if self.is_exit is None:
00092         self.is_exit = False
00093       if self.is_goal is None:
00094         self.is_goal = False
00095       if self.is_lane_change is None:
00096         self.is_lane_change = False
00097       if self.is_spot is None:
00098         self.is_spot = False
00099       if self.is_stop is None:
00100         self.is_stop = False
00101       if self.is_perimeter is None:
00102         self.is_perimeter = False
00103       if self.checkpoint_id is None:
00104         self.checkpoint_id = 0
00105       if self.lane_width is None:
00106         self.lane_width = 0.
00107     else:
00108       self.latitude = 0.
00109       self.longitude = 0.
00110       self.mapxy = geometry_msgs.msg.Point32()
00111       self.id = art_msgs.msg.MapID()
00112       self.index = 0
00113       self.is_entry = False
00114       self.is_exit = False
00115       self.is_goal = False
00116       self.is_lane_change = False
00117       self.is_spot = False
00118       self.is_stop = False
00119       self.is_perimeter = False
00120       self.checkpoint_id = 0
00121       self.lane_width = 0.
00122 
00123   def _get_types(self):
00124     """
00125     internal API method
00126     """
00127     return self._slot_types
00128 
00129   def serialize(self, buff):
00130     """
00131     serialize message into buffer
00132     :param buff: buffer, ``StringIO``
00133     """
00134     try:
00135       _x = self
00136       buff.write(_struct_2d3f4H7Bif.pack(_x.latitude, _x.longitude, _x.mapxy.x, _x.mapxy.y, _x.mapxy.z, _x.id.seg, _x.id.lane, _x.id.pt, _x.index, _x.is_entry, _x.is_exit, _x.is_goal, _x.is_lane_change, _x.is_spot, _x.is_stop, _x.is_perimeter, _x.checkpoint_id, _x.lane_width))
00137     except struct.error as se: self._check_types(se)
00138     except TypeError as te: self._check_types(te)
00139 
00140   def deserialize(self, str):
00141     """
00142     unpack serialized message in str into this message instance
00143     :param str: byte array of serialized message, ``str``
00144     """
00145     try:
00146       if self.mapxy is None:
00147         self.mapxy = geometry_msgs.msg.Point32()
00148       if self.id is None:
00149         self.id = art_msgs.msg.MapID()
00150       end = 0
00151       _x = self
00152       start = end
00153       end += 51
00154       (_x.latitude, _x.longitude, _x.mapxy.x, _x.mapxy.y, _x.mapxy.z, _x.id.seg, _x.id.lane, _x.id.pt, _x.index, _x.is_entry, _x.is_exit, _x.is_goal, _x.is_lane_change, _x.is_spot, _x.is_stop, _x.is_perimeter, _x.checkpoint_id, _x.lane_width,) = _struct_2d3f4H7Bif.unpack(str[start:end])
00155       self.is_entry = bool(self.is_entry)
00156       self.is_exit = bool(self.is_exit)
00157       self.is_goal = bool(self.is_goal)
00158       self.is_lane_change = bool(self.is_lane_change)
00159       self.is_spot = bool(self.is_spot)
00160       self.is_stop = bool(self.is_stop)
00161       self.is_perimeter = bool(self.is_perimeter)
00162       return self
00163     except struct.error as e:
00164       raise genpy.DeserializationError(e) #most likely buffer underfill
00165 
00166 
00167   def serialize_numpy(self, buff, numpy):
00168     """
00169     serialize message with numpy array types into buffer
00170     :param buff: buffer, ``StringIO``
00171     :param numpy: numpy python module
00172     """
00173     try:
00174       _x = self
00175       buff.write(_struct_2d3f4H7Bif.pack(_x.latitude, _x.longitude, _x.mapxy.x, _x.mapxy.y, _x.mapxy.z, _x.id.seg, _x.id.lane, _x.id.pt, _x.index, _x.is_entry, _x.is_exit, _x.is_goal, _x.is_lane_change, _x.is_spot, _x.is_stop, _x.is_perimeter, _x.checkpoint_id, _x.lane_width))
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.mapxy is None:
00187         self.mapxy = geometry_msgs.msg.Point32()
00188       if self.id is None:
00189         self.id = art_msgs.msg.MapID()
00190       end = 0
00191       _x = self
00192       start = end
00193       end += 51
00194       (_x.latitude, _x.longitude, _x.mapxy.x, _x.mapxy.y, _x.mapxy.z, _x.id.seg, _x.id.lane, _x.id.pt, _x.index, _x.is_entry, _x.is_exit, _x.is_goal, _x.is_lane_change, _x.is_spot, _x.is_stop, _x.is_perimeter, _x.checkpoint_id, _x.lane_width,) = _struct_2d3f4H7Bif.unpack(str[start:end])
00195       self.is_entry = bool(self.is_entry)
00196       self.is_exit = bool(self.is_exit)
00197       self.is_goal = bool(self.is_goal)
00198       self.is_lane_change = bool(self.is_lane_change)
00199       self.is_spot = bool(self.is_spot)
00200       self.is_stop = bool(self.is_stop)
00201       self.is_perimeter = bool(self.is_perimeter)
00202       return self
00203     except struct.error as e:
00204       raise genpy.DeserializationError(e) #most likely buffer underfill
00205 
00206 _struct_I = genpy.struct_I
00207 _struct_2d3f4H7Bif = struct.Struct("<2d3f4H7Bif")


art_msgs
Author(s): Jack O'Quin
autogenerated on Fri Jan 3 2014 11:08:05