00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <ros/console.h>
00038 #include <console_bridge/console.h>
00039 #include "rosconsole_bridge/bridge.h"
00040
00041 namespace rosconsole_bridge
00042 {
00043
00044 OutputHandlerROS::OutputHandlerROS(void) : OutputHandler()
00045 {
00046 }
00047
00048 OutputHandlerROS::~OutputHandlerROS(void) {
00049 console_bridge::restorePreviousOutputHandler();
00050 }
00051
00052 void OutputHandlerROS::log(const std::string &text, console_bridge::LogLevel level, const char *filename, int line)
00053 {
00054 std::string prefix;
00055
00056
00057
00058 static const std::string NEEDLE_STRING = ": ";
00059 size_t sub_index = text.find(NEEDLE_STRING);
00060 size_t space_index = text.find(" ");
00061
00062 if (sub_index != std::string::npos &&
00063 sub_index > 0 &&
00064 space_index > sub_index &&
00065 text.length() > space_index + 1)
00066 {
00067 prefix = std::string(ROSCONSOLE_NAME_PREFIX) + "." + text.substr(0, sub_index);
00068
00069 sub_index += NEEDLE_STRING.length();
00070 }
00071 else
00072 {
00073 prefix = std::string(ROSCONSOLE_NAME_PREFIX) + ".console_bridge";
00074 sub_index = 0;
00075 }
00076
00077
00078 switch (level)
00079 {
00080 case console_bridge::CONSOLE_BRIDGE_LOG_INFO:
00081 {
00082 ROSCONSOLE_DEFINE_LOCATION(true, ::ros::console::levels::Info, prefix);
00083 if (ROS_UNLIKELY(__rosconsole_define_location__enabled))
00084 {
00085 ::ros::console::print(NULL, __rosconsole_define_location__loc.logger_, __rosconsole_define_location__loc.level_, filename, line, "", "%s",
00086 text.substr(sub_index, std::string::npos).c_str());
00087 }
00088 }
00089 break;
00090 case console_bridge::CONSOLE_BRIDGE_LOG_WARN:
00091 {
00092 ROSCONSOLE_DEFINE_LOCATION(true, ::ros::console::levels::Warn, prefix);
00093 if (ROS_UNLIKELY(__rosconsole_define_location__enabled))
00094 {
00095 ::ros::console::print(NULL, __rosconsole_define_location__loc.logger_, __rosconsole_define_location__loc.level_, filename, line, "", "%s",
00096 text.substr(sub_index, std::string::npos).c_str());
00097 }
00098 }
00099 break;
00100 case console_bridge::CONSOLE_BRIDGE_LOG_ERROR:
00101 {
00102 ROSCONSOLE_DEFINE_LOCATION(true, ::ros::console::levels::Error, prefix);
00103 if (ROS_UNLIKELY(__rosconsole_define_location__enabled))
00104 {
00105 ::ros::console::print(NULL, __rosconsole_define_location__loc.logger_, __rosconsole_define_location__loc.level_, filename, line, "", "%s",
00106 text.substr(sub_index, std::string::npos).c_str());
00107 }
00108 }
00109 break;
00110 default:
00111
00112 {
00113 ROSCONSOLE_DEFINE_LOCATION(true, ::ros::console::levels::Debug, prefix);
00114 if (ROS_UNLIKELY(__rosconsole_define_location__enabled))
00115 {
00116 ::ros::console::print(NULL, __rosconsole_define_location__loc.logger_, __rosconsole_define_location__loc.level_, filename, line, "", "%s",
00117 text.substr(sub_index, std::string::npos).c_str());
00118 }
00119 }
00120 break;
00121 }
00122 }
00123
00124 RegisterOutputHandlerProxy::RegisterOutputHandlerProxy(void)
00125 {
00126 static OutputHandlerROS oh_ros;
00127 console_bridge::useOutputHandler(&oh_ros);
00128
00129
00130 console_bridge::setLogLevel(console_bridge::CONSOLE_BRIDGE_LOG_DEBUG);
00131 }
00132
00133 }