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