SensorState.h
Go to the documentation of this file.
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-groovy-kobuki/doc_stacks/2012-11-15_17-55-48.690038/kobuki/kobuki_comms/msg/SensorState.msg */
00002 #ifndef KOBUKI_COMMS_MESSAGE_SENSORSTATE_H
00003 #define KOBUKI_COMMS_MESSAGE_SENSORSTATE_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 kobuki_comms
00020 {
00021 template <class ContainerAllocator>
00022 struct SensorState_ {
00023   typedef SensorState_<ContainerAllocator> Type;
00024 
00025   SensorState_()
00026   : header()
00027   , time_stamp(0)
00028   , bumper(0)
00029   , wheel_drop(0)
00030   , cliff(0)
00031   , left_encoder(0)
00032   , right_encoder(0)
00033   , left_pwm(0)
00034   , right_pwm(0)
00035   , buttons(0)
00036   , charger(0)
00037   , battery(0)
00038   , bottom()
00039   , current()
00040   , digital_input(0)
00041   , analog_input()
00042   {
00043   }
00044 
00045   SensorState_(const ContainerAllocator& _alloc)
00046   : header(_alloc)
00047   , time_stamp(0)
00048   , bumper(0)
00049   , wheel_drop(0)
00050   , cliff(0)
00051   , left_encoder(0)
00052   , right_encoder(0)
00053   , left_pwm(0)
00054   , right_pwm(0)
00055   , buttons(0)
00056   , charger(0)
00057   , battery(0)
00058   , bottom(_alloc)
00059   , current(_alloc)
00060   , digital_input(0)
00061   , analog_input(_alloc)
00062   {
00063   }
00064 
00065   typedef  ::std_msgs::Header_<ContainerAllocator>  _header_type;
00066    ::std_msgs::Header_<ContainerAllocator>  header;
00067 
00068   typedef uint16_t _time_stamp_type;
00069   uint16_t time_stamp;
00070 
00071   typedef uint8_t _bumper_type;
00072   uint8_t bumper;
00073 
00074   typedef uint8_t _wheel_drop_type;
00075   uint8_t wheel_drop;
00076 
00077   typedef uint8_t _cliff_type;
00078   uint8_t cliff;
00079 
00080   typedef uint16_t _left_encoder_type;
00081   uint16_t left_encoder;
00082 
00083   typedef uint16_t _right_encoder_type;
00084   uint16_t right_encoder;
00085 
00086   typedef int8_t _left_pwm_type;
00087   int8_t left_pwm;
00088 
00089   typedef int8_t _right_pwm_type;
00090   int8_t right_pwm;
00091 
00092   typedef uint8_t _buttons_type;
00093   uint8_t buttons;
00094 
00095   typedef uint8_t _charger_type;
00096   uint8_t charger;
00097 
00098   typedef uint8_t _battery_type;
00099   uint8_t battery;
00100 
00101   typedef std::vector<uint16_t, typename ContainerAllocator::template rebind<uint16_t>::other >  _bottom_type;
00102   std::vector<uint16_t, typename ContainerAllocator::template rebind<uint16_t>::other >  bottom;
00103 
00104   typedef std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other >  _current_type;
00105   std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other >  current;
00106 
00107   typedef uint16_t _digital_input_type;
00108   uint16_t digital_input;
00109 
00110   typedef std::vector<uint16_t, typename ContainerAllocator::template rebind<uint16_t>::other >  _analog_input_type;
00111   std::vector<uint16_t, typename ContainerAllocator::template rebind<uint16_t>::other >  analog_input;
00112 
00113   enum { Button0 = 1 };
00114   enum { Button1 = 2 };
00115   enum { Button2 = 4 };
00116   enum { ADAPTER = 16 };
00117   enum { DISCHARGING = 0 };
00118   enum { CHARGED = 2 };
00119   enum { CHARGING = 6 };
00120 
00121   typedef boost::shared_ptr< ::kobuki_comms::SensorState_<ContainerAllocator> > Ptr;
00122   typedef boost::shared_ptr< ::kobuki_comms::SensorState_<ContainerAllocator>  const> ConstPtr;
00123   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00124 }; // struct SensorState
00125 typedef  ::kobuki_comms::SensorState_<std::allocator<void> > SensorState;
00126 
00127 typedef boost::shared_ptr< ::kobuki_comms::SensorState> SensorStatePtr;
00128 typedef boost::shared_ptr< ::kobuki_comms::SensorState const> SensorStateConstPtr;
00129 
00130 
00131 template<typename ContainerAllocator>
00132 std::ostream& operator<<(std::ostream& s, const  ::kobuki_comms::SensorState_<ContainerAllocator> & v)
00133 {
00134   ros::message_operations::Printer< ::kobuki_comms::SensorState_<ContainerAllocator> >::stream(s, "", v);
00135   return s;}
00136 
00137 } // namespace kobuki_comms
00138 
00139 namespace ros
00140 {
00141 namespace message_traits
00142 {
00143 template<class ContainerAllocator> struct IsMessage< ::kobuki_comms::SensorState_<ContainerAllocator> > : public TrueType {};
00144 template<class ContainerAllocator> struct IsMessage< ::kobuki_comms::SensorState_<ContainerAllocator>  const> : public TrueType {};
00145 template<class ContainerAllocator>
00146 struct MD5Sum< ::kobuki_comms::SensorState_<ContainerAllocator> > {
00147   static const char* value() 
00148   {
00149     return "98cbcd372761832ea3a9c795bb69a09f";
00150   }
00151 
00152   static const char* value(const  ::kobuki_comms::SensorState_<ContainerAllocator> &) { return value(); } 
00153   static const uint64_t static_value1 = 0x98cbcd372761832eULL;
00154   static const uint64_t static_value2 = 0xa3a9c795bb69a09fULL;
00155 };
00156 
00157 template<class ContainerAllocator>
00158 struct DataType< ::kobuki_comms::SensorState_<ContainerAllocator> > {
00159   static const char* value() 
00160   {
00161     return "kobuki_comms/SensorState";
00162   }
00163 
00164   static const char* value(const  ::kobuki_comms::SensorState_<ContainerAllocator> &) { return value(); } 
00165 };
00166 
00167 template<class ContainerAllocator>
00168 struct Definition< ::kobuki_comms::SensorState_<ContainerAllocator> > {
00169   static const char* value() 
00170   {
00171     return "# Kobuki Sensor Data Messages\n\
00172 #\n\
00173 \n\
00174 # Buttons bitmasks to decode byte \"buttons\"\n\
00175 uint8 Button0 = 1  # 0x02\n\
00176 uint8 Button1 = 2  # 0x01\n\
00177 uint8 Button2 = 4  # 0x04\n\
00178 \n\
00179 # Byte \"charger\" format:\n\
00180 # - first four bits distinguish between adapter or docking base charging\n\
00181 uint8 ADAPTER     = 16 # bitmask 0x10\n\
00182 # - last 4 bits specified the charging status\n\
00183 uint8 DISCHARGING = 0\n\
00184 uint8 CHARGED     = 2\n\
00185 uint8 CHARGING    = 6\n\
00186 \n\
00187 \n\
00188 Header header\n\
00189 \n\
00190 ###################\n\
00191 # Core Packet\n\
00192 ###################\n\
00193 uint16 time_stamp\n\
00194 uint8  bumper\n\
00195 uint8  wheel_drop\n\
00196 uint8  cliff\n\
00197 uint16 left_encoder\n\
00198 uint16 right_encoder\n\
00199 int8  left_pwm\n\
00200 int8  right_pwm\n\
00201 uint8  buttons\n\
00202 uint8  charger\n\
00203 uint8  battery\n\
00204 \n\
00205 ###################\n\
00206 # Cliff Packet\n\
00207 ###################\n\
00208 uint16[] bottom\n\
00209 \n\
00210 ###################\n\
00211 # Current Packet\n\
00212 ###################\n\
00213 uint8[] current\n\
00214 \n\
00215 ###################\n\
00216 # GP Input Packet\n\
00217 ###################\n\
00218 uint16 digital_input\n\
00219 uint16[] analog_input\n\
00220 \n\
00221 ================================================================================\n\
00222 MSG: std_msgs/Header\n\
00223 # Standard metadata for higher-level stamped data types.\n\
00224 # This is generally used to communicate timestamped data \n\
00225 # in a particular coordinate frame.\n\
00226 # \n\
00227 # sequence ID: consecutively increasing ID \n\
00228 uint32 seq\n\
00229 #Two-integer timestamp that is expressed as:\n\
00230 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00231 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00232 # time-handling sugar is provided by the client library\n\
00233 time stamp\n\
00234 #Frame this data is associated with\n\
00235 # 0: no frame\n\
00236 # 1: global frame\n\
00237 string frame_id\n\
00238 \n\
00239 ";
00240   }
00241 
00242   static const char* value(const  ::kobuki_comms::SensorState_<ContainerAllocator> &) { return value(); } 
00243 };
00244 
00245 template<class ContainerAllocator> struct HasHeader< ::kobuki_comms::SensorState_<ContainerAllocator> > : public TrueType {};
00246 template<class ContainerAllocator> struct HasHeader< const ::kobuki_comms::SensorState_<ContainerAllocator> > : public TrueType {};
00247 } // namespace message_traits
00248 } // namespace ros
00249 
00250 namespace ros
00251 {
00252 namespace serialization
00253 {
00254 
00255 template<class ContainerAllocator> struct Serializer< ::kobuki_comms::SensorState_<ContainerAllocator> >
00256 {
00257   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00258   {
00259     stream.next(m.header);
00260     stream.next(m.time_stamp);
00261     stream.next(m.bumper);
00262     stream.next(m.wheel_drop);
00263     stream.next(m.cliff);
00264     stream.next(m.left_encoder);
00265     stream.next(m.right_encoder);
00266     stream.next(m.left_pwm);
00267     stream.next(m.right_pwm);
00268     stream.next(m.buttons);
00269     stream.next(m.charger);
00270     stream.next(m.battery);
00271     stream.next(m.bottom);
00272     stream.next(m.current);
00273     stream.next(m.digital_input);
00274     stream.next(m.analog_input);
00275   }
00276 
00277   ROS_DECLARE_ALLINONE_SERIALIZER;
00278 }; // struct SensorState_
00279 } // namespace serialization
00280 } // namespace ros
00281 
00282 namespace ros
00283 {
00284 namespace message_operations
00285 {
00286 
00287 template<class ContainerAllocator>
00288 struct Printer< ::kobuki_comms::SensorState_<ContainerAllocator> >
00289 {
00290   template<typename Stream> static void stream(Stream& s, const std::string& indent, const  ::kobuki_comms::SensorState_<ContainerAllocator> & v) 
00291   {
00292     s << indent << "header: ";
00293 s << std::endl;
00294     Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + "  ", v.header);
00295     s << indent << "time_stamp: ";
00296     Printer<uint16_t>::stream(s, indent + "  ", v.time_stamp);
00297     s << indent << "bumper: ";
00298     Printer<uint8_t>::stream(s, indent + "  ", v.bumper);
00299     s << indent << "wheel_drop: ";
00300     Printer<uint8_t>::stream(s, indent + "  ", v.wheel_drop);
00301     s << indent << "cliff: ";
00302     Printer<uint8_t>::stream(s, indent + "  ", v.cliff);
00303     s << indent << "left_encoder: ";
00304     Printer<uint16_t>::stream(s, indent + "  ", v.left_encoder);
00305     s << indent << "right_encoder: ";
00306     Printer<uint16_t>::stream(s, indent + "  ", v.right_encoder);
00307     s << indent << "left_pwm: ";
00308     Printer<int8_t>::stream(s, indent + "  ", v.left_pwm);
00309     s << indent << "right_pwm: ";
00310     Printer<int8_t>::stream(s, indent + "  ", v.right_pwm);
00311     s << indent << "buttons: ";
00312     Printer<uint8_t>::stream(s, indent + "  ", v.buttons);
00313     s << indent << "charger: ";
00314     Printer<uint8_t>::stream(s, indent + "  ", v.charger);
00315     s << indent << "battery: ";
00316     Printer<uint8_t>::stream(s, indent + "  ", v.battery);
00317     s << indent << "bottom[]" << std::endl;
00318     for (size_t i = 0; i < v.bottom.size(); ++i)
00319     {
00320       s << indent << "  bottom[" << i << "]: ";
00321       Printer<uint16_t>::stream(s, indent + "  ", v.bottom[i]);
00322     }
00323     s << indent << "current[]" << std::endl;
00324     for (size_t i = 0; i < v.current.size(); ++i)
00325     {
00326       s << indent << "  current[" << i << "]: ";
00327       Printer<uint8_t>::stream(s, indent + "  ", v.current[i]);
00328     }
00329     s << indent << "digital_input: ";
00330     Printer<uint16_t>::stream(s, indent + "  ", v.digital_input);
00331     s << indent << "analog_input[]" << std::endl;
00332     for (size_t i = 0; i < v.analog_input.size(); ++i)
00333     {
00334       s << indent << "  analog_input[" << i << "]: ";
00335       Printer<uint16_t>::stream(s, indent + "  ", v.analog_input[i]);
00336     }
00337   }
00338 };
00339 
00340 
00341 } // namespace message_operations
00342 } // namespace ros
00343 
00344 #endif // KOBUKI_COMMS_MESSAGE_SENSORSTATE_H
00345 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends


kobuki_comms
Author(s): Daniel Stonier, 주영훈
autogenerated on Thu Nov 15 2012 18:05:16