Go to the documentation of this file.00001
00002 #ifndef ROOMBA_500_SERIES_MESSAGE_BUTTONS_H
00003 #define ROOMBA_500_SERIES_MESSAGE_BUTTONS_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
00019 namespace roomba_500_series
00020 {
00021 template <class ContainerAllocator>
00022 struct Buttons_ {
00023 typedef Buttons_<ContainerAllocator> Type;
00024
00025 Buttons_()
00026 : header()
00027 , clean(false)
00028 , spot(false)
00029 , dock(false)
00030 , day(false)
00031 , hour(false)
00032 , minute(false)
00033 , schedule(false)
00034 , clock(false)
00035 {
00036 }
00037
00038 Buttons_(const ContainerAllocator& _alloc)
00039 : header(_alloc)
00040 , clean(false)
00041 , spot(false)
00042 , dock(false)
00043 , day(false)
00044 , hour(false)
00045 , minute(false)
00046 , schedule(false)
00047 , clock(false)
00048 {
00049 }
00050
00051 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00052 ::std_msgs::Header_<ContainerAllocator> header;
00053
00054 typedef uint8_t _clean_type;
00055 uint8_t clean;
00056
00057 typedef uint8_t _spot_type;
00058 uint8_t spot;
00059
00060 typedef uint8_t _dock_type;
00061 uint8_t dock;
00062
00063 typedef uint8_t _day_type;
00064 uint8_t day;
00065
00066 typedef uint8_t _hour_type;
00067 uint8_t hour;
00068
00069 typedef uint8_t _minute_type;
00070 uint8_t minute;
00071
00072 typedef uint8_t _schedule_type;
00073 uint8_t schedule;
00074
00075 typedef uint8_t _clock_type;
00076 uint8_t clock;
00077
00078
00079 typedef boost::shared_ptr< ::roomba_500_series::Buttons_<ContainerAllocator> > Ptr;
00080 typedef boost::shared_ptr< ::roomba_500_series::Buttons_<ContainerAllocator> const> ConstPtr;
00081 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00082 };
00083 typedef ::roomba_500_series::Buttons_<std::allocator<void> > Buttons;
00084
00085 typedef boost::shared_ptr< ::roomba_500_series::Buttons> ButtonsPtr;
00086 typedef boost::shared_ptr< ::roomba_500_series::Buttons const> ButtonsConstPtr;
00087
00088
00089 template<typename ContainerAllocator>
00090 std::ostream& operator<<(std::ostream& s, const ::roomba_500_series::Buttons_<ContainerAllocator> & v)
00091 {
00092 ros::message_operations::Printer< ::roomba_500_series::Buttons_<ContainerAllocator> >::stream(s, "", v);
00093 return s;}
00094
00095 }
00096
00097 namespace ros
00098 {
00099 namespace message_traits
00100 {
00101 template<class ContainerAllocator> struct IsMessage< ::roomba_500_series::Buttons_<ContainerAllocator> > : public TrueType {};
00102 template<class ContainerAllocator> struct IsMessage< ::roomba_500_series::Buttons_<ContainerAllocator> const> : public TrueType {};
00103 template<class ContainerAllocator>
00104 struct MD5Sum< ::roomba_500_series::Buttons_<ContainerAllocator> > {
00105 static const char* value()
00106 {
00107 return "2c6635fea08c0a11307b4518b1f7fd79";
00108 }
00109
00110 static const char* value(const ::roomba_500_series::Buttons_<ContainerAllocator> &) { return value(); }
00111 static const uint64_t static_value1 = 0x2c6635fea08c0a11ULL;
00112 static const uint64_t static_value2 = 0x307b4518b1f7fd79ULL;
00113 };
00114
00115 template<class ContainerAllocator>
00116 struct DataType< ::roomba_500_series::Buttons_<ContainerAllocator> > {
00117 static const char* value()
00118 {
00119 return "roomba_500_series/Buttons";
00120 }
00121
00122 static const char* value(const ::roomba_500_series::Buttons_<ContainerAllocator> &) { return value(); }
00123 };
00124
00125 template<class ContainerAllocator>
00126 struct Definition< ::roomba_500_series::Buttons_<ContainerAllocator> > {
00127 static const char* value()
00128 {
00129 return "Header header\n\
00130 bool clean\n\
00131 bool spot\n\
00132 bool dock\n\
00133 bool day\n\
00134 bool hour\n\
00135 bool minute\n\
00136 bool schedule\n\
00137 bool clock\n\
00138 \n\
00139 ================================================================================\n\
00140 MSG: std_msgs/Header\n\
00141 # Standard metadata for higher-level stamped data types.\n\
00142 # This is generally used to communicate timestamped data \n\
00143 # in a particular coordinate frame.\n\
00144 # \n\
00145 # sequence ID: consecutively increasing ID \n\
00146 uint32 seq\n\
00147 #Two-integer timestamp that is expressed as:\n\
00148 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00149 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00150 # time-handling sugar is provided by the client library\n\
00151 time stamp\n\
00152 #Frame this data is associated with\n\
00153 # 0: no frame\n\
00154 # 1: global frame\n\
00155 string frame_id\n\
00156 \n\
00157 ";
00158 }
00159
00160 static const char* value(const ::roomba_500_series::Buttons_<ContainerAllocator> &) { return value(); }
00161 };
00162
00163 template<class ContainerAllocator> struct HasHeader< ::roomba_500_series::Buttons_<ContainerAllocator> > : public TrueType {};
00164 template<class ContainerAllocator> struct HasHeader< const ::roomba_500_series::Buttons_<ContainerAllocator> > : public TrueType {};
00165 }
00166 }
00167
00168 namespace ros
00169 {
00170 namespace serialization
00171 {
00172
00173 template<class ContainerAllocator> struct Serializer< ::roomba_500_series::Buttons_<ContainerAllocator> >
00174 {
00175 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00176 {
00177 stream.next(m.header);
00178 stream.next(m.clean);
00179 stream.next(m.spot);
00180 stream.next(m.dock);
00181 stream.next(m.day);
00182 stream.next(m.hour);
00183 stream.next(m.minute);
00184 stream.next(m.schedule);
00185 stream.next(m.clock);
00186 }
00187
00188 ROS_DECLARE_ALLINONE_SERIALIZER;
00189 };
00190 }
00191 }
00192
00193 namespace ros
00194 {
00195 namespace message_operations
00196 {
00197
00198 template<class ContainerAllocator>
00199 struct Printer< ::roomba_500_series::Buttons_<ContainerAllocator> >
00200 {
00201 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::roomba_500_series::Buttons_<ContainerAllocator> & v)
00202 {
00203 s << indent << "header: ";
00204 s << std::endl;
00205 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00206 s << indent << "clean: ";
00207 Printer<uint8_t>::stream(s, indent + " ", v.clean);
00208 s << indent << "spot: ";
00209 Printer<uint8_t>::stream(s, indent + " ", v.spot);
00210 s << indent << "dock: ";
00211 Printer<uint8_t>::stream(s, indent + " ", v.dock);
00212 s << indent << "day: ";
00213 Printer<uint8_t>::stream(s, indent + " ", v.day);
00214 s << indent << "hour: ";
00215 Printer<uint8_t>::stream(s, indent + " ", v.hour);
00216 s << indent << "minute: ";
00217 Printer<uint8_t>::stream(s, indent + " ", v.minute);
00218 s << indent << "schedule: ";
00219 Printer<uint8_t>::stream(s, indent + " ", v.schedule);
00220 s << indent << "clock: ";
00221 Printer<uint8_t>::stream(s, indent + " ", v.clock);
00222 }
00223 };
00224
00225
00226 }
00227 }
00228
00229 #endif // ROOMBA_500_SERIES_MESSAGE_BUTTONS_H
00230