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

enable/disable rosout logging in each node individually #469

Merged
merged 3 commits into from
Dec 5, 2019
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
1 change: 1 addition & 0 deletions rclpy/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -194,6 +194,7 @@ if(BUILD_TESTING)
test/test_handle.py
test/test_init_shutdown.py
test/test_logging.py
test/test_logging_rosout.py
test/test_messages.py
test/test_node.py
test/test_parameter.py
Expand Down
3 changes: 3 additions & 0 deletions rclpy/rclpy/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -110,6 +110,7 @@ def create_node(
cli_args: List[str] = None,
namespace: str = None,
use_global_arguments: bool = True,
enable_rosout: bool = True,
start_parameter_services: bool = True,
parameter_overrides: List[Parameter] = None,
allow_undeclared_parameters: bool = False,
Expand All @@ -127,6 +128,7 @@ def create_node(
(node name, topics, etc).
:param use_global_arguments: ``False`` if the node should ignore process-wide command line
arguments.
:param enable_rosout: ``False`` if the node should ignore rosout logging.
:param start_parameter_services: ``False`` if the node should not create parameter services.
:param parameter_overrides: A list of :class:`.Parameter` which are used to override the
initial values of parameters declared on this node.
Expand All @@ -141,6 +143,7 @@ def create_node(
return Node(
node_name, context=context, cli_args=cli_args, namespace=namespace,
use_global_arguments=use_global_arguments,
enable_rosout=enable_rosout,
start_parameter_services=start_parameter_services,
parameter_overrides=parameter_overrides,
allow_undeclared_parameters=allow_undeclared_parameters,
Expand Down
9 changes: 8 additions & 1 deletion rclpy/rclpy/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -108,6 +108,7 @@ def __init__(
cli_args: List[str] = None,
namespace: str = None,
use_global_arguments: bool = True,
enable_rosout: bool = True,
start_parameter_services: bool = True,
parameter_overrides: List[Parameter] = None,
allow_undeclared_parameters: bool = False,
Expand All @@ -126,6 +127,7 @@ def __init__(
Validated by :func:`validate_namespace`.
:param use_global_arguments: ``False`` if the node should ignore process-wide command line
args.
:param enable_rosout: ``False`` if the node should ignore rosout logging.
:param start_parameter_services: ``False`` if the node should not create parameter
services.
:param parameter_overrides: A list of overrides for initial values for parameters declared
Expand Down Expand Up @@ -157,7 +159,12 @@ def __init__(
raise NotInitializedException('cannot create node')
try:
self.__handle = Handle(_rclpy.rclpy_create_node(
node_name, namespace, self._context.handle, cli_args, use_global_arguments
node_name,
namespace,
self._context.handle,
cli_args,
use_global_arguments,
enable_rosout
))
except ValueError:
# these will raise more specific errors if the name or namespace is bad
Expand Down
10 changes: 9 additions & 1 deletion rclpy/src/rclpy/_rclpy.c
Original file line number Diff line number Diff line change
Expand Up @@ -637,9 +637,16 @@ rclpy_create_node(PyObject * Py_UNUSED(self), PyObject * args)
PyObject * pycontext;
PyObject * py_cli_args;
int use_global_arguments;
int enable_rosout;

if (!PyArg_ParseTuple(
args, "ssOOp", &node_name, &namespace_, &pycontext, &py_cli_args, &use_global_arguments))
args, "ssOOpp",
&node_name,
&namespace_,
&pycontext,
&py_cli_args,
&use_global_arguments,
&enable_rosout))
{
return NULL;
}
Expand All @@ -666,6 +673,7 @@ rclpy_create_node(PyObject * Py_UNUSED(self), PyObject * args)
rcl_node_options_t options = rcl_node_get_default_options();
options.use_global_arguments = use_global_arguments;
options.arguments = arguments;
options.enable_rosout = enable_rosout;
ret = rcl_node_init(node, node_name, namespace_, context, &options);
if (ret != RCL_RET_OK) {
if (ret == RCL_RET_BAD_ALLOC) {
Expand Down
85 changes: 85 additions & 0 deletions rclpy/test/test_logging_rosout.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,85 @@
# Copyright 2019 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import pytest

from rcl_interfaces.msg import Log
import rclpy
from rclpy.executors import SingleThreadedExecutor

TEST_PARAMETERS = [
('enable_global_rosout_enable_node_rosout', True, True, True),
('enable_global_rosout_disable_node_rosout', True, False, False),
('disable_global_rosout_enable_node_rosout', False, True, False),
('disable_global_rosout_disable_node_rosout', False, False, False),
]

raw_subscription_msg = None # None=No result yet


def raw_subscription_callback(msg):
global raw_subscription_msg
raw_subscription_msg = msg


@pytest.mark.parametrize(
'name,enable_global_rosout_logs,enable_node_rosout,expected_data',
TEST_PARAMETERS)
def test_enable_rosout(
name,
enable_global_rosout_logs,
enable_node_rosout,
expected_data
):
if enable_global_rosout_logs:
args = ['--ros-args', '--enable-rosout-logs']
else:
args = ['--ros-args', '--disable-rosout-logs']

context = rclpy.context.Context()
rclpy.init(context=context, args=args)
executor = SingleThreadedExecutor(context=context)

# create node
node = rclpy.create_node(
node_name='my_node_'+name,
namespace='/my_ns',
enable_rosout=enable_node_rosout,
context=context
)
executor.add_node(node)

global raw_subscription_msg
raw_subscription_msg = None
# create subscriber of 'rosout' topic
node.create_subscription(
Log,
'rosout',
raw_subscription_callback,
1,
raw=True
)

node.get_logger().info('SOMETHING')
executor.spin_once(timeout_sec=1)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@ivanpauno (tagging you because you reviewed it), watch out for things like this. It's really fragile, we're seeing this test fail a lot either due to the timeout before the event or because spinning once does not guarantee that the event you wanted handled was the one that would be handled...

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@wjwwood

our bad, sorry about that.
we will submit issue against problem and try to fix it.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks @wjwwood.
I overlooked that when reviewing, but the test is definitely flaky.

I've created an issue #546.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@fujitatomoya if you're not planning to work on a fix in a near future, let me know and I will work on it. Thanks!

Copy link
Collaborator

@fujitatomoya fujitatomoya Apr 24, 2020

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@ivanpauno

i think i can work on this early next week, but if you already have idea, you can go ahead.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@wjwwood

Thank you for pointing out my mistake. I will fix it.

@ivanpauno @fujitatomoya

It's my fault. I will fix this problem tomorrow in #546.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No worries, I wasn't trying to call anyone out, just wanted to point it out before I forgot and explain why it is fragile.


if expected_data:
assert (raw_subscription_msg is not None)
assert (type(raw_subscription_msg) == bytes)
assert (len(raw_subscription_msg) != 0)
else:
assert (raw_subscription_msg is None)

node.destroy_node()
rclpy.shutdown(context=context)