$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/NavigatorCommand.msg */ 00002 #ifndef ART_MSGS_MESSAGE_NAVIGATORCOMMAND_H 00003 #define ART_MSGS_MESSAGE_NAVIGATORCOMMAND_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 "std_msgs/Header.h" 00018 #include "art_msgs/Order.h" 00019 00020 namespace art_msgs 00021 { 00022 template <class ContainerAllocator> 00023 struct NavigatorCommand_ { 00024 typedef NavigatorCommand_<ContainerAllocator> Type; 00025 00026 NavigatorCommand_() 00027 : header() 00028 , order() 00029 { 00030 } 00031 00032 NavigatorCommand_(const ContainerAllocator& _alloc) 00033 : header(_alloc) 00034 , order(_alloc) 00035 { 00036 } 00037 00038 typedef ::std_msgs::Header_<ContainerAllocator> _header_type; 00039 ::std_msgs::Header_<ContainerAllocator> header; 00040 00041 typedef ::art_msgs::Order_<ContainerAllocator> _order_type; 00042 ::art_msgs::Order_<ContainerAllocator> order; 00043 00044 00045 private: 00046 static const char* __s_getDataType_() { return "art_msgs/NavigatorCommand"; } 00047 public: 00048 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00049 00050 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00051 00052 private: 00053 static const char* __s_getMD5Sum_() { return "415e5ee8b2ed1c9329a949ed123760f3"; } 00054 public: 00055 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00056 00057 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00058 00059 private: 00060 static const char* __s_getMessageDefinition_() { return "# navigator command message\n\ 00061 # $Id: NavigatorCommand.msg 615 2010-09-24 16:07:50Z jack.oquin $\n\ 00062 \n\ 00063 Header header\n\ 00064 Order order\n\ 00065 \n\ 00066 ================================================================================\n\ 00067 MSG: std_msgs/Header\n\ 00068 # Standard metadata for higher-level stamped data types.\n\ 00069 # This is generally used to communicate timestamped data \n\ 00070 # in a particular coordinate frame.\n\ 00071 # \n\ 00072 # sequence ID: consecutively increasing ID \n\ 00073 uint32 seq\n\ 00074 #Two-integer timestamp that is expressed as:\n\ 00075 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00076 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00077 # time-handling sugar is provided by the client library\n\ 00078 time stamp\n\ 00079 #Frame this data is associated with\n\ 00080 # 0: no frame\n\ 00081 # 1: global frame\n\ 00082 string frame_id\n\ 00083 \n\ 00084 ================================================================================\n\ 00085 MSG: art_msgs/Order\n\ 00086 # commander order for the navigator\n\ 00087 # $Id: Order.msg 615 2010-09-24 16:07:50Z jack.oquin $\n\ 00088 \n\ 00089 uint32 N_WAYPTS = 5 # number of way-points in order\n\ 00090 uint32 N_CHKPTS = 2 # number of checkpoints in order\n\ 00091 \n\ 00092 Behavior behavior # requested behavior\n\ 00093 art_msgs/WayPoint[5] waypt # way-point array\n\ 00094 art_msgs/WayPoint[2] chkpt # next two goal checkpoints\n\ 00095 float32 min_speed # in meters/sec\n\ 00096 float32 max_speed\n\ 00097 int32 replan_num\n\ 00098 int32 next_uturn # Uturn between [1] and [2]\n\ 00099 \n\ 00100 ================================================================================\n\ 00101 MSG: art_msgs/Behavior\n\ 00102 # ART Navigator behaviors (lower numbers have higher priority)\n\ 00103 # $Id: Behavior.msg 996 2011-02-27 16:07:34Z jack.oquin $\n\ 00104 \n\ 00105 # enumerated behavior values\n\ 00106 int16 Abort = 0\n\ 00107 int16 Quit = 1\n\ 00108 int16 Pause = 2\n\ 00109 int16 Run = 3\n\ 00110 int16 Suspend = 4\n\ 00111 int16 Initialize = 5\n\ 00112 int16 Go = 6\n\ 00113 int16 NONE = 7\n\ 00114 int16 N_behaviors = 8\n\ 00115 \n\ 00116 int16 value\n\ 00117 \n\ 00118 ================================================================================\n\ 00119 MSG: art_msgs/WayPoint\n\ 00120 # Way-point attributes\n\ 00121 # $Id: WayPoint.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\ 00122 \n\ 00123 float64 latitude # latitude in degrees\n\ 00124 float64 longitude # longitude in degrees\n\ 00125 geometry_msgs/Point32 mapxy # MapXY position\n\ 00126 MapID id # way-point ID\n\ 00127 uint16 index # parser index of waypoint\n\ 00128 \n\ 00129 # way-point flags\n\ 00130 bool is_entry # lane or zone exit point\n\ 00131 bool is_exit # lane or zone entry point\n\ 00132 bool is_goal # this is a goal checkpoint\n\ 00133 bool is_lane_change # change lanes after here\n\ 00134 bool is_spot # parking spot\n\ 00135 bool is_stop # stop line here\n\ 00136 bool is_perimeter # zone perimeter point\n\ 00137 int32 checkpoint_id # checkpoint ID or zero\n\ 00138 float32 lane_width\n\ 00139 \n\ 00140 ================================================================================\n\ 00141 MSG: geometry_msgs/Point32\n\ 00142 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00143 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00144 # \n\ 00145 # This recommendation is to promote interoperability. \n\ 00146 #\n\ 00147 # This message is designed to take up less space when sending\n\ 00148 # lots of points at once, as in the case of a PointCloud. \n\ 00149 \n\ 00150 float32 x\n\ 00151 float32 y\n\ 00152 float32 z\n\ 00153 ================================================================================\n\ 00154 MSG: art_msgs/MapID\n\ 00155 # Road map identifier for segments, lanes and way-points.\n\ 00156 # $Id: MapID.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\ 00157 \n\ 00158 uint16 NULL_ID = 65535\n\ 00159 \n\ 00160 uint16 seg # segment ID\n\ 00161 uint16 lane # lane ID\n\ 00162 uint16 pt # way-point ID\n\ 00163 \n\ 00164 "; } 00165 public: 00166 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00167 00168 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00169 00170 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00171 { 00172 ros::serialization::OStream stream(write_ptr, 1000000000); 00173 ros::serialization::serialize(stream, header); 00174 ros::serialization::serialize(stream, order); 00175 return stream.getData(); 00176 } 00177 00178 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00179 { 00180 ros::serialization::IStream stream(read_ptr, 1000000000); 00181 ros::serialization::deserialize(stream, header); 00182 ros::serialization::deserialize(stream, order); 00183 return stream.getData(); 00184 } 00185 00186 ROS_DEPRECATED virtual uint32_t serializationLength() const 00187 { 00188 uint32_t size = 0; 00189 size += ros::serialization::serializationLength(header); 00190 size += ros::serialization::serializationLength(order); 00191 return size; 00192 } 00193 00194 typedef boost::shared_ptr< ::art_msgs::NavigatorCommand_<ContainerAllocator> > Ptr; 00195 typedef boost::shared_ptr< ::art_msgs::NavigatorCommand_<ContainerAllocator> const> ConstPtr; 00196 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00197 }; // struct NavigatorCommand 00198 typedef ::art_msgs::NavigatorCommand_<std::allocator<void> > NavigatorCommand; 00199 00200 typedef boost::shared_ptr< ::art_msgs::NavigatorCommand> NavigatorCommandPtr; 00201 typedef boost::shared_ptr< ::art_msgs::NavigatorCommand const> NavigatorCommandConstPtr; 00202 00203 00204 template<typename ContainerAllocator> 00205 std::ostream& operator<<(std::ostream& s, const ::art_msgs::NavigatorCommand_<ContainerAllocator> & v) 00206 { 00207 ros::message_operations::Printer< ::art_msgs::NavigatorCommand_<ContainerAllocator> >::stream(s, "", v); 00208 return s;} 00209 00210 } // namespace art_msgs 00211 00212 namespace ros 00213 { 00214 namespace message_traits 00215 { 00216 template<class ContainerAllocator> struct IsMessage< ::art_msgs::NavigatorCommand_<ContainerAllocator> > : public TrueType {}; 00217 template<class ContainerAllocator> struct IsMessage< ::art_msgs::NavigatorCommand_<ContainerAllocator> const> : public TrueType {}; 00218 template<class ContainerAllocator> 00219 struct MD5Sum< ::art_msgs::NavigatorCommand_<ContainerAllocator> > { 00220 static const char* value() 00221 { 00222 return "415e5ee8b2ed1c9329a949ed123760f3"; 00223 } 00224 00225 static const char* value(const ::art_msgs::NavigatorCommand_<ContainerAllocator> &) { return value(); } 00226 static const uint64_t static_value1 = 0x415e5ee8b2ed1c93ULL; 00227 static const uint64_t static_value2 = 0x29a949ed123760f3ULL; 00228 }; 00229 00230 template<class ContainerAllocator> 00231 struct DataType< ::art_msgs::NavigatorCommand_<ContainerAllocator> > { 00232 static const char* value() 00233 { 00234 return "art_msgs/NavigatorCommand"; 00235 } 00236 00237 static const char* value(const ::art_msgs::NavigatorCommand_<ContainerAllocator> &) { return value(); } 00238 }; 00239 00240 template<class ContainerAllocator> 00241 struct Definition< ::art_msgs::NavigatorCommand_<ContainerAllocator> > { 00242 static const char* value() 00243 { 00244 return "# navigator command message\n\ 00245 # $Id: NavigatorCommand.msg 615 2010-09-24 16:07:50Z jack.oquin $\n\ 00246 \n\ 00247 Header header\n\ 00248 Order order\n\ 00249 \n\ 00250 ================================================================================\n\ 00251 MSG: std_msgs/Header\n\ 00252 # Standard metadata for higher-level stamped data types.\n\ 00253 # This is generally used to communicate timestamped data \n\ 00254 # in a particular coordinate frame.\n\ 00255 # \n\ 00256 # sequence ID: consecutively increasing ID \n\ 00257 uint32 seq\n\ 00258 #Two-integer timestamp that is expressed as:\n\ 00259 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00260 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00261 # time-handling sugar is provided by the client library\n\ 00262 time stamp\n\ 00263 #Frame this data is associated with\n\ 00264 # 0: no frame\n\ 00265 # 1: global frame\n\ 00266 string frame_id\n\ 00267 \n\ 00268 ================================================================================\n\ 00269 MSG: art_msgs/Order\n\ 00270 # commander order for the navigator\n\ 00271 # $Id: Order.msg 615 2010-09-24 16:07:50Z jack.oquin $\n\ 00272 \n\ 00273 uint32 N_WAYPTS = 5 # number of way-points in order\n\ 00274 uint32 N_CHKPTS = 2 # number of checkpoints in order\n\ 00275 \n\ 00276 Behavior behavior # requested behavior\n\ 00277 art_msgs/WayPoint[5] waypt # way-point array\n\ 00278 art_msgs/WayPoint[2] chkpt # next two goal checkpoints\n\ 00279 float32 min_speed # in meters/sec\n\ 00280 float32 max_speed\n\ 00281 int32 replan_num\n\ 00282 int32 next_uturn # Uturn between [1] and [2]\n\ 00283 \n\ 00284 ================================================================================\n\ 00285 MSG: art_msgs/Behavior\n\ 00286 # ART Navigator behaviors (lower numbers have higher priority)\n\ 00287 # $Id: Behavior.msg 996 2011-02-27 16:07:34Z jack.oquin $\n\ 00288 \n\ 00289 # enumerated behavior values\n\ 00290 int16 Abort = 0\n\ 00291 int16 Quit = 1\n\ 00292 int16 Pause = 2\n\ 00293 int16 Run = 3\n\ 00294 int16 Suspend = 4\n\ 00295 int16 Initialize = 5\n\ 00296 int16 Go = 6\n\ 00297 int16 NONE = 7\n\ 00298 int16 N_behaviors = 8\n\ 00299 \n\ 00300 int16 value\n\ 00301 \n\ 00302 ================================================================================\n\ 00303 MSG: art_msgs/WayPoint\n\ 00304 # Way-point attributes\n\ 00305 # $Id: WayPoint.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\ 00306 \n\ 00307 float64 latitude # latitude in degrees\n\ 00308 float64 longitude # longitude in degrees\n\ 00309 geometry_msgs/Point32 mapxy # MapXY position\n\ 00310 MapID id # way-point ID\n\ 00311 uint16 index # parser index of waypoint\n\ 00312 \n\ 00313 # way-point flags\n\ 00314 bool is_entry # lane or zone exit point\n\ 00315 bool is_exit # lane or zone entry point\n\ 00316 bool is_goal # this is a goal checkpoint\n\ 00317 bool is_lane_change # change lanes after here\n\ 00318 bool is_spot # parking spot\n\ 00319 bool is_stop # stop line here\n\ 00320 bool is_perimeter # zone perimeter point\n\ 00321 int32 checkpoint_id # checkpoint ID or zero\n\ 00322 float32 lane_width\n\ 00323 \n\ 00324 ================================================================================\n\ 00325 MSG: geometry_msgs/Point32\n\ 00326 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00327 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00328 # \n\ 00329 # This recommendation is to promote interoperability. \n\ 00330 #\n\ 00331 # This message is designed to take up less space when sending\n\ 00332 # lots of points at once, as in the case of a PointCloud. \n\ 00333 \n\ 00334 float32 x\n\ 00335 float32 y\n\ 00336 float32 z\n\ 00337 ================================================================================\n\ 00338 MSG: art_msgs/MapID\n\ 00339 # Road map identifier for segments, lanes and way-points.\n\ 00340 # $Id: MapID.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\ 00341 \n\ 00342 uint16 NULL_ID = 65535\n\ 00343 \n\ 00344 uint16 seg # segment ID\n\ 00345 uint16 lane # lane ID\n\ 00346 uint16 pt # way-point ID\n\ 00347 \n\ 00348 "; 00349 } 00350 00351 static const char* value(const ::art_msgs::NavigatorCommand_<ContainerAllocator> &) { return value(); } 00352 }; 00353 00354 template<class ContainerAllocator> struct HasHeader< ::art_msgs::NavigatorCommand_<ContainerAllocator> > : public TrueType {}; 00355 template<class ContainerAllocator> struct HasHeader< const ::art_msgs::NavigatorCommand_<ContainerAllocator> > : public TrueType {}; 00356 } // namespace message_traits 00357 } // namespace ros 00358 00359 namespace ros 00360 { 00361 namespace serialization 00362 { 00363 00364 template<class ContainerAllocator> struct Serializer< ::art_msgs::NavigatorCommand_<ContainerAllocator> > 00365 { 00366 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00367 { 00368 stream.next(m.header); 00369 stream.next(m.order); 00370 } 00371 00372 ROS_DECLARE_ALLINONE_SERIALIZER; 00373 }; // struct NavigatorCommand_ 00374 } // namespace serialization 00375 } // namespace ros 00376 00377 namespace ros 00378 { 00379 namespace message_operations 00380 { 00381 00382 template<class ContainerAllocator> 00383 struct Printer< ::art_msgs::NavigatorCommand_<ContainerAllocator> > 00384 { 00385 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::art_msgs::NavigatorCommand_<ContainerAllocator> & v) 00386 { 00387 s << indent << "header: "; 00388 s << std::endl; 00389 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header); 00390 s << indent << "order: "; 00391 s << std::endl; 00392 Printer< ::art_msgs::Order_<ContainerAllocator> >::stream(s, indent + " ", v.order); 00393 } 00394 }; 00395 00396 00397 } // namespace message_operations 00398 } // namespace ros 00399 00400 #endif // ART_MSGS_MESSAGE_NAVIGATORCOMMAND_H 00401