Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

improved rospy core logger test. #1144

Merged
merged 7 commits into from
Aug 28, 2017
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 3 additions & 2 deletions clients/rospy/src/rospy/core.py
Original file line number Diff line number Diff line change
Expand Up @@ -344,10 +344,11 @@ def configure_logging(node_name, level=logging.INFO):
filename = os.path.abspath(logfilename_remap)
else:
# fix filesystem-unsafe chars
filename = node_name.replace('/', '_') + '.log'
suffix = '.log'
filename = node_name.replace('/', '_') + suffix
if filename[0] == '_':
filename = filename[1:]
if not filename:
if filename == suffix:
raise rospy.exceptions.ROSException('invalid configure_logging parameter: %s'%node_name)
_log_filename = rosgraph.roslogging.configure_logging('rospy', level, filename=filename)

Expand Down
4 changes: 2 additions & 2 deletions clients/rospy/src/rospy/impl/init.py
Original file line number Diff line number Diff line change
Expand Up @@ -107,5 +107,5 @@ def start_node(environ, resolved_name, master_uri=None, port=0, tcpros_port=0):
return node

class RosStreamHandler(rosgraph.roslogging.RosStreamHandler):
def __init__(self, colorize=True):
super(RosStreamHandler, self).__init__(colorize)
def __init__(self, colorize=True, stdout=None, stderr=None):
super(RosStreamHandler, self).__init__(colorize=colorize, stdout=stdout, stderr=stderr)
190 changes: 112 additions & 78 deletions test/test_rospy/test/rostest/test_rospy_client_online.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,13 @@
import unittest
import time
import random
import logging
import rosgraph.roslogging

try:
from cStringIO import StringIO
except ImportError:
from io import StringIO

import rosunit

Expand Down Expand Up @@ -68,141 +75,168 @@ def __init__(self, *args):
rospy.init_node('test_rospy_online')

def test_log(self):
# we can't do anything fancy here like capture stdout as rospy
# grabs the streams before we do. Instead, just make sure the
# routines don't crash.

real_stdout = sys.stdout
real_stderr = sys.stderr
rosout_logger = logging.getLogger('rosout')
import rospy

self.assertTrue(len(rosout_logger.handlers) == 2)
self.assertTrue(rosout_logger.handlers[0], rosgraph.roslogging.RosStreamHandler)
self.assertTrue(rosout_logger.handlers[1], rospy.impl.rosout.RosOutHandler)

default_ros_handler = rosout_logger.handlers[0]

# Remap stdout for testing
lout = StringIO()
lerr = StringIO()
test_ros_handler = rosgraph.roslogging.RosStreamHandler(colorize=False, stdout=lout, stderr=lerr)

try:
try:
from cStringIO import StringIO
except ImportError:
from io import StringIO
sys.stdout = StringIO()
sys.stderr = StringIO()
# hack to replace the stream handler with a debug version
rosout_logger.removeHandler(default_ros_handler)
rosout_logger.addHandler(test_ros_handler)

import rospy
rospy.loginfo("test 1")
self.assert_("test 1" in sys.stdout.getvalue())
lout_last = lout.getvalue().splitlines()[-1]
self.assert_("test 1" in lout_last)

rospy.logwarn("test 2")
self.assert_("[WARN]" in sys.stderr.getvalue())
self.assert_("test 2" in sys.stderr.getvalue())

sys.stderr = StringIO()
rospy.logerr("test 3")
self.assert_("[ERROR]" in sys.stderr.getvalue())
self.assert_("test 3" in sys.stderr.getvalue())

sys.stderr = StringIO()
rospy.logfatal("test 4")
self.assert_("[FATAL]" in sys.stderr.getvalue())
self.assert_("test 4" in sys.stderr.getvalue())
rospy.logwarn("test 2")
lerr_last = lerr.getvalue().splitlines()[-1]
self.assert_("[WARN]" in lerr_last)
self.assert_("test 2" in lerr_last)

rospy.logerr("test 3")
lerr_last = lerr.getvalue().splitlines()[-1]
self.assert_("[ERROR]" in lerr_last)
self.assert_("test 3" in lerr_last)

rospy.logfatal("test 4")
lerr_last = lerr.getvalue().splitlines()[-1]
self.assert_("[FATAL]" in lerr_last)
self.assert_("test 4" in lerr_last)

# logXXX_once
lout_len = -1
for i in range(3):
sys.stdout = StringIO()
rospy.loginfo_once("test 1")
lout_last = lout.getvalue().splitlines()[-1]
if i == 0:
self.assert_("test 1" in sys.stdout.getvalue())
else:
self.assert_("" == sys.stdout.getvalue())
self.assert_("test 1" in lout_last)
lout_len = len(lout.getvalue())
else: # making sure the length of lout doesnt change
self.assert_(lout_len == len(lout.getvalue()))

lerr_len = -1
for i in range(3):
sys.stderr = StringIO()
rospy.logwarn_once("test 2")
lerr_last = lerr.getvalue().splitlines()[-1]
if i == 0:
self.assert_("test 2" in sys.stderr.getvalue())
else:
self.assert_("" == sys.stderr.getvalue())
self.assert_("test 2" in lerr_last)
lerr_len = len(lerr.getvalue())
else: # making sure the length of lerr doesnt change
self.assert_(lerr_len == len(lerr.getvalue()))

lerr_len = -1
for i in range(3):
sys.stderr = StringIO()
rospy.logerr_once("test 3")
lerr_last = lerr.getvalue().splitlines()[-1]
if i == 0:
self.assert_("test 3" in sys.stderr.getvalue())
else:
self.assert_("" == sys.stderr.getvalue())
self.assert_("test 3" in lerr_last)
lerr_len = len(lerr.getvalue())
else: # making sure the length of lerr doesnt change
self.assert_(lerr_len == len(lerr.getvalue()))

lerr_len = -1
for i in range(3):
sys.stderr = StringIO()
rospy.logfatal_once("test 4")
lerr_last = lerr.getvalue().splitlines()[-1]
if i == 0:
self.assert_("test 4" in sys.stderr.getvalue())
else:
self.assert_("" == sys.stderr.getvalue())
self.assert_("test 4" in lerr_last)
lerr_len = len(lerr.getvalue())
else: # making sure the length of lerr doesnt change
self.assert_(lerr_len == len(lerr.getvalue()))

# logXXX_throttle
lout_len = -1
for i in range(3):
sys.stdout = StringIO()
rospy.loginfo_throttle(3, "test 1")
lout_last = lout.getvalue().splitlines()[-1]
if i == 0:
self.assert_("test 1" in sys.stdout.getvalue())
self.assert_("test 1" in lout_last)
lout_len = len(lout.getvalue())
rospy.sleep(rospy.Duration(1))
elif i == 1:
self.assert_("" == sys.stdout.getvalue())
elif i == 1: # making sure the length of lerr doesnt change
self.assert_(lout_len == len(lout.getvalue()))
rospy.sleep(rospy.Duration(2))
else:
self.assert_("test 1" in sys.stdout.getvalue())
self.assert_("test 1" in lout_last)

lerr_len = -1
for i in range(3):
sys.stderr = StringIO()
rospy.logwarn_throttle(3, "test 2")
lerr_last = lerr.getvalue().splitlines()[-1]
if i == 0:
self.assert_("test 2" in sys.stderr.getvalue())
self.assert_("test 2" in lerr_last)
lerr_len = len(lerr.getvalue())
rospy.sleep(rospy.Duration(1))
elif i == 1:
self.assert_("" == sys.stderr.getvalue())
elif i == 1: # making sure the length of lerr doesnt change
self.assert_(lerr_len == len(lerr.getvalue()))
rospy.sleep(rospy.Duration(2))
else:
self.assert_("test 2" in sys.stderr.getvalue())
self.assert_("test 2" in lerr_last)

lerr_len = -1
for i in range(3):
sys.stderr = StringIO()
rospy.logerr_throttle(3, "test 3")
lerr_last = lerr.getvalue().splitlines()[-1]
if i == 0:
self.assert_("test 3" in sys.stderr.getvalue())
self.assert_("test 3" in lerr_last)
lerr_len = len(lerr.getvalue())
rospy.sleep(rospy.Duration(1))
elif i == 1:
self.assert_("" == sys.stderr.getvalue())
elif i == 1: # making sure the length of lerr doesnt change
self.assert_(lerr_len == len(lerr.getvalue()))
rospy.sleep(rospy.Duration(2))
else:
self.assert_("test 3" in sys.stderr.getvalue())
self.assert_("test 3" in lerr_last)

lerr_len = -1
for i in range(3):
sys.stderr = StringIO()
rospy.logfatal_throttle(3, "test 4")
lerr_last = lerr.getvalue().splitlines()[-1]
if i == 0:
self.assert_("test 4" in sys.stderr.getvalue())
self.assert_("test 4" in lerr_last)
lerr_len = len(lerr.getvalue())
rospy.sleep(rospy.Duration(1))
elif i == 1:
self.assert_("" == sys.stderr.getvalue())
elif i == 1: # making sure the length of lerr doesnt change
self.assert_(lerr_len == len(lerr.getvalue()))
rospy.sleep(rospy.Duration(2))
else:
self.assert_("test 4" in sys.stderr.getvalue())
self.assert_("test 4" in lerr_last)

rospy.loginfo("test child logger 1", logger_name="log1")
self.assert_("test child logger 1" in sys.stdout.getvalue())

rospy.logwarn("test child logger 2", logger_name="log2")
self.assert_("[WARN]" in sys.stderr.getvalue())
self.assert_("test child logger 2" in sys.stderr.getvalue())

sys.stderr = StringIO()
rospy.logerr("test child logger 3", logger_name="log3")
self.assert_("[ERROR]" in sys.stderr.getvalue())
self.assert_("test child logger 3" in sys.stderr.getvalue())
lout_last = lout.getvalue().splitlines()[-1]
self.assert_("test child logger 1" in lout_last)

sys.stderr = StringIO()
rospy.logfatal("test child logger 4", logger_name="log4")
self.assert_("[FATAL]" in sys.stderr.getvalue())
self.assert_("test child logger 4" in sys.stderr.getvalue())
rospy.logwarn("test child logger 2", logger_name="log2")
lerr_last = lerr.getvalue().splitlines()[-1]
self.assert_("[WARN]" in lerr_last)
self.assert_("test child logger 2" in lerr_last)

rospy.logerr("test child logger 3", logger_name="log3")
lerr_last = lerr.getvalue().splitlines()[-1]
self.assert_("[ERROR]" in lerr_last)
self.assert_("test child logger 3" in lerr_last)

rospy.logfatal("test child logger 4", logger_name="log4")
lerr_last = lerr.getvalue().splitlines()[-1]
self.assert_("[FATAL]" in lerr_last)
self.assert_("test child logger 4" in lerr_last)

finally:
sys.stdout = real_stdout
sys.stderr = real_stderr
# restoring default ros handler
rosout_logger.removeHandler(test_ros_handler)
lout.close()
lerr.close()
rosout_logger.addHandler(default_ros_handler)

def test_wait_for_service(self):
# lazy-import for coverage
Expand Down
Loading