Skip to content

Commit

Permalink
[subscribers] stricter arg handling (#104)
Browse files Browse the repository at this point in the history
* [subscribers] stricter arg handling

Require users to provide, especially, ros comms arguments given that
there are more things that can go wrong in ros2 by blindly setting
best effort guesses.

* [subscribers] first test added
* [utilities] add a default unlatched profile for demo/tests
  • Loading branch information
stonier committed Sep 18, 2019
1 parent ec2be7b commit a69289d
Show file tree
Hide file tree
Showing 8 changed files with 220 additions and 73 deletions.
1 change: 1 addition & 0 deletions .settings/org.eclipse.core.resources.prefs
Original file line number Diff line number Diff line change
Expand Up @@ -15,4 +15,5 @@ encoding//py_trees_ros/subscribers.py=utf-8
encoding//py_trees_ros/trees.py=utf-8
encoding//py_trees_ros/utilities.py=utf-8
encoding//tests/test_action_client.py=utf-8
encoding//tests/test_subscribers.py=utf-8
encoding/setup.py=utf-8
8 changes: 6 additions & 2 deletions py_trees_ros/battery.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
##############################################################################

import py_trees
import rclpy.qos
import sensor_msgs.msg as sensor_msgs

from . import subscribers
Expand All @@ -41,17 +42,20 @@ class ToBlackboard(subscribers.ToBlackboard):
* battery_low_warning (:obj:`bool`)[w]: False if battery is ok, True if critically low
Args:
name: name of the behaviour
topic_name: name of the battery state topic
qos_profile: qos profile for the subscriber
name: name of the behaviour
threshold: percentage level threshold for flagging as low (0-100)
"""
def __init__(self,
topic_name: str,
qos_profile: rclpy.qos.QoSProfile,
name: str=py_trees.common.Name.AUTO_GENERATED,
topic_name: str="/battery/state",
threshold: float=30.0):
super().__init__(name=name,
topic_name=topic_name,
topic_type=sensor_msgs.BatteryState,
qos_profile=qos_profile,
blackboard_variables={"battery": None},
clearing_policy=py_trees.common.ClearingPolicy.NEVER
)
Expand Down
4 changes: 2 additions & 2 deletions py_trees_ros/blackboard.py
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ def __init__(
self.publisher = self.node.create_publisher(
msg_type=std_msgs.String,
topic=topic_name,
qos_profile=utilities.qos_profile_latched_topic()
qos_profile=utilities.qos_profile_latched()
)

def shutdown(self):
Expand Down Expand Up @@ -220,7 +220,7 @@ def setup(self, timeout):
self.publisher = self.node.create_publisher(
msg_type=std_msgs.String,
topic='~/exchange/blackboard',
qos_profile=utilities.qos_profile_latched_topic()
qos_profile=utilities.qos_profile_latched()
)
for name in ["get_blackboard_variables",
"open_blackboard_watcher",
Expand Down
2 changes: 1 addition & 1 deletion py_trees_ros/programs/blackboard_watcher.py
Original file line number Diff line number Diff line change
Expand Up @@ -167,7 +167,7 @@ def main(command_line_args=sys.argv[1:]):
msg_type=std_msgs.String,
topic=watcher_topic_name,
callback=blackboard_watcher.echo_blackboard_contents,
qos_profile=rclpy.qos.qos_profile_system_default
qos_profile=py_trees_ros.utilities.qos_profile_unlatched()
)
# stream
try:
Expand Down
2 changes: 1 addition & 1 deletion py_trees_ros/programs/echo.py
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ def create_subscription(node, latched, topic_name, message_type, callback):
raise RuntimeError('Could not determine the type for the passed topic')

msg_module = ros2topic.api.import_message_type(topic_name, message_type)
qos_profile = py_trees_ros.utilities.qos_profile_latched_topic() if latched else rclpy.qos.qos_profile_default
qos_profile = py_trees_ros.utilities.qos_profile_latched() if latched else py_trees_ros.utilities.qos_profile_unlatched()
return node.create_subscription(
msg_module,
topic_name,
Expand Down
126 changes: 64 additions & 62 deletions py_trees_ros/subscribers.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,10 +27,12 @@

import copy
import operator
import threading
import typing

import py_trees
import rclpy.qos
import std_msgs.msg as std_msgs
import threading

from . import utilities

Expand Down Expand Up @@ -73,20 +75,20 @@ class Handler(py_trees.behaviour.Behaviour):
some data (e.g. CameraInfo).
Args:
name (:obj:`str`): name of the behaviour
topic_name (:obj:`str`): name of the topic to connect to
topic_type (:obj:`any`): class of the message type (e.g. :obj:`std_msgs.msg.String`)
qos_profile (:obj:`bool`): qos profile for the subscriber
clearing_policy (:class:`~py_trees.common.ClearingPolicy`): when to clear the data
topic_name: name of the topic to connect to
topic_type: class of the message type (e.g. :obj:`std_msgs.msg.String`)
qos_profile: qos profile for the subscriber
name: name of the behaviour
clearing_policy: when to clear the data
"""
def __init__(self,
name="Subscriber Handler",
topic_name="/foo",
topic_type=None,
qos_profile=rclpy.qos.qos_profile_system_default,
clearing_policy=py_trees.common.ClearingPolicy.ON_INITIALISE
topic_name: str,
topic_type: typing.Any,
qos_profile: rclpy.qos.QoSProfile,
name: str=py_trees.common.Name.AUTO_GENERATED,
clearing_policy: py_trees.common.ClearingPolicy=py_trees.common.ClearingPolicy.ON_INITIALISE
):
super(Handler, self).__init__(name)
super(Handler, self).__init__(name=name)
self.topic_name = topic_name
self.topic_type = topic_type
self.msg = None
Expand Down Expand Up @@ -160,16 +162,16 @@ class CheckData(Handler):
- fail_if_bad_comparison=True
Args:
name (:obj:`str`): name of the behaviour
topic_name (:obj:`str`): name of the topic to connect to
topic_type (:obj:`any`): class of the message type (e.g. :obj:`std_msgs.msg.String`)
qos_profile (:obj:`bool`): qos profile for the subscriber
variable_name (:obj:`str`): name of the variable to check
expected_value (:obj:`any`): expected value of the variable
fail_if_no_data (:obj:`bool`): :attr:`~py_trees.common.Status.FAILURE` instead of :attr:`~py_trees.common.Status.RUNNING` if there is no data yet
fail_if_bad_comparison (:obj:`bool`): :attr:`~py_trees.common.Status.FAILURE` instead of :attr:`~py_trees.common.Status.RUNNING` if comparison failed
comparison_operator (:obj:`func`): one from the python `operator module`_
clearing_policy (:class:`~py_trees.common.ClearingPolicy`): when to clear the data
topic_name: name of the topic to connect to
topic_type: class of the message type (e.g. :obj:`std_msgs.msg.String`)
qos_profile: qos profile for the subscriber
variable_name: name of the variable to check
expected_value: expected value of the variable
comparison_operator: one from the python `operator module`_
fail_if_no_data: :attr:`~py_trees.common.Status.FAILURE` instead of :attr:`~py_trees.common.Status.RUNNING` if there is no data yet
fail_if_bad_comparison: :attr:`~py_trees.common.Status.FAILURE` instead of :attr:`~py_trees.common.Status.RUNNING` if comparison failed
name: name of the behaviour
clearing_policy: when to clear the data
.. tip::
Expand All @@ -180,19 +182,19 @@ class CheckData(Handler):
"""
def __init__(self,
name="Check Data",
topic_name="/foo",
topic_type=None,
qos_profile=utilities.qos_profile_latched_topic(),
variable_name="bar",
expected_value=None,
topic_name: str,
topic_type: typing.Any,
qos_profile: rclpy.qos.QoSProfile,
variable_name: str,
expected_value: typing.Any,
comparison_operator=operator.eq,
fail_if_no_data=False,
fail_if_bad_comparison=False,
comparison_operator=operator.eq,
name=py_trees.common.Name.AUTO_GENERATED,
clearing_policy=py_trees.common.ClearingPolicy.ON_INITIALISE
):
super(CheckData, self).__init__(
name,
name=name,
topic_name=topic_name,
topic_type=topic_type,
qos_profile=qos_profile,
Expand Down Expand Up @@ -276,21 +278,21 @@ class WaitForData(Handler):
which we do with to reset (and subsequently look for the next event). e.g. button events.
Args:
name (:obj:`str`): name of the behaviour
topic_name (:obj:`str`): name of the topic to connect to
topic_type (:obj:`any`): class of the message type (e.g. :obj:`std_msgs.msg.String`)
qos_profile (:obj:`bool`): qos profile for the subscriber
clearing_policy (:class:`~py_trees.common.ClearingPolicy`): when to clear the data
topic_name: name of the topic to connect to
topic_type: class of the message type (e.g. :obj:`std_msgs.msg.String`)
qos_profile: qos profile for the subscriber
name: name of the behaviour
clearing_policy: when to clear the data
"""
def __init__(self,
name="Wait For Data",
topic_name="chatter",
topic_type=None,
qos_profile=utilities.qos_profile_latched_topic(),
topic_name: str,
topic_type: typing.Any,
qos_profile: rclpy.qos.QoSProfile,
name=py_trees.common.Name.AUTO_GENERATED,
clearing_policy=py_trees.common.ClearingPolicy.ON_INITIALISE
):
super().__init__(
name,
name=name,
topic_name=topic_name,
topic_type=topic_type,
qos_profile=qos_profile,
Expand Down Expand Up @@ -324,13 +326,13 @@ class ToBlackboard(Handler):
designated, in which case they will write to the specified keys.
Args:
name (:obj:`str`): name of the behaviour
topic_name (:obj:`str`): name of the topic to connect to
topic_type (:obj:`any`): class of the message type (e.g. :obj:`std_msgs.msg.String`)
qos_profile (:obj:`bool`): qos profile for the subscriber
blackboard_variables (:obj:`dict`): blackboard variable string or dict {names (keys) - message subfields (values)}, use a value of None to indicate the entire message
initialise_variables (:obj:`bool`): initialise the blackboard variables to some defaults
clearing_policy (:class:`~py_trees.common.ClearingPolicy`): when to clear the data
topic_name: name of the topic to connect to
topic_type: class of the message type (e.g. :obj:`std_msgs.msg.String`)
qos_profile: qos profile for the subscriber
blackboard_variables: blackboard variable string or dict {names (keys) - message subfields (values)}, use a value of None to indicate the entire message
initialise_variables: initialise the blackboard variables to some defaults
name: name of the behaviour
clearing_policy: when to clear the data
Examples:
Expand Down Expand Up @@ -359,16 +361,16 @@ class ToBlackboard(Handler):
blackboard_variables={"pose_with_covariance_stamped": None, "pose": "pose.pose"}
"""
def __init__(self,
name="ToBlackboard",
topic_name="chatter",
topic_type=None,
qos_profile=utilities.qos_profile_latched_topic(),
blackboard_variables={"chatter": None},
initialise_variables={},
topic_name: str,
topic_type: typing.Any,
qos_profile: rclpy.qos.QoSProfile,
blackboard_variables: typing.Dict[str, typing.Any]={}, # e.g. {"chatter": None}
initialise_variables: typing.Dict[str, typing.Any]={},
name=py_trees.common.Name.AUTO_GENERATED,
clearing_policy=py_trees.common.ClearingPolicy.ON_INITIALISE
):
super().__init__(
name,
name=name,
topic_name=topic_name,
topic_type=topic_type,
qos_profile=qos_profile,
Expand Down Expand Up @@ -439,16 +441,16 @@ class EventToBlackboard(Handler):
tree can utilise the variables.
Args:
name (:obj:`str`): name of the behaviour
topic_name (:obj:`str`): name of the topic to connect to
qos_profile (:obj:`bool`): qos profile for the subscriber
variable_name (:obj:`str`): name to write the boolean result on the blackboard
topic_name: name of the topic to connect to
qos_profile: qos profile for the subscriber
variable_name: name to write the boolean result on the blackboard
name: name of the behaviour
"""
def __init__(self,
name="Event to Blackboard",
topic_name="/event",
qos_profile=utilities.qos_profile_latched_topic(),
variable_name="event"
topic_name: str,
qos_profile: rclpy.qos.QoSProfile,
variable_name: str,
name=py_trees.common.Name.AUTO_GENERATED,
):
super().__init__(
name=name,
Expand Down
22 changes: 17 additions & 5 deletions py_trees_ros/utilities.py
Original file line number Diff line number Diff line change
Expand Up @@ -156,7 +156,7 @@ def get_py_trees_home():
return home


def qos_profile_latched_topic():
def qos_profile_latched():
"""
Convenience retrieval for a latched topic (publisher / subscriber)
"""
Expand All @@ -168,6 +168,18 @@ def qos_profile_latched_topic():
)


def qos_profile_unlatched():
"""
Default profile for an unlatched topic (in py_trees_ros).
"""
return rclpy.qos.QoSProfile(
history=rclpy.qos.QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST,
depth=1,
durability=rclpy.qos.QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_VOLATILE,
reliability=rclpy.qos.QoSReliabilityPolicy.RMW_QOS_POLICY_RELIABILITY_RELIABLE
)


def resolve_name(node, name):
"""
Convenience function for getting the resolved name (similar to 'publisher.resolved_name' in ROS1).
Expand Down Expand Up @@ -232,13 +244,13 @@ def __init__(self, node, publisher_details, introspection_topic_name="publishers
self.__dict__[name] = node.create_publisher(
msg_type=publisher_type,
topic=topic_name,
qos_profile=qos_profile_latched_topic()
qos_profile=qos_profile_latched()
)
else:
self.__dict__[name] = node.create_publisher(
msg_type=publisher_type,
topic=topic_name,
qos_profile=rclpy.qos.qos_profile_system_default
qos_profile=qos_profile_unlatched()
)
resolved_name = resolve_name(node, topic_name)
message_type = publisher_type.__class__.__module__.split('.')[0] + "/" + publisher_type.__class__.__name__
Expand Down Expand Up @@ -292,14 +304,14 @@ def __init__(self, node, subscriber_details, introspection_topic_name="subscribe
msg_type=subscriber_type,
topic=topic_name,
callback=callback,
qos_profile=qos_profile_latched_topic()
qos_profile=qos_profile_latched()
)
else:
self.__dict__[name] = node.create_subscription(
msg_type=subscriber_type,
topic=topic_name,
callback=callback,
qos_profile=rclpy.qos.qos_profile_system_default
qos_profile=qos_profile_unlatched()
)

resolved_name = resolve_name(node, topic_name)
Expand Down

0 comments on commit a69289d

Please sign in to comment.