AccessPoint.h
Go to the documentation of this file.
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-groovy-pr2_common/doc_stacks/2014-10-06_03-28-41.757574/pr2_common/pr2_msgs/msg/AccessPoint.msg */
00002 #ifndef PR2_MSGS_MESSAGE_ACCESSPOINT_H
00003 #define PR2_MSGS_MESSAGE_ACCESSPOINT_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 pr2_msgs
00020 {
00021 template <class ContainerAllocator>
00022 struct AccessPoint_ {
00023   typedef AccessPoint_<ContainerAllocator> Type;
00024 
00025   AccessPoint_()
00026   : header()
00027   , essid()
00028   , macaddr()
00029   , signal(0)
00030   , noise(0)
00031   , snr(0)
00032   , channel(0)
00033   , rate()
00034   , tx_power()
00035   , quality(0)
00036   {
00037   }
00038 
00039   AccessPoint_(const ContainerAllocator& _alloc)
00040   : header(_alloc)
00041   , essid(_alloc)
00042   , macaddr(_alloc)
00043   , signal(0)
00044   , noise(0)
00045   , snr(0)
00046   , channel(0)
00047   , rate(_alloc)
00048   , tx_power(_alloc)
00049   , quality(0)
00050   {
00051   }
00052 
00053   typedef  ::std_msgs::Header_<ContainerAllocator>  _header_type;
00054    ::std_msgs::Header_<ContainerAllocator>  header;
00055 
00056   typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  _essid_type;
00057   std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  essid;
00058 
00059   typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  _macaddr_type;
00060   std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  macaddr;
00061 
00062   typedef int32_t _signal_type;
00063   int32_t signal;
00064 
00065   typedef int32_t _noise_type;
00066   int32_t noise;
00067 
00068   typedef int32_t _snr_type;
00069   int32_t snr;
00070 
00071   typedef int32_t _channel_type;
00072   int32_t channel;
00073 
00074   typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  _rate_type;
00075   std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  rate;
00076 
00077   typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  _tx_power_type;
00078   std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  tx_power;
00079 
00080   typedef int32_t _quality_type;
00081   int32_t quality;
00082 
00083 
00084   typedef boost::shared_ptr< ::pr2_msgs::AccessPoint_<ContainerAllocator> > Ptr;
00085   typedef boost::shared_ptr< ::pr2_msgs::AccessPoint_<ContainerAllocator>  const> ConstPtr;
00086   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00087 }; // struct AccessPoint
00088 typedef  ::pr2_msgs::AccessPoint_<std::allocator<void> > AccessPoint;
00089 
00090 typedef boost::shared_ptr< ::pr2_msgs::AccessPoint> AccessPointPtr;
00091 typedef boost::shared_ptr< ::pr2_msgs::AccessPoint const> AccessPointConstPtr;
00092 
00093 
00094 template<typename ContainerAllocator>
00095 std::ostream& operator<<(std::ostream& s, const  ::pr2_msgs::AccessPoint_<ContainerAllocator> & v)
00096 {
00097   ros::message_operations::Printer< ::pr2_msgs::AccessPoint_<ContainerAllocator> >::stream(s, "", v);
00098   return s;}
00099 
00100 } // namespace pr2_msgs
00101 
00102 namespace ros
00103 {
00104 namespace message_traits
00105 {
00106 template<class ContainerAllocator> struct IsMessage< ::pr2_msgs::AccessPoint_<ContainerAllocator> > : public TrueType {};
00107 template<class ContainerAllocator> struct IsMessage< ::pr2_msgs::AccessPoint_<ContainerAllocator>  const> : public TrueType {};
00108 template<class ContainerAllocator>
00109 struct MD5Sum< ::pr2_msgs::AccessPoint_<ContainerAllocator> > {
00110   static const char* value() 
00111   {
00112     return "810217d9e35df31ffb396ea5673d7d1b";
00113   }
00114 
00115   static const char* value(const  ::pr2_msgs::AccessPoint_<ContainerAllocator> &) { return value(); } 
00116   static const uint64_t static_value1 = 0x810217d9e35df31fULL;
00117   static const uint64_t static_value2 = 0xfb396ea5673d7d1bULL;
00118 };
00119 
00120 template<class ContainerAllocator>
00121 struct DataType< ::pr2_msgs::AccessPoint_<ContainerAllocator> > {
00122   static const char* value() 
00123   {
00124     return "pr2_msgs/AccessPoint";
00125   }
00126 
00127   static const char* value(const  ::pr2_msgs::AccessPoint_<ContainerAllocator> &) { return value(); } 
00128 };
00129 
00130 template<class ContainerAllocator>
00131 struct Definition< ::pr2_msgs::AccessPoint_<ContainerAllocator> > {
00132   static const char* value() 
00133   {
00134     return "# This message communicates the state of the PR2's wifi access point.\n\
00135 Header header\n\
00136 string essid\n\
00137 string macaddr\n\
00138 int32 signal\n\
00139 int32 noise\n\
00140 int32 snr\n\
00141 int32 channel\n\
00142 string rate\n\
00143 string tx_power\n\
00144 int32 quality\n\
00145 \n\
00146 ================================================================================\n\
00147 MSG: std_msgs/Header\n\
00148 # Standard metadata for higher-level stamped data types.\n\
00149 # This is generally used to communicate timestamped data \n\
00150 # in a particular coordinate frame.\n\
00151 # \n\
00152 # sequence ID: consecutively increasing ID \n\
00153 uint32 seq\n\
00154 #Two-integer timestamp that is expressed as:\n\
00155 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00156 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00157 # time-handling sugar is provided by the client library\n\
00158 time stamp\n\
00159 #Frame this data is associated with\n\
00160 # 0: no frame\n\
00161 # 1: global frame\n\
00162 string frame_id\n\
00163 \n\
00164 ";
00165   }
00166 
00167   static const char* value(const  ::pr2_msgs::AccessPoint_<ContainerAllocator> &) { return value(); } 
00168 };
00169 
00170 template<class ContainerAllocator> struct HasHeader< ::pr2_msgs::AccessPoint_<ContainerAllocator> > : public TrueType {};
00171 template<class ContainerAllocator> struct HasHeader< const ::pr2_msgs::AccessPoint_<ContainerAllocator> > : public TrueType {};
00172 } // namespace message_traits
00173 } // namespace ros
00174 
00175 namespace ros
00176 {
00177 namespace serialization
00178 {
00179 
00180 template<class ContainerAllocator> struct Serializer< ::pr2_msgs::AccessPoint_<ContainerAllocator> >
00181 {
00182   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00183   {
00184     stream.next(m.header);
00185     stream.next(m.essid);
00186     stream.next(m.macaddr);
00187     stream.next(m.signal);
00188     stream.next(m.noise);
00189     stream.next(m.snr);
00190     stream.next(m.channel);
00191     stream.next(m.rate);
00192     stream.next(m.tx_power);
00193     stream.next(m.quality);
00194   }
00195 
00196   ROS_DECLARE_ALLINONE_SERIALIZER;
00197 }; // struct AccessPoint_
00198 } // namespace serialization
00199 } // namespace ros
00200 
00201 namespace ros
00202 {
00203 namespace message_operations
00204 {
00205 
00206 template<class ContainerAllocator>
00207 struct Printer< ::pr2_msgs::AccessPoint_<ContainerAllocator> >
00208 {
00209   template<typename Stream> static void stream(Stream& s, const std::string& indent, const  ::pr2_msgs::AccessPoint_<ContainerAllocator> & v) 
00210   {
00211     s << indent << "header: ";
00212 s << std::endl;
00213     Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + "  ", v.header);
00214     s << indent << "essid: ";
00215     Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + "  ", v.essid);
00216     s << indent << "macaddr: ";
00217     Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + "  ", v.macaddr);
00218     s << indent << "signal: ";
00219     Printer<int32_t>::stream(s, indent + "  ", v.signal);
00220     s << indent << "noise: ";
00221     Printer<int32_t>::stream(s, indent + "  ", v.noise);
00222     s << indent << "snr: ";
00223     Printer<int32_t>::stream(s, indent + "  ", v.snr);
00224     s << indent << "channel: ";
00225     Printer<int32_t>::stream(s, indent + "  ", v.channel);
00226     s << indent << "rate: ";
00227     Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + "  ", v.rate);
00228     s << indent << "tx_power: ";
00229     Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + "  ", v.tx_power);
00230     s << indent << "quality: ";
00231     Printer<int32_t>::stream(s, indent + "  ", v.quality);
00232   }
00233 };
00234 
00235 
00236 } // namespace message_operations
00237 } // namespace ros
00238 
00239 #endif // PR2_MSGS_MESSAGE_ACCESSPOINT_H
00240 


pr2_msgs
Author(s): Eric Berger and many others
autogenerated on Mon Oct 6 2014 03:30:41