$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-rosserial/doc_stacks/2013-03-02_13-24-08.697680/rosserial/rosserial_msgs/msg/Log.msg */ 00002 #ifndef ROSSERIAL_MSGS_MESSAGE_LOG_H 00003 #define ROSSERIAL_MSGS_MESSAGE_LOG_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 00018 namespace rosserial_msgs 00019 { 00020 template <class ContainerAllocator> 00021 struct Log_ { 00022 typedef Log_<ContainerAllocator> Type; 00023 00024 Log_() 00025 : level(0) 00026 , msg() 00027 { 00028 } 00029 00030 Log_(const ContainerAllocator& _alloc) 00031 : level(0) 00032 , msg(_alloc) 00033 { 00034 } 00035 00036 typedef uint8_t _level_type; 00037 uint8_t level; 00038 00039 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _msg_type; 00040 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > msg; 00041 00042 enum { DEBUG = 0 }; 00043 enum { INFO = 1 }; 00044 enum { WARN = 2 }; 00045 enum { ERROR = 3 }; 00046 enum { FATAL = 4 }; 00047 00048 private: 00049 static const char* __s_getDataType_() { return "rosserial_msgs/Log"; } 00050 public: 00051 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00052 00053 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00054 00055 private: 00056 static const char* __s_getMD5Sum_() { return "7170d5aec999754ba0d9f762bf49b913"; } 00057 public: 00058 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00059 00060 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00061 00062 private: 00063 static const char* __s_getMessageDefinition_() { return "\n\ 00064 #ROS Logging Levels\n\ 00065 uint8 DEBUG=0\n\ 00066 uint8 INFO=1\n\ 00067 uint8 WARN=2\n\ 00068 uint8 ERROR=3\n\ 00069 uint8 FATAL=4\n\ 00070 \n\ 00071 uint8 level\n\ 00072 string msg\n\ 00073 \n\ 00074 "; } 00075 public: 00076 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00077 00078 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00079 00080 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00081 { 00082 ros::serialization::OStream stream(write_ptr, 1000000000); 00083 ros::serialization::serialize(stream, level); 00084 ros::serialization::serialize(stream, msg); 00085 return stream.getData(); 00086 } 00087 00088 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00089 { 00090 ros::serialization::IStream stream(read_ptr, 1000000000); 00091 ros::serialization::deserialize(stream, level); 00092 ros::serialization::deserialize(stream, msg); 00093 return stream.getData(); 00094 } 00095 00096 ROS_DEPRECATED virtual uint32_t serializationLength() const 00097 { 00098 uint32_t size = 0; 00099 size += ros::serialization::serializationLength(level); 00100 size += ros::serialization::serializationLength(msg); 00101 return size; 00102 } 00103 00104 typedef boost::shared_ptr< ::rosserial_msgs::Log_<ContainerAllocator> > Ptr; 00105 typedef boost::shared_ptr< ::rosserial_msgs::Log_<ContainerAllocator> const> ConstPtr; 00106 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00107 }; // struct Log 00108 typedef ::rosserial_msgs::Log_<std::allocator<void> > Log; 00109 00110 typedef boost::shared_ptr< ::rosserial_msgs::Log> LogPtr; 00111 typedef boost::shared_ptr< ::rosserial_msgs::Log const> LogConstPtr; 00112 00113 00114 template<typename ContainerAllocator> 00115 std::ostream& operator<<(std::ostream& s, const ::rosserial_msgs::Log_<ContainerAllocator> & v) 00116 { 00117 ros::message_operations::Printer< ::rosserial_msgs::Log_<ContainerAllocator> >::stream(s, "", v); 00118 return s;} 00119 00120 } // namespace rosserial_msgs 00121 00122 namespace ros 00123 { 00124 namespace message_traits 00125 { 00126 template<class ContainerAllocator> struct IsMessage< ::rosserial_msgs::Log_<ContainerAllocator> > : public TrueType {}; 00127 template<class ContainerAllocator> struct IsMessage< ::rosserial_msgs::Log_<ContainerAllocator> const> : public TrueType {}; 00128 template<class ContainerAllocator> 00129 struct MD5Sum< ::rosserial_msgs::Log_<ContainerAllocator> > { 00130 static const char* value() 00131 { 00132 return "7170d5aec999754ba0d9f762bf49b913"; 00133 } 00134 00135 static const char* value(const ::rosserial_msgs::Log_<ContainerAllocator> &) { return value(); } 00136 static const uint64_t static_value1 = 0x7170d5aec999754bULL; 00137 static const uint64_t static_value2 = 0xa0d9f762bf49b913ULL; 00138 }; 00139 00140 template<class ContainerAllocator> 00141 struct DataType< ::rosserial_msgs::Log_<ContainerAllocator> > { 00142 static const char* value() 00143 { 00144 return "rosserial_msgs/Log"; 00145 } 00146 00147 static const char* value(const ::rosserial_msgs::Log_<ContainerAllocator> &) { return value(); } 00148 }; 00149 00150 template<class ContainerAllocator> 00151 struct Definition< ::rosserial_msgs::Log_<ContainerAllocator> > { 00152 static const char* value() 00153 { 00154 return "\n\ 00155 #ROS Logging Levels\n\ 00156 uint8 DEBUG=0\n\ 00157 uint8 INFO=1\n\ 00158 uint8 WARN=2\n\ 00159 uint8 ERROR=3\n\ 00160 uint8 FATAL=4\n\ 00161 \n\ 00162 uint8 level\n\ 00163 string msg\n\ 00164 \n\ 00165 "; 00166 } 00167 00168 static const char* value(const ::rosserial_msgs::Log_<ContainerAllocator> &) { return value(); } 00169 }; 00170 00171 } // namespace message_traits 00172 } // namespace ros 00173 00174 namespace ros 00175 { 00176 namespace serialization 00177 { 00178 00179 template<class ContainerAllocator> struct Serializer< ::rosserial_msgs::Log_<ContainerAllocator> > 00180 { 00181 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00182 { 00183 stream.next(m.level); 00184 stream.next(m.msg); 00185 } 00186 00187 ROS_DECLARE_ALLINONE_SERIALIZER; 00188 }; // struct Log_ 00189 } // namespace serialization 00190 } // namespace ros 00191 00192 namespace ros 00193 { 00194 namespace message_operations 00195 { 00196 00197 template<class ContainerAllocator> 00198 struct Printer< ::rosserial_msgs::Log_<ContainerAllocator> > 00199 { 00200 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::rosserial_msgs::Log_<ContainerAllocator> & v) 00201 { 00202 s << indent << "level: "; 00203 Printer<uint8_t>::stream(s, indent + " ", v.level); 00204 s << indent << "msg: "; 00205 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.msg); 00206 } 00207 }; 00208 00209 00210 } // namespace message_operations 00211 } // namespace ros 00212 00213 #endif // ROSSERIAL_MSGS_MESSAGE_LOG_H 00214