Skip to content

Commit

Permalink
add --set-master-logger-level option for 'rosmaster' to output LOG_API (
Browse files Browse the repository at this point in the history
#1180)

* add -d option for 'rosmaster' to output LOG_API

* change --set-master-logger-level to --master-logger-level

* level = levels, since it contains multiple elements

* ignore the case

* fix typo unkonwn -> unknown

* forget to set rosmaster.master_api.LOG_API

* space after comma

* do not pass --master-logger-level if it is False

* simplify

* use keyword arg
  • Loading branch information
k-okada authored and dirk-thomas committed Oct 17, 2017
1 parent 4cb38ae commit cd7efd4
Show file tree
Hide file tree
Showing 6 changed files with 39 additions and 7 deletions.
3 changes: 3 additions & 0 deletions tools/roslaunch/scripts/roscore
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,9 @@ def _get_optparse():
parser.add_option("-t", "--timeout",
dest="timeout",
help="override the socket connection timeout (in seconds).", metavar="TIMEOUT")
parser.add_option("--master-logger-level",
dest="master_logger_level", default=False, type=str,
help="set rosmaster.master logger level ('debug', 'info', 'warn', 'error', 'fatal')")
return parser


Expand Down
6 changes: 5 additions & 1 deletion tools/roslaunch/src/roslaunch/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -181,6 +181,9 @@ def _get_optparse():
parser.add_option("-t", "--timeout",
dest="timeout",
help="override the socket connection timeout (in seconds). Only valid for core services.", metavar="TIMEOUT")
parser.add_option("--master-logger-level",
dest="master_logger_level", default=False, type=str,
help="set rosmaster.master logger level ('debug', 'info', 'warn', 'error', 'fatal')")

return parser

Expand Down Expand Up @@ -310,7 +313,8 @@ def main(argv=sys.argv):
p = roslaunch_parent.ROSLaunchParent(uuid, args, roslaunch_strs=roslaunch_strs,
is_core=options.core, port=options.port, local_only=options.local_only,
verbose=options.verbose, force_screen=options.force_screen,
num_workers=options.num_workers, timeout=options.timeout)
num_workers=options.num_workers, timeout=options.timeout,
master_logger_level=options.master_logger_level)
p.start()
p.spin()

Expand Down
9 changes: 7 additions & 2 deletions tools/roslaunch/src/roslaunch/launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -235,7 +235,7 @@ class ROSLaunchRunner(object):
monitored.
"""

def __init__(self, run_id, config, server_uri=None, pmon=None, is_core=False, remote_runner=None, is_child=False, is_rostest=False, num_workers=NUM_WORKERS, timeout=None):
def __init__(self, run_id, config, server_uri=None, pmon=None, is_core=False, remote_runner=None, is_child=False, is_rostest=False, num_workers=NUM_WORKERS, timeout=None, master_logger_level=False):
"""
@param run_id: /run_id for this launch. If the core is not
running, this value will be used to initialize /run_id. If
Expand Down Expand Up @@ -264,6 +264,8 @@ def __init__(self, run_id, config, server_uri=None, pmon=None, is_core=False, re
@type num_workers: int
@param timeout: If this is the core, the socket-timeout to use.
@type timeout: Float or None
@param master_logger_level: Specify roscore's rosmaster.master logger level, use default if it is False.
@type master_logger_level: str or False
"""
if run_id is None:
raise RLException("run_id is None")
Expand All @@ -281,6 +283,7 @@ def __init__(self, run_id, config, server_uri=None, pmon=None, is_core=False, re
self.is_rostest = is_rostest
self.num_workers = num_workers
self.timeout = timeout
self.master_logger_level = master_logger_level
self.logger = logging.getLogger('roslaunch')
self.pm = pmon or start_process_monitor()

Expand Down Expand Up @@ -397,7 +400,9 @@ def _launch_master(self):
validate_master_launch(m, self.is_core, self.is_rostest)

printlog("auto-starting new master")
p = create_master_process(self.run_id, m.type, get_ros_root(), m.get_port(), self.num_workers, self.timeout)
p = create_master_process(
self.run_id, m.type, get_ros_root(), m.get_port(), self.num_workers,
self.timeout, master_logger_level=self.master_logger_level)
self.pm.register_core_proc(p)
success = p.start()
if not success:
Expand Down
8 changes: 6 additions & 2 deletions tools/roslaunch/src/roslaunch/nodeprocess.py
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ def _next_counter():
_counter += 1
return _counter

def create_master_process(run_id, type_, ros_root, port, num_workers=NUM_WORKERS, timeout=None):
def create_master_process(run_id, type_, ros_root, port, num_workers=NUM_WORKERS, timeout=None, master_logger_level=False):
"""
Launch a master
@param type_: name of master executable (currently just Master.ZENMASTER)
Expand All @@ -78,11 +78,13 @@ def create_master_process(run_id, type_, ros_root, port, num_workers=NUM_WORKERS
@param timeout: socket timeout for connections.
@type timeout: float
@raise RLException: if type_ or port is invalid
@param master_logger_level: rosmaster.master logger debug level
@type master_logger_level=: str or False
"""
if port < 1 or port > 65535:
raise RLException("invalid port assignment: %s"%port)

_logger.info("create_master_process: %s, %s, %s, %s, %s", type_, ros_root, port, num_workers, timeout)
_logger.info("create_master_process: %s, %s, %s, %s, %s, %s", type_, ros_root, port, num_workers, timeout, master_logger_level)
# catkin/fuerte: no longer use ROS_ROOT-relative executables, search path instead
master = type_
# zenmaster is deprecated and aliased to rosmaster
Expand All @@ -91,6 +93,8 @@ def create_master_process(run_id, type_, ros_root, port, num_workers=NUM_WORKERS
args = [master, '--core', '-p', str(port), '-w', str(num_workers)]
if timeout is not None:
args += ['-t', str(timeout)]
if master_logger_level:
args += ['--master-logger-level', str(master_logger_level)]
else:
raise RLException("unknown master typ_: %s"%type_)

Expand Down
7 changes: 5 additions & 2 deletions tools/roslaunch/src/roslaunch/parent.py
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ class ROSLaunchParent(object):
"""

def __init__(self, run_id, roslaunch_files, is_core=False, port=None, local_only=False, process_listeners=None,
verbose=False, force_screen=False, is_rostest=False, roslaunch_strs=None, num_workers=NUM_WORKERS, timeout=None):
verbose=False, force_screen=False, is_rostest=False, roslaunch_strs=None, num_workers=NUM_WORKERS, timeout=None, master_logger_level=False):
"""
@param run_id: UUID of roslaunch session
@type run_id: str
Expand Down Expand Up @@ -101,6 +101,8 @@ def __init__(self, run_id, roslaunch_files, is_core=False, port=None, local_only
@param timeout: If this is the core, the socket-timeout to use.
@type timeout: Float or None
@throws RLException
@param master_logger_level: Specify roscore's rosmaster.master logger level, use default if it is False.
@type master_logger_level: str or False
"""

self.logger = logging.getLogger('roslaunch.parent')
Expand All @@ -116,6 +118,7 @@ def __init__(self, run_id, roslaunch_files, is_core=False, port=None, local_only
self.verbose = verbose
self.num_workers = num_workers
self.timeout = timeout
self.master_logger_level = master_logger_level

# I don't think we should have to pass in so many options from
# the outside into the roslaunch parent. One possibility is to
Expand Down Expand Up @@ -152,7 +155,7 @@ def _init_runner(self):
raise RLException("pm is not initialized")
if self.server is None:
raise RLException("server is not initialized")
self.runner = roslaunch.launch.ROSLaunchRunner(self.run_id, self.config, server_uri=self.server.uri, pmon=self.pm, is_core=self.is_core, remote_runner=self.remote_runner, is_rostest=self.is_rostest, num_workers=self.num_workers, timeout=self.timeout)
self.runner = roslaunch.launch.ROSLaunchRunner(self.run_id, self.config, server_uri=self.server.uri, pmon=self.pm, is_core=self.is_core, remote_runner=self.remote_runner, is_rostest=self.is_rostest, num_workers=self.num_workers, timeout=self.timeout, master_logger_level=self.master_logger_level)

# print runner info to user, put errors last to make the more visible
if self.is_core:
Expand Down
13 changes: 13 additions & 0 deletions tools/rosmaster/src/rosmaster/main.py
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,10 @@ def rosmaster_main(argv=sys.argv, stdout=sys.stdout, env=os.environ):
parser.add_option("-t", "--timeout",
dest="timeout",
help="override the socket connection timeout (in seconds).", metavar="TIMEOUT")
parser.add_option("--master-logger-level",
dest="master_logger_level", default=False, type=str,
help="set rosmaster.master logger level ('debug', 'info', 'warn', 'error', 'fatal')")

options, args = parser.parse_args(argv[1:])

# only arg that zenmaster supports is __log remapping of logfilename
Expand Down Expand Up @@ -108,6 +112,15 @@ def rosmaster_main(argv=sys.argv, stdout=sys.stdout, env=os.environ):
import socket
socket.setdefaulttimeout(float(options.timeout))

if options.master_logger_level:
levels = {'debug': logging.DEBUG, 'info': logging.INFO, 'warn': logging.WARN, 'error': logging.ERROR, 'fatal': logging.FATAL}
if options.master_logger_level.lower() in levels.keys():
logger.info("set rosmaster.master logger level '{}'".format(options.master_logger_level))
rosmaster.master_api.LOG_API = True
logging.getLogger("rosmaster.master").setLevel(levels[options.master_logger_level.lower()])
else:
logger.error("--master-logger-level received unknown option '{}'".format(options.master_logger_level))

try:
logger.info("Starting ROS Master Node")
master = rosmaster.master.Master(port, options.num_workers)
Expand Down

0 comments on commit cd7efd4

Please sign in to comment.