00001
00002 #ifndef PR2_MSGS_MESSAGE_ACCESSPOINT_H
00003 #define PR2_MSGS_MESSAGE_ACCESSPOINT_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
00015 namespace pr2_msgs
00016 {
00017 template <class ContainerAllocator>
00018 struct AccessPoint_ : public ros::Message
00019 {
00020 typedef AccessPoint_<ContainerAllocator> Type;
00021
00022 AccessPoint_()
00023 : header()
00024 , essid()
00025 , macaddr()
00026 , signal(0)
00027 , noise(0)
00028 , snr(0)
00029 , channel(0)
00030 , rate()
00031 , tx_power()
00032 , quality(0)
00033 {
00034 }
00035
00036 AccessPoint_(const ContainerAllocator& _alloc)
00037 : header(_alloc)
00038 , essid(_alloc)
00039 , macaddr(_alloc)
00040 , signal(0)
00041 , noise(0)
00042 , snr(0)
00043 , channel(0)
00044 , rate(_alloc)
00045 , tx_power(_alloc)
00046 , quality(0)
00047 {
00048 }
00049
00050 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00051 ::std_msgs::Header_<ContainerAllocator> header;
00052
00053 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _essid_type;
00054 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > essid;
00055
00056 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _macaddr_type;
00057 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > macaddr;
00058
00059 typedef int32_t _signal_type;
00060 int32_t signal;
00061
00062 typedef int32_t _noise_type;
00063 int32_t noise;
00064
00065 typedef int32_t _snr_type;
00066 int32_t snr;
00067
00068 typedef int32_t _channel_type;
00069 int32_t channel;
00070
00071 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _rate_type;
00072 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > rate;
00073
00074 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _tx_power_type;
00075 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > tx_power;
00076
00077 typedef int32_t _quality_type;
00078 int32_t quality;
00079
00080
00081 private:
00082 static const char* __s_getDataType_() { return "pr2_msgs/AccessPoint"; }
00083 public:
00084 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00085
00086 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00087
00088 private:
00089 static const char* __s_getMD5Sum_() { return "810217d9e35df31ffb396ea5673d7d1b"; }
00090 public:
00091 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00092
00093 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00094
00095 private:
00096 static const char* __s_getMessageDefinition_() { return "# This message communicates the state of the PR2's wifi access point.\n\
00097 Header header\n\
00098 string essid\n\
00099 string macaddr\n\
00100 int32 signal\n\
00101 int32 noise\n\
00102 int32 snr\n\
00103 int32 channel\n\
00104 string rate\n\
00105 string tx_power\n\
00106 int32 quality\n\
00107 \n\
00108 ================================================================================\n\
00109 MSG: std_msgs/Header\n\
00110 # Standard metadata for higher-level stamped data types.\n\
00111 # This is generally used to communicate timestamped data \n\
00112 # in a particular coordinate frame.\n\
00113 # \n\
00114 # sequence ID: consecutively increasing ID \n\
00115 uint32 seq\n\
00116 #Two-integer timestamp that is expressed as:\n\
00117 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00118 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00119 # time-handling sugar is provided by the client library\n\
00120 time stamp\n\
00121 #Frame this data is associated with\n\
00122 # 0: no frame\n\
00123 # 1: global frame\n\
00124 string frame_id\n\
00125 \n\
00126 "; }
00127 public:
00128 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00129
00130 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00131
00132 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00133 {
00134 ros::serialization::OStream stream(write_ptr, 1000000000);
00135 ros::serialization::serialize(stream, header);
00136 ros::serialization::serialize(stream, essid);
00137 ros::serialization::serialize(stream, macaddr);
00138 ros::serialization::serialize(stream, signal);
00139 ros::serialization::serialize(stream, noise);
00140 ros::serialization::serialize(stream, snr);
00141 ros::serialization::serialize(stream, channel);
00142 ros::serialization::serialize(stream, rate);
00143 ros::serialization::serialize(stream, tx_power);
00144 ros::serialization::serialize(stream, quality);
00145 return stream.getData();
00146 }
00147
00148 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00149 {
00150 ros::serialization::IStream stream(read_ptr, 1000000000);
00151 ros::serialization::deserialize(stream, header);
00152 ros::serialization::deserialize(stream, essid);
00153 ros::serialization::deserialize(stream, macaddr);
00154 ros::serialization::deserialize(stream, signal);
00155 ros::serialization::deserialize(stream, noise);
00156 ros::serialization::deserialize(stream, snr);
00157 ros::serialization::deserialize(stream, channel);
00158 ros::serialization::deserialize(stream, rate);
00159 ros::serialization::deserialize(stream, tx_power);
00160 ros::serialization::deserialize(stream, quality);
00161 return stream.getData();
00162 }
00163
00164 ROS_DEPRECATED virtual uint32_t serializationLength() const
00165 {
00166 uint32_t size = 0;
00167 size += ros::serialization::serializationLength(header);
00168 size += ros::serialization::serializationLength(essid);
00169 size += ros::serialization::serializationLength(macaddr);
00170 size += ros::serialization::serializationLength(signal);
00171 size += ros::serialization::serializationLength(noise);
00172 size += ros::serialization::serializationLength(snr);
00173 size += ros::serialization::serializationLength(channel);
00174 size += ros::serialization::serializationLength(rate);
00175 size += ros::serialization::serializationLength(tx_power);
00176 size += ros::serialization::serializationLength(quality);
00177 return size;
00178 }
00179
00180 typedef boost::shared_ptr< ::pr2_msgs::AccessPoint_<ContainerAllocator> > Ptr;
00181 typedef boost::shared_ptr< ::pr2_msgs::AccessPoint_<ContainerAllocator> const> ConstPtr;
00182 };
00183 typedef ::pr2_msgs::AccessPoint_<std::allocator<void> > AccessPoint;
00184
00185 typedef boost::shared_ptr< ::pr2_msgs::AccessPoint> AccessPointPtr;
00186 typedef boost::shared_ptr< ::pr2_msgs::AccessPoint const> AccessPointConstPtr;
00187
00188
00189 template<typename ContainerAllocator>
00190 std::ostream& operator<<(std::ostream& s, const ::pr2_msgs::AccessPoint_<ContainerAllocator> & v)
00191 {
00192 ros::message_operations::Printer< ::pr2_msgs::AccessPoint_<ContainerAllocator> >::stream(s, "", v);
00193 return s;}
00194
00195 }
00196
00197 namespace ros
00198 {
00199 namespace message_traits
00200 {
00201 template<class ContainerAllocator>
00202 struct MD5Sum< ::pr2_msgs::AccessPoint_<ContainerAllocator> > {
00203 static const char* value()
00204 {
00205 return "810217d9e35df31ffb396ea5673d7d1b";
00206 }
00207
00208 static const char* value(const ::pr2_msgs::AccessPoint_<ContainerAllocator> &) { return value(); }
00209 static const uint64_t static_value1 = 0x810217d9e35df31fULL;
00210 static const uint64_t static_value2 = 0xfb396ea5673d7d1bULL;
00211 };
00212
00213 template<class ContainerAllocator>
00214 struct DataType< ::pr2_msgs::AccessPoint_<ContainerAllocator> > {
00215 static const char* value()
00216 {
00217 return "pr2_msgs/AccessPoint";
00218 }
00219
00220 static const char* value(const ::pr2_msgs::AccessPoint_<ContainerAllocator> &) { return value(); }
00221 };
00222
00223 template<class ContainerAllocator>
00224 struct Definition< ::pr2_msgs::AccessPoint_<ContainerAllocator> > {
00225 static const char* value()
00226 {
00227 return "# This message communicates the state of the PR2's wifi access point.\n\
00228 Header header\n\
00229 string essid\n\
00230 string macaddr\n\
00231 int32 signal\n\
00232 int32 noise\n\
00233 int32 snr\n\
00234 int32 channel\n\
00235 string rate\n\
00236 string tx_power\n\
00237 int32 quality\n\
00238 \n\
00239 ================================================================================\n\
00240 MSG: std_msgs/Header\n\
00241 # Standard metadata for higher-level stamped data types.\n\
00242 # This is generally used to communicate timestamped data \n\
00243 # in a particular coordinate frame.\n\
00244 # \n\
00245 # sequence ID: consecutively increasing ID \n\
00246 uint32 seq\n\
00247 #Two-integer timestamp that is expressed as:\n\
00248 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00249 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00250 # time-handling sugar is provided by the client library\n\
00251 time stamp\n\
00252 #Frame this data is associated with\n\
00253 # 0: no frame\n\
00254 # 1: global frame\n\
00255 string frame_id\n\
00256 \n\
00257 ";
00258 }
00259
00260 static const char* value(const ::pr2_msgs::AccessPoint_<ContainerAllocator> &) { return value(); }
00261 };
00262
00263 template<class ContainerAllocator> struct HasHeader< ::pr2_msgs::AccessPoint_<ContainerAllocator> > : public TrueType {};
00264 template<class ContainerAllocator> struct HasHeader< const ::pr2_msgs::AccessPoint_<ContainerAllocator> > : public TrueType {};
00265 }
00266 }
00267
00268 namespace ros
00269 {
00270 namespace serialization
00271 {
00272
00273 template<class ContainerAllocator> struct Serializer< ::pr2_msgs::AccessPoint_<ContainerAllocator> >
00274 {
00275 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00276 {
00277 stream.next(m.header);
00278 stream.next(m.essid);
00279 stream.next(m.macaddr);
00280 stream.next(m.signal);
00281 stream.next(m.noise);
00282 stream.next(m.snr);
00283 stream.next(m.channel);
00284 stream.next(m.rate);
00285 stream.next(m.tx_power);
00286 stream.next(m.quality);
00287 }
00288
00289 ROS_DECLARE_ALLINONE_SERIALIZER;
00290 };
00291 }
00292 }
00293
00294 namespace ros
00295 {
00296 namespace message_operations
00297 {
00298
00299 template<class ContainerAllocator>
00300 struct Printer< ::pr2_msgs::AccessPoint_<ContainerAllocator> >
00301 {
00302 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::pr2_msgs::AccessPoint_<ContainerAllocator> & v)
00303 {
00304 s << indent << "header: ";
00305 s << std::endl;
00306 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00307 s << indent << "essid: ";
00308 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.essid);
00309 s << indent << "macaddr: ";
00310 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.macaddr);
00311 s << indent << "signal: ";
00312 Printer<int32_t>::stream(s, indent + " ", v.signal);
00313 s << indent << "noise: ";
00314 Printer<int32_t>::stream(s, indent + " ", v.noise);
00315 s << indent << "snr: ";
00316 Printer<int32_t>::stream(s, indent + " ", v.snr);
00317 s << indent << "channel: ";
00318 Printer<int32_t>::stream(s, indent + " ", v.channel);
00319 s << indent << "rate: ";
00320 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.rate);
00321 s << indent << "tx_power: ";
00322 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.tx_power);
00323 s << indent << "quality: ";
00324 Printer<int32_t>::stream(s, indent + " ", v.quality);
00325 }
00326 };
00327
00328
00329 }
00330 }
00331
00332 #endif // PR2_MSGS_MESSAGE_ACCESSPOINT_H
00333