#include <Log.h>
Public Types | |
enum | { DEBUG = 1 } |
enum | { INFO = 2 } |
enum | { WARN = 4 } |
enum | { ERROR = 8 } |
enum | { FATAL = 16 } |
Public Member Functions | |
virtual int | deserialize (unsigned char *inbuffer) |
const char * | getMD5 () |
const char * | getType () |
virtual int | serialize (unsigned char *outbuffer) const |
Public Attributes | |
char * | file |
char * | function |
std_msgs::Header | header |
int8_t | level |
uint32_t | line |
char * | msg |
char * | name |
char * | st_topics |
char ** | topics |
uint8_t | topics_length |
Definition at line 13 of file rosgraph_msgs/Log.h.
anonymous enum |
Definition at line 26 of file rosgraph_msgs/Log.h.
anonymous enum |
Definition at line 27 of file rosgraph_msgs/Log.h.
anonymous enum |
Definition at line 28 of file rosgraph_msgs/Log.h.
anonymous enum |
Definition at line 29 of file rosgraph_msgs/Log.h.
anonymous enum |
Definition at line 30 of file rosgraph_msgs/Log.h.
virtual int rosgraph_msgs::Log::deserialize | ( | unsigned char * | inbuffer | ) | [inline, virtual] |
Implements ros::Msg.
Definition at line 82 of file rosgraph_msgs/Log.h.
const char* rosgraph_msgs::Log::getMD5 | ( | ) | [inline, virtual] |
Implements ros::Msg.
Definition at line 156 of file rosgraph_msgs/Log.h.
const char* rosgraph_msgs::Log::getType | ( | ) | [inline, virtual] |
Implements ros::Msg.
Definition at line 155 of file rosgraph_msgs/Log.h.
virtual int rosgraph_msgs::Log::serialize | ( | unsigned char * | outbuffer | ) | const [inline, virtual] |
Implements ros::Msg.
Definition at line 32 of file rosgraph_msgs/Log.h.
char* rosgraph_msgs::Log::file |
Definition at line 20 of file rosgraph_msgs/Log.h.
Definition at line 21 of file rosgraph_msgs/Log.h.
Definition at line 16 of file rosgraph_msgs/Log.h.
int8_t rosgraph_msgs::Log::level |
Definition at line 17 of file rosgraph_msgs/Log.h.
uint32_t rosgraph_msgs::Log::line |
Definition at line 22 of file rosgraph_msgs/Log.h.
char* rosgraph_msgs::Log::msg |
Definition at line 19 of file rosgraph_msgs/Log.h.
char* rosgraph_msgs::Log::name |
Definition at line 18 of file rosgraph_msgs/Log.h.
Definition at line 24 of file rosgraph_msgs/Log.h.
char* * rosgraph_msgs::Log::topics |
Definition at line 25 of file rosgraph_msgs/Log.h.
Definition at line 23 of file rosgraph_msgs/Log.h.