6 from rosgraph_msgs.msg 
import Log
 
   12     cmsg = re.sub(
r'\x1b\[31m', 
'<span style="color: red">', cmsg)
 
   13     cmsg = re.sub(
r'\x1b\[32m', 
'<span style="color: green">', cmsg)
 
   14     cmsg = re.sub(
r'\x1b\[33m', 
'<span style="color: yellow">', cmsg)
 
   15     cmsg = re.sub(
r'\x1b\[34m', 
'<span style="color: blue">', cmsg)
 
   16     cmsg = re.sub(
r'\x1b\[35m', 
'<span style="color: purple">', cmsg)
 
   17     cmsg = re.sub(
r'\x1b\[36m', 
'<span style="color: cyan">', cmsg)
 
   18     cmsg = re.sub(
r'\x1b\[0m', 
'</span>', cmsg)
 
   19     if msg.level == Log.DEBUG:
 
   20         return '<span style="color: rgb(120,120,120);">%s</span>' % cmsg
 
   21     elif msg.level == Log.INFO:
 
   22         return '<span style="color: white;">%s</span>' % cmsg
 
   23     elif msg.level == Log.WARN:
 
   24         return '<span style="color: yellow;">%s</span>' % cmsg
 
   25     elif msg.level == Log.ERROR:
 
   26         return '<span style="color: red;">%s</span>' % cmsg
 
   27     elif msg.level == Log.FATAL:
 
   28         return '<span style="color: red;">%s</span>' % cmsg
 
   32     for exclude_regex 
in exclude_regexes:
 
   33         if re.match(exclude_regex, msg.msg):
 
   37     if msg.name 
not in ignore_nodes:
 
   38         if msg.name 
in nodes 
or len(nodes) == 0:
 
   39             if len(nodes_regexp) == 0 
or nodes_regexp_compiled.match(msg.name):
 
   42                     if len(lines) > line_buffer_length:
 
   43                         lines = lines[0:line_buffer_length]
 
   46                     if len(lines) > line_buffer_length:
 
   47                         lines = lines[-line_buffer_length:]
 
   56                 text.text = 
"\n".join(lines)
 
   60 if __name__ == 
"__main__":
 
   61     rospy.init_node(
"rosconsole_overlay_text")
 
   62     nodes = rospy.get_param(
"~nodes", [])
 
   63     nodes_regexp = rospy.get_param(
"~nodes_regexp", 
"")
 
   65         nodes_regexp_compiled = re.compile(nodes_regexp)
 
   66     ignore_nodes = rospy.get_param(
"~ignore_nodes", [])
 
   67     exclude_regexes = rospy.get_param(
"~exclude_regexes", [])
 
   68     line_buffer_length = rospy.get_param(
"~line_buffer_length", 100)
 
   69     reverse_lines = rospy.get_param(
"~reverse_lines", 
True)
 
   71     sub = rospy.Subscriber(
"/rosout", Log, callback)
 
   72     pub = rospy.Publisher(
"~output", OverlayText, queue_size=1)