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

Remove deprecated QoS functionality #431

Merged
merged 1 commit into from
Sep 18, 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
25 changes: 4 additions & 21 deletions rclpy/rclpy/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@
from typing import TypeVar
from typing import Union

import warnings
import weakref

from rcl_interfaces.msg import FloatingPointRange
Expand Down Expand Up @@ -57,7 +56,6 @@
from rclpy.parameter import Parameter, PARAMETER_SEPARATOR_STRING
from rclpy.parameter_service import ParameterService
from rclpy.publisher import Publisher
from rclpy.qos import DeprecatedQoSProfile
from rclpy.qos import qos_profile_parameter_events
from rclpy.qos import qos_profile_services_default
from rclpy.qos import QoSProfile
Expand Down Expand Up @@ -1035,9 +1033,6 @@ 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()))
return qos_or_depth
elif isinstance(qos_or_depth, int):
if qos_or_depth < 0:
Expand Down Expand Up @@ -1069,7 +1064,7 @@ def create_publisher(
self,
msg_type,
topic: str,
qos_profile: Union[QoSProfile, int] = None,
qos_profile: Union[QoSProfile, int],
*,
callback_group: Optional[CallbackGroup] = None,
event_callbacks: Optional[PublisherEventCallbacks] = None,
Expand All @@ -1080,7 +1075,6 @@ 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: 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.
Expand All @@ -1089,12 +1083,7 @@ def create_publisher(
: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_profile is None:
warnings.warn("Pass an explicit 'qos_profile' argument")
qos_profile = QoSProfile(depth=10)
else:
qos_profile = self._validate_qos_or_depth_parameter(qos_profile)
qos_profile = self._validate_qos_or_depth_parameter(qos_profile)

callback_group = callback_group or self.default_callback_group

Expand Down Expand Up @@ -1130,7 +1119,7 @@ def create_subscription(
msg_type,
topic: str,
callback: Callable[[MsgType], None],
qos_profile: Union[QoSProfile, int] = None,
qos_profile: Union[QoSProfile, int],
*,
callback_group: Optional[CallbackGroup] = None,
event_callbacks: Optional[SubscriptionEventCallbacks] = None,
Expand All @@ -1144,7 +1133,6 @@ def create_subscription(
:param callback: A user-defined callback function that is called when a message is
received by the subscription.
:param qos_profile: 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.
Expand All @@ -1154,12 +1142,7 @@ def create_subscription(
: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_profile is None:
warnings.warn("Pass an explicit 'qos_profile' argument")
qos_profile = QoSProfile(depth=10)
else:
qos_profile = self._validate_qos_or_depth_parameter(qos_profile)
qos_profile = self._validate_qos_or_depth_parameter(qos_profile)

callback_group = callback_group or self.default_callback_group

Expand Down
83 changes: 30 additions & 53 deletions rclpy/rclpy/qos.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,23 +12,27 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from argparse import Namespace
from enum import Enum
from enum import IntEnum
import warnings

from rclpy.duration import Duration
from rclpy.impl.implementation_singleton import rclpy_action_implementation as _rclpy_action
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy

# "Forward-declare" this value so that it can be used in the QoSProfile initializer.
# It will have a value by the end of definitions, before user code runs.
_qos_profile_default = None

class InvalidQoSProfileException(Exception):
"""Raised when concstructing a QoSProfile with invalid arguments."""

def __init__(self, *args):
Exception.__init__(self, 'Invalid QoSProfile', *args)


class QoSProfile:
"""Define Quality of Service policies."""

# default QoS profile not exposed to the user to encourage them to think about QoS settings
__qos_profile_default_dict = _rclpy.rclpy_get_rmw_qos_profile('qos_profile_default')

__slots__ = [
'_history',
'_depth',
Expand All @@ -45,42 +49,34 @@ def __init__(self, **kwargs):
assert all('_' + key in self.__slots__ for key in kwargs.keys()), \
'Invalid arguments passed to constructor: %r' % kwargs.keys()

if not _qos_profile_default:
# It is still definition time, and all calls to this initializer are expected to be
# fully-defined preset profiles from the C side.
assert all(kwargs[slot[1:]] is not None for slot in self.__slots__)
# Any of the setters, upon receiving these None values, would assert
# if the above assertion failed.
from_profile = Namespace(**{slot[1:]: None for slot in self.__slots__})
else:
from_profile = _qos_profile_default

if 'history' not in kwargs:
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",
stacklevel=2)
self.history = kwargs.get('history', from_profile.history)
if 'depth' not in kwargs:
raise InvalidQoSProfileException('History and/or depth settings are required.')
kwargs['history'] = QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST

self.history = kwargs.get('history')

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',
stacklevel=2)

self.depth = kwargs.get('depth', from_profile.depth)
self.reliability = kwargs.get('reliability', from_profile.reliability)
self.durability = kwargs.get('durability', from_profile.durability)
self.lifespan = kwargs.get('lifespan', from_profile.lifespan)
self.deadline = kwargs.get('deadline', from_profile.deadline)
self.liveliness = kwargs.get('liveliness', from_profile.liveliness)
raise InvalidQoSProfileException('History set to KEEP_LAST without a depth setting.')

self.depth = kwargs.get('depth', QoSProfile.__qos_profile_default_dict['depth'])
self.reliability = kwargs.get(
'reliability', QoSProfile.__qos_profile_default_dict['reliability'])
self.durability = kwargs.get(
'durability', QoSProfile.__qos_profile_default_dict['durability'])
self.lifespan = kwargs.get('lifespan', QoSProfile.__qos_profile_default_dict['lifespan'])
self.deadline = kwargs.get('deadline', QoSProfile.__qos_profile_default_dict['deadline'])
self.liveliness = kwargs.get(
'liveliness', QoSProfile.__qos_profile_default_dict['liveliness'])
self.liveliness_lease_duration = kwargs.get(
'liveliness_lease_duration', from_profile.liveliness_lease_duration)
'liveliness_lease_duration',
QoSProfile.__qos_profile_default_dict['liveliness_lease_duration'])
self.avoid_ros_namespace_conventions = kwargs.get(
'avoid_ros_namespace_conventions', from_profile.avoid_ros_namespace_conventions)
'avoid_ros_namespace_conventions',
QoSProfile.__qos_profile_default_dict['avoid_ros_namespace_conventions'])

@property
def history(self):
Expand Down Expand Up @@ -333,25 +329,6 @@ class LivelinessPolicy(QoSPolicyEnum):
# Alias with the old name, for retrocompatibility
QoSLivelinessPolicy = LivelinessPolicy


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 = QoSProfile(**_rclpy.rclpy_get_rmw_qos_profile('qos_profile_default'))
qos_profile_default = DeprecatedQoSProfile(_qos_profile_default, 'qos_profile_default')
qos_profile_system_default = QoSProfile(**_rclpy.rclpy_get_rmw_qos_profile(
'qos_profile_system_default'))
qos_profile_sensor_data = QoSProfile(**_rclpy.rclpy_get_rmw_qos_profile(
Expand Down
30 changes: 0 additions & 30 deletions rclpy/test/test_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@

import unittest
from unittest.mock import Mock
import warnings

from rcl_interfaces.msg import FloatingPointRange
from rcl_interfaces.msg import IntegerRange
Expand All @@ -34,7 +33,6 @@
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 rclpy.time_source import USE_SIM_TIME_NAME
from test_msgs.msg import BasicTypes
Expand Down Expand Up @@ -145,34 +143,6 @@ 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):
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, 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, 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, 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, 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, UserWarning)

def test_service_names_and_types(self):
# test that it doesn't raise
self.node.get_service_names_and_types()
Expand Down
41 changes: 6 additions & 35 deletions rclpy/test/test_qos.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,11 +13,10 @@
# limitations under the License.

import unittest
import warnings

from rclpy.duration import Duration
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
from rclpy.qos import _qos_profile_default
from rclpy.qos import InvalidQoSProfileException
from rclpy.qos import qos_profile_system_default
from rclpy.qos import QoSDurabilityPolicy
from rclpy.qos import QoSHistoryPolicy
Expand Down Expand Up @@ -96,33 +95,13 @@ def test_alldata_round_trip(self):
)
self.convert_and_assert_equality(source_profile)

def test_deprecation_warnings(self):
with warnings.catch_warnings(record=True) as w:
warnings.simplefilter('always')
def test_invalid_qos(self):
with self.assertRaises(InvalidQoSProfileException):
# No history or depth settings provided
QoSProfile()
assert len(w) == 2 # must supply depth or history, _and_ KEEP_LAST needs depth
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
with self.assertRaises(InvalidQoSProfileException):
# History is KEEP_LAST, but no depth is provided
QoSProfile(history=QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST)
assert len(w) == 1
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)

def test_policy_short_names(self):
# Full test on History to show the mechanism works
Expand All @@ -143,11 +122,3 @@ def test_preset_profiles(self):
assert (
QoSPresetProfiles.SYSTEM_DEFAULT.value ==
QoSPresetProfiles.get_from_short_key('system_default'))

def test_default_profile(self):
with warnings.catch_warnings(record=True):
warnings.simplefilter('always')
profile = QoSProfile()
assert all(
profile.__getattribute__(k) == _qos_profile_default.__getattribute__(k)
for k in profile.__slots__)