5 #ifndef SENSOR_MSGS_MESSAGE_RELATIVEHUMIDITY_H 6 #define SENSOR_MSGS_MESSAGE_RELATIVEHUMIDITY_H 22 template <
class ContainerAllocator>
67 template<
typename ContainerAllocator>
68 std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::RelativeHumidity_<ContainerAllocator> &
v)
78 namespace message_traits
91 template <
class ContainerAllocator>
96 template <
class ContainerAllocator>
101 template <
class ContainerAllocator>
106 template <
class ContainerAllocator>
111 template <
class ContainerAllocator>
116 template <
class ContainerAllocator>
122 template<
class ContainerAllocator>
127 return "8730015b05955b7e992ce29a2678d90f";
130 static const char*
value(const ::sensor_msgs::RelativeHumidity_<ContainerAllocator>&) {
return value(); }
131 static const uint64_t static_value1 = 0x8730015b05955b7eULL;
132 static const uint64_t static_value2 = 0x992ce29a2678d90fULL;
135 template<
class ContainerAllocator>
140 return "sensor_msgs/RelativeHumidity";
143 static const char*
value(const ::sensor_msgs::RelativeHumidity_<ContainerAllocator>&) {
return value(); }
146 template<
class ContainerAllocator>
151 return " # Single reading from a relative humidity sensor. Defines the ratio of partial\n\ 152 # pressure of water vapor to the saturated vapor pressure at a temperature.\n\ 154 Header header # timestamp of the measurement\n\ 155 # frame_id is the location of the humidity sensor\n\ 157 float64 relative_humidity # Expression of the relative humidity\n\ 158 # from 0.0 to 1.0.\n\ 159 # 0.0 is no partial pressure of water vapor\n\ 160 # 1.0 represents partial pressure of saturation\n\ 162 float64 variance # 0 is interpreted as variance unknown\n\ 163 ================================================================================\n\ 164 MSG: std_msgs/Header\n\ 165 # Standard metadata for higher-level stamped data types.\n\ 166 # This is generally used to communicate timestamped data \n\ 167 # in a particular coordinate frame.\n\ 169 # sequence ID: consecutively increasing ID \n\ 171 #Two-integer timestamp that is expressed as:\n\ 172 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ 173 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ 174 # time-handling sugar is provided by the client library\n\ 176 #Frame this data is associated with\n\ 183 static const char*
value(const ::sensor_msgs::RelativeHumidity_<ContainerAllocator>&) {
return value(); }
191 namespace serialization
198 stream.next(m.header);
199 stream.next(m.relative_humidity);
200 stream.next(m.variance);
211 namespace message_operations
214 template<
class ContainerAllocator>
217 template<
typename Stream>
static void stream(Stream&
s,
const std::string& indent, const ::sensor_msgs::RelativeHumidity_<ContainerAllocator>&
v)
219 s << indent <<
"header: ";
222 s << indent <<
"relative_humidity: ";
224 s << indent <<
"variance: ";
232 #endif // SENSOR_MSGS_MESSAGE_RELATIVEHUMIDITY_H static const char * value(const ::sensor_msgs::RelativeHumidity_< ContainerAllocator > &)
::std_msgs::Header_< ContainerAllocator > _header_type
boost::shared_ptr< ::sensor_msgs::RelativeHumidity const > RelativeHumidityConstPtr
typedef void(APIENTRY *GLDEBUGPROC)(GLenum source
::sensor_msgs::RelativeHumidity_< std::allocator< void > > RelativeHumidity
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
Specialize to provide the md5sum for a message.
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
static const char * value()
GLsizei const GLchar *const * string
static const char * value(const ::sensor_msgs::RelativeHumidity_< ContainerAllocator > &)
static const char * value(const ::sensor_msgs::RelativeHumidity_< ContainerAllocator > &)
Specialize to provide the datatype for a message.
A fixed-size datatype is one whose size is constant, i.e. it has no variable-length arrays or strings...
Stream base-class, provides common functionality for IStream and OStream.
_relative_humidity_type relative_humidity
RelativeHumidity_< ContainerAllocator > Type
Tools for manipulating sensor_msgs.
#define ROS_DECLARE_ALLINONE_SERIALIZER
Declare your serializer to use an allInOne member instead of requiring 3 different serialization func...
unsigned __int64 uint64_t
RelativeHumidity_(const ContainerAllocator &_alloc)
Specialize to provide the definition for a message.
static const char * value()
static void stream(Stream &s, const std::string &indent, const ::sensor_msgs::RelativeHumidity_< ContainerAllocator > &v)
static void allInOne(Stream &stream, T m)
boost::shared_ptr< ::sensor_msgs::RelativeHumidity_< ContainerAllocator > const > ConstPtr
static const char * value()
boost::shared_ptr< ::sensor_msgs::RelativeHumidity > RelativeHumidityPtr
double _relative_humidity_type
Templated serialization class. Default implementation provides backwards compatibility with old messa...
boost::shared_ptr< ::sensor_msgs::RelativeHumidity_< ContainerAllocator > > Ptr