Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #include "log.hpp"
00019
00020 #include <qicore/logmessage.hpp>
00021 #include <queue>
00022
00023 #include <std_msgs/String.h>
00024
00025 #include <boost/algorithm/string.hpp>
00026 #include <boost/thread/mutex.hpp>
00027 #include <boost/foreach.hpp>
00028
00029 #include <ros/console.h>
00030
00031 #define for_each BOOST_FOREACH
00032
00033 namespace naoqi
00034 {
00035 namespace converter
00036 {
00037
00039 boost::mutex MUTEX_LOGS;
00041 std::queue<rosgraph_msgs::Log> LOGS;
00043 class LogLevel
00044 {
00045 public:
00046 LogLevel(qi::LogLevel qi, rosgraph_msgs::Log::_level_type ros_msg, ros::console::levels::Level ros_console) :
00047 qi_(qi), ros_msg_(ros_msg), ros_console_(ros_console)
00048 {
00049 all_.push_back(*this);
00050 }
00051
00052 static const LogLevel& get_from_qi(qi::LogLevel qi)
00053 {
00054 for_each(const LogLevel& log_level, all_)
00055 if (log_level.qi_ == qi)
00056 return log_level;
00057 }
00058
00059 static const LogLevel& get_from_ros_msg(rosgraph_msgs::Log::_level_type ros_msg)
00060 {
00061 for_each(const LogLevel& log_level, all_)
00062 if (log_level.ros_msg_ == ros_msg)
00063 return log_level;
00064 }
00065
00066 static const LogLevel& get_from_ros_console(ros::console::levels::Level ros_console)
00067 {
00068 for_each(const LogLevel& log_level, all_)
00069 if (log_level.ros_console_ == ros_console)
00070 return log_level;
00071 }
00072
00073 qi::LogLevel qi_;
00074 rosgraph_msgs::Log::_level_type ros_msg_;
00075 ros::console::levels::Level ros_console_;
00076
00077 private:
00078 static std::vector<LogLevel> all_;
00079 };
00080
00081 std::vector<LogLevel> LogLevel::all_ = std::vector<LogLevel>();
00082
00085 void logCallback(const qi::LogMessage& msg)
00086 {
00087
00088 rosgraph_msgs::Log log;
00089
00090 std::vector<std::string> results;
00091 boost::split(results, msg.source, boost::is_any_of(":"));
00092 log.file = results[0];
00093 log.function = results[1];
00094 log.line = atoi(results[2].c_str());
00095 log.level = LogLevel::get_from_qi(msg.level).ros_msg_;
00096 log.name = msg.category;
00097 log.msg = msg.message;
00098 log.header.stamp = ros::Time(msg.timestamp.tv_sec, msg.timestamp.tv_usec);
00099
00100
00101
00102 boost::mutex::scoped_lock lock( MUTEX_LOGS );
00103 while (LOGS.size() > 1000)
00104 {
00105 LOGS.pop();
00106 }
00107 LOGS.push(log);
00108 }
00109
00110 LogConverter::LogConverter( const std::string& name, float frequency, const qi::SessionPtr& session )
00111 : BaseConverter( name, frequency, session ),
00112 logger_( session->service("LogManager") ),
00113
00114 log_level_(qi::LogLevel_Info)
00115 {
00116
00117 LogLevel(qi::LogLevel_Silent, rosgraph_msgs::Log::DEBUG, ros::console::levels::Debug);
00118 LogLevel(qi::LogLevel_Fatal, rosgraph_msgs::Log::FATAL, ros::console::levels::Fatal);
00119 LogLevel(qi::LogLevel_Error, rosgraph_msgs::Log::ERROR, ros::console::levels::Error);
00120 LogLevel(qi::LogLevel_Warning, rosgraph_msgs::Log::WARN, ros::console::levels::Warn);
00121 LogLevel(qi::LogLevel_Info, rosgraph_msgs::Log::INFO, ros::console::levels::Info);
00122 LogLevel(qi::LogLevel_Verbose, rosgraph_msgs::Log::DEBUG, ros::console::levels::Debug);
00123 LogLevel(qi::LogLevel_Debug, rosgraph_msgs::Log::DEBUG, ros::console::levels::Debug);
00124
00125 listener_ = logger_->getListener();
00126 set_qi_logger_level();
00127 listener_->onLogMessage.connect(logCallback);
00128 }
00129
00130 void LogConverter::registerCallback( const message_actions::MessageAction action, Callback_t cb )
00131 {
00132 callbacks_[action] = cb;
00133 }
00134
00135 void LogConverter::callAll( const std::vector<message_actions::MessageAction>& actions )
00136 {
00137 while ( !LOGS.empty() )
00138 {
00139 rosgraph_msgs::Log& log_msg = LOGS.front();
00140 for_each( const message_actions::MessageAction& action, actions)
00141 {
00142 callbacks_[action](log_msg);
00143 }
00144 {
00145 boost::mutex::scoped_lock lock( MUTEX_LOGS );
00146 LOGS.pop();
00147 }
00148 }
00149 set_qi_logger_level();
00150 }
00151
00152 void LogConverter::reset( )
00153 {
00154 }
00155
00156 void LogConverter::set_qi_logger_level( )
00157 {
00158
00159 std::map<std::string, ros::console::levels::Level> loggers;
00160 ros::console::get_loggers(loggers);
00161
00162 std::map<std::string, ros::console::levels::Level>::iterator iter = loggers.find("ros.naoqi_driver");
00163
00164 if (iter == loggers.end())
00165 return;
00166
00167 qi::LogLevel new_level = LogLevel::get_from_ros_console(iter->second).qi_;
00168
00169 if (new_level == log_level_)
00170 return;
00171
00172 log_level_ = new_level;
00173 qi::log::setLogLevel(log_level_);
00174 }
00175
00176 }
00177 }