SensorPacket.h
Go to the documentation of this file.
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-fuerte-brown_drivers/doc_stacks/2014-01-03_11-09-06.156299/brown_drivers/irobot_create_2_1/msg/SensorPacket.msg */
00002 #ifndef IROBOT_CREATE_2_1_MESSAGE_SENSORPACKET_H
00003 #define IROBOT_CREATE_2_1_MESSAGE_SENSORPACKET_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 irobot_create_2_1
00020 {
00021 template <class ContainerAllocator>
00022 struct SensorPacket_ {
00023   typedef SensorPacket_<ContainerAllocator> Type;
00024 
00025   SensorPacket_()
00026   : header()
00027   , wheeldropCaster(false)
00028   , wheeldropLeft(false)
00029   , wheeldropRight(false)
00030   , bumpLeft(false)
00031   , bumpRight(false)
00032   , wall(false)
00033   , cliffLeft(false)
00034   , cliffFronLeft(false)
00035   , cliffFrontRight(false)
00036   , cliffRight(false)
00037   , virtualWall(false)
00038   , infraredByte(0)
00039   , advance(false)
00040   , play(false)
00041   , distance(0)
00042   , angle(0)
00043   , chargingState(0)
00044   , voltage(0)
00045   , current(0)
00046   , batteryTemperature(0)
00047   , batteryCharge(0)
00048   , batteryCapacity(0)
00049   , wallSignal(0)
00050   , cliffLeftSignal(0)
00051   , cliffFrontLeftSignal(0)
00052   , cliffFrontRightSignal(0)
00053   , cliffRightSignal(0)
00054   , homeBase(false)
00055   , internalCharger(false)
00056   , songNumber(0)
00057   , songPlaying(0)
00058   {
00059   }
00060 
00061   SensorPacket_(const ContainerAllocator& _alloc)
00062   : header(_alloc)
00063   , wheeldropCaster(false)
00064   , wheeldropLeft(false)
00065   , wheeldropRight(false)
00066   , bumpLeft(false)
00067   , bumpRight(false)
00068   , wall(false)
00069   , cliffLeft(false)
00070   , cliffFronLeft(false)
00071   , cliffFrontRight(false)
00072   , cliffRight(false)
00073   , virtualWall(false)
00074   , infraredByte(0)
00075   , advance(false)
00076   , play(false)
00077   , distance(0)
00078   , angle(0)
00079   , chargingState(0)
00080   , voltage(0)
00081   , current(0)
00082   , batteryTemperature(0)
00083   , batteryCharge(0)
00084   , batteryCapacity(0)
00085   , wallSignal(0)
00086   , cliffLeftSignal(0)
00087   , cliffFrontLeftSignal(0)
00088   , cliffFrontRightSignal(0)
00089   , cliffRightSignal(0)
00090   , homeBase(false)
00091   , internalCharger(false)
00092   , songNumber(0)
00093   , songPlaying(0)
00094   {
00095   }
00096 
00097   typedef  ::std_msgs::Header_<ContainerAllocator>  _header_type;
00098    ::std_msgs::Header_<ContainerAllocator>  header;
00099 
00100   typedef uint8_t _wheeldropCaster_type;
00101   uint8_t wheeldropCaster;
00102 
00103   typedef uint8_t _wheeldropLeft_type;
00104   uint8_t wheeldropLeft;
00105 
00106   typedef uint8_t _wheeldropRight_type;
00107   uint8_t wheeldropRight;
00108 
00109   typedef uint8_t _bumpLeft_type;
00110   uint8_t bumpLeft;
00111 
00112   typedef uint8_t _bumpRight_type;
00113   uint8_t bumpRight;
00114 
00115   typedef uint8_t _wall_type;
00116   uint8_t wall;
00117 
00118   typedef uint8_t _cliffLeft_type;
00119   uint8_t cliffLeft;
00120 
00121   typedef uint8_t _cliffFronLeft_type;
00122   uint8_t cliffFronLeft;
00123 
00124   typedef uint8_t _cliffFrontRight_type;
00125   uint8_t cliffFrontRight;
00126 
00127   typedef uint8_t _cliffRight_type;
00128   uint8_t cliffRight;
00129 
00130   typedef uint8_t _virtualWall_type;
00131   uint8_t virtualWall;
00132 
00133   typedef uint8_t _infraredByte_type;
00134   uint8_t infraredByte;
00135 
00136   typedef uint8_t _advance_type;
00137   uint8_t advance;
00138 
00139   typedef uint8_t _play_type;
00140   uint8_t play;
00141 
00142   typedef int16_t _distance_type;
00143   int16_t distance;
00144 
00145   typedef int16_t _angle_type;
00146   int16_t angle;
00147 
00148   typedef uint8_t _chargingState_type;
00149   uint8_t chargingState;
00150 
00151   typedef uint16_t _voltage_type;
00152   uint16_t voltage;
00153 
00154   typedef int16_t _current_type;
00155   int16_t current;
00156 
00157   typedef int8_t _batteryTemperature_type;
00158   int8_t batteryTemperature;
00159 
00160   typedef uint16_t _batteryCharge_type;
00161   uint16_t batteryCharge;
00162 
00163   typedef uint16_t _batteryCapacity_type;
00164   uint16_t batteryCapacity;
00165 
00166   typedef uint16_t _wallSignal_type;
00167   uint16_t wallSignal;
00168 
00169   typedef uint16_t _cliffLeftSignal_type;
00170   uint16_t cliffLeftSignal;
00171 
00172   typedef uint16_t _cliffFrontLeftSignal_type;
00173   uint16_t cliffFrontLeftSignal;
00174 
00175   typedef uint16_t _cliffFrontRightSignal_type;
00176   uint16_t cliffFrontRightSignal;
00177 
00178   typedef uint16_t _cliffRightSignal_type;
00179   uint16_t cliffRightSignal;
00180 
00181   typedef uint8_t _homeBase_type;
00182   uint8_t homeBase;
00183 
00184   typedef uint8_t _internalCharger_type;
00185   uint8_t internalCharger;
00186 
00187   typedef uint8_t _songNumber_type;
00188   uint8_t songNumber;
00189 
00190   typedef uint8_t _songPlaying_type;
00191   uint8_t songPlaying;
00192 
00193 
00194   typedef boost::shared_ptr< ::irobot_create_2_1::SensorPacket_<ContainerAllocator> > Ptr;
00195   typedef boost::shared_ptr< ::irobot_create_2_1::SensorPacket_<ContainerAllocator>  const> ConstPtr;
00196   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00197 }; // struct SensorPacket
00198 typedef  ::irobot_create_2_1::SensorPacket_<std::allocator<void> > SensorPacket;
00199 
00200 typedef boost::shared_ptr< ::irobot_create_2_1::SensorPacket> SensorPacketPtr;
00201 typedef boost::shared_ptr< ::irobot_create_2_1::SensorPacket const> SensorPacketConstPtr;
00202 
00203 
00204 template<typename ContainerAllocator>
00205 std::ostream& operator<<(std::ostream& s, const  ::irobot_create_2_1::SensorPacket_<ContainerAllocator> & v)
00206 {
00207   ros::message_operations::Printer< ::irobot_create_2_1::SensorPacket_<ContainerAllocator> >::stream(s, "", v);
00208   return s;}
00209 
00210 } // namespace irobot_create_2_1
00211 
00212 namespace ros
00213 {
00214 namespace message_traits
00215 {
00216 template<class ContainerAllocator> struct IsMessage< ::irobot_create_2_1::SensorPacket_<ContainerAllocator> > : public TrueType {};
00217 template<class ContainerAllocator> struct IsMessage< ::irobot_create_2_1::SensorPacket_<ContainerAllocator>  const> : public TrueType {};
00218 template<class ContainerAllocator>
00219 struct MD5Sum< ::irobot_create_2_1::SensorPacket_<ContainerAllocator> > {
00220   static const char* value() 
00221   {
00222     return "56f92e8d70d283e7e15aa47855e73ea7";
00223   }
00224 
00225   static const char* value(const  ::irobot_create_2_1::SensorPacket_<ContainerAllocator> &) { return value(); } 
00226   static const uint64_t static_value1 = 0x56f92e8d70d283e7ULL;
00227   static const uint64_t static_value2 = 0xe15aa47855e73ea7ULL;
00228 };
00229 
00230 template<class ContainerAllocator>
00231 struct DataType< ::irobot_create_2_1::SensorPacket_<ContainerAllocator> > {
00232   static const char* value() 
00233   {
00234     return "irobot_create_2_1/SensorPacket";
00235   }
00236 
00237   static const char* value(const  ::irobot_create_2_1::SensorPacket_<ContainerAllocator> &) { return value(); } 
00238 };
00239 
00240 template<class ContainerAllocator>
00241 struct Definition< ::irobot_create_2_1::SensorPacket_<ContainerAllocator> > {
00242   static const char* value() 
00243   {
00244     return "Header header\n\
00245 bool wheeldropCaster\n\
00246 bool wheeldropLeft\n\
00247 bool wheeldropRight\n\
00248 bool bumpLeft\n\
00249 bool bumpRight\n\
00250 bool wall\n\
00251 bool cliffLeft\n\
00252 bool cliffFronLeft\n\
00253 bool cliffFrontRight\n\
00254 bool cliffRight\n\
00255 bool virtualWall\n\
00256 uint8 infraredByte\n\
00257 bool advance\n\
00258 bool play\n\
00259 int16 distance\n\
00260 int16 angle\n\
00261 uint8 chargingState\n\
00262 uint16 voltage\n\
00263 int16 current\n\
00264 int8 batteryTemperature\n\
00265 uint16 batteryCharge\n\
00266 uint16 batteryCapacity\n\
00267 uint16 wallSignal\n\
00268 uint16 cliffLeftSignal\n\
00269 uint16 cliffFrontLeftSignal\n\
00270 uint16 cliffFrontRightSignal\n\
00271 uint16 cliffRightSignal\n\
00272 bool homeBase\n\
00273 bool internalCharger\n\
00274 uint8 songNumber\n\
00275 uint8 songPlaying\n\
00276 \n\
00277 ================================================================================\n\
00278 MSG: std_msgs/Header\n\
00279 # Standard metadata for higher-level stamped data types.\n\
00280 # This is generally used to communicate timestamped data \n\
00281 # in a particular coordinate frame.\n\
00282 # \n\
00283 # sequence ID: consecutively increasing ID \n\
00284 uint32 seq\n\
00285 #Two-integer timestamp that is expressed as:\n\
00286 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00287 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00288 # time-handling sugar is provided by the client library\n\
00289 time stamp\n\
00290 #Frame this data is associated with\n\
00291 # 0: no frame\n\
00292 # 1: global frame\n\
00293 string frame_id\n\
00294 \n\
00295 ";
00296   }
00297 
00298   static const char* value(const  ::irobot_create_2_1::SensorPacket_<ContainerAllocator> &) { return value(); } 
00299 };
00300 
00301 template<class ContainerAllocator> struct HasHeader< ::irobot_create_2_1::SensorPacket_<ContainerAllocator> > : public TrueType {};
00302 template<class ContainerAllocator> struct HasHeader< const ::irobot_create_2_1::SensorPacket_<ContainerAllocator> > : public TrueType {};
00303 } // namespace message_traits
00304 } // namespace ros
00305 
00306 namespace ros
00307 {
00308 namespace serialization
00309 {
00310 
00311 template<class ContainerAllocator> struct Serializer< ::irobot_create_2_1::SensorPacket_<ContainerAllocator> >
00312 {
00313   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00314   {
00315     stream.next(m.header);
00316     stream.next(m.wheeldropCaster);
00317     stream.next(m.wheeldropLeft);
00318     stream.next(m.wheeldropRight);
00319     stream.next(m.bumpLeft);
00320     stream.next(m.bumpRight);
00321     stream.next(m.wall);
00322     stream.next(m.cliffLeft);
00323     stream.next(m.cliffFronLeft);
00324     stream.next(m.cliffFrontRight);
00325     stream.next(m.cliffRight);
00326     stream.next(m.virtualWall);
00327     stream.next(m.infraredByte);
00328     stream.next(m.advance);
00329     stream.next(m.play);
00330     stream.next(m.distance);
00331     stream.next(m.angle);
00332     stream.next(m.chargingState);
00333     stream.next(m.voltage);
00334     stream.next(m.current);
00335     stream.next(m.batteryTemperature);
00336     stream.next(m.batteryCharge);
00337     stream.next(m.batteryCapacity);
00338     stream.next(m.wallSignal);
00339     stream.next(m.cliffLeftSignal);
00340     stream.next(m.cliffFrontLeftSignal);
00341     stream.next(m.cliffFrontRightSignal);
00342     stream.next(m.cliffRightSignal);
00343     stream.next(m.homeBase);
00344     stream.next(m.internalCharger);
00345     stream.next(m.songNumber);
00346     stream.next(m.songPlaying);
00347   }
00348 
00349   ROS_DECLARE_ALLINONE_SERIALIZER;
00350 }; // struct SensorPacket_
00351 } // namespace serialization
00352 } // namespace ros
00353 
00354 namespace ros
00355 {
00356 namespace message_operations
00357 {
00358 
00359 template<class ContainerAllocator>
00360 struct Printer< ::irobot_create_2_1::SensorPacket_<ContainerAllocator> >
00361 {
00362   template<typename Stream> static void stream(Stream& s, const std::string& indent, const  ::irobot_create_2_1::SensorPacket_<ContainerAllocator> & v) 
00363   {
00364     s << indent << "header: ";
00365 s << std::endl;
00366     Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + "  ", v.header);
00367     s << indent << "wheeldropCaster: ";
00368     Printer<uint8_t>::stream(s, indent + "  ", v.wheeldropCaster);
00369     s << indent << "wheeldropLeft: ";
00370     Printer<uint8_t>::stream(s, indent + "  ", v.wheeldropLeft);
00371     s << indent << "wheeldropRight: ";
00372     Printer<uint8_t>::stream(s, indent + "  ", v.wheeldropRight);
00373     s << indent << "bumpLeft: ";
00374     Printer<uint8_t>::stream(s, indent + "  ", v.bumpLeft);
00375     s << indent << "bumpRight: ";
00376     Printer<uint8_t>::stream(s, indent + "  ", v.bumpRight);
00377     s << indent << "wall: ";
00378     Printer<uint8_t>::stream(s, indent + "  ", v.wall);
00379     s << indent << "cliffLeft: ";
00380     Printer<uint8_t>::stream(s, indent + "  ", v.cliffLeft);
00381     s << indent << "cliffFronLeft: ";
00382     Printer<uint8_t>::stream(s, indent + "  ", v.cliffFronLeft);
00383     s << indent << "cliffFrontRight: ";
00384     Printer<uint8_t>::stream(s, indent + "  ", v.cliffFrontRight);
00385     s << indent << "cliffRight: ";
00386     Printer<uint8_t>::stream(s, indent + "  ", v.cliffRight);
00387     s << indent << "virtualWall: ";
00388     Printer<uint8_t>::stream(s, indent + "  ", v.virtualWall);
00389     s << indent << "infraredByte: ";
00390     Printer<uint8_t>::stream(s, indent + "  ", v.infraredByte);
00391     s << indent << "advance: ";
00392     Printer<uint8_t>::stream(s, indent + "  ", v.advance);
00393     s << indent << "play: ";
00394     Printer<uint8_t>::stream(s, indent + "  ", v.play);
00395     s << indent << "distance: ";
00396     Printer<int16_t>::stream(s, indent + "  ", v.distance);
00397     s << indent << "angle: ";
00398     Printer<int16_t>::stream(s, indent + "  ", v.angle);
00399     s << indent << "chargingState: ";
00400     Printer<uint8_t>::stream(s, indent + "  ", v.chargingState);
00401     s << indent << "voltage: ";
00402     Printer<uint16_t>::stream(s, indent + "  ", v.voltage);
00403     s << indent << "current: ";
00404     Printer<int16_t>::stream(s, indent + "  ", v.current);
00405     s << indent << "batteryTemperature: ";
00406     Printer<int8_t>::stream(s, indent + "  ", v.batteryTemperature);
00407     s << indent << "batteryCharge: ";
00408     Printer<uint16_t>::stream(s, indent + "  ", v.batteryCharge);
00409     s << indent << "batteryCapacity: ";
00410     Printer<uint16_t>::stream(s, indent + "  ", v.batteryCapacity);
00411     s << indent << "wallSignal: ";
00412     Printer<uint16_t>::stream(s, indent + "  ", v.wallSignal);
00413     s << indent << "cliffLeftSignal: ";
00414     Printer<uint16_t>::stream(s, indent + "  ", v.cliffLeftSignal);
00415     s << indent << "cliffFrontLeftSignal: ";
00416     Printer<uint16_t>::stream(s, indent + "  ", v.cliffFrontLeftSignal);
00417     s << indent << "cliffFrontRightSignal: ";
00418     Printer<uint16_t>::stream(s, indent + "  ", v.cliffFrontRightSignal);
00419     s << indent << "cliffRightSignal: ";
00420     Printer<uint16_t>::stream(s, indent + "  ", v.cliffRightSignal);
00421     s << indent << "homeBase: ";
00422     Printer<uint8_t>::stream(s, indent + "  ", v.homeBase);
00423     s << indent << "internalCharger: ";
00424     Printer<uint8_t>::stream(s, indent + "  ", v.internalCharger);
00425     s << indent << "songNumber: ";
00426     Printer<uint8_t>::stream(s, indent + "  ", v.songNumber);
00427     s << indent << "songPlaying: ";
00428     Printer<uint8_t>::stream(s, indent + "  ", v.songPlaying);
00429   }
00430 };
00431 
00432 
00433 } // namespace message_operations
00434 } // namespace ros
00435 
00436 #endif // IROBOT_CREATE_2_1_MESSAGE_SENSORPACKET_H
00437 


irobot_create_2_1
Author(s): Graylin Trevor Jay, Brian Thomas
autogenerated on Fri Jan 3 2014 11:10:15