00001
00002 #ifndef ART_MSGS_MESSAGE_NAVIGATORSTATE_H
00003 #define ART_MSGS_MESSAGE_NAVIGATORSTATE_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 "std_msgs/Header.h"
00014 #include "art_msgs/EstopState.h"
00015 #include "art_msgs/RoadState.h"
00016 #include "art_msgs/MapID.h"
00017 #include "art_msgs/MapID.h"
00018 #include "art_msgs/Order.h"
00019
00020 namespace art_msgs
00021 {
00022 template <class ContainerAllocator>
00023 struct NavigatorState_ : public ros::Message
00024 {
00025 typedef NavigatorState_<ContainerAllocator> Type;
00026
00027 NavigatorState_()
00028 : header()
00029 , estop()
00030 , road()
00031 , last_waypt()
00032 , replan_waypt()
00033 , cur_poly(0)
00034 , alarm(false)
00035 , flasher(false)
00036 , lane_blocked(false)
00037 , road_blocked(false)
00038 , reverse(false)
00039 , signal_left(false)
00040 , signal_right(false)
00041 , stopped(false)
00042 , have_zones(false)
00043 , last_order()
00044 {
00045 }
00046
00047 NavigatorState_(const ContainerAllocator& _alloc)
00048 : header(_alloc)
00049 , estop(_alloc)
00050 , road(_alloc)
00051 , last_waypt(_alloc)
00052 , replan_waypt(_alloc)
00053 , cur_poly(0)
00054 , alarm(false)
00055 , flasher(false)
00056 , lane_blocked(false)
00057 , road_blocked(false)
00058 , reverse(false)
00059 , signal_left(false)
00060 , signal_right(false)
00061 , stopped(false)
00062 , have_zones(false)
00063 , last_order(_alloc)
00064 {
00065 }
00066
00067 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00068 ::std_msgs::Header_<ContainerAllocator> header;
00069
00070 typedef ::art_msgs::EstopState_<ContainerAllocator> _estop_type;
00071 ::art_msgs::EstopState_<ContainerAllocator> estop;
00072
00073 typedef ::art_msgs::RoadState_<ContainerAllocator> _road_type;
00074 ::art_msgs::RoadState_<ContainerAllocator> road;
00075
00076 typedef ::art_msgs::MapID_<ContainerAllocator> _last_waypt_type;
00077 ::art_msgs::MapID_<ContainerAllocator> last_waypt;
00078
00079 typedef ::art_msgs::MapID_<ContainerAllocator> _replan_waypt_type;
00080 ::art_msgs::MapID_<ContainerAllocator> replan_waypt;
00081
00082 typedef int32_t _cur_poly_type;
00083 int32_t cur_poly;
00084
00085 typedef uint8_t _alarm_type;
00086 uint8_t alarm;
00087
00088 typedef uint8_t _flasher_type;
00089 uint8_t flasher;
00090
00091 typedef uint8_t _lane_blocked_type;
00092 uint8_t lane_blocked;
00093
00094 typedef uint8_t _road_blocked_type;
00095 uint8_t road_blocked;
00096
00097 typedef uint8_t _reverse_type;
00098 uint8_t reverse;
00099
00100 typedef uint8_t _signal_left_type;
00101 uint8_t signal_left;
00102
00103 typedef uint8_t _signal_right_type;
00104 uint8_t signal_right;
00105
00106 typedef uint8_t _stopped_type;
00107 uint8_t stopped;
00108
00109 typedef uint8_t _have_zones_type;
00110 uint8_t have_zones;
00111
00112 typedef ::art_msgs::Order_<ContainerAllocator> _last_order_type;
00113 ::art_msgs::Order_<ContainerAllocator> last_order;
00114
00115
00116 private:
00117 static const char* __s_getDataType_() { return "art_msgs/NavigatorState"; }
00118 public:
00119 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00120
00121 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00122
00123 private:
00124 static const char* __s_getMD5Sum_() { return "c40e5f1fdc1b82b80af736960035d5c8"; }
00125 public:
00126 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00127
00128 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00129
00130 private:
00131 static const char* __s_getMessageDefinition_() { return "# navigator state message\n\
00132 # $Id: NavigatorState.msg 615 2010-09-24 16:07:50Z jack.oquin $\n\
00133 \n\
00134 Header header\n\
00135 \n\
00136 EstopState estop\n\
00137 RoadState road\n\
00138 \n\
00139 art_msgs/MapID last_waypt # last way-point reached\n\
00140 art_msgs/MapID replan_waypt # next way-point for replan\n\
00141 \n\
00142 int32 cur_poly # current polygon, -1 if none\n\
00143 \n\
00144 # status flags\n\
00145 bool alarm\n\
00146 bool flasher\n\
00147 bool lane_blocked\n\
00148 bool road_blocked\n\
00149 bool reverse\n\
00150 bool signal_left\n\
00151 bool signal_right\n\
00152 bool stopped\n\
00153 bool have_zones\n\
00154 \n\
00155 Order last_order # last commander order received\n\
00156 \n\
00157 ================================================================================\n\
00158 MSG: std_msgs/Header\n\
00159 # Standard metadata for higher-level stamped data types.\n\
00160 # This is generally used to communicate timestamped data \n\
00161 # in a particular coordinate frame.\n\
00162 # \n\
00163 # sequence ID: consecutively increasing ID \n\
00164 uint32 seq\n\
00165 #Two-integer timestamp that is expressed as:\n\
00166 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00167 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00168 # time-handling sugar is provided by the client library\n\
00169 time stamp\n\
00170 #Frame this data is associated with\n\
00171 # 0: no frame\n\
00172 # 1: global frame\n\
00173 string frame_id\n\
00174 \n\
00175 ================================================================================\n\
00176 MSG: art_msgs/EstopState\n\
00177 # Navigator E-stop state values\n\
00178 # $Id: EstopState.msg 996 2011-02-27 16:07:34Z jack.oquin $\n\
00179 \n\
00180 uint16 Pause = 0 # E-stop pause (initial state)\n\
00181 uint16 Run = 1 # E-stop run enabled\n\
00182 uint16 Done = 2 # mission finished (disabled)\n\
00183 uint16 Suspend = 3 # suspend autonomous operation\n\
00184 uint16 N_states = 4\n\
00185 \n\
00186 uint16 state\n\
00187 \n\
00188 ================================================================================\n\
00189 MSG: art_msgs/RoadState\n\
00190 # Navigator Road state values\n\
00191 # $Id: RoadState.msg 615 2010-09-24 16:07:50Z jack.oquin $\n\
00192 \n\
00193 uint16 Init = 0\n\
00194 uint16 Block = 1\n\
00195 uint16 Evade = 2\n\
00196 uint16 Follow = 3\n\
00197 uint16 Pass = 4\n\
00198 uint16 Uturn = 5\n\
00199 uint16 WaitCross = 6\n\
00200 uint16 WaitLane = 7\n\
00201 uint16 WaitPass = 8\n\
00202 uint16 WaitStop = 9\n\
00203 uint16 Zone = 10\n\
00204 uint16 N_states = 11\n\
00205 \n\
00206 uint16 state\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/Order\n\
00221 # commander order for the navigator\n\
00222 # $Id: Order.msg 615 2010-09-24 16:07:50Z jack.oquin $\n\
00223 \n\
00224 uint32 N_WAYPTS = 5 # number of way-points in order\n\
00225 uint32 N_CHKPTS = 2 # number of checkpoints in order\n\
00226 \n\
00227 Behavior behavior # requested behavior\n\
00228 art_msgs/WayPoint[5] waypt # way-point array\n\
00229 art_msgs/WayPoint[2] chkpt # next two goal checkpoints\n\
00230 float32 min_speed # in meters/sec\n\
00231 float32 max_speed\n\
00232 int32 replan_num\n\
00233 int32 next_uturn # Uturn between [1] and [2]\n\
00234 \n\
00235 ================================================================================\n\
00236 MSG: art_msgs/Behavior\n\
00237 # ART Navigator behaviors (lower numbers have higher priority)\n\
00238 # $Id: Behavior.msg 996 2011-02-27 16:07:34Z jack.oquin $\n\
00239 \n\
00240 # enumerated behavior values\n\
00241 int16 Abort = 0\n\
00242 int16 Quit = 1\n\
00243 int16 Pause = 2\n\
00244 int16 Run = 3\n\
00245 int16 Suspend = 4\n\
00246 int16 Initialize = 5\n\
00247 int16 Go = 6\n\
00248 int16 NONE = 7\n\
00249 int16 N_behaviors = 8\n\
00250 \n\
00251 int16 value\n\
00252 \n\
00253 ================================================================================\n\
00254 MSG: art_msgs/WayPoint\n\
00255 # Way-point attributes\n\
00256 # $Id: WayPoint.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\
00257 \n\
00258 float64 latitude # latitude in degrees\n\
00259 float64 longitude # longitude in degrees\n\
00260 geometry_msgs/Point32 mapxy # MapXY position\n\
00261 MapID id # way-point ID\n\
00262 uint16 index # parser index of waypoint\n\
00263 \n\
00264 # way-point flags\n\
00265 bool is_entry # lane or zone exit point\n\
00266 bool is_exit # lane or zone entry point\n\
00267 bool is_goal # this is a goal checkpoint\n\
00268 bool is_lane_change # change lanes after here\n\
00269 bool is_spot # parking spot\n\
00270 bool is_stop # stop line here\n\
00271 bool is_perimeter # zone perimeter point\n\
00272 int32 checkpoint_id # checkpoint ID or zero\n\
00273 float32 lane_width\n\
00274 \n\
00275 ================================================================================\n\
00276 MSG: geometry_msgs/Point32\n\
00277 # This contains the position of a point in free space(with 32 bits of precision).\n\
00278 # It is recommeded to use Point wherever possible instead of Point32. \n\
00279 # \n\
00280 # This recommendation is to promote interoperability. \n\
00281 #\n\
00282 # This message is designed to take up less space when sending\n\
00283 # lots of points at once, as in the case of a PointCloud. \n\
00284 \n\
00285 float32 x\n\
00286 float32 y\n\
00287 float32 z\n\
00288 "; }
00289 public:
00290 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00291
00292 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00293
00294 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00295 {
00296 ros::serialization::OStream stream(write_ptr, 1000000000);
00297 ros::serialization::serialize(stream, header);
00298 ros::serialization::serialize(stream, estop);
00299 ros::serialization::serialize(stream, road);
00300 ros::serialization::serialize(stream, last_waypt);
00301 ros::serialization::serialize(stream, replan_waypt);
00302 ros::serialization::serialize(stream, cur_poly);
00303 ros::serialization::serialize(stream, alarm);
00304 ros::serialization::serialize(stream, flasher);
00305 ros::serialization::serialize(stream, lane_blocked);
00306 ros::serialization::serialize(stream, road_blocked);
00307 ros::serialization::serialize(stream, reverse);
00308 ros::serialization::serialize(stream, signal_left);
00309 ros::serialization::serialize(stream, signal_right);
00310 ros::serialization::serialize(stream, stopped);
00311 ros::serialization::serialize(stream, have_zones);
00312 ros::serialization::serialize(stream, last_order);
00313 return stream.getData();
00314 }
00315
00316 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00317 {
00318 ros::serialization::IStream stream(read_ptr, 1000000000);
00319 ros::serialization::deserialize(stream, header);
00320 ros::serialization::deserialize(stream, estop);
00321 ros::serialization::deserialize(stream, road);
00322 ros::serialization::deserialize(stream, last_waypt);
00323 ros::serialization::deserialize(stream, replan_waypt);
00324 ros::serialization::deserialize(stream, cur_poly);
00325 ros::serialization::deserialize(stream, alarm);
00326 ros::serialization::deserialize(stream, flasher);
00327 ros::serialization::deserialize(stream, lane_blocked);
00328 ros::serialization::deserialize(stream, road_blocked);
00329 ros::serialization::deserialize(stream, reverse);
00330 ros::serialization::deserialize(stream, signal_left);
00331 ros::serialization::deserialize(stream, signal_right);
00332 ros::serialization::deserialize(stream, stopped);
00333 ros::serialization::deserialize(stream, have_zones);
00334 ros::serialization::deserialize(stream, last_order);
00335 return stream.getData();
00336 }
00337
00338 ROS_DEPRECATED virtual uint32_t serializationLength() const
00339 {
00340 uint32_t size = 0;
00341 size += ros::serialization::serializationLength(header);
00342 size += ros::serialization::serializationLength(estop);
00343 size += ros::serialization::serializationLength(road);
00344 size += ros::serialization::serializationLength(last_waypt);
00345 size += ros::serialization::serializationLength(replan_waypt);
00346 size += ros::serialization::serializationLength(cur_poly);
00347 size += ros::serialization::serializationLength(alarm);
00348 size += ros::serialization::serializationLength(flasher);
00349 size += ros::serialization::serializationLength(lane_blocked);
00350 size += ros::serialization::serializationLength(road_blocked);
00351 size += ros::serialization::serializationLength(reverse);
00352 size += ros::serialization::serializationLength(signal_left);
00353 size += ros::serialization::serializationLength(signal_right);
00354 size += ros::serialization::serializationLength(stopped);
00355 size += ros::serialization::serializationLength(have_zones);
00356 size += ros::serialization::serializationLength(last_order);
00357 return size;
00358 }
00359
00360 typedef boost::shared_ptr< ::art_msgs::NavigatorState_<ContainerAllocator> > Ptr;
00361 typedef boost::shared_ptr< ::art_msgs::NavigatorState_<ContainerAllocator> const> ConstPtr;
00362 };
00363 typedef ::art_msgs::NavigatorState_<std::allocator<void> > NavigatorState;
00364
00365 typedef boost::shared_ptr< ::art_msgs::NavigatorState> NavigatorStatePtr;
00366 typedef boost::shared_ptr< ::art_msgs::NavigatorState const> NavigatorStateConstPtr;
00367
00368
00369 template<typename ContainerAllocator>
00370 std::ostream& operator<<(std::ostream& s, const ::art_msgs::NavigatorState_<ContainerAllocator> & v)
00371 {
00372 ros::message_operations::Printer< ::art_msgs::NavigatorState_<ContainerAllocator> >::stream(s, "", v);
00373 return s;}
00374
00375 }
00376
00377 namespace ros
00378 {
00379 namespace message_traits
00380 {
00381 template<class ContainerAllocator>
00382 struct MD5Sum< ::art_msgs::NavigatorState_<ContainerAllocator> > {
00383 static const char* value()
00384 {
00385 return "c40e5f1fdc1b82b80af736960035d5c8";
00386 }
00387
00388 static const char* value(const ::art_msgs::NavigatorState_<ContainerAllocator> &) { return value(); }
00389 static const uint64_t static_value1 = 0xc40e5f1fdc1b82b8ULL;
00390 static const uint64_t static_value2 = 0x0af736960035d5c8ULL;
00391 };
00392
00393 template<class ContainerAllocator>
00394 struct DataType< ::art_msgs::NavigatorState_<ContainerAllocator> > {
00395 static const char* value()
00396 {
00397 return "art_msgs/NavigatorState";
00398 }
00399
00400 static const char* value(const ::art_msgs::NavigatorState_<ContainerAllocator> &) { return value(); }
00401 };
00402
00403 template<class ContainerAllocator>
00404 struct Definition< ::art_msgs::NavigatorState_<ContainerAllocator> > {
00405 static const char* value()
00406 {
00407 return "# navigator state message\n\
00408 # $Id: NavigatorState.msg 615 2010-09-24 16:07:50Z jack.oquin $\n\
00409 \n\
00410 Header header\n\
00411 \n\
00412 EstopState estop\n\
00413 RoadState road\n\
00414 \n\
00415 art_msgs/MapID last_waypt # last way-point reached\n\
00416 art_msgs/MapID replan_waypt # next way-point for replan\n\
00417 \n\
00418 int32 cur_poly # current polygon, -1 if none\n\
00419 \n\
00420 # status flags\n\
00421 bool alarm\n\
00422 bool flasher\n\
00423 bool lane_blocked\n\
00424 bool road_blocked\n\
00425 bool reverse\n\
00426 bool signal_left\n\
00427 bool signal_right\n\
00428 bool stopped\n\
00429 bool have_zones\n\
00430 \n\
00431 Order last_order # last commander order received\n\
00432 \n\
00433 ================================================================================\n\
00434 MSG: std_msgs/Header\n\
00435 # Standard metadata for higher-level stamped data types.\n\
00436 # This is generally used to communicate timestamped data \n\
00437 # in a particular coordinate frame.\n\
00438 # \n\
00439 # sequence ID: consecutively increasing ID \n\
00440 uint32 seq\n\
00441 #Two-integer timestamp that is expressed as:\n\
00442 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00443 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00444 # time-handling sugar is provided by the client library\n\
00445 time stamp\n\
00446 #Frame this data is associated with\n\
00447 # 0: no frame\n\
00448 # 1: global frame\n\
00449 string frame_id\n\
00450 \n\
00451 ================================================================================\n\
00452 MSG: art_msgs/EstopState\n\
00453 # Navigator E-stop state values\n\
00454 # $Id: EstopState.msg 996 2011-02-27 16:07:34Z jack.oquin $\n\
00455 \n\
00456 uint16 Pause = 0 # E-stop pause (initial state)\n\
00457 uint16 Run = 1 # E-stop run enabled\n\
00458 uint16 Done = 2 # mission finished (disabled)\n\
00459 uint16 Suspend = 3 # suspend autonomous operation\n\
00460 uint16 N_states = 4\n\
00461 \n\
00462 uint16 state\n\
00463 \n\
00464 ================================================================================\n\
00465 MSG: art_msgs/RoadState\n\
00466 # Navigator Road state values\n\
00467 # $Id: RoadState.msg 615 2010-09-24 16:07:50Z jack.oquin $\n\
00468 \n\
00469 uint16 Init = 0\n\
00470 uint16 Block = 1\n\
00471 uint16 Evade = 2\n\
00472 uint16 Follow = 3\n\
00473 uint16 Pass = 4\n\
00474 uint16 Uturn = 5\n\
00475 uint16 WaitCross = 6\n\
00476 uint16 WaitLane = 7\n\
00477 uint16 WaitPass = 8\n\
00478 uint16 WaitStop = 9\n\
00479 uint16 Zone = 10\n\
00480 uint16 N_states = 11\n\
00481 \n\
00482 uint16 state\n\
00483 \n\
00484 ================================================================================\n\
00485 MSG: art_msgs/MapID\n\
00486 # Road map identifier for segments, lanes and way-points.\n\
00487 # $Id: MapID.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\
00488 \n\
00489 uint16 NULL_ID = 65535\n\
00490 \n\
00491 uint16 seg # segment ID\n\
00492 uint16 lane # lane ID\n\
00493 uint16 pt # way-point ID\n\
00494 \n\
00495 ================================================================================\n\
00496 MSG: art_msgs/Order\n\
00497 # commander order for the navigator\n\
00498 # $Id: Order.msg 615 2010-09-24 16:07:50Z jack.oquin $\n\
00499 \n\
00500 uint32 N_WAYPTS = 5 # number of way-points in order\n\
00501 uint32 N_CHKPTS = 2 # number of checkpoints in order\n\
00502 \n\
00503 Behavior behavior # requested behavior\n\
00504 art_msgs/WayPoint[5] waypt # way-point array\n\
00505 art_msgs/WayPoint[2] chkpt # next two goal checkpoints\n\
00506 float32 min_speed # in meters/sec\n\
00507 float32 max_speed\n\
00508 int32 replan_num\n\
00509 int32 next_uturn # Uturn between [1] and [2]\n\
00510 \n\
00511 ================================================================================\n\
00512 MSG: art_msgs/Behavior\n\
00513 # ART Navigator behaviors (lower numbers have higher priority)\n\
00514 # $Id: Behavior.msg 996 2011-02-27 16:07:34Z jack.oquin $\n\
00515 \n\
00516 # enumerated behavior values\n\
00517 int16 Abort = 0\n\
00518 int16 Quit = 1\n\
00519 int16 Pause = 2\n\
00520 int16 Run = 3\n\
00521 int16 Suspend = 4\n\
00522 int16 Initialize = 5\n\
00523 int16 Go = 6\n\
00524 int16 NONE = 7\n\
00525 int16 N_behaviors = 8\n\
00526 \n\
00527 int16 value\n\
00528 \n\
00529 ================================================================================\n\
00530 MSG: art_msgs/WayPoint\n\
00531 # Way-point attributes\n\
00532 # $Id: WayPoint.msg 614 2010-09-24 15:08:46Z jack.oquin $\n\
00533 \n\
00534 float64 latitude # latitude in degrees\n\
00535 float64 longitude # longitude in degrees\n\
00536 geometry_msgs/Point32 mapxy # MapXY position\n\
00537 MapID id # way-point ID\n\
00538 uint16 index # parser index of waypoint\n\
00539 \n\
00540 # way-point flags\n\
00541 bool is_entry # lane or zone exit point\n\
00542 bool is_exit # lane or zone entry point\n\
00543 bool is_goal # this is a goal checkpoint\n\
00544 bool is_lane_change # change lanes after here\n\
00545 bool is_spot # parking spot\n\
00546 bool is_stop # stop line here\n\
00547 bool is_perimeter # zone perimeter point\n\
00548 int32 checkpoint_id # checkpoint ID or zero\n\
00549 float32 lane_width\n\
00550 \n\
00551 ================================================================================\n\
00552 MSG: geometry_msgs/Point32\n\
00553 # This contains the position of a point in free space(with 32 bits of precision).\n\
00554 # It is recommeded to use Point wherever possible instead of Point32. \n\
00555 # \n\
00556 # This recommendation is to promote interoperability. \n\
00557 #\n\
00558 # This message is designed to take up less space when sending\n\
00559 # lots of points at once, as in the case of a PointCloud. \n\
00560 \n\
00561 float32 x\n\
00562 float32 y\n\
00563 float32 z\n\
00564 ";
00565 }
00566
00567 static const char* value(const ::art_msgs::NavigatorState_<ContainerAllocator> &) { return value(); }
00568 };
00569
00570 template<class ContainerAllocator> struct HasHeader< ::art_msgs::NavigatorState_<ContainerAllocator> > : public TrueType {};
00571 template<class ContainerAllocator> struct HasHeader< const ::art_msgs::NavigatorState_<ContainerAllocator> > : public TrueType {};
00572 }
00573 }
00574
00575 namespace ros
00576 {
00577 namespace serialization
00578 {
00579
00580 template<class ContainerAllocator> struct Serializer< ::art_msgs::NavigatorState_<ContainerAllocator> >
00581 {
00582 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00583 {
00584 stream.next(m.header);
00585 stream.next(m.estop);
00586 stream.next(m.road);
00587 stream.next(m.last_waypt);
00588 stream.next(m.replan_waypt);
00589 stream.next(m.cur_poly);
00590 stream.next(m.alarm);
00591 stream.next(m.flasher);
00592 stream.next(m.lane_blocked);
00593 stream.next(m.road_blocked);
00594 stream.next(m.reverse);
00595 stream.next(m.signal_left);
00596 stream.next(m.signal_right);
00597 stream.next(m.stopped);
00598 stream.next(m.have_zones);
00599 stream.next(m.last_order);
00600 }
00601
00602 ROS_DECLARE_ALLINONE_SERIALIZER;
00603 };
00604 }
00605 }
00606
00607 namespace ros
00608 {
00609 namespace message_operations
00610 {
00611
00612 template<class ContainerAllocator>
00613 struct Printer< ::art_msgs::NavigatorState_<ContainerAllocator> >
00614 {
00615 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::art_msgs::NavigatorState_<ContainerAllocator> & v)
00616 {
00617 s << indent << "header: ";
00618 s << std::endl;
00619 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00620 s << indent << "estop: ";
00621 s << std::endl;
00622 Printer< ::art_msgs::EstopState_<ContainerAllocator> >::stream(s, indent + " ", v.estop);
00623 s << indent << "road: ";
00624 s << std::endl;
00625 Printer< ::art_msgs::RoadState_<ContainerAllocator> >::stream(s, indent + " ", v.road);
00626 s << indent << "last_waypt: ";
00627 s << std::endl;
00628 Printer< ::art_msgs::MapID_<ContainerAllocator> >::stream(s, indent + " ", v.last_waypt);
00629 s << indent << "replan_waypt: ";
00630 s << std::endl;
00631 Printer< ::art_msgs::MapID_<ContainerAllocator> >::stream(s, indent + " ", v.replan_waypt);
00632 s << indent << "cur_poly: ";
00633 Printer<int32_t>::stream(s, indent + " ", v.cur_poly);
00634 s << indent << "alarm: ";
00635 Printer<uint8_t>::stream(s, indent + " ", v.alarm);
00636 s << indent << "flasher: ";
00637 Printer<uint8_t>::stream(s, indent + " ", v.flasher);
00638 s << indent << "lane_blocked: ";
00639 Printer<uint8_t>::stream(s, indent + " ", v.lane_blocked);
00640 s << indent << "road_blocked: ";
00641 Printer<uint8_t>::stream(s, indent + " ", v.road_blocked);
00642 s << indent << "reverse: ";
00643 Printer<uint8_t>::stream(s, indent + " ", v.reverse);
00644 s << indent << "signal_left: ";
00645 Printer<uint8_t>::stream(s, indent + " ", v.signal_left);
00646 s << indent << "signal_right: ";
00647 Printer<uint8_t>::stream(s, indent + " ", v.signal_right);
00648 s << indent << "stopped: ";
00649 Printer<uint8_t>::stream(s, indent + " ", v.stopped);
00650 s << indent << "have_zones: ";
00651 Printer<uint8_t>::stream(s, indent + " ", v.have_zones);
00652 s << indent << "last_order: ";
00653 s << std::endl;
00654 Printer< ::art_msgs::Order_<ContainerAllocator> >::stream(s, indent + " ", v.last_order);
00655 }
00656 };
00657
00658
00659 }
00660 }
00661
00662 #endif // ART_MSGS_MESSAGE_NAVIGATORSTATE_H
00663