Go to the documentation of this file.00001 #ifndef __ROS_LOGGER_H
00002 #define __ROS_LOGGER_H
00003
00004 #include "pointmatcher/PointMatcher.h"
00005
00006 namespace PointMatcherSupport
00007 {
00008 struct ROSLogger: public Logger
00009 {
00010 inline static const std::string description()
00011 {
00012 return "Log using ROS console.";
00013 }
00014
00015 virtual bool hasInfoChannel() const{ return true; };
00016 virtual void beginInfoEntry(const char *file, unsigned line, const char *func);
00017 virtual std::ostream* infoStream() { return &_infoStream; }
00018 virtual void finishInfoEntry(const char *file, unsigned line, const char *func);
00019 virtual bool hasWarningChannel() const { return true; }
00020 virtual void beginWarningEntry(const char *file, unsigned line, const char *func);
00021 virtual std::ostream* warningStream() { return &_warningStream; }
00022 virtual void finishWarningEntry(const char *file, unsigned line, const char *func);
00023
00024 protected:
00025 void writeRosLog(ros::console::Level level, const char* file, int line, const char *func, const std::string& text);
00026
00027 std::ostringstream _infoStream;
00028 std::ostringstream _warningStream;
00029 };
00030
00031 void ROSLogger::beginInfoEntry(const char *file, unsigned line, const char *func)
00032 {
00033 _infoStream.str("");
00034 }
00035
00036 void ROSLogger::finishInfoEntry(const char *file, unsigned line, const char *func)
00037 {
00038 writeRosLog(ros::console::levels::Info, file, line, func, _infoStream.str());
00039 }
00040
00041 void ROSLogger::beginWarningEntry(const char *file, unsigned line, const char *func)
00042 {
00043 _warningStream.str("");
00044 }
00045
00046 void ROSLogger::finishWarningEntry(const char *file, unsigned line, const char *func)
00047 {
00048 writeRosLog(ros::console::levels::Warn, file, line, func, _warningStream.str());
00049 }
00050
00051 void ROSLogger::writeRosLog(ros::console::Level level, const char* file, int line, const char *func, const std::string& text)
00052 {
00053 ROSCONSOLE_DEFINE_LOCATION(true, level, ROSCONSOLE_DEFAULT_NAME);
00054 if (enabled)
00055 ros::console::print(0, loc.logger_, loc.level_, file, line, func, "%s", text.c_str());
00056 }
00057 };
00058
00059 #endif // __ROS_LOGGER_H