$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-art_vehicle/doc_stacks/2013-03-01_14-08-11.497537/art_vehicle/art_msgs/msg/ArtQuadrilateral.msg */ 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 private: 00105 static const char* __s_getDataType_() { return "art_msgs/ArtQuadrilateral"; } 00106 public: 00107 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00108 00109 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00110 00111 private: 00112 static const char* __s_getMD5Sum_() { return "d704c9f78f17e5d333efb87e5729a41e"; } 00113 public: 00114 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00115 00116 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00117 00118 private: 00119 static const char* __s_getMessageDefinition_() { return "# ART quadrilateral polygon\n\ 00120 # $Id: ArtQuadrilateral.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\ 00121 \n\ 00122 # Each of these polygons is a quadrilateral. The four vertex points\n\ 00123 # are ordered relative to the heading of the lane containing it.\n\ 00124 \n\ 00125 geometry_msgs/Polygon poly\n\ 00126 int32 bottom_left = 0\n\ 00127 int32 top_left = 1\n\ 00128 int32 top_right = 2\n\ 00129 int32 bottom_right = 3\n\ 00130 int32 quad_size = 4\n\ 00131 \n\ 00132 geometry_msgs/Point midpoint # Middle of the polygon\n\ 00133 \n\ 00134 float32 heading # average of right and left boundary headings\n\ 00135 float32 length # length of the polygon\n\ 00136 int32 poly_id # unique MapLanes ID\n\ 00137 \n\ 00138 bool is_stop # this poly has a stop waypoint\n\ 00139 bool is_transition # not a lane polygon, no waypoint\n\ 00140 bool contains_way # both start_way and end_way are the contained waypoint\n\ 00141 \n\ 00142 MapID start_way\n\ 00143 MapID end_way\n\ 00144 \n\ 00145 LaneMarking left_boundary\n\ 00146 LaneMarking right_boundary\n\ 00147 \n\ 00148 ================================================================================\n\ 00149 MSG: geometry_msgs/Polygon\n\ 00150 #A specification of a polygon where the first and last points are assumed to be connected\n\ 00151 geometry_msgs/Point32[] points\n\ 00152 \n\ 00153 ================================================================================\n\ 00154 MSG: geometry_msgs/Point32\n\ 00155 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00156 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00157 # \n\ 00158 # This recommendation is to promote interoperability. \n\ 00159 #\n\ 00160 # This message is designed to take up less space when sending\n\ 00161 # lots of points at once, as in the case of a PointCloud. \n\ 00162 \n\ 00163 float32 x\n\ 00164 float32 y\n\ 00165 float32 z\n\ 00166 ================================================================================\n\ 00167 MSG: geometry_msgs/Point\n\ 00168 # This contains the position of a point in free space\n\ 00169 float64 x\n\ 00170 float64 y\n\ 00171 float64 z\n\ 00172 \n\ 00173 ================================================================================\n\ 00174 MSG: art_msgs/MapID\n\ 00175 # Road map identifier for segments, lanes and way-points.\n\ 00176 # $Id: MapID.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\ 00177 \n\ 00178 uint16 NULL_ID = 65535\n\ 00179 \n\ 00180 uint16 seg # segment ID\n\ 00181 uint16 lane # lane ID\n\ 00182 uint16 pt # way-point ID\n\ 00183 \n\ 00184 ================================================================================\n\ 00185 MSG: art_msgs/LaneMarking\n\ 00186 # Route Network Definition File lane marking\n\ 00187 # $Id: LaneMarking.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\ 00188 \n\ 00189 int16 DOUBLE_YELLOW = 0\n\ 00190 int16 SOLID_YELLOW = 1\n\ 00191 int16 SOLID_WHITE = 2\n\ 00192 int16 BROKEN_WHITE = 3\n\ 00193 int16 UNDEFINED = 4\n\ 00194 \n\ 00195 int16 lane_marking\n\ 00196 \n\ 00197 "; } 00198 public: 00199 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00200 00201 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00202 00203 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00204 { 00205 ros::serialization::OStream stream(write_ptr, 1000000000); 00206 ros::serialization::serialize(stream, poly); 00207 ros::serialization::serialize(stream, midpoint); 00208 ros::serialization::serialize(stream, heading); 00209 ros::serialization::serialize(stream, length); 00210 ros::serialization::serialize(stream, poly_id); 00211 ros::serialization::serialize(stream, is_stop); 00212 ros::serialization::serialize(stream, is_transition); 00213 ros::serialization::serialize(stream, contains_way); 00214 ros::serialization::serialize(stream, start_way); 00215 ros::serialization::serialize(stream, end_way); 00216 ros::serialization::serialize(stream, left_boundary); 00217 ros::serialization::serialize(stream, right_boundary); 00218 return stream.getData(); 00219 } 00220 00221 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00222 { 00223 ros::serialization::IStream stream(read_ptr, 1000000000); 00224 ros::serialization::deserialize(stream, poly); 00225 ros::serialization::deserialize(stream, midpoint); 00226 ros::serialization::deserialize(stream, heading); 00227 ros::serialization::deserialize(stream, length); 00228 ros::serialization::deserialize(stream, poly_id); 00229 ros::serialization::deserialize(stream, is_stop); 00230 ros::serialization::deserialize(stream, is_transition); 00231 ros::serialization::deserialize(stream, contains_way); 00232 ros::serialization::deserialize(stream, start_way); 00233 ros::serialization::deserialize(stream, end_way); 00234 ros::serialization::deserialize(stream, left_boundary); 00235 ros::serialization::deserialize(stream, right_boundary); 00236 return stream.getData(); 00237 } 00238 00239 ROS_DEPRECATED virtual uint32_t serializationLength() const 00240 { 00241 uint32_t size = 0; 00242 size += ros::serialization::serializationLength(poly); 00243 size += ros::serialization::serializationLength(midpoint); 00244 size += ros::serialization::serializationLength(heading); 00245 size += ros::serialization::serializationLength(length); 00246 size += ros::serialization::serializationLength(poly_id); 00247 size += ros::serialization::serializationLength(is_stop); 00248 size += ros::serialization::serializationLength(is_transition); 00249 size += ros::serialization::serializationLength(contains_way); 00250 size += ros::serialization::serializationLength(start_way); 00251 size += ros::serialization::serializationLength(end_way); 00252 size += ros::serialization::serializationLength(left_boundary); 00253 size += ros::serialization::serializationLength(right_boundary); 00254 return size; 00255 } 00256 00257 typedef boost::shared_ptr< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> > Ptr; 00258 typedef boost::shared_ptr< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> const> ConstPtr; 00259 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00260 }; // struct ArtQuadrilateral 00261 typedef ::art_msgs::ArtQuadrilateral_<std::allocator<void> > ArtQuadrilateral; 00262 00263 typedef boost::shared_ptr< ::art_msgs::ArtQuadrilateral> ArtQuadrilateralPtr; 00264 typedef boost::shared_ptr< ::art_msgs::ArtQuadrilateral const> ArtQuadrilateralConstPtr; 00265 00266 00267 template<typename ContainerAllocator> 00268 std::ostream& operator<<(std::ostream& s, const ::art_msgs::ArtQuadrilateral_<ContainerAllocator> & v) 00269 { 00270 ros::message_operations::Printer< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> >::stream(s, "", v); 00271 return s;} 00272 00273 } // namespace art_msgs 00274 00275 namespace ros 00276 { 00277 namespace message_traits 00278 { 00279 template<class ContainerAllocator> struct IsMessage< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> > : public TrueType {}; 00280 template<class ContainerAllocator> struct IsMessage< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> const> : public TrueType {}; 00281 template<class ContainerAllocator> 00282 struct MD5Sum< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> > { 00283 static const char* value() 00284 { 00285 return "d704c9f78f17e5d333efb87e5729a41e"; 00286 } 00287 00288 static const char* value(const ::art_msgs::ArtQuadrilateral_<ContainerAllocator> &) { return value(); } 00289 static const uint64_t static_value1 = 0xd704c9f78f17e5d3ULL; 00290 static const uint64_t static_value2 = 0x33efb87e5729a41eULL; 00291 }; 00292 00293 template<class ContainerAllocator> 00294 struct DataType< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> > { 00295 static const char* value() 00296 { 00297 return "art_msgs/ArtQuadrilateral"; 00298 } 00299 00300 static const char* value(const ::art_msgs::ArtQuadrilateral_<ContainerAllocator> &) { return value(); } 00301 }; 00302 00303 template<class ContainerAllocator> 00304 struct Definition< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> > { 00305 static const char* value() 00306 { 00307 return "# ART quadrilateral polygon\n\ 00308 # $Id: ArtQuadrilateral.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\ 00309 \n\ 00310 # Each of these polygons is a quadrilateral. The four vertex points\n\ 00311 # are ordered relative to the heading of the lane containing it.\n\ 00312 \n\ 00313 geometry_msgs/Polygon poly\n\ 00314 int32 bottom_left = 0\n\ 00315 int32 top_left = 1\n\ 00316 int32 top_right = 2\n\ 00317 int32 bottom_right = 3\n\ 00318 int32 quad_size = 4\n\ 00319 \n\ 00320 geometry_msgs/Point midpoint # Middle of the polygon\n\ 00321 \n\ 00322 float32 heading # average of right and left boundary headings\n\ 00323 float32 length # length of the polygon\n\ 00324 int32 poly_id # unique MapLanes ID\n\ 00325 \n\ 00326 bool is_stop # this poly has a stop waypoint\n\ 00327 bool is_transition # not a lane polygon, no waypoint\n\ 00328 bool contains_way # both start_way and end_way are the contained waypoint\n\ 00329 \n\ 00330 MapID start_way\n\ 00331 MapID end_way\n\ 00332 \n\ 00333 LaneMarking left_boundary\n\ 00334 LaneMarking right_boundary\n\ 00335 \n\ 00336 ================================================================================\n\ 00337 MSG: geometry_msgs/Polygon\n\ 00338 #A specification of a polygon where the first and last points are assumed to be connected\n\ 00339 geometry_msgs/Point32[] points\n\ 00340 \n\ 00341 ================================================================================\n\ 00342 MSG: geometry_msgs/Point32\n\ 00343 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00344 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00345 # \n\ 00346 # This recommendation is to promote interoperability. \n\ 00347 #\n\ 00348 # This message is designed to take up less space when sending\n\ 00349 # lots of points at once, as in the case of a PointCloud. \n\ 00350 \n\ 00351 float32 x\n\ 00352 float32 y\n\ 00353 float32 z\n\ 00354 ================================================================================\n\ 00355 MSG: geometry_msgs/Point\n\ 00356 # This contains the position of a point in free space\n\ 00357 float64 x\n\ 00358 float64 y\n\ 00359 float64 z\n\ 00360 \n\ 00361 ================================================================================\n\ 00362 MSG: art_msgs/MapID\n\ 00363 # Road map identifier for segments, lanes and way-points.\n\ 00364 # $Id: MapID.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\ 00365 \n\ 00366 uint16 NULL_ID = 65535\n\ 00367 \n\ 00368 uint16 seg # segment ID\n\ 00369 uint16 lane # lane ID\n\ 00370 uint16 pt # way-point ID\n\ 00371 \n\ 00372 ================================================================================\n\ 00373 MSG: art_msgs/LaneMarking\n\ 00374 # Route Network Definition File lane marking\n\ 00375 # $Id: LaneMarking.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\ 00376 \n\ 00377 int16 DOUBLE_YELLOW = 0\n\ 00378 int16 SOLID_YELLOW = 1\n\ 00379 int16 SOLID_WHITE = 2\n\ 00380 int16 BROKEN_WHITE = 3\n\ 00381 int16 UNDEFINED = 4\n\ 00382 \n\ 00383 int16 lane_marking\n\ 00384 \n\ 00385 "; 00386 } 00387 00388 static const char* value(const ::art_msgs::ArtQuadrilateral_<ContainerAllocator> &) { return value(); } 00389 }; 00390 00391 } // namespace message_traits 00392 } // namespace ros 00393 00394 namespace ros 00395 { 00396 namespace serialization 00397 { 00398 00399 template<class ContainerAllocator> struct Serializer< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> > 00400 { 00401 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00402 { 00403 stream.next(m.poly); 00404 stream.next(m.midpoint); 00405 stream.next(m.heading); 00406 stream.next(m.length); 00407 stream.next(m.poly_id); 00408 stream.next(m.is_stop); 00409 stream.next(m.is_transition); 00410 stream.next(m.contains_way); 00411 stream.next(m.start_way); 00412 stream.next(m.end_way); 00413 stream.next(m.left_boundary); 00414 stream.next(m.right_boundary); 00415 } 00416 00417 ROS_DECLARE_ALLINONE_SERIALIZER; 00418 }; // struct ArtQuadrilateral_ 00419 } // namespace serialization 00420 } // namespace ros 00421 00422 namespace ros 00423 { 00424 namespace message_operations 00425 { 00426 00427 template<class ContainerAllocator> 00428 struct Printer< ::art_msgs::ArtQuadrilateral_<ContainerAllocator> > 00429 { 00430 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::art_msgs::ArtQuadrilateral_<ContainerAllocator> & v) 00431 { 00432 s << indent << "poly: "; 00433 s << std::endl; 00434 Printer< ::geometry_msgs::Polygon_<ContainerAllocator> >::stream(s, indent + " ", v.poly); 00435 s << indent << "midpoint: "; 00436 s << std::endl; 00437 Printer< ::geometry_msgs::Point_<ContainerAllocator> >::stream(s, indent + " ", v.midpoint); 00438 s << indent << "heading: "; 00439 Printer<float>::stream(s, indent + " ", v.heading); 00440 s << indent << "length: "; 00441 Printer<float>::stream(s, indent + " ", v.length); 00442 s << indent << "poly_id: "; 00443 Printer<int32_t>::stream(s, indent + " ", v.poly_id); 00444 s << indent << "is_stop: "; 00445 Printer<uint8_t>::stream(s, indent + " ", v.is_stop); 00446 s << indent << "is_transition: "; 00447 Printer<uint8_t>::stream(s, indent + " ", v.is_transition); 00448 s << indent << "contains_way: "; 00449 Printer<uint8_t>::stream(s, indent + " ", v.contains_way); 00450 s << indent << "start_way: "; 00451 s << std::endl; 00452 Printer< ::art_msgs::MapID_<ContainerAllocator> >::stream(s, indent + " ", v.start_way); 00453 s << indent << "end_way: "; 00454 s << std::endl; 00455 Printer< ::art_msgs::MapID_<ContainerAllocator> >::stream(s, indent + " ", v.end_way); 00456 s << indent << "left_boundary: "; 00457 s << std::endl; 00458 Printer< ::art_msgs::LaneMarking_<ContainerAllocator> >::stream(s, indent + " ", v.left_boundary); 00459 s << indent << "right_boundary: "; 00460 s << std::endl; 00461 Printer< ::art_msgs::LaneMarking_<ContainerAllocator> >::stream(s, indent + " ", v.right_boundary); 00462 } 00463 }; 00464 00465 00466 } // namespace message_operations 00467 } // namespace ros 00468 00469 #endif // ART_MSGS_MESSAGE_ARTQUADRILATERAL_H 00470