Go to the documentation of this file.00001
00002 import rospy
00003
00004 from flexbe_core.proxy import ProxyPublisher
00005 from flexbe_msgs.msg import BehaviorLog
00006
00007
00008 '''
00009 Created on 12/17/2014
00010
00011 @author: Philipp Schillinger
00012 '''
00013 class Logger(object):
00014 '''
00015 Realizes behavior-specific logging.
00016 '''
00017 REPORT_INFO = BehaviorLog.INFO
00018 REPORT_WARN = BehaviorLog.WARN
00019 REPORT_HINT = BehaviorLog.HINT
00020 REPORT_ERROR = BehaviorLog.ERROR
00021
00022 LOGGING_TOPIC = 'flexbe/log'
00023
00024 _last_status_update = None
00025 _pub = None
00026
00027 @staticmethod
00028 def initialize():
00029 Logger._pub = ProxyPublisher({Logger.LOGGING_TOPIC: BehaviorLog})
00030
00031 @staticmethod
00032 def log(text, severity):
00033 if Logger._last_status_update is not None:
00034 elapsed = rospy.get_rostime() - Logger._last_status_update;
00035 if (elapsed.to_sec() < 0.1):
00036 rospy.sleep(0.05)
00037 Logger._last_status_update = rospy.get_rostime()
00038
00039 msg = BehaviorLog()
00040 msg.text = str(text)
00041 msg.status_code = severity
00042 Logger._pub.publish(Logger.LOGGING_TOPIC, msg)
00043
00044 if severity == Logger.REPORT_INFO:
00045 rospy.loginfo(text)
00046 elif severity == Logger.REPORT_WARN:
00047 rospy.logwarn(text)
00048 elif severity == Logger.REPORT_HINT:
00049 rospy.loginfo('\033[94mBehavior Hint: %s\033[0m', text)
00050 elif severity == Logger.REPORT_ERROR:
00051 rospy.logerr(text)
00052
00053
00054 @staticmethod
00055 def loginfo(text):
00056 Logger.log(text, Logger.REPORT_INFO)
00057
00058 @staticmethod
00059 def logwarn(text):
00060 Logger.log(text, Logger.REPORT_WARN)
00061
00062 @staticmethod
00063 def loghint(text):
00064 Logger.log(text, Logger.REPORT_HINT)
00065
00066 @staticmethod
00067 def logerr(text):
00068 Logger.log(text, Logger.REPORT_ERROR)