From ea9111182d229da3e64503947256bd8b66fd3cd9 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Fri, 10 May 2019 16:17:55 -0700 Subject: [PATCH 1/7] Encourage users to always provide a QoS history depth * Added a new parameter to methods for creating publishers and subscriptions The new parameter is required and must be a QoSProfile object or an integer value for the history depth. For now, it is possible to not use the parameter for backwards compatibility, but a deprecation warning is made. * Add deprecation warning when constructing a QoSProfile without a history depth If the history setting is KEEP_ALL, then it is not required to pass the depth setting. Signed-off-by: Jacob Perron --- rclpy/rclpy/node.py | 46 +++++++++++++++++++++++++++-- rclpy/rclpy/qos.py | 11 +++++++ rclpy/test/test_node.py | 65 ++++++++++++++++++++++++++++++++++++----- rclpy/test/test_qos.py | 55 +++++++++++++++++++++++++++------- 4 files changed, 158 insertions(+), 19 deletions(-) diff --git a/rclpy/rclpy/node.py b/rclpy/rclpy/node.py index 0afa6f4da..ea34ee895 100644 --- a/rclpy/rclpy/node.py +++ b/rclpy/rclpy/node.py @@ -18,7 +18,9 @@ from typing import Optional from typing import Tuple from typing import TypeVar +from typing import Union +import warnings import weakref from rcl_interfaces.msg import Parameter as ParameterMsg @@ -51,6 +53,7 @@ from rclpy.qos import qos_profile_default from rclpy.qos import qos_profile_parameter_events from rclpy.qos import qos_profile_services_default +from rclpy.qos import QoSHistoryPolicy from rclpy.qos import QoSProfile from rclpy.qos_event import PublisherEventCallbacks from rclpy.qos_event import SubscriptionEventCallbacks @@ -675,6 +678,19 @@ def _validate_topic_or_service_name(self, topic_or_service_name, *, is_service=F expanded_topic_or_service_name = expand_topic_name(topic_or_service_name, name, namespace) validate_full_topic_name(expanded_topic_or_service_name, is_service=is_service) + def _validate_qos_or_depth_parameter(self, qos_or_depth) -> QoSProfile: + if isinstance(qos_or_depth, QoSProfile): + return qos_or_depth + elif isinstance(qos_or_depth, int): + if qos_or_depth < 0: + raise ValueError('history depth must be greater than or equal to zero') + return QoSProfile( + history=QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST, + depth=qos_or_depth) + else: + raise TypeError( + 'Expected QoSProfile or int, but received {!r}'.format(type(qos_or_depth))) + def add_waitable(self, waitable: Waitable) -> None: """ Add a class that is capable of adding things to the wait set. @@ -697,6 +713,7 @@ def create_publisher( self, msg_type, topic: str, + qos_or_depth: Union[QoSProfile, int] = None, *, qos_profile: QoSProfile = qos_profile_default, callback_group: Optional[CallbackGroup] = None, @@ -707,12 +724,24 @@ def create_publisher( :param msg_type: The type of ROS messages the publisher will publish. :param topic: The name of the topic the publisher will publish to. - :param qos_profile: The quality of service profile to apply to the publisher. + :param qos_or_depth: A QoSProfile or a history depth to apply to the publisher. + This is a required parameter, and only defaults to None for backwards compatibility. + In the case that a history depth is provided, the QoS history is set to + RMW_QOS_POLICY_HISTORY_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. + :param qos_profile: **This parameter is deprecated; use the qos_or_depth parameter + instead.** :param callback_group: The callback group for the publisher's event handlers. If ``None``, then the node's default callback group is used. :param event_callbacks: User-defined callbacks for middleware events. :return: The new publisher. """ + # if the new API is not used, issue a deprecation warning and continue with the old API + if qos_or_depth is None: + warnings.warn("Use the new 'qos_or_depth' parameter", DeprecationWarning) + else: + qos_profile = self._validate_qos_or_depth_parameter(qos_or_depth) + callback_group = callback_group or self.default_callback_group # this line imports the typesupport for the message module if not already done @@ -747,6 +776,7 @@ def create_subscription( msg_type, topic: str, callback: Callable[[MsgType], None], + qos_or_depth: Union[QoSProfile, int] = None, *, qos_profile: QoSProfile = qos_profile_default, callback_group: Optional[CallbackGroup] = None, @@ -760,13 +790,25 @@ def create_subscription( :param topic: The name of the topic the subscription will subscribe to. :param callback: A user-defined callback function that is called when a message is received by the subscription. - :param qos_profile: The quality of service profile to apply to the subscription. + :param qos_or_depth: A QoSProfile or a history depth to apply to the subscription. + This is a required parameter, and only defaults to None for backwards compatibility. + In the case that a history depth is provided, the QoS history is set to + RMW_QOS_POLICY_HISTORY_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. + :param qos_profile: **This parameter is deprecated; use the qos_or_depth parameter + instead.** :param callback_group: The callback group for the subscription. If ``None``, then the nodes default callback group is used. :param event_callbacks: User-defined callbacks for middleware events. :param raw: If ``True``, then received messages will be stored in raw binary representation. """ + # if the new API is not used, issue a deprecation warning and continue with the old API + if qos_or_depth is None: + warnings.warn("Use the new 'qos_or_depth' parameter", DeprecationWarning) + else: + qos_profile = self._validate_qos_or_depth_parameter(qos_or_depth) + callback_group = callback_group or self.default_callback_group # this line imports the typesupport for the message module if not already done diff --git a/rclpy/rclpy/qos.py b/rclpy/rclpy/qos.py index 52dad30d8..a00422847 100644 --- a/rclpy/rclpy/qos.py +++ b/rclpy/rclpy/qos.py @@ -13,6 +13,7 @@ # limitations under the License. from enum import IntEnum +import warnings from rclpy.duration import Duration from rclpy.impl.implementation_singleton import rclpy_action_implementation as _rclpy_action @@ -37,9 +38,19 @@ class QoSProfile: def __init__(self, **kwargs): assert all('_' + key in self.__slots__ for key in kwargs.keys()), \ 'Invalid arguments passed to constructor: %r' % kwargs.keys() + if 'history' not in kwargs: + warnings.warn( + "QoSProfile needs a 'history' setting when constructed", DeprecationWarning) self.history = kwargs.get( 'history', QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT) + if ( + QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST == self.history and + 'depth' not in kwargs + ): + warnings.warn( + 'A QoSProfile with history set to KEEP_LAST needs a depth specified', + DeprecationWarning) self.depth = kwargs.get('depth', int()) self.reliability = kwargs.get( 'reliability', diff --git a/rclpy/test/test_node.py b/rclpy/test/test_node.py index 92b08d318..be5b38d0d 100644 --- a/rclpy/test/test_node.py +++ b/rclpy/test/test_node.py @@ -14,6 +14,7 @@ import unittest from unittest.mock import Mock +import warnings from rcl_interfaces.msg import ParameterDescriptor from rcl_interfaces.msg import ParameterValue @@ -29,6 +30,7 @@ from rclpy.exceptions import ParameterNotDeclaredException from rclpy.executors import SingleThreadedExecutor from rclpy.parameter import Parameter +from rclpy.qos import qos_profile_sensor_data from test_msgs.msg import BasicTypes TEST_NODE = 'my_node' @@ -60,21 +62,36 @@ def test_accessors(self): def test_create_publisher(self): self.node.create_publisher(BasicTypes, 'chatter') + self.node.create_publisher(BasicTypes, 'chatter', 0) + self.node.create_publisher(BasicTypes, 'chatter', 1) + self.node.create_publisher(BasicTypes, 'chatter', qos_profile_sensor_data) with self.assertRaisesRegex(InvalidTopicNameException, 'must not contain characters'): - self.node.create_publisher(BasicTypes, 'chatter?') + self.node.create_publisher(BasicTypes, 'chatter?', 1) with self.assertRaisesRegex(InvalidTopicNameException, 'must not start with a number'): - self.node.create_publisher(BasicTypes, '/chatter/42_is_the_answer') + self.node.create_publisher(BasicTypes, '/chatter/42_is_the_answer', 1) with self.assertRaisesRegex(ValueError, 'unknown substitution'): - self.node.create_publisher(BasicTypes, 'chatter/{bad_sub}') + self.node.create_publisher(BasicTypes, 'chatter/{bad_sub}', 1) + with self.assertRaisesRegex(ValueError, 'must be greater than or equal to zero'): + self.node.create_publisher(BasicTypes, 'chatter', -1) + with self.assertRaisesRegex(TypeError, 'Expected QoSProfile or int'): + self.node.create_publisher(BasicTypes, 'chatter', 'foo') def test_create_subscription(self): self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg)) + self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg), 0) + self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg), 1) + self.node.create_subscription( + BasicTypes, 'chatter', lambda msg: print(msg), qos_profile_sensor_data) with self.assertRaisesRegex(InvalidTopicNameException, 'must not contain characters'): - self.node.create_subscription(BasicTypes, 'chatter?', lambda msg: print(msg)) + self.node.create_subscription(BasicTypes, 'chatter?', lambda msg: print(msg), 1) with self.assertRaisesRegex(InvalidTopicNameException, 'must not start with a number'): - self.node.create_subscription(BasicTypes, '/chatter/42ish', lambda msg: print(msg)) + self.node.create_subscription(BasicTypes, '/chatter/42ish', lambda msg: print(msg), 1) with self.assertRaisesRegex(ValueError, 'unknown substitution'): - self.node.create_subscription(BasicTypes, 'foo/{bad_sub}', lambda msg: print(msg)) + self.node.create_subscription(BasicTypes, 'foo/{bad_sub}', lambda msg: print(msg), 1) + with self.assertRaisesRegex(ValueError, 'must be greater than or equal to zero'): + self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg), -1) + with self.assertRaisesRegex(TypeError, 'Expected QoSProfile or int'): + self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg), 'foo') def raw_subscription_callback(self, msg): print('Raw subscription callback: %s length %d' % (msg, len(msg))) @@ -83,7 +100,7 @@ def raw_subscription_callback(self, msg): def test_create_raw_subscription(self): executor = SingleThreadedExecutor(context=self.context) executor.add_node(self.node) - basic_types_pub = self.node.create_publisher(BasicTypes, 'raw_subscription_test') + basic_types_pub = self.node.create_publisher(BasicTypes, 'raw_subscription_test', 1) self.raw_subscription_msg = None # None=No result yet self.node.create_subscription( BasicTypes, @@ -123,6 +140,40 @@ def test_create_service(self): with self.assertRaisesRegex(ValueError, 'unknown substitution'): self.node.create_service(GetParameters, 'foo/{bad_sub}', lambda req: None) + def test_deprecation_warnings(self): + warnings.simplefilter('always') + with warnings.catch_warnings(record=True) as w: + self.node.create_publisher(BasicTypes, 'chatter') + assert len(w) == 1 + assert issubclass(w[0].category, DeprecationWarning) + with warnings.catch_warnings(record=True) as w: + self.node.create_publisher(BasicTypes, 'chatter', qos_profile=qos_profile_sensor_data) + assert len(w) == 1 + assert issubclass(w[0].category, DeprecationWarning) + with warnings.catch_warnings(record=True) as w: + self.node.create_publisher(BasicTypes, 'chatter', qos_profile=qos_profile_sensor_data) + assert len(w) == 1 + assert issubclass(w[0].category, DeprecationWarning) + with warnings.catch_warnings(record=True) as w: + self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg)) + assert len(w) == 1 + assert issubclass(w[0].category, DeprecationWarning) + with warnings.catch_warnings(record=True) as w: + self.node.create_subscription( + BasicTypes, 'chatter', lambda msg: print(msg), qos_profile=qos_profile_sensor_data) + assert len(w) == 1 + assert issubclass(w[0].category, DeprecationWarning) + with warnings.catch_warnings(record=True) as w: + self.node.create_subscription( + BasicTypes, 'chatter', lambda msg: print(msg), qos_profile=qos_profile_sensor_data) + assert len(w) == 1 + assert issubclass(w[0].category, DeprecationWarning) + with warnings.catch_warnings(record=True) as w: + self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg), raw=True) + assert len(w) == 1 + assert issubclass(w[0].category, DeprecationWarning) + warnings.simplefilter('default') + def test_service_names_and_types(self): # test that it doesn't raise self.node.get_service_names_and_types() diff --git a/rclpy/test/test_qos.py b/rclpy/test/test_qos.py index a08bcd30a..c2f9fa6c5 100644 --- a/rclpy/test/test_qos.py +++ b/rclpy/test/test_qos.py @@ -13,6 +13,7 @@ # limitations under the License. import unittest +import warnings from rclpy.duration import Duration from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy @@ -31,32 +32,46 @@ def convert_and_assert_equality(self, qos_profile): self.assertEqual(qos_profile, converted_profile) def test_eq_operator(self): - profile_1 = QoSProfile() - profile_same = QoSProfile() - profile_different_number = QoSProfile(depth=1) - profile_different_duration = QoSProfile(deadline=Duration(seconds=2)) - profile_equal_duration = QoSProfile(deadline=Duration(seconds=2)) + profile_1 = QoSProfile(history=QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST, depth=1) + profile_same = QoSProfile( + history=QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST, depth=1) + profile_different_depth = QoSProfile( + history=QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST, depth=2) + profile_different_duration = QoSProfile( + history=QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST, + depth=1, + deadline=Duration(seconds=2)) + profile_equal_duration = QoSProfile( + history=QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST, + depth=1, + deadline=Duration(seconds=2)) self.assertEqual(profile_1, profile_same) - self.assertNotEqual(profile_1, profile_different_number) + self.assertNotEqual(profile_1, profile_different_depth) self.assertNotEqual(profile_1, profile_different_duration) self.assertEqual(profile_different_duration, profile_equal_duration) def test_simple_round_trip(self): - source_profile = QoSProfile() + source_profile = QoSProfile(history=QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_ALL) self.convert_and_assert_equality(source_profile) def test_big_nanoseconds(self): # Under 31 bits - no_problem = QoSProfile(lifespan=Duration(seconds=2)) + no_problem = QoSProfile( + history=QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_ALL, + lifespan=Duration(seconds=2)) self.convert_and_assert_equality(no_problem) # Total nanoseconds in duration is too large to store in 32 bit signed int - int32_problem = QoSProfile(lifespan=Duration(seconds=4)) + int32_problem = QoSProfile( + history=QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_ALL, + lifespan=Duration(seconds=4)) self.convert_and_assert_equality(int32_problem) # Total nanoseconds in duration is too large to store in 32 bit unsigned int - uint32_problem = QoSProfile(lifespan=Duration(seconds=5)) + uint32_problem = QoSProfile( + history=QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_ALL, + lifespan=Duration(seconds=5)) self.convert_and_assert_equality(uint32_problem) def test_alldata_round_trip(self): @@ -72,3 +87,23 @@ def test_alldata_round_trip(self): avoid_ros_namespace_conventions=True ) self.convert_and_assert_equality(source_profile) + + def test_deprecation_warnings(self): + warnings.simplefilter('always') + with warnings.catch_warnings(record=True) as w: + QoSProfile() + assert len(w) == 1 + assert issubclass(w[0].category, DeprecationWarning) + with warnings.catch_warnings(record=True) as w: + # No deprecation if history is supplied + QoSProfile(history=QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_ALL) + assert len(w) == 0, str(w[-1].message) + with warnings.catch_warnings(record=True) as w: + # Deprecation warning if KEEP_LAST, but no depth + QoSProfile(history=QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST) + assert len(w) == 1 + assert issubclass(w[0].category, DeprecationWarning) + with warnings.catch_warnings(record=True) as w: + # No deprecation if 'depth' is present + QoSProfile(history=QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST, depth=1) + assert len(w) == 0, str(w[-1].message) From a96d03a3b3c4bb23ddab875372c8594d2d32c61f Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 13 May 2019 10:24:21 -0700 Subject: [PATCH 2/7] Allow creating QoSProfile with just a depth Signed-off-by: Jacob Perron --- rclpy/rclpy/node.py | 5 +---- rclpy/rclpy/qos.py | 8 ++++++-- rclpy/test/test_qos.py | 9 +++++++++ 3 files changed, 16 insertions(+), 6 deletions(-) diff --git a/rclpy/rclpy/node.py b/rclpy/rclpy/node.py index ea34ee895..1091013c1 100644 --- a/rclpy/rclpy/node.py +++ b/rclpy/rclpy/node.py @@ -53,7 +53,6 @@ from rclpy.qos import qos_profile_default from rclpy.qos import qos_profile_parameter_events from rclpy.qos import qos_profile_services_default -from rclpy.qos import QoSHistoryPolicy from rclpy.qos import QoSProfile from rclpy.qos_event import PublisherEventCallbacks from rclpy.qos_event import SubscriptionEventCallbacks @@ -684,9 +683,7 @@ def _validate_qos_or_depth_parameter(self, qos_or_depth) -> QoSProfile: elif isinstance(qos_or_depth, int): if qos_or_depth < 0: raise ValueError('history depth must be greater than or equal to zero') - return QoSProfile( - history=QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST, - depth=qos_or_depth) + return QoSProfile(depth=qos_or_depth) else: raise TypeError( 'Expected QoSProfile or int, but received {!r}'.format(type(qos_or_depth))) diff --git a/rclpy/rclpy/qos.py b/rclpy/rclpy/qos.py index a00422847..511f0d70c 100644 --- a/rclpy/rclpy/qos.py +++ b/rclpy/rclpy/qos.py @@ -39,8 +39,12 @@ def __init__(self, **kwargs): assert all('_' + key in self.__slots__ for key in kwargs.keys()), \ 'Invalid arguments passed to constructor: %r' % kwargs.keys() if 'history' not in kwargs: - warnings.warn( - "QoSProfile needs a 'history' setting when constructed", DeprecationWarning) + if 'depth' in kwargs: + kwargs['history'] = QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST + else: + warnings.warn( + "QoSProfile needs a 'history' and/or 'depth' setting when constructed", + DeprecationWarning) self.history = kwargs.get( 'history', QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT) diff --git a/rclpy/test/test_qos.py b/rclpy/test/test_qos.py index c2f9fa6c5..0dfe3fc38 100644 --- a/rclpy/test/test_qos.py +++ b/rclpy/test/test_qos.py @@ -31,6 +31,11 @@ def convert_and_assert_equality(self, qos_profile): converted_profile = _rclpy.rclpy_convert_to_py_qos_policy(c_profile) self.assertEqual(qos_profile, converted_profile) + def test_depth_only_constructor(self): + qos = QoSProfile(depth=1) + assert qos.depth == 1 + assert qos.history == QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST + def test_eq_operator(self): profile_1 = QoSProfile(history=QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST, depth=1) profile_same = QoSProfile( @@ -107,3 +112,7 @@ def test_deprecation_warnings(self): # No deprecation if 'depth' is present QoSProfile(history=QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST, depth=1) assert len(w) == 0, str(w[-1].message) + with warnings.catch_warnings(record=True) as w: + # No deprecation if only depth + QoSProfile(depth=1) + assert len(w) == 0, str(w[-1].message) From 71df77d230506cd997039b3d94f8cc1123625baf Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 13 May 2019 12:00:58 -0700 Subject: [PATCH 3/7] Deprecated 'qos_profile_default' Signed-off-by: Jacob Perron --- rclpy/rclpy/node.py | 5 +++++ rclpy/rclpy/qos.py | 25 ++++++++++++++++++++++--- rclpy/test/test_node.py | 10 ++++++++++ 3 files changed, 37 insertions(+), 3 deletions(-) diff --git a/rclpy/rclpy/node.py b/rclpy/rclpy/node.py index 1091013c1..3e83aabc8 100644 --- a/rclpy/rclpy/node.py +++ b/rclpy/rclpy/node.py @@ -50,6 +50,7 @@ from rclpy.parameter import Parameter from rclpy.parameter_service import ParameterService from rclpy.publisher import Publisher +from rclpy.qos import DeprecatedQoSProfile from rclpy.qos import qos_profile_default from rclpy.qos import qos_profile_parameter_events from rclpy.qos import qos_profile_services_default @@ -679,6 +680,10 @@ def _validate_topic_or_service_name(self, topic_or_service_name, *, is_service=F def _validate_qos_or_depth_parameter(self, qos_or_depth) -> QoSProfile: if isinstance(qos_or_depth, QoSProfile): + if isinstance(qos_or_depth, DeprecatedQoSProfile): + warnings.warn( + "Using deprecated QoSProfile '{qos_or_depth.name}'".format_map(locals()), + DeprecationWarning) return qos_or_depth elif isinstance(qos_or_depth, int): if qos_or_depth < 0: diff --git a/rclpy/rclpy/qos.py b/rclpy/rclpy/qos.py index 511f0d70c..e52f2dea3 100644 --- a/rclpy/rclpy/qos.py +++ b/rclpy/rclpy/qos.py @@ -44,7 +44,8 @@ def __init__(self, **kwargs): else: warnings.warn( "QoSProfile needs a 'history' and/or 'depth' setting when constructed", - DeprecationWarning) + DeprecationWarning, + stacklevel=2) self.history = kwargs.get( 'history', QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT) @@ -54,7 +55,8 @@ def __init__(self, **kwargs): ): warnings.warn( 'A QoSProfile with history set to KEEP_LAST needs a depth specified', - DeprecationWarning) + DeprecationWarning, + stacklevel=2) self.depth = kwargs.get('depth', int()) self.reliability = kwargs.get( 'reliability', @@ -277,8 +279,25 @@ class QoSLivelinessPolicy(IntEnum): RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC = 3 -qos_profile_default = _rclpy.rclpy_get_rmw_qos_profile( +class DeprecatedQoSProfile(QoSProfile): + + def __init__(self, qos_profile: QoSProfile, profile_name: str): + super().__init__( + history=qos_profile.history, + depth=qos_profile.depth, + reliability=qos_profile.reliability, + durability=qos_profile.durability, + lifespan=qos_profile.lifespan, + deadline=qos_profile.deadline, + liveliness=qos_profile.liveliness, + liveliness_lease_duration=qos_profile.liveliness_lease_duration, + avoid_ros_namespace_conventions=qos_profile.avoid_ros_namespace_conventions) + self.name = profile_name + + +__qos_profile_default = _rclpy.rclpy_get_rmw_qos_profile( 'qos_profile_default') +qos_profile_default = DeprecatedQoSProfile(__qos_profile_default, 'qos_profile_default') qos_profile_system_default = _rclpy.rclpy_get_rmw_qos_profile( 'qos_profile_system_default') qos_profile_sensor_data = _rclpy.rclpy_get_rmw_qos_profile( diff --git a/rclpy/test/test_node.py b/rclpy/test/test_node.py index be5b38d0d..d20110cd4 100644 --- a/rclpy/test/test_node.py +++ b/rclpy/test/test_node.py @@ -30,6 +30,7 @@ from rclpy.exceptions import ParameterNotDeclaredException from rclpy.executors import SingleThreadedExecutor from rclpy.parameter import Parameter +from rclpy.qos import qos_profile_default from rclpy.qos import qos_profile_sensor_data from test_msgs.msg import BasicTypes @@ -154,6 +155,10 @@ def test_deprecation_warnings(self): self.node.create_publisher(BasicTypes, 'chatter', qos_profile=qos_profile_sensor_data) assert len(w) == 1 assert issubclass(w[0].category, DeprecationWarning) + with warnings.catch_warnings(record=True) as w: + self.node.create_publisher(BasicTypes, 'chatter', qos_profile_default) + assert len(w) == 1 + assert issubclass(w[0].category, DeprecationWarning) with warnings.catch_warnings(record=True) as w: self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg)) assert len(w) == 1 @@ -168,6 +173,11 @@ def test_deprecation_warnings(self): BasicTypes, 'chatter', lambda msg: print(msg), qos_profile=qos_profile_sensor_data) assert len(w) == 1 assert issubclass(w[0].category, DeprecationWarning) + with warnings.catch_warnings(record=True) as w: + self.node.create_subscription( + BasicTypes, 'chatter', lambda msg: print(msg), qos_profile_default) + assert len(w) == 1 + assert issubclass(w[0].category, DeprecationWarning) with warnings.catch_warnings(record=True) as w: self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg), raw=True) assert len(w) == 1 From 6ad06dbc43a024b30d3e1d8aea27dafe1d4308fb Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 13 May 2019 12:38:14 -0700 Subject: [PATCH 4/7] Construct QoSProfile with keyword arguments in C extension conversion function This is to avoid deprecation warnings. Signed-off-by: Jacob Perron --- rclpy/src/rclpy_common/src/common.c | 90 +++++++++++++++-------------- 1 file changed, 46 insertions(+), 44 deletions(-) diff --git a/rclpy/src/rclpy_common/src/common.c b/rclpy/src/rclpy_common/src/common.c index 146bf1749..a8a354f70 100644 --- a/rclpy/src/rclpy_common/src/common.c +++ b/rclpy/src/rclpy_common/src/common.c @@ -160,74 +160,48 @@ _convert_rmw_time_to_py_duration(const rmw_time_t * duration) PyObject * rclpy_common_convert_to_py_qos_policy(const rmw_qos_profile_t * qos_profile) { - PyObject * pyqos_module = PyImport_ImportModule("rclpy.qos"); - if (!pyqos_module) { - return NULL; - } - - PyObject * pyqos_policy_class = PyObject_GetAttrString(pyqos_module, "QoSProfile"); - Py_DECREF(pyqos_module); - if (!pyqos_policy_class) { - return NULL; - } - - PyObject * pyqos_profile = PyObject_CallObject(pyqos_policy_class, NULL); - Py_DECREF(pyqos_policy_class); - if (!pyqos_profile) { - return NULL; - } - - // start qos setting + // Convert rmw members to Python objects rclpy_qos_profile_t rclpy_qos; init_rclpy_qos_profile(&rclpy_qos); - int set_result = -1; - rclpy_qos.depth = PyLong_FromSize_t(qos_profile->depth); if (!rclpy_qos.depth) { - Py_DECREF(pyqos_profile); cleanup_rclpy_qos_profile(&rclpy_qos); return NULL; } rclpy_qos.history = PyLong_FromUnsignedLong(qos_profile->history); if (!rclpy_qos.history) { - Py_DECREF(pyqos_profile); cleanup_rclpy_qos_profile(&rclpy_qos); return NULL; } rclpy_qos.reliability = PyLong_FromUnsignedLong(qos_profile->reliability); if (!rclpy_qos.reliability) { - Py_DECREF(pyqos_profile); cleanup_rclpy_qos_profile(&rclpy_qos); return NULL; } rclpy_qos.durability = PyLong_FromUnsignedLong(qos_profile->durability); if (!rclpy_qos.durability) { - Py_DECREF(pyqos_profile); cleanup_rclpy_qos_profile(&rclpy_qos); return NULL; } rclpy_qos.lifespan = _convert_rmw_time_to_py_duration(&qos_profile->lifespan); if (!rclpy_qos.lifespan) { - Py_DECREF(pyqos_profile); cleanup_rclpy_qos_profile(&rclpy_qos); return NULL; } rclpy_qos.deadline = _convert_rmw_time_to_py_duration(&qos_profile->deadline); if (!rclpy_qos.deadline) { - Py_DECREF(pyqos_profile); cleanup_rclpy_qos_profile(&rclpy_qos); return NULL; } rclpy_qos.liveliness = PyLong_FromUnsignedLong(qos_profile->liveliness); if (!rclpy_qos.liveliness) { - Py_DECREF(pyqos_profile); cleanup_rclpy_qos_profile(&rclpy_qos); return NULL; } @@ -235,7 +209,6 @@ rclpy_common_convert_to_py_qos_policy(const rmw_qos_profile_t * qos_profile) rclpy_qos.liveliness_lease_duration = _convert_rmw_time_to_py_duration( &qos_profile->liveliness_lease_duration); if (!rclpy_qos.liveliness_lease_duration) { - Py_DECREF(pyqos_profile); cleanup_rclpy_qos_profile(&rclpy_qos); return NULL; } @@ -243,31 +216,60 @@ rclpy_common_convert_to_py_qos_policy(const rmw_qos_profile_t * qos_profile) rclpy_qos.avoid_ros_namespace_conventions = PyBool_FromLong(qos_profile->avoid_ros_namespace_conventions); if (!rclpy_qos.avoid_ros_namespace_conventions) { - Py_DECREF(pyqos_profile); cleanup_rclpy_qos_profile(&rclpy_qos); return NULL; } - // A success returns 0, and a failure returns -1 - set_result = 0; - set_result += PyObject_SetAttrString(pyqos_profile, "depth", rclpy_qos.depth); - set_result += PyObject_SetAttrString(pyqos_profile, "history", rclpy_qos.history); - set_result += PyObject_SetAttrString(pyqos_profile, "reliability", rclpy_qos.reliability); - set_result += PyObject_SetAttrString(pyqos_profile, "durability", rclpy_qos.durability); - set_result += PyObject_SetAttrString(pyqos_profile, "lifespan", rclpy_qos.lifespan); - set_result += PyObject_SetAttrString(pyqos_profile, "deadline", rclpy_qos.deadline); - set_result += PyObject_SetAttrString(pyqos_profile, "liveliness", rclpy_qos.liveliness); - set_result += PyObject_SetAttrString(pyqos_profile, - "liveliness_lease_duration", rclpy_qos.liveliness_lease_duration); - set_result += PyObject_SetAttrString(pyqos_profile, - "avoid_ros_namespace_conventions", rclpy_qos.avoid_ros_namespace_conventions); + // Create dictionary to hold QoSProfile keyword arguments + PyObject * pyqos_kwargs = PyDict_New(); + if (!pyqos_kwargs) { + cleanup_rclpy_qos_profile(&rclpy_qos); + return NULL; + } + // Populate keyword arguments for QoSProfile object + // A success returns 0, and a failure returns -1 + int set_result = 0; + set_result += PyDict_SetItemString(pyqos_kwargs, "depth", rclpy_qos.depth); + set_result += PyDict_SetItemString(pyqos_kwargs, "history", rclpy_qos.history); + set_result += PyDict_SetItemString(pyqos_kwargs, "reliability", rclpy_qos.reliability); + set_result += PyDict_SetItemString(pyqos_kwargs, "durability", rclpy_qos.durability); + set_result += PyDict_SetItemString(pyqos_kwargs, "lifespan", rclpy_qos.lifespan); + set_result += PyDict_SetItemString(pyqos_kwargs, "deadline", rclpy_qos.deadline); + set_result += PyDict_SetItemString(pyqos_kwargs, "liveliness", rclpy_qos.liveliness); + set_result += PyDict_SetItemString( + pyqos_kwargs, "liveliness_lease_duration", rclpy_qos.liveliness_lease_duration); + set_result += PyDict_SetItemString( + pyqos_kwargs, "avoid_ros_namespace_conventions", rclpy_qos.avoid_ros_namespace_conventions); cleanup_rclpy_qos_profile(&rclpy_qos); - if (0 != set_result) { - Py_DECREF(pyqos_profile); + Py_DECREF(pyqos_kwargs); + return NULL; + } + + // Construct Python QoSProfile object + PyObject * pyqos_module = PyImport_ImportModule("rclpy.qos"); + if (!pyqos_module) { + Py_DECREF(pyqos_kwargs); + return NULL; + } + PyObject * pyqos_profile_class = PyObject_GetAttrString(pyqos_module, "QoSProfile"); + Py_DECREF(pyqos_module); + if (!pyqos_profile_class) { + Py_DECREF(pyqos_kwargs); + return NULL; + } + // There are no positional arguments, but we're required to pass an empty tuple anyways + PyObject * pyqos_args = PyTuple_New(0); + if (!pyqos_args) { + Py_DECREF(pyqos_kwargs); + Py_DECREF(pyqos_profile_class); return NULL; } + PyObject * pyqos_profile = PyObject_Call(pyqos_profile_class, pyqos_args, pyqos_kwargs); + Py_DECREF(pyqos_profile_class); + Py_DECREF(pyqos_args); + Py_DECREF(pyqos_kwargs); return pyqos_profile; } From 2f2027d7623ad0c82df0d1edef4a201a63ba2e46 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 13 May 2019 15:05:17 -0700 Subject: [PATCH 5/7] Use default UserWarning for visibilty DeprecatedWarning is not visible by default until Python 3.7. Signed-off-by: Jacob Perron --- rclpy/rclpy/node.py | 7 +++---- rclpy/rclpy/qos.py | 2 -- rclpy/test/test_node.py | 30 +++++++++++++++++++----------- rclpy/test/test_qos.py | 10 +++++++--- 4 files changed, 29 insertions(+), 20 deletions(-) diff --git a/rclpy/rclpy/node.py b/rclpy/rclpy/node.py index 3e83aabc8..ad8375b02 100644 --- a/rclpy/rclpy/node.py +++ b/rclpy/rclpy/node.py @@ -682,8 +682,7 @@ def _validate_qos_or_depth_parameter(self, qos_or_depth) -> QoSProfile: if isinstance(qos_or_depth, QoSProfile): if isinstance(qos_or_depth, DeprecatedQoSProfile): warnings.warn( - "Using deprecated QoSProfile '{qos_or_depth.name}'".format_map(locals()), - DeprecationWarning) + "Using deprecated QoSProfile '{qos_or_depth.name}'".format_map(locals())) return qos_or_depth elif isinstance(qos_or_depth, int): if qos_or_depth < 0: @@ -740,7 +739,7 @@ def create_publisher( """ # if the new API is not used, issue a deprecation warning and continue with the old API if qos_or_depth is None: - warnings.warn("Use the new 'qos_or_depth' parameter", DeprecationWarning) + warnings.warn("Use the new 'qos_or_depth' parameter, instead of 'qos_profile'") else: qos_profile = self._validate_qos_or_depth_parameter(qos_or_depth) @@ -807,7 +806,7 @@ def create_subscription( """ # if the new API is not used, issue a deprecation warning and continue with the old API if qos_or_depth is None: - warnings.warn("Use the new 'qos_or_depth' parameter", DeprecationWarning) + warnings.warn("Use the new 'qos_or_depth' parameter, instead of 'qos_profile'") else: qos_profile = self._validate_qos_or_depth_parameter(qos_or_depth) diff --git a/rclpy/rclpy/qos.py b/rclpy/rclpy/qos.py index e52f2dea3..3d33ae201 100644 --- a/rclpy/rclpy/qos.py +++ b/rclpy/rclpy/qos.py @@ -44,7 +44,6 @@ def __init__(self, **kwargs): else: warnings.warn( "QoSProfile needs a 'history' and/or 'depth' setting when constructed", - DeprecationWarning, stacklevel=2) self.history = kwargs.get( 'history', @@ -55,7 +54,6 @@ def __init__(self, **kwargs): ): warnings.warn( 'A QoSProfile with history set to KEEP_LAST needs a depth specified', - DeprecationWarning, stacklevel=2) self.depth = kwargs.get('depth', int()) self.reliability = kwargs.get( diff --git a/rclpy/test/test_node.py b/rclpy/test/test_node.py index d20110cd4..6bb8beb8d 100644 --- a/rclpy/test/test_node.py +++ b/rclpy/test/test_node.py @@ -34,6 +34,7 @@ from rclpy.qos import qos_profile_sensor_data from test_msgs.msg import BasicTypes + TEST_NODE = 'my_node' TEST_NAMESPACE = '/my_ns' @@ -142,47 +143,54 @@ def test_create_service(self): self.node.create_service(GetParameters, 'foo/{bad_sub}', lambda req: None) def test_deprecation_warnings(self): - warnings.simplefilter('always') with warnings.catch_warnings(record=True) as w: + warnings.simplefilter('always') self.node.create_publisher(BasicTypes, 'chatter') assert len(w) == 1 - assert issubclass(w[0].category, DeprecationWarning) + assert issubclass(w[0].category, UserWarning) with warnings.catch_warnings(record=True) as w: + warnings.simplefilter('always') self.node.create_publisher(BasicTypes, 'chatter', qos_profile=qos_profile_sensor_data) assert len(w) == 1 - assert issubclass(w[0].category, DeprecationWarning) + assert issubclass(w[0].category, UserWarning) with warnings.catch_warnings(record=True) as w: + warnings.simplefilter('always') self.node.create_publisher(BasicTypes, 'chatter', qos_profile=qos_profile_sensor_data) assert len(w) == 1 - assert issubclass(w[0].category, DeprecationWarning) + assert issubclass(w[0].category, UserWarning) with warnings.catch_warnings(record=True) as w: + warnings.simplefilter('always') self.node.create_publisher(BasicTypes, 'chatter', qos_profile_default) assert len(w) == 1 - assert issubclass(w[0].category, DeprecationWarning) + assert issubclass(w[0].category, UserWarning) with warnings.catch_warnings(record=True) as w: + warnings.simplefilter('always') self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg)) assert len(w) == 1 - assert issubclass(w[0].category, DeprecationWarning) + assert issubclass(w[0].category, UserWarning) with warnings.catch_warnings(record=True) as w: + warnings.simplefilter('always') self.node.create_subscription( BasicTypes, 'chatter', lambda msg: print(msg), qos_profile=qos_profile_sensor_data) assert len(w) == 1 - assert issubclass(w[0].category, DeprecationWarning) + assert issubclass(w[0].category, UserWarning) with warnings.catch_warnings(record=True) as w: + warnings.simplefilter('always') self.node.create_subscription( BasicTypes, 'chatter', lambda msg: print(msg), qos_profile=qos_profile_sensor_data) assert len(w) == 1 - assert issubclass(w[0].category, DeprecationWarning) + assert issubclass(w[0].category, UserWarning) with warnings.catch_warnings(record=True) as w: + warnings.simplefilter('always') self.node.create_subscription( BasicTypes, 'chatter', lambda msg: print(msg), qos_profile_default) assert len(w) == 1 - assert issubclass(w[0].category, DeprecationWarning) + assert issubclass(w[0].category, UserWarning) with warnings.catch_warnings(record=True) as w: + warnings.simplefilter('always') self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg), raw=True) assert len(w) == 1 - assert issubclass(w[0].category, DeprecationWarning) - warnings.simplefilter('default') + assert issubclass(w[0].category, UserWarning) def test_service_names_and_types(self): # test that it doesn't raise diff --git a/rclpy/test/test_qos.py b/rclpy/test/test_qos.py index 0dfe3fc38..589ee8b9c 100644 --- a/rclpy/test/test_qos.py +++ b/rclpy/test/test_qos.py @@ -94,25 +94,29 @@ def test_alldata_round_trip(self): self.convert_and_assert_equality(source_profile) def test_deprecation_warnings(self): - warnings.simplefilter('always') with warnings.catch_warnings(record=True) as w: + warnings.simplefilter('always') QoSProfile() assert len(w) == 1 - assert issubclass(w[0].category, DeprecationWarning) + assert issubclass(w[0].category, UserWarning) with warnings.catch_warnings(record=True) as w: + warnings.simplefilter('always') # No deprecation if history is supplied QoSProfile(history=QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_ALL) assert len(w) == 0, str(w[-1].message) with warnings.catch_warnings(record=True) as w: + warnings.simplefilter('always') # Deprecation warning if KEEP_LAST, but no depth QoSProfile(history=QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST) assert len(w) == 1 - assert issubclass(w[0].category, DeprecationWarning) + assert issubclass(w[0].category, UserWarning) with warnings.catch_warnings(record=True) as w: + warnings.simplefilter('always') # No deprecation if 'depth' is present QoSProfile(history=QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST, depth=1) assert len(w) == 0, str(w[-1].message) with warnings.catch_warnings(record=True) as w: + warnings.simplefilter('always') # No deprecation if only depth QoSProfile(depth=1) assert len(w) == 0, str(w[-1].message) From 394e93eaf807950466dca5eb6080ed68bef63718 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 13 May 2019 16:42:22 -0700 Subject: [PATCH 6/7] Fix deprecation warnings Signed-off-by: Jacob Perron --- rclpy/rclpy/node.py | 2 +- rclpy/rclpy/time_source.py | 3 ++- rclpy/test/test_action_client.py | 2 +- rclpy/test/test_action_server.py | 7 +++++-- rclpy/test/test_callback_group.py | 4 ++-- rclpy/test/test_create_while_spinning.py | 4 ++-- rclpy/test/test_destruction.py | 12 ++++++------ rclpy/test/test_messages.py | 4 ++-- rclpy/test/test_node.py | 10 ++++------ rclpy/test/test_time_source.py | 4 ++-- rclpy/test/test_waitable.py | 2 +- 11 files changed, 28 insertions(+), 26 deletions(-) diff --git a/rclpy/rclpy/node.py b/rclpy/rclpy/node.py index ad8375b02..47af7f0d5 100644 --- a/rclpy/rclpy/node.py +++ b/rclpy/rclpy/node.py @@ -163,7 +163,7 @@ def __init__( self.__executor_weakref = None self._parameter_event_publisher = self.create_publisher( - ParameterEvent, 'parameter_events', qos_profile=qos_profile_parameter_events) + ParameterEvent, 'parameter_events', qos_profile_parameter_events) with self.handle as capsule: self._initial_parameters = _rclpy.rclpy_get_node_parameters(Parameter, capsule) diff --git a/rclpy/rclpy/time_source.py b/rclpy/rclpy/time_source.py index f3b6a499a..1a73a63c8 100644 --- a/rclpy/rclpy/time_source.py +++ b/rclpy/rclpy/time_source.py @@ -57,7 +57,8 @@ def _subscribe_to_clock_topic(self): self._clock_sub = self._node.create_subscription( rosgraph_msgs.msg.Clock, CLOCK_TOPIC, - self.clock_callback + self.clock_callback, + 10 ) def attach_node(self, node): diff --git a/rclpy/test/test_action_client.py b/rclpy/test/test_action_client.py index b7b664465..e4189a64e 100644 --- a/rclpy/test/test_action_client.py +++ b/rclpy/test/test_action_client.py @@ -43,7 +43,7 @@ def __init__(self, node): Fibonacci.Impl.GetResultService, '/fibonacci/_action/get_result', self.result_callback) self.feedback_pub = node.create_publisher( - Fibonacci.Impl.FeedbackMessage, '/fibonacci/_action/feedback') + Fibonacci.Impl.FeedbackMessage, '/fibonacci/_action/feedback', 1) def goal_callback(self, request, response): response.accepted = True diff --git a/rclpy/test/test_action_server.py b/rclpy/test/test_action_server.py index ca5d29366..206c96de4 100644 --- a/rclpy/test/test_action_server.py +++ b/rclpy/test/test_action_server.py @@ -40,9 +40,12 @@ def __init__(self, node): self.result_srv = node.create_client( Fibonacci.Impl.GetResultService, '/fibonacci/_action/get_result') self.feedback_sub = node.create_subscription( - Fibonacci.Impl.FeedbackMessage, '/fibonacci/_action/feedback', self.feedback_callback) + Fibonacci.Impl.FeedbackMessage, + '/fibonacci/_action/feedback', + self.feedback_callback, + 1) self.status_sub = node.create_subscription( - Fibonacci.Impl.GoalStatusMessage, '/fibonacci/_action/status', self.status_callback) + Fibonacci.Impl.GoalStatusMessage, '/fibonacci/_action/status', self.status_callback, 1) def reset(self): self.feedback_msg = None diff --git a/rclpy/test/test_callback_group.py b/rclpy/test/test_callback_group.py index f02a915ee..755e78f87 100644 --- a/rclpy/test/test_callback_group.py +++ b/rclpy/test/test_callback_group.py @@ -71,10 +71,10 @@ def test_create_timer_with_group(self): self.assertTrue(group.has_entity(tmr2)) def test_create_subscription_with_group(self): - sub1 = self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg)) + sub1 = self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg), 1) group = ReentrantCallbackGroup() sub2 = self.node.create_subscription( - BasicTypes, 'chatter', lambda msg: print(msg), callback_group=group) + BasicTypes, 'chatter', lambda msg: print(msg), 1, callback_group=group) self.assertFalse(group.has_entity(sub1)) self.assertTrue(group.has_entity(sub2)) diff --git a/rclpy/test/test_create_while_spinning.py b/rclpy/test/test_create_while_spinning.py index 8bb7d2051..6dd207ea7 100644 --- a/rclpy/test/test_create_while_spinning.py +++ b/rclpy/test/test_create_while_spinning.py @@ -54,8 +54,8 @@ def tearDown(self): def test_publish_subscribe(self): evt = threading.Event() - self.node.create_subscription(BasicTypes, 'foo', lambda msg: evt.set()) - pub = self.node.create_publisher(BasicTypes, 'foo') + self.node.create_subscription(BasicTypes, 'foo', lambda msg: evt.set(), 1) + pub = self.node.create_publisher(BasicTypes, 'foo', 1) pub.publish(BasicTypes()) assert evt.wait(TIMEOUT) diff --git a/rclpy/test/test_destruction.py b/rclpy/test/test_destruction.py index 14292f0fd..3113a84dd 100644 --- a/rclpy/test/test_destruction.py +++ b/rclpy/test/test_destruction.py @@ -71,16 +71,16 @@ def test_destroy_entities(): timer = node.create_timer(0.1, None) timer # noqa assert 1 == len(tuple(node.timers)) - pub1 = node.create_publisher(BasicTypes, 'pub1_topic') + pub1 = node.create_publisher(BasicTypes, 'pub1_topic', 1) assert 2 == len(tuple(node.publishers)) - pub2 = node.create_publisher(BasicTypes, 'pub2_topic') + pub2 = node.create_publisher(BasicTypes, 'pub2_topic', 1) pub2 # noqa assert 3 == len(tuple(node.publishers)) sub1 = node.create_subscription( - BasicTypes, 'sub1_topic', lambda msg: ...) + BasicTypes, 'sub1_topic', lambda msg: ..., 1) assert 1 == len(tuple(node.subscriptions)) sub2 = node.create_subscription( - BasicTypes, 'sub2_topic', lambda msg: ...) + BasicTypes, 'sub2_topic', lambda msg: ..., 1) sub2 # noqa assert 2 == len(tuple(node.subscriptions)) @@ -105,7 +105,7 @@ def test_destroy_subscription_asap(): try: node = rclpy.create_node('test_destroy_subscription_asap', context=context) try: - sub = node.create_subscription(BasicTypes, 'sub_topic', lambda msg: ...) + sub = node.create_subscription(BasicTypes, 'sub_topic', lambda msg: ..., 1) # handle valid with sub.handle: @@ -154,7 +154,7 @@ def test_destroy_publisher_asap(): try: node = rclpy.create_node('test_destroy_publisher_asap', context=context) try: - pub = node.create_publisher(BasicTypes, 'pub_topic') + pub = node.create_publisher(BasicTypes, 'pub_topic', 1) # handle valid with pub.handle: diff --git a/rclpy/test/test_messages.py b/rclpy/test/test_messages.py index d5ad18b43..012761809 100644 --- a/rclpy/test/test_messages.py +++ b/rclpy/test/test_messages.py @@ -42,11 +42,11 @@ def tearDownClass(cls): def test_invalid_string_raises(self): msg = Strings() msg.string_value = 'ñu' - pub = self.node.create_publisher(Strings, 'chatter') + pub = self.node.create_publisher(Strings, 'chatter', 1) with self.assertRaises(UnicodeEncodeError): pub.publish(msg) def test_different_type_raises(self): - pub = self.node.create_publisher(BasicTypes, 'chatter') + pub = self.node.create_publisher(BasicTypes, 'chatter', 1) with self.assertRaises(TypeError): pub.publish('different message type') diff --git a/rclpy/test/test_node.py b/rclpy/test/test_node.py index 6bb8beb8d..04e0af0ae 100644 --- a/rclpy/test/test_node.py +++ b/rclpy/test/test_node.py @@ -34,7 +34,6 @@ from rclpy.qos import qos_profile_sensor_data from test_msgs.msg import BasicTypes - TEST_NODE = 'my_node' TEST_NAMESPACE = '/my_ns' @@ -63,7 +62,6 @@ def test_accessors(self): self.assertEqual(self.node.get_clock().clock_type, ClockType.ROS_TIME) def test_create_publisher(self): - self.node.create_publisher(BasicTypes, 'chatter') self.node.create_publisher(BasicTypes, 'chatter', 0) self.node.create_publisher(BasicTypes, 'chatter', 1) self.node.create_publisher(BasicTypes, 'chatter', qos_profile_sensor_data) @@ -79,7 +77,6 @@ def test_create_publisher(self): self.node.create_publisher(BasicTypes, 'chatter', 'foo') def test_create_subscription(self): - self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg)) self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg), 0) self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg), 1) self.node.create_subscription( @@ -108,6 +105,7 @@ def test_create_raw_subscription(self): BasicTypes, 'raw_subscription_test', self.raw_subscription_callback, + 1, raw=True ) basic_types_msg = BasicTypes() @@ -216,15 +214,15 @@ def test_count_publishers_subscribers(self): self.assertEqual(0, self.node.count_publishers(fq_topic_name)) self.assertEqual(0, self.node.count_subscribers(fq_topic_name)) - self.node.create_publisher(BasicTypes, short_topic_name) + self.node.create_publisher(BasicTypes, short_topic_name, 1) self.assertEqual(1, self.node.count_publishers(short_topic_name)) self.assertEqual(1, self.node.count_publishers(fq_topic_name)) - self.node.create_subscription(BasicTypes, short_topic_name, lambda msg: print(msg)) + self.node.create_subscription(BasicTypes, short_topic_name, lambda msg: print(msg), 1) self.assertEqual(1, self.node.count_subscribers(short_topic_name)) self.assertEqual(1, self.node.count_subscribers(fq_topic_name)) - self.node.create_subscription(BasicTypes, short_topic_name, lambda msg: print(msg)) + self.node.create_subscription(BasicTypes, short_topic_name, lambda msg: print(msg), 1) self.assertEqual(2, self.node.count_subscribers(short_topic_name)) self.assertEqual(2, self.node.count_subscribers(fq_topic_name)) diff --git a/rclpy/test/test_time_source.py b/rclpy/test/test_time_source.py index 489160247..a9999e332 100644 --- a/rclpy/test/test_time_source.py +++ b/rclpy/test/test_time_source.py @@ -46,7 +46,7 @@ def tearDown(self): rclpy.shutdown(context=self.context) def publish_clock_messages(self): - clock_pub = self.node.create_publisher(rosgraph_msgs.msg.Clock, CLOCK_TOPIC) + clock_pub = self.node.create_publisher(rosgraph_msgs.msg.Clock, CLOCK_TOPIC, 1) cycle_count = 0 time_msg = rosgraph_msgs.msg.Clock() while rclpy.ok(context=self.context) and cycle_count < 5: @@ -59,7 +59,7 @@ def publish_clock_messages(self): time.sleep(1) def publish_reversed_clock_messages(self): - clock_pub = self.node.create_publisher(rosgraph_msgs.msg.Clock, CLOCK_TOPIC) + clock_pub = self.node.create_publisher(rosgraph_msgs.msg.Clock, CLOCK_TOPIC, 1) cycle_count = 0 time_msg = rosgraph_msgs.msg.Clock() while rclpy.ok(context=self.context) and cycle_count < 5: diff --git a/rclpy/test/test_waitable.py b/rclpy/test/test_waitable.py index 73dd09a6a..8b7bd3b54 100644 --- a/rclpy/test/test_waitable.py +++ b/rclpy/test/test_waitable.py @@ -349,7 +349,7 @@ def test_waitable_with_timer(self): def test_waitable_with_subscription(self): self.waitable = SubscriptionWaitable(self.node) self.node.add_waitable(self.waitable) - pub = self.node.create_publisher(EmptyMsg, 'test_topic') + pub = self.node.create_publisher(EmptyMsg, 'test_topic', 1) thr = self.start_spin_thread(self.waitable) pub.publish(EmptyMsg()) From 61c421f3f494b8658849c861c2bd67d3c8e77926 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Mon, 13 May 2019 17:00:09 -0700 Subject: [PATCH 7/7] Replace use of deprecated object 'qos_profile_default' Signed-off-by: Jacob Perron --- rclpy/rclpy/action/client.py | 5 +++-- rclpy/rclpy/action/server.py | 5 +++-- rclpy/rclpy/node.py | 5 ++--- rclpy/test/test_action_client.py | 10 +++++----- rclpy/test/test_action_server.py | 10 +++++----- rclpy/test/test_waitable.py | 8 ++++---- 6 files changed, 22 insertions(+), 21 deletions(-) diff --git a/rclpy/rclpy/action/client.py b/rclpy/rclpy/action/client.py index 238308b8e..fad5ddb3d 100644 --- a/rclpy/rclpy/action/client.py +++ b/rclpy/rclpy/action/client.py @@ -23,7 +23,8 @@ from rclpy.executors import await_or_execute from rclpy.impl.implementation_singleton import rclpy_action_implementation as _rclpy_action from rclpy.qos import qos_profile_action_status_default -from rclpy.qos import qos_profile_default, qos_profile_services_default +from rclpy.qos import qos_profile_services_default +from rclpy.qos import QoSProfile from rclpy.task import Future from rclpy.type_support import check_for_type_support from rclpy.waitable import NumberOfEntities, Waitable @@ -120,7 +121,7 @@ def __init__( goal_service_qos_profile=qos_profile_services_default, result_service_qos_profile=qos_profile_services_default, cancel_service_qos_profile=qos_profile_services_default, - feedback_sub_qos_profile=qos_profile_default, + feedback_sub_qos_profile=QoSProfile(depth=10), status_sub_qos_profile=qos_profile_action_status_default ): """ diff --git a/rclpy/rclpy/action/server.py b/rclpy/rclpy/action/server.py index da3889795..8e86546a8 100644 --- a/rclpy/rclpy/action/server.py +++ b/rclpy/rclpy/action/server.py @@ -21,7 +21,8 @@ from rclpy.executors import await_or_execute from rclpy.impl.implementation_singleton import rclpy_action_implementation as _rclpy_action from rclpy.qos import qos_profile_action_status_default -from rclpy.qos import qos_profile_default, qos_profile_services_default +from rclpy.qos import qos_profile_services_default +from rclpy.qos import QoSProfile from rclpy.task import Future from rclpy.type_support import check_for_type_support from rclpy.waitable import NumberOfEntities, Waitable @@ -203,7 +204,7 @@ def __init__( goal_service_qos_profile=qos_profile_services_default, result_service_qos_profile=qos_profile_services_default, cancel_service_qos_profile=qos_profile_services_default, - feedback_pub_qos_profile=qos_profile_default, + feedback_pub_qos_profile=QoSProfile(depth=10), status_pub_qos_profile=qos_profile_action_status_default, result_timeout=900 ): diff --git a/rclpy/rclpy/node.py b/rclpy/rclpy/node.py index 47af7f0d5..86fd8adc5 100644 --- a/rclpy/rclpy/node.py +++ b/rclpy/rclpy/node.py @@ -51,7 +51,6 @@ from rclpy.parameter_service import ParameterService from rclpy.publisher import Publisher from rclpy.qos import DeprecatedQoSProfile -from rclpy.qos import qos_profile_default from rclpy.qos import qos_profile_parameter_events from rclpy.qos import qos_profile_services_default from rclpy.qos import QoSProfile @@ -716,7 +715,7 @@ def create_publisher( topic: str, qos_or_depth: Union[QoSProfile, int] = None, *, - qos_profile: QoSProfile = qos_profile_default, + qos_profile: QoSProfile = QoSProfile(depth=10), callback_group: Optional[CallbackGroup] = None, event_callbacks: Optional[PublisherEventCallbacks] = None, ) -> Publisher: @@ -779,7 +778,7 @@ def create_subscription( callback: Callable[[MsgType], None], qos_or_depth: Union[QoSProfile, int] = None, *, - qos_profile: QoSProfile = qos_profile_default, + qos_profile: QoSProfile = QoSProfile(depth=10), callback_group: Optional[CallbackGroup] = None, event_callbacks: Optional[SubscriptionEventCallbacks] = None, raw: bool = False diff --git a/rclpy/test/test_action_client.py b/rclpy/test/test_action_client.py index e4189a64e..d7cbc6681 100644 --- a/rclpy/test/test_action_client.py +++ b/rclpy/test/test_action_client.py @@ -98,11 +98,11 @@ def test_constructor_no_defaults(self): self.node, Fibonacci, 'fibonacci', - goal_service_qos_profile=rclpy.qos.qos_profile_default, - result_service_qos_profile=rclpy.qos.qos_profile_default, - cancel_service_qos_profile=rclpy.qos.qos_profile_default, - feedback_sub_qos_profile=rclpy.qos.qos_profile_default, - status_sub_qos_profile=rclpy.qos.qos_profile_default + goal_service_qos_profile=rclpy.qos.QoSProfile(depth=10), + result_service_qos_profile=rclpy.qos.QoSProfile(depth=10), + cancel_service_qos_profile=rclpy.qos.QoSProfile(depth=10), + feedback_sub_qos_profile=rclpy.qos.QoSProfile(depth=10), + status_sub_qos_profile=rclpy.qos.QoSProfile(depth=10) ) ac.destroy() diff --git a/rclpy/test/test_action_server.py b/rclpy/test/test_action_server.py index 206c96de4..6eae4578c 100644 --- a/rclpy/test/test_action_server.py +++ b/rclpy/test/test_action_server.py @@ -112,11 +112,11 @@ def test_constructor_no_defaults(self): goal_callback=lambda req: GoalResponse.REJECT, handle_accepted_callback=lambda gh: None, cancel_callback=lambda req: CancelResponse.REJECT, - goal_service_qos_profile=rclpy.qos.qos_profile_default, - result_service_qos_profile=rclpy.qos.qos_profile_default, - cancel_service_qos_profile=rclpy.qos.qos_profile_default, - feedback_pub_qos_profile=rclpy.qos.qos_profile_default, - status_pub_qos_profile=rclpy.qos.qos_profile_default, + goal_service_qos_profile=rclpy.qos.QoSProfile(depth=10), + result_service_qos_profile=rclpy.qos.QoSProfile(depth=10), + cancel_service_qos_profile=rclpy.qos.QoSProfile(depth=10), + feedback_pub_qos_profile=rclpy.qos.QoSProfile(depth=10), + status_pub_qos_profile=rclpy.qos.QoSProfile(depth=10), result_timeout=300, ) action_server.destroy() diff --git a/rclpy/test/test_waitable.py b/rclpy/test/test_waitable.py index 8b7bd3b54..c648bec99 100644 --- a/rclpy/test/test_waitable.py +++ b/rclpy/test/test_waitable.py @@ -23,7 +23,7 @@ from rclpy.executors import SingleThreadedExecutor from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy from rclpy.node import check_for_type_support -from rclpy.qos import qos_profile_default +from rclpy.qos import QoSProfile from rclpy.task import Future from rclpy.waitable import NumberOfEntities from rclpy.waitable import Waitable @@ -43,7 +43,7 @@ def __init__(self, node): with node.handle as node_capsule: self.client = _rclpy.rclpy_create_client( - node_capsule, EmptySrv, 'test_client', qos_profile_default.get_c_qos_profile()) + node_capsule, EmptySrv, 'test_client', QoSProfile(depth=10).get_c_qos_profile()) self.client_index = None self.client_is_ready = False @@ -86,7 +86,7 @@ def __init__(self, node): with node.handle as node_capsule: self.server = _rclpy.rclpy_create_service( - node_capsule, EmptySrv, 'test_server', qos_profile_default.get_c_qos_profile()) + node_capsule, EmptySrv, 'test_server', QoSProfile(depth=10).get_c_qos_profile()) self.server_index = None self.server_is_ready = False @@ -175,7 +175,7 @@ def __init__(self, node): with node.handle as node_capsule: self.subscription = _rclpy.rclpy_create_subscription( - node_capsule, EmptyMsg, 'test_topic', qos_profile_default.get_c_qos_profile()) + node_capsule, EmptyMsg, 'test_topic', QoSProfile(depth=10).get_c_qos_profile()) self.subscription_index = None self.subscription_is_ready = False