00001
00002 #ifndef ART_MSGS_MESSAGE_ARTQUADRILATERAL_H
00003 #define ART_MSGS_MESSAGE_ARTQUADRILATERAL_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "geometry_msgs/Polygon.h"
00014 #include "geometry_msgs/Point.h"
00015 #include "art_msgs/MapID.h"
00016 #include "art_msgs/MapID.h"
00017 #include "art_msgs/LaneMarking.h"
00018 #include "art_msgs/LaneMarking.h"
00019
00020 namespace art_msgs
00021 {
00022 template <class ContainerAllocator>
00023 struct ArtQuadrilateral_ : public ros::Message
00024 {
00025 typedef ArtQuadrilateral_<ContainerAllocator> Type;
00026
00027 ArtQuadrilateral_()
00028 : poly()
00029 , midpoint()
00030 , heading(0.0)
00031 , length(0.0)
00032 , poly_id(0)
00033 , is_stop(false)
00034 , is_transition(false)
00035 , contains_way(false)
00036 , start_way()
00037 , end_way()
00038 , left_boundary()
00039 , right_boundary()
00040 {
00041 }
00042
00043 ArtQuadrilateral_(const ContainerAllocator& _alloc)
00044 : poly(_alloc)
00045 , midpoint(_alloc)
00046 , heading(0.0)
00047 , length(0.0)
00048 , poly_id(0)
00049 , is_stop(false)
00050 , is_transition(false)
00051 , contains_way(false)
00052 , start_way(_alloc)
00053 , end_way(_alloc)
00054 , left_boundary(_alloc)
00055 , right_boundary(_alloc)
00056 {
00057 }
00058
00059 typedef ::geometry_msgs::Polygon_<ContainerAllocator> _poly_type;
00060 ::geometry_msgs::Polygon_<ContainerAllocator> poly;
00061
00062 typedef ::geometry_msgs::Point_<ContainerAllocator> _midpoint_type;
00063 ::geometry_msgs::Point_<ContainerAllocator> midpoint;
00064
00065 typedef float _heading_type;
00066 float heading;
00067
00068 typedef float _length_type;
00069 float length;
00070
00071 typedef int32_t _poly_id_type;
00072 int32_t poly_id;
00073
00074 typedef uint8_t _is_stop_type;
00075 uint8_t is_stop;
00076
00077 typedef uint8_t _is_transition_type;
00078 uint8_t is_transition;
00079
00080 typedef uint8_t _contains_way_type;
00081 uint8_t contains_way;
00082
00083 typedef ::art_msgs::MapID_<ContainerAllocator> _start_way_type;
00084 ::art_msgs::MapID_<ContainerAllocator> start_way;
00085
00086 typedef ::art_msgs::MapID_<ContainerAllocator> _end_way_type;
00087 ::art_msgs::MapID_<ContainerAllocator> end_way;
00088
00089 typedef ::art_msgs::LaneMarking_<ContainerAllocator> _left_boundary_type;
00090 ::art_msgs::LaneMarking_<ContainerAllocator> left_boundary;
00091
00092 typedef ::art_msgs::LaneMarking_<ContainerAllocator> _right_boundary_type;
00093 ::art_msgs::LaneMarking_<ContainerAllocator> right_boundary;
00094
00095 enum { bottom_left = 0 };
00096 enum { top_left = 1 };
00097 enum { top_right = 2 };
00098 enum { bottom_right = 3 };
00099 enum { quad_size = 4 };
00100
00101 private:
00102 static const char* __s_getDataType_() { return "art_msgs/ArtQuadrilateral"; }
00103 public:
00104 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00105
00106 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00107
00108 private:
00109 static const char* __s_getMD5Sum_() { return "d704c9f78f17e5d333efb87e5729a41e"; }
00110 public:
00111 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00112
00113 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00114
00115 private:
00116 static const char* __s_getMessageDefinition_() { return "# ART quadrilateral polygon\n\
00117 # $Id: ArtQuadrilateral.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\
00118 \n\
00119 # Each of these polygons is a quadrilateral. The four vertex points\n\
00120 # are ordered relative to the heading of the lane containing it.\n\
00121 \n\
00122 geometry_msgs/Polygon poly\n\
00123 int32 bottom_left = 0\n\
00124 int32 top_left = 1\n\
00125 int32 top_right = 2\n\
00126 int32 bottom_right = 3\n\
00127 int32 quad_size = 4\n\
00128 \n\
00129 geometry_msgs/Point midpoint # Middle of the polygon\n\
00130 \n\
00131 float32 heading # average of right and left boundary headings\n\
00132 float32 length # length of the polygon\n\
00133 int32 poly_id # unique MapLanes ID\n\
00134 \n\
00135 bool is_stop # this poly has a stop waypoint\n\
00136 bool is_transition # not a lane polygon, no waypoint\n\
00137 bool contains_way # both start_way and end_way are the contained waypoint\n\
00138 \n\
00139 MapID start_way\n\
00140 MapID end_way\n\
00141 \n\
00142 LaneMarking left_boundary\n\
00143 LaneMarking right_boundary\n\
00144 \n\
00145 ================================================================================\n\
00146 MSG: geometry_msgs/Polygon\n\
00147 #A specification of a polygon where the first and last points are assumed to be connected\n\
00148 geometry_msgs/Point32[] points\n\
00149 \n\
00150 ================================================================================\n\
00151 MSG: geometry_msgs/Point32\n\
00152 # This contains the position of a point in free space(with 32 bits of precision).\n\
00153 # It is recommeded to use Point wherever possible instead of Point32. \n\
00154 # \n\
00155 # This recommendation is to promote interoperability. \n\
00156 #\n\
00157 # This message is designed to take up less space when sending\n\
00158 # lots of points at once, as in the case of a PointCloud. \n\
00159 \n\
00160 float32 x\n\
00161 float32 y\n\
00162 float32 z\n\
00163 ================================================================================\n\
00164 MSG: geometry_msgs/Point\n\
00165 # This contains the position of a point in free space\n\
00166 float64 x\n\
00167 float64 y\n\
00168 float64 z\n\
00169 \n\
00170 ================================================================================\n\
00171 MSG: art_msgs/MapID\n\
00172 # Road map identifier for segments, lanes and way-points.\n\
00173 # $Id: MapID.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\
00174 \n\
00175 uint16 NULL_ID = 65535\n\
00176 \n\
00177 uint16 seg # segment ID\n\
00178 uint16 lane # lane ID\n\
00179 uint16 pt # way-point ID\n\
00180 \n\
00181 ================================================================================\n\
00182 MSG: art_msgs/LaneMarking\n\
00183 # Route Network Definition File lane marking\n\
00184 # $Id: LaneMarking.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\
00185 \n\
00186 int16 DOUBLE_YELLOW = 0\n\
00187 int16 SOLID_YELLOW = 1\n\
00188 int16 SOLID_WHITE = 2\n\
00189 int16 BROKEN_WHITE = 3\n\
00190 int16 UNDEFINED = 4\n\
00191 \n\
00192 int16 lane_marking\n\
00193 \n\
00194 "; }
00195 public:
00196 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00197
00198 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00199
00200 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00201 {
00202 ros::serialization::OStream stream(write_ptr, 1000000000);
00203 ros::serialization::serialize(stream, poly);
00204 ros::serialization::serialize(stream, midpoint);
00205 ros::serialization::serialize(stream, heading);
00206 ros::serialization::serialize(stream, length);
00207 ros::serialization::serialize(stream, poly_id);
00208 ros::serialization::serialize(stream, is_stop);
00209 ros::serialization::serialize(stream, is_transition);
00210 ros::serialization::serialize(stream, contains_way);
00211 ros::serialization::serialize(stream, start_way);
00212 ros::serialization::serialize(stream, end_way);
00213 ros::serialization::serialize(stream, left_boundary);
00214 ros::serialization::serialize(stream, right_boundary);
00215 return stream.getData();
00216 }
00217
00218 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00219 {
00220 ros::serialization::IStream stream(read_ptr, 1000000000);
00221 ros::serialization::deserialize(stream, poly);
00222 ros::serialization::deserialize(stream, midpoint);
00223 ros::serialization::deserialize(stream, heading);
00224 ros::serialization::deserialize(stream, length);
00225 ros::serialization::deserialize(stream, poly_id);
00226 ros::serialization::deserialize(stream, is_stop);
00227 ros::serialization::deserialize(stream, is_transition);
00228 ros::serialization::deserialize(stream, contains_way);
00229 ros::serialization::deserialize(stream, start_way);
00230 ros::serialization::deserialize(stream, end_way);
00231 ros::serialization::deserialize(stream, left_boundary);
00232 ros::serialization::deserialize(stream, right_boundary);
00233 return stream.getData();
00234 }
00235
00236 ROS_DEPRECATED virtual uint32_t serializationLength() const
00237 {
00238 uint32_t size = 0;
00239 size += ros::serialization::serializationLength(poly);
00240 size += ros::serialization::serializationLength(midpoint);
00241 size += ros::serialization::serializationLength(heading);
00242 size += ros::serialization::serializationLength(length);
00243 size += ros::serialization::serializationLength(poly_id);
00244 size += ros::serialization::serializationLength(is_stop);
00245 size += ros::serialization::serializationLength(is_transition);
00246 size += ros::serialization::serializationLength(contains_way);
00247 size += ros::serialization::serializationLength(start_way);
00248 size += ros::serialization::serializationLength(end_way);
00249 size += ros::serialization::serializationLength(left_boundary);
00250 size += ros::serialization::serializationLength(right_boundary);
00251 return size;
00252 }
00253
00254 typedef boost::shared_ptr< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> > Ptr;
00255 typedef boost::shared_ptr< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> const> ConstPtr;
00256 };
00257 typedef ::art_msgs::ArtQuadrilateral_<std::allocator<void> > ArtQuadrilateral;
00258
00259 typedef boost::shared_ptr< ::art_msgs::ArtQuadrilateral> ArtQuadrilateralPtr;
00260 typedef boost::shared_ptr< ::art_msgs::ArtQuadrilateral const> ArtQuadrilateralConstPtr;
00261
00262
00263 template<typename ContainerAllocator>
00264 std::ostream& operator<<(std::ostream& s, const ::art_msgs::ArtQuadrilateral_<ContainerAllocator> & v)
00265 {
00266 ros::message_operations::Printer< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> >::stream(s, "", v);
00267 return s;}
00268
00269 }
00270
00271 namespace ros
00272 {
00273 namespace message_traits
00274 {
00275 template<class ContainerAllocator>
00276 struct MD5Sum< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> > {
00277 static const char* value()
00278 {
00279 return "d704c9f78f17e5d333efb87e5729a41e";
00280 }
00281
00282 static const char* value(const ::art_msgs::ArtQuadrilateral_<ContainerAllocator> &) { return value(); }
00283 static const uint64_t static_value1 = 0xd704c9f78f17e5d3ULL;
00284 static const uint64_t static_value2 = 0x33efb87e5729a41eULL;
00285 };
00286
00287 template<class ContainerAllocator>
00288 struct DataType< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> > {
00289 static const char* value()
00290 {
00291 return "art_msgs/ArtQuadrilateral";
00292 }
00293
00294 static const char* value(const ::art_msgs::ArtQuadrilateral_<ContainerAllocator> &) { return value(); }
00295 };
00296
00297 template<class ContainerAllocator>
00298 struct Definition< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> > {
00299 static const char* value()
00300 {
00301 return "# ART quadrilateral polygon\n\
00302 # $Id: ArtQuadrilateral.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\
00303 \n\
00304 # Each of these polygons is a quadrilateral. The four vertex points\n\
00305 # are ordered relative to the heading of the lane containing it.\n\
00306 \n\
00307 geometry_msgs/Polygon poly\n\
00308 int32 bottom_left = 0\n\
00309 int32 top_left = 1\n\
00310 int32 top_right = 2\n\
00311 int32 bottom_right = 3\n\
00312 int32 quad_size = 4\n\
00313 \n\
00314 geometry_msgs/Point midpoint # Middle of the polygon\n\
00315 \n\
00316 float32 heading # average of right and left boundary headings\n\
00317 float32 length # length of the polygon\n\
00318 int32 poly_id # unique MapLanes ID\n\
00319 \n\
00320 bool is_stop # this poly has a stop waypoint\n\
00321 bool is_transition # not a lane polygon, no waypoint\n\
00322 bool contains_way # both start_way and end_way are the contained waypoint\n\
00323 \n\
00324 MapID start_way\n\
00325 MapID end_way\n\
00326 \n\
00327 LaneMarking left_boundary\n\
00328 LaneMarking right_boundary\n\
00329 \n\
00330 ================================================================================\n\
00331 MSG: geometry_msgs/Polygon\n\
00332 #A specification of a polygon where the first and last points are assumed to be connected\n\
00333 geometry_msgs/Point32[] points\n\
00334 \n\
00335 ================================================================================\n\
00336 MSG: geometry_msgs/Point32\n\
00337 # This contains the position of a point in free space(with 32 bits of precision).\n\
00338 # It is recommeded to use Point wherever possible instead of Point32. \n\
00339 # \n\
00340 # This recommendation is to promote interoperability. \n\
00341 #\n\
00342 # This message is designed to take up less space when sending\n\
00343 # lots of points at once, as in the case of a PointCloud. \n\
00344 \n\
00345 float32 x\n\
00346 float32 y\n\
00347 float32 z\n\
00348 ================================================================================\n\
00349 MSG: geometry_msgs/Point\n\
00350 # This contains the position of a point in free space\n\
00351 float64 x\n\
00352 float64 y\n\
00353 float64 z\n\
00354 \n\
00355 ================================================================================\n\
00356 MSG: art_msgs/MapID\n\
00357 # Road map identifier for segments, lanes and way-points.\n\
00358 # $Id: MapID.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\
00359 \n\
00360 uint16 NULL_ID = 65535\n\
00361 \n\
00362 uint16 seg # segment ID\n\
00363 uint16 lane # lane ID\n\
00364 uint16 pt # way-point ID\n\
00365 \n\
00366 ================================================================================\n\
00367 MSG: art_msgs/LaneMarking\n\
00368 # Route Network Definition File lane marking\n\
00369 # $Id: LaneMarking.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\
00370 \n\
00371 int16 DOUBLE_YELLOW = 0\n\
00372 int16 SOLID_YELLOW = 1\n\
00373 int16 SOLID_WHITE = 2\n\
00374 int16 BROKEN_WHITE = 3\n\
00375 int16 UNDEFINED = 4\n\
00376 \n\
00377 int16 lane_marking\n\
00378 \n\
00379 ";
00380 }
00381
00382 static const char* value(const ::art_msgs::ArtQuadrilateral_<ContainerAllocator> &) { return value(); }
00383 };
00384
00385 }
00386 }
00387
00388 namespace ros
00389 {
00390 namespace serialization
00391 {
00392
00393 template<class ContainerAllocator> struct Serializer< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> >
00394 {
00395 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00396 {
00397 stream.next(m.poly);
00398 stream.next(m.midpoint);
00399 stream.next(m.heading);
00400 stream.next(m.length);
00401 stream.next(m.poly_id);
00402 stream.next(m.is_stop);
00403 stream.next(m.is_transition);
00404 stream.next(m.contains_way);
00405 stream.next(m.start_way);
00406 stream.next(m.end_way);
00407 stream.next(m.left_boundary);
00408 stream.next(m.right_boundary);
00409 }
00410
00411 ROS_DECLARE_ALLINONE_SERIALIZER;
00412 };
00413 }
00414 }
00415
00416 namespace ros
00417 {
00418 namespace message_operations
00419 {
00420
00421 template<class ContainerAllocator>
00422 struct Printer< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> >
00423 {
00424 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::art_msgs::ArtQuadrilateral_<ContainerAllocator> & v)
00425 {
00426 s << indent << "poly: ";
00427 s << std::endl;
00428 Printer< ::geometry_msgs::Polygon_<ContainerAllocator> >::stream(s, indent + " ", v.poly);
00429 s << indent << "midpoint: ";
00430 s << std::endl;
00431 Printer< ::geometry_msgs::Point_<ContainerAllocator> >::stream(s, indent + " ", v.midpoint);
00432 s << indent << "heading: ";
00433 Printer<float>::stream(s, indent + " ", v.heading);
00434 s << indent << "length: ";
00435 Printer<float>::stream(s, indent + " ", v.length);
00436 s << indent << "poly_id: ";
00437 Printer<int32_t>::stream(s, indent + " ", v.poly_id);
00438 s << indent << "is_stop: ";
00439 Printer<uint8_t>::stream(s, indent + " ", v.is_stop);
00440 s << indent << "is_transition: ";
00441 Printer<uint8_t>::stream(s, indent + " ", v.is_transition);
00442 s << indent << "contains_way: ";
00443 Printer<uint8_t>::stream(s, indent + " ", v.contains_way);
00444 s << indent << "start_way: ";
00445 s << std::endl;
00446 Printer< ::art_msgs::MapID_<ContainerAllocator> >::stream(s, indent + " ", v.start_way);
00447 s << indent << "end_way: ";
00448 s << std::endl;
00449 Printer< ::art_msgs::MapID_<ContainerAllocator> >::stream(s, indent + " ", v.end_way);
00450 s << indent << "left_boundary: ";
00451 s << std::endl;
00452 Printer< ::art_msgs::LaneMarking_<ContainerAllocator> >::stream(s, indent + " ", v.left_boundary);
00453 s << indent << "right_boundary: ";
00454 s << std::endl;
00455 Printer< ::art_msgs::LaneMarking_<ContainerAllocator> >::stream(s, indent + " ", v.right_boundary);
00456 }
00457 };
00458
00459
00460 }
00461 }
00462
00463 #endif // ART_MSGS_MESSAGE_ARTQUADRILATERAL_H
00464