00001
00002 #ifndef ART_MSGS_MESSAGE_ARTQUADRILATERAL_H
00003 #define ART_MSGS_MESSAGE_ARTQUADRILATERAL_H
00004 #include <string>
00005 #include <vector>
00006 #include <map>
00007 #include <ostream>
00008 #include "ros/serialization.h"
00009 #include "ros/builtin_message_traits.h"
00010 #include "ros/message_operations.h"
00011 #include "ros/time.h"
00012
00013 #include "ros/macros.h"
00014
00015 #include "ros/assert.h"
00016
00017 #include "geometry_msgs/Polygon.h"
00018 #include "geometry_msgs/Point.h"
00019 #include "art_msgs/MapID.h"
00020 #include "art_msgs/MapID.h"
00021 #include "art_msgs/LaneMarking.h"
00022 #include "art_msgs/LaneMarking.h"
00023
00024 namespace art_msgs
00025 {
00026 template <class ContainerAllocator>
00027 struct ArtQuadrilateral_ {
00028 typedef ArtQuadrilateral_<ContainerAllocator> Type;
00029
00030 ArtQuadrilateral_()
00031 : poly()
00032 , midpoint()
00033 , heading(0.0)
00034 , length(0.0)
00035 , poly_id(0)
00036 , is_stop(false)
00037 , is_transition(false)
00038 , contains_way(false)
00039 , start_way()
00040 , end_way()
00041 , left_boundary()
00042 , right_boundary()
00043 {
00044 }
00045
00046 ArtQuadrilateral_(const ContainerAllocator& _alloc)
00047 : poly(_alloc)
00048 , midpoint(_alloc)
00049 , heading(0.0)
00050 , length(0.0)
00051 , poly_id(0)
00052 , is_stop(false)
00053 , is_transition(false)
00054 , contains_way(false)
00055 , start_way(_alloc)
00056 , end_way(_alloc)
00057 , left_boundary(_alloc)
00058 , right_boundary(_alloc)
00059 {
00060 }
00061
00062 typedef ::geometry_msgs::Polygon_<ContainerAllocator> _poly_type;
00063 ::geometry_msgs::Polygon_<ContainerAllocator> poly;
00064
00065 typedef ::geometry_msgs::Point_<ContainerAllocator> _midpoint_type;
00066 ::geometry_msgs::Point_<ContainerAllocator> midpoint;
00067
00068 typedef float _heading_type;
00069 float heading;
00070
00071 typedef float _length_type;
00072 float length;
00073
00074 typedef int32_t _poly_id_type;
00075 int32_t poly_id;
00076
00077 typedef uint8_t _is_stop_type;
00078 uint8_t is_stop;
00079
00080 typedef uint8_t _is_transition_type;
00081 uint8_t is_transition;
00082
00083 typedef uint8_t _contains_way_type;
00084 uint8_t contains_way;
00085
00086 typedef ::art_msgs::MapID_<ContainerAllocator> _start_way_type;
00087 ::art_msgs::MapID_<ContainerAllocator> start_way;
00088
00089 typedef ::art_msgs::MapID_<ContainerAllocator> _end_way_type;
00090 ::art_msgs::MapID_<ContainerAllocator> end_way;
00091
00092 typedef ::art_msgs::LaneMarking_<ContainerAllocator> _left_boundary_type;
00093 ::art_msgs::LaneMarking_<ContainerAllocator> left_boundary;
00094
00095 typedef ::art_msgs::LaneMarking_<ContainerAllocator> _right_boundary_type;
00096 ::art_msgs::LaneMarking_<ContainerAllocator> right_boundary;
00097
00098 enum { bottom_left = 0 };
00099 enum { top_left = 1 };
00100 enum { top_right = 2 };
00101 enum { bottom_right = 3 };
00102 enum { quad_size = 4 };
00103
00104 typedef boost::shared_ptr< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> > Ptr;
00105 typedef boost::shared_ptr< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> const> ConstPtr;
00106 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00107 };
00108 typedef ::art_msgs::ArtQuadrilateral_<std::allocator<void> > ArtQuadrilateral;
00109
00110 typedef boost::shared_ptr< ::art_msgs::ArtQuadrilateral> ArtQuadrilateralPtr;
00111 typedef boost::shared_ptr< ::art_msgs::ArtQuadrilateral const> ArtQuadrilateralConstPtr;
00112
00113
00114 template<typename ContainerAllocator>
00115 std::ostream& operator<<(std::ostream& s, const ::art_msgs::ArtQuadrilateral_<ContainerAllocator> & v)
00116 {
00117 ros::message_operations::Printer< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> >::stream(s, "", v);
00118 return s;}
00119
00120 }
00121
00122 namespace ros
00123 {
00124 namespace message_traits
00125 {
00126 template<class ContainerAllocator> struct IsMessage< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> > : public TrueType {};
00127 template<class ContainerAllocator> struct IsMessage< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> const> : public TrueType {};
00128 template<class ContainerAllocator>
00129 struct MD5Sum< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> > {
00130 static const char* value()
00131 {
00132 return "d704c9f78f17e5d333efb87e5729a41e";
00133 }
00134
00135 static const char* value(const ::art_msgs::ArtQuadrilateral_<ContainerAllocator> &) { return value(); }
00136 static const uint64_t static_value1 = 0xd704c9f78f17e5d3ULL;
00137 static const uint64_t static_value2 = 0x33efb87e5729a41eULL;
00138 };
00139
00140 template<class ContainerAllocator>
00141 struct DataType< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> > {
00142 static const char* value()
00143 {
00144 return "art_msgs/ArtQuadrilateral";
00145 }
00146
00147 static const char* value(const ::art_msgs::ArtQuadrilateral_<ContainerAllocator> &) { return value(); }
00148 };
00149
00150 template<class ContainerAllocator>
00151 struct Definition< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> > {
00152 static const char* value()
00153 {
00154 return "# ART quadrilateral polygon\n\
00155 # $Id: ArtQuadrilateral.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\
00156 \n\
00157 # Each of these polygons is a quadrilateral. The four vertex points\n\
00158 # are ordered relative to the heading of the lane containing it.\n\
00159 \n\
00160 geometry_msgs/Polygon poly\n\
00161 int32 bottom_left = 0\n\
00162 int32 top_left = 1\n\
00163 int32 top_right = 2\n\
00164 int32 bottom_right = 3\n\
00165 int32 quad_size = 4\n\
00166 \n\
00167 geometry_msgs/Point midpoint # Middle of the polygon\n\
00168 \n\
00169 float32 heading # average of right and left boundary headings\n\
00170 float32 length # length of the polygon\n\
00171 int32 poly_id # unique MapLanes ID\n\
00172 \n\
00173 bool is_stop # this poly has a stop waypoint\n\
00174 bool is_transition # not a lane polygon, no waypoint\n\
00175 bool contains_way # both start_way and end_way are the contained waypoint\n\
00176 \n\
00177 MapID start_way\n\
00178 MapID end_way\n\
00179 \n\
00180 LaneMarking left_boundary\n\
00181 LaneMarking right_boundary\n\
00182 \n\
00183 ================================================================================\n\
00184 MSG: geometry_msgs/Polygon\n\
00185 #A specification of a polygon where the first and last points are assumed to be connected\n\
00186 Point32[] points\n\
00187 \n\
00188 ================================================================================\n\
00189 MSG: geometry_msgs/Point32\n\
00190 # This contains the position of a point in free space(with 32 bits of precision).\n\
00191 # It is recommeded to use Point wherever possible instead of Point32. \n\
00192 # \n\
00193 # This recommendation is to promote interoperability. \n\
00194 #\n\
00195 # This message is designed to take up less space when sending\n\
00196 # lots of points at once, as in the case of a PointCloud. \n\
00197 \n\
00198 float32 x\n\
00199 float32 y\n\
00200 float32 z\n\
00201 ================================================================================\n\
00202 MSG: geometry_msgs/Point\n\
00203 # This contains the position of a point in free space\n\
00204 float64 x\n\
00205 float64 y\n\
00206 float64 z\n\
00207 \n\
00208 ================================================================================\n\
00209 MSG: art_msgs/MapID\n\
00210 # Road map identifier for segments, lanes and way-points.\n\
00211 # $Id: MapID.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\
00212 \n\
00213 uint16 NULL_ID = 65535\n\
00214 \n\
00215 uint16 seg # segment ID\n\
00216 uint16 lane # lane ID\n\
00217 uint16 pt # way-point ID\n\
00218 \n\
00219 ================================================================================\n\
00220 MSG: art_msgs/LaneMarking\n\
00221 # Route Network Definition File lane marking\n\
00222 # $Id: LaneMarking.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\
00223 \n\
00224 int16 DOUBLE_YELLOW = 0\n\
00225 int16 SOLID_YELLOW = 1\n\
00226 int16 SOLID_WHITE = 2\n\
00227 int16 BROKEN_WHITE = 3\n\
00228 int16 UNDEFINED = 4\n\
00229 \n\
00230 int16 lane_marking\n\
00231 \n\
00232 ";
00233 }
00234
00235 static const char* value(const ::art_msgs::ArtQuadrilateral_<ContainerAllocator> &) { return value(); }
00236 };
00237
00238 }
00239 }
00240
00241 namespace ros
00242 {
00243 namespace serialization
00244 {
00245
00246 template<class ContainerAllocator> struct Serializer< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> >
00247 {
00248 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00249 {
00250 stream.next(m.poly);
00251 stream.next(m.midpoint);
00252 stream.next(m.heading);
00253 stream.next(m.length);
00254 stream.next(m.poly_id);
00255 stream.next(m.is_stop);
00256 stream.next(m.is_transition);
00257 stream.next(m.contains_way);
00258 stream.next(m.start_way);
00259 stream.next(m.end_way);
00260 stream.next(m.left_boundary);
00261 stream.next(m.right_boundary);
00262 }
00263
00264 ROS_DECLARE_ALLINONE_SERIALIZER;
00265 };
00266 }
00267 }
00268
00269 namespace ros
00270 {
00271 namespace message_operations
00272 {
00273
00274 template<class ContainerAllocator>
00275 struct Printer< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> >
00276 {
00277 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::art_msgs::ArtQuadrilateral_<ContainerAllocator> & v)
00278 {
00279 s << indent << "poly: ";
00280 s << std::endl;
00281 Printer< ::geometry_msgs::Polygon_<ContainerAllocator> >::stream(s, indent + " ", v.poly);
00282 s << indent << "midpoint: ";
00283 s << std::endl;
00284 Printer< ::geometry_msgs::Point_<ContainerAllocator> >::stream(s, indent + " ", v.midpoint);
00285 s << indent << "heading: ";
00286 Printer<float>::stream(s, indent + " ", v.heading);
00287 s << indent << "length: ";
00288 Printer<float>::stream(s, indent + " ", v.length);
00289 s << indent << "poly_id: ";
00290 Printer<int32_t>::stream(s, indent + " ", v.poly_id);
00291 s << indent << "is_stop: ";
00292 Printer<uint8_t>::stream(s, indent + " ", v.is_stop);
00293 s << indent << "is_transition: ";
00294 Printer<uint8_t>::stream(s, indent + " ", v.is_transition);
00295 s << indent << "contains_way: ";
00296 Printer<uint8_t>::stream(s, indent + " ", v.contains_way);
00297 s << indent << "start_way: ";
00298 s << std::endl;
00299 Printer< ::art_msgs::MapID_<ContainerAllocator> >::stream(s, indent + " ", v.start_way);
00300 s << indent << "end_way: ";
00301 s << std::endl;
00302 Printer< ::art_msgs::MapID_<ContainerAllocator> >::stream(s, indent + " ", v.end_way);
00303 s << indent << "left_boundary: ";
00304 s << std::endl;
00305 Printer< ::art_msgs::LaneMarking_<ContainerAllocator> >::stream(s, indent + " ", v.left_boundary);
00306 s << indent << "right_boundary: ";
00307 s << std::endl;
00308 Printer< ::art_msgs::LaneMarking_<ContainerAllocator> >::stream(s, indent + " ", v.right_boundary);
00309 }
00310 };
00311
00312
00313 }
00314 }
00315
00316 #endif // ART_MSGS_MESSAGE_ARTQUADRILATERAL_H
00317