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

add QoS Profile/Depth support to Node. #1376

Open
wants to merge 4 commits into
base: rolling
Choose a base branch
from
Open
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
9 changes: 9 additions & 0 deletions rclpy/rclpy/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -45,9 +45,12 @@
from typing import Optional
from typing import Type
from typing import TYPE_CHECKING
from typing import Union

from rclpy.context import Context
from rclpy.parameter import Parameter
from rclpy.qos import qos_profile_rosout_default
from rclpy.qos import QoSProfile
from rclpy.signals import install_signal_handlers
from rclpy.signals import SignalHandlerOptions
from rclpy.signals import uninstall_signal_handlers
Expand Down Expand Up @@ -214,6 +217,7 @@ def create_node(
namespace: Optional[str] = None,
use_global_arguments: bool = True,
enable_rosout: bool = True,
rosout_qos_profile: Optional[Union[QoSProfile, int]] = qos_profile_rosout_default,
start_parameter_services: bool = True,
parameter_overrides: Optional[List[Parameter]] = None,
allow_undeclared_parameters: bool = False,
Expand All @@ -233,6 +237,10 @@ def create_node(
: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 rosout_qos_profile: A QoSProfile or a history depth to apply to rosout publisher.
In the case that a history depth is provided, the QoS history is set to KEEP_LAST,
the QoS history depth is set to the value of the parameter,
and all other QoS settings are set to their default values.
fujitatomoya marked this conversation as resolved.
Show resolved Hide resolved
: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 @@ -251,6 +259,7 @@ def create_node(
node_name, context=context, cli_args=cli_args, namespace=namespace,
use_global_arguments=use_global_arguments,
enable_rosout=enable_rosout,
rosout_qos_profile=rosout_qos_profile,
start_parameter_services=start_parameter_services,
parameter_overrides=parameter_overrides,
allow_undeclared_parameters=allow_undeclared_parameters,
Expand Down
3 changes: 2 additions & 1 deletion rclpy/rclpy/impl/_rclpy_pybind11.pyi
Original file line number Diff line number Diff line change
Expand Up @@ -430,7 +430,8 @@ class Timer(Destroyable):
PredefinedQosProfileTNames = Literal['qos_profile_sensor_data', 'qos_profile_default',
'qos_profile_system_default', 'qos_profile_services_default',
'qos_profile_unknown', 'qos_profile_parameters',
'qos_profile_parameter_events', 'qos_profile_best_available']
'qos_profile_parameter_events', 'qos_profile_best_available',
'qos_profile_rosout_default']


class rmw_qos_profile_dict(TypedDict):
Expand Down
11 changes: 10 additions & 1 deletion rclpy/rclpy/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,7 @@
from rclpy.parameter_service import ParameterService
from rclpy.publisher import Publisher
from rclpy.qos import qos_profile_parameter_events
from rclpy.qos import qos_profile_rosout_default
from rclpy.qos import qos_profile_services_default
from rclpy.qos import QoSProfile
from rclpy.qos_overriding_options import _declare_qos_parameters
Expand Down Expand Up @@ -139,6 +140,7 @@ def __init__(
namespace: Optional[str] = None,
use_global_arguments: bool = True,
enable_rosout: bool = True,
rosout_qos_profile: Optional[Union[QoSProfile, int]] = qos_profile_rosout_default,
start_parameter_services: bool = True,
parameter_overrides: Optional[List[Parameter[Any]]] = None,
allow_undeclared_parameters: bool = False,
Expand All @@ -159,6 +161,10 @@ def __init__(
: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 rosout_qos_profile: A QoSProfile or a history depth to apply to rosout publisher.
In the case that a history depth is provided, the QoS history is set to KEEP_LAST
the QoS history depth is set to the value of the parameter,
and all other QoS settings are set to their default value.
: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 @@ -196,6 +202,8 @@ def __init__(
if self._context.handle is None or not self._context.ok():
raise NotInitializedException('cannot create node')

rosout_qos_profile = self._validate_qos_or_depth_parameter(rosout_qos_profile)

with self._context.handle:
try:
self.__node = _rclpy.Node(
Expand All @@ -204,7 +212,8 @@ def __init__(
self._context.handle,
cli_args,
use_global_arguments,
enable_rosout
enable_rosout,
rosout_qos_profile.get_c_qos_profile()
)
except ValueError:
# these will raise more specific errors if the name or namespace is bad
Expand Down
5 changes: 4 additions & 1 deletion rclpy/rclpy/qos.py
Original file line number Diff line number Diff line change
Expand Up @@ -479,13 +479,15 @@ class LivelinessPolicy(QoSPolicyEnum):
#: can occur due to races with discovery.
qos_profile_best_available = QoSProfile(**_rclpy.rmw_qos_profile_t.predefined(
'qos_profile_best_available').to_dict())

# Separate rcl_action profile defined at
# ros2/rcl : rcl/rcl_action/include/rcl_action/default_qos.h
#
#: For actions, using reliable reliability, transient-local durability.
qos_profile_action_status_default = QoSProfile(**_rclpy.rclpy_action_get_rmw_qos_profile(
'rcl_action_qos_profile_status_default'))
#: The default qos profile setting for topic /rosout publisher.
qos_profile_rosout_default = QoSProfile(**_rclpy.rmw_qos_profile_t.predefined(
'qos_profile_rosout_default').to_dict())


class QoSPresetProfiles(Enum):
Expand All @@ -498,6 +500,7 @@ class QoSPresetProfiles(Enum):
PARAMETER_EVENTS = qos_profile_parameter_events
ACTION_STATUS_DEFAULT = qos_profile_action_status_default
BEST_AVAILABLE = qos_profile_best_available
ROSOUT_DEFAULT = qos_profile_rosout_default

"""Noted that the following are duplicated from QoSPolicyEnum.

Expand Down
9 changes: 7 additions & 2 deletions rclpy/src/rclpy/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -408,7 +408,8 @@ Node::Node(
Context & context,
py::object pycli_args,
bool use_global_arguments,
bool enable_rosout)
bool enable_rosout,
py::object rosout_qos_profile)
: context_(context)
{
rcl_ret_t ret;
Expand Down Expand Up @@ -500,6 +501,10 @@ Node::Node(
options.arguments = arguments;
options.enable_rosout = enable_rosout;

if (!rosout_qos_profile.is_none()) {
options.rosout_qos = rosout_qos_profile.cast<rmw_qos_profile_t>();
}

ret = rcl_node_init(
rcl_node_.get(), node_name, namespace_, context.rcl_ptr(), &options);

Expand Down Expand Up @@ -581,7 +586,7 @@ void
define_node(py::object module)
{
py::class_<Node, Destroyable, std::shared_ptr<Node>>(module, "Node")
.def(py::init<const char *, const char *, Context &, py::object, bool, bool>())
.def(py::init<const char *, const char *, Context &, py::object, bool, bool, py::object>())
.def_property_readonly(
"pointer", [](const Node & node) {
return reinterpret_cast<size_t>(node.rcl_ptr());
Expand Down
4 changes: 3 additions & 1 deletion rclpy/src/rclpy/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,14 +45,16 @@ class Node : public Destroyable, public std::enable_shared_from_this<Node>
* \param[in] pycli_args a sequence of command line arguments for just this node, or None
* \param[in] use_global_arguments if true then the node will also use cli arguments on context
* \param[in] enable rosout if true then enable rosout logging
* \param[in] rosout_qos_profile rmw_qos_profile_t object for rosout publisher.
*/
Node(
const char * node_name,
const char * namespace_,
Context & context,
py::object pycli_args,
bool use_global_arguments,
bool enable_rosout);
bool enable_rosout,
py::object rosout_qos_profile);

/// Get the fully qualified name of the node.
/**
Expand Down
3 changes: 3 additions & 0 deletions rclpy/src/rclpy/qos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -152,6 +152,9 @@ predefined_qos_profile_from_name(const char * qos_profile_name)
if (0 == strcmp(qos_profile_name, "qos_profile_best_available")) {
return rmw_qos_profile_best_available;
}
if (0 == strcmp(qos_profile_name, "qos_profile_rosout_default")) {
return rmw_qos_profile_rosout_default;
}

std::string error_text = "Requested unknown rmw_qos_profile: ";
error_text += qos_profile_name;
Expand Down
68 changes: 68 additions & 0 deletions rclpy/test/test_create_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,15 @@

import rclpy

from rclpy.duration import Duration
from rclpy.exceptions import InvalidNamespaceException
from rclpy.exceptions import InvalidNodeNameException
from rclpy.parameter import Parameter
from rclpy.qos import QoSDurabilityPolicy
from rclpy.qos import QoSHistoryPolicy
from rclpy.qos import QoSLivelinessPolicy
from rclpy.qos import QoSProfile
from rclpy.qos import QoSReliabilityPolicy


class TestCreateNode(unittest.TestCase):
Expand All @@ -32,6 +38,34 @@ def setUpClass(cls):
def tearDownClass(cls):
rclpy.shutdown(context=cls.context)

def assert_qos_equal(self, expected_qos_profile, actual_qos_profile, *, is_publisher):
# Depth and history are skipped because they are not retrieved.
self.assertEqual(
expected_qos_profile.durability,
actual_qos_profile.durability,
'Durability is unequal')
self.assertEqual(
expected_qos_profile.reliability,
actual_qos_profile.reliability,
'Reliability is unequal')
if is_publisher:
self.assertEqual(
expected_qos_profile.lifespan,
actual_qos_profile.lifespan,
'lifespan is unequal')
self.assertEqual(
expected_qos_profile.deadline,
actual_qos_profile.deadline,
'Deadline is unequal')
self.assertEqual(
expected_qos_profile.liveliness,
actual_qos_profile.liveliness,
'liveliness is unequal')
self.assertEqual(
expected_qos_profile.liveliness_lease_duration,
actual_qos_profile.liveliness_lease_duration,
'liveliness_lease_duration is unequal')

def test_create_node(self) -> None:
node_name = 'create_node_test'
rclpy.create_node(node_name, context=self.context).destroy_node()
Expand Down Expand Up @@ -82,6 +116,40 @@ def test_create_node_with_parameter_overrides(self) -> None:
]
).destroy_node()

def test_create_node_disable_rosout(self):
node_name = 'create_node_test_disable_rosout'
namespace = '/ns'
node = rclpy.create_node(
node_name, namespace=namespace, context=self.context, enable_rosout=False)
# topic /rosout publisher should not exist
self.assertFalse(node.get_publishers_info_by_topic('/rosout'))
node.destroy_node()

def test_create_node_rosout_qos_profile(self):
test_qos_profile = QoSProfile(
depth=10,
history=QoSHistoryPolicy.KEEP_ALL,
deadline=Duration(seconds=1, nanoseconds=12345),
lifespan=Duration(seconds=20, nanoseconds=9887665),
reliability=QoSReliabilityPolicy.BEST_EFFORT,
durability=QoSDurabilityPolicy.TRANSIENT_LOCAL,
liveliness_lease_duration=Duration(seconds=5, nanoseconds=23456),
liveliness=QoSLivelinessPolicy.MANUAL_BY_TOPIC)
node_name = 'create_node_test_rosout_qos_profile'
namespace = '/ns'
node = rclpy.create_node(
node_name, namespace=namespace, context=self.context, enable_rosout=True,
rosout_qos_profile=test_qos_profile)
publisher_list = node.get_publishers_info_by_topic('/rosout')
# only test node /rosout topic publisher should exist
self.assertEqual(1, len(publisher_list))
self.assertEqual(node.get_name(), publisher_list[0].node_name)
self.assertEqual(node.get_namespace(), publisher_list[0].node_namespace)
actual_qos_profile = publisher_list[0].qos_profile
# QoS should match except depth and history cz that are not retrieved from rmw.
self.assert_qos_equal(test_qos_profile, actual_qos_profile, is_publisher=True)
node.destroy_node()


if __name__ == '__main__':
unittest.main()