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

Encourage users to always provide a QoS history depth #344

Merged
merged 7 commits into from
May 14, 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
5 changes: 3 additions & 2 deletions rclpy/rclpy/action/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
):
"""
Expand Down
5 changes: 3 additions & 2 deletions rclpy/rclpy/action/server.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
):
Expand Down
54 changes: 48 additions & 6 deletions rclpy/rclpy/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -48,7 +50,7 @@
from rclpy.parameter import Parameter
from rclpy.parameter_service import ParameterService
from rclpy.publisher import Publisher
from rclpy.qos import qos_profile_default
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 @@ -160,7 +162,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)
Expand Down Expand Up @@ -675,6 +677,20 @@ 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):
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:
raise ValueError('history depth must be greater than or equal to zero')
return QoSProfile(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.
Expand All @@ -697,8 +713,9 @@ def create_publisher(
self,
msg_type,
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:
Expand All @@ -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, instead of 'qos_profile'")
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
Expand Down Expand Up @@ -747,8 +776,9 @@ def create_subscription(
msg_type,
topic: str,
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
Expand All @@ -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, instead of 'qos_profile'")
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
Expand Down
34 changes: 33 additions & 1 deletion rclpy/rclpy/qos.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -37,9 +38,23 @@ 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:
jacobperron marked this conversation as resolved.
Show resolved Hide resolved
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',
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',
stacklevel=2)
self.depth = kwargs.get('depth', int())
self.reliability = kwargs.get(
'reliability',
Expand Down Expand Up @@ -262,8 +277,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(
Expand Down
3 changes: 2 additions & 1 deletion rclpy/rclpy/time_source.py
Original file line number Diff line number Diff line change
Expand Up @@ -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):
Expand Down
90 changes: 46 additions & 44 deletions rclpy/src/rclpy_common/src/common.c
Original file line number Diff line number Diff line change
Expand Up @@ -160,114 +160,116 @@ _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;
}

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;
}

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;
}

Expand Down
Loading