You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.

300 lines
9.1 KiB

// Generated by gencpp from file rosgraph_msgs/Log.msg
// DO NOT EDIT!
#ifndef ROSGRAPH_MSGS_MESSAGE_LOG_H
#define ROSGRAPH_MSGS_MESSAGE_LOG_H
#include <memory>
#include <string>
#include <vector>
#include <map>
#include <ros/types.h>
#include <ros/serialization.h>
#include <ros/builtin_message_traits.h>
#include <ros/message_operations.h>
#include <std_msgs/Header.h>
namespace rosgraph_msgs
{
template <class ContainerAllocator>
struct Log_
{
typedef Log_<ContainerAllocator> Type;
Log_()
: header()
, level(0)
, name()
, msg()
, file()
, function()
, line(0)
, topics() {
}
Log_(const ContainerAllocator& _alloc)
: header(_alloc)
, level(0)
, name(_alloc)
, msg(_alloc)
, file(_alloc)
, function(_alloc)
, line(0)
, topics(_alloc) {
(void)_alloc;
}
typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
_header_type header;
typedef int8_t _level_type;
_level_type level;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > _name_type;
_name_type name;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > _msg_type;
_msg_type msg;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > _file_type;
_file_type file;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > _function_type;
_function_type function;
typedef uint32_t _line_type;
_line_type line;
typedef std::vector<std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char>::other > , typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char > > > > _topics_type;
_topics_type topics;
#undef ERROR
enum { DEBUG = 1 };
enum { INFO = 2 };
enum { WARN = 4 };
enum { ERROR = 8 };
enum { FATAL = 16 };
typedef std::shared_ptr< ::rosgraph_msgs::Log_<ContainerAllocator> > Ptr;
typedef std::shared_ptr< ::rosgraph_msgs::Log_<ContainerAllocator> const> ConstPtr;
}; // struct Log_
typedef ::rosgraph_msgs::Log_<std::allocator<void> > Log;
typedef std::shared_ptr< ::rosgraph_msgs::Log > LogPtr;
typedef std::shared_ptr< ::rosgraph_msgs::Log const> LogConstPtr;
// constants requiring out of line definition
template<typename ContainerAllocator>
std::ostream& operator<<(std::ostream& s, const ::rosgraph_msgs::Log_<ContainerAllocator> & v)
{
rs2rosinternal::message_operations::Printer< ::rosgraph_msgs::Log_<ContainerAllocator> >::stream(s, "", v);
return s;
}
} // namespace rosgraph_msgs
namespace rs2rosinternal
{
namespace message_traits
{
// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True}
// {'rosgraph_msgs': ['/tmp/binarydeb/ros-kinetic-rosgraph-msgs-1.11.2/msg'], 'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg']}
// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types']
template <class ContainerAllocator>
struct IsFixedSize< ::rosgraph_msgs::Log_<ContainerAllocator> >
: std::false_type
{ };
template <class ContainerAllocator>
struct IsFixedSize< ::rosgraph_msgs::Log_<ContainerAllocator> const>
: std::false_type
{ };
template <class ContainerAllocator>
struct IsMessage< ::rosgraph_msgs::Log_<ContainerAllocator> >
: std::true_type
{ };
template <class ContainerAllocator>
struct IsMessage< ::rosgraph_msgs::Log_<ContainerAllocator> const>
: std::true_type
{ };
template <class ContainerAllocator>
struct HasHeader< ::rosgraph_msgs::Log_<ContainerAllocator> >
: std::true_type
{ };
template <class ContainerAllocator>
struct HasHeader< ::rosgraph_msgs::Log_<ContainerAllocator> const>
: std::true_type
{ };
template<class ContainerAllocator>
struct MD5Sum< ::rosgraph_msgs::Log_<ContainerAllocator> >
{
static const char* value()
{
return "acffd30cd6b6de30f120938c17c593fb";
}
static const char* value(const ::rosgraph_msgs::Log_<ContainerAllocator>&) { return value(); }
static const uint64_t static_value1 = 0xacffd30cd6b6de30ULL;
static const uint64_t static_value2 = 0xf120938c17c593fbULL;
};
template<class ContainerAllocator>
struct DataType< ::rosgraph_msgs::Log_<ContainerAllocator> >
{
static const char* value()
{
return "rosgraph_msgs/Log";
}
static const char* value(const ::rosgraph_msgs::Log_<ContainerAllocator>&) { return value(); }
};
template<class ContainerAllocator>
struct Definition< ::rosgraph_msgs::Log_<ContainerAllocator> >
{
static const char* value()
{
return "##\n\
## Severity level constants\n\
##\n\
byte DEBUG=1 #debug level\n\
byte INFO=2 #general level\n\
byte WARN=4 #warning level\n\
byte ERROR=8 #error level\n\
byte FATAL=16 #fatal/critical level\n\
##\n\
## Fields\n\
##\n\
Header header\n\
byte level\n\
string name # name of the node\n\
string msg # message \n\
string file # file the message came from\n\
string function # function the message came from\n\
uint32 line # line the message came from\n\
string[] topics # topic names that the node publishes\n\
\n\
================================================================================\n\
MSG: std_msgs/Header\n\
# Standard metadata for higher-level stamped data types.\n\
# This is generally used to communicate timestamped data \n\
# in a particular coordinate frame.\n\
# \n\
# sequence ID: consecutively increasing ID \n\
uint32 seq\n\
#Two-integer timestamp that is expressed as:\n\
# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
# time-handling sugar is provided by the client library\n\
time stamp\n\
#Frame this data is associated with\n\
# 0: no frame\n\
# 1: global frame\n\
string frame_id\n\
";
}
static const char* value(const ::rosgraph_msgs::Log_<ContainerAllocator>&) { return value(); }
};
} // namespace message_traits
} // namespace rs2rosinternal
namespace rs2rosinternal
{
namespace serialization
{
template<class ContainerAllocator> struct Serializer< ::rosgraph_msgs::Log_<ContainerAllocator> >
{
template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
{
stream.next(m.header);
stream.next(m.level);
stream.next(m.name);
stream.next(m.msg);
stream.next(m.file);
stream.next(m.function);
stream.next(m.line);
stream.next(m.topics);
}
ROS_DECLARE_ALLINONE_SERIALIZER
}; // struct Log_
} // namespace serialization
} // namespace rs2rosinternal
namespace rs2rosinternal
{
namespace message_operations
{
template<class ContainerAllocator>
struct Printer< ::rosgraph_msgs::Log_<ContainerAllocator> >
{
template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::rosgraph_msgs::Log_<ContainerAllocator>& v)
{
s << indent << "header: ";
s << std::endl;
Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
s << indent << "level: ";
Printer<int8_t>::stream(s, indent + " ", v.level);
s << indent << "name: ";
Printer<std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > >::stream(s, indent + " ", v.name);
s << indent << "msg: ";
Printer<std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > >::stream(s, indent + " ", v.msg);
s << indent << "file: ";
Printer<std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > >::stream(s, indent + " ", v.file);
s << indent << "function: ";
Printer<std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > >::stream(s, indent + " ", v.function);
s << indent << "line: ";
Printer<uint32_t>::stream(s, indent + " ", v.line);
s << indent << "topics[]" << std::endl;
for (size_t i = 0; i < v.topics.size(); ++i)
{
s << indent << " topics[" << i << "]: ";
Printer<std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > >::stream(s, indent + " ", v.topics[i]);
}
}
};
} // namespace message_operations
} // namespace rs2rosinternal
#endif // ROSGRAPH_MSGS_MESSAGE_LOG_H