diff --git a/ros_bt_py/package.xml b/ros_bt_py/package.xml
index c7ff2e1..a420123 100644
--- a/ros_bt_py/package.xml
+++ b/ros_bt_py/package.xml
@@ -15,6 +15,9 @@
ros_bt_py_interfaces
std_msgs
diagnostic_msgs
+
+ example_interfaces
+
std_srvs
geometry_msgs
sensor_msgs
diff --git a/ros_bt_py/ros_bt_py/custom_types.py b/ros_bt_py/ros_bt_py/custom_types.py
new file mode 100644
index 0000000..589910e
--- /dev/null
+++ b/ros_bt_py/ros_bt_py/custom_types.py
@@ -0,0 +1,98 @@
+# Copyright 2024 FZI Forschungszentrum Informatik
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions are met:
+#
+# * Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+#
+# * Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in the
+# documentation and/or other materials provided with the distribution.
+#
+# * Neither the name of the FZI Forschungszentrum Informatik nor the names of its
+# contributors may be used to endorse or promote products derived from
+# this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
+# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+
+from abc import ABC, abstractmethod
+import rosidl_runtime_py
+import rosidl_runtime_py.utilities
+
+# TODO Math types for operation and operand remain in `helpers.py`
+# to not cause a breaking change. If those are ever updated,
+# they should be moved here.
+from .helpers import MathBinaryOperator, MathUnaryOperator
+from .helpers import MathOperandType, MathUnaryOperandType
+
+
+class FilePath(object):
+ def __init__(self, path=""):
+ self.path = path
+
+
+class RosType(ABC):
+ # NOTE Subclasses should supply a working default
+ @abstractmethod
+ def __init__(self, type_str):
+ self.type_str = type_str
+
+ # NOTE We can't do the conversion in `__init__`,
+ # because jsonpickle bypasses the init function.
+ @abstractmethod
+ def get_type_obj(self):
+ pass
+
+
+class RosTopicType(RosType):
+ def __init__(self, type_str="std_msgs/msg/Empty"):
+ super().__init__(type_str)
+
+ def get_type_obj(self):
+ return rosidl_runtime_py.utilities.get_message(self.type_str)
+
+
+class RosServiceType(RosType):
+ def __init__(self, type_str="std_srvs/srv/Trigger"):
+ super().__init__(type_str)
+
+ def get_type_obj(self):
+ return rosidl_runtime_py.utilities.get_service(self.type_str)
+
+
+class RosActionType(RosType):
+ def __init__(self, type_str="example_interfaces/action/Fibonacci"):
+ super().__init__(type_str)
+
+ def get_type_obj(self):
+ return rosidl_runtime_py.utilities.get_action(self.type_str)
+
+
+# NOTE These should only be used if the service name is specified via options.
+# If the name is specified via inputs just use string instead
+class RosName(ABC):
+ def __init__(self, name=""):
+ self.name = name
+
+
+class RosTopicName(RosName):
+ pass
+
+
+class RosServiceName(RosName):
+ pass
+
+
+class RosActionName(RosName):
+ pass
diff --git a/ros_bt_py/ros_bt_py/helpers.py b/ros_bt_py/ros_bt_py/helpers.py
index 74e5eef..7427d42 100644
--- a/ros_bt_py/ros_bt_py/helpers.py
+++ b/ros_bt_py/ros_bt_py/helpers.py
@@ -55,6 +55,23 @@ def set_node_state_to_shutdown(tree):
return tree
+class MathUnaryOperator(object):
+ def __init__(self, operator='sqrt'):
+ self.operator = operator
+
+class MathBinaryOperator(object):
+ def __init__(self, operator='+'):
+ self.operator = operator
+
+class MathOperandType(object):
+ def __init__(self, operand_type='float'):
+ self.operand_type = operand_type
+
+class MathUnaryOperandType(object):
+ def __init__(self, operand_type='float'):
+ self.operand_type = operand_type
+
+
# handling nested objects,
# see https://stackoverflow.com/questions/31174295/getattr-and-setattr-on-nested-objects
def rgetattr(obj, attr, *args):
@@ -106,25 +123,6 @@ def json_decode(data):
return jsonpickle.decode(data)
-class MathUnaryOperator(object):
- def __init__(self, operator):
- self.operator = operator
-
-
-class MathBinaryOperator(object):
- def __init__(self, operator):
- self.operator = operator
-
-
-class MathOperandType(object):
- def __init__(self, operand_type):
- self.operand_type = operand_type
-
-
-class MathUnaryOperandType(object):
- def __init__(self, operand_type):
- self.operand_type = operand_type
-
class HashableCapabilityInterface:
"""Wrapper class to allow for the hashing of capability interfaces."""
diff --git a/ros_bt_py/ros_bt_py/node_data.py b/ros_bt_py/ros_bt_py/node_data.py
index 6770996..b7c91b6 100644
--- a/ros_bt_py/ros_bt_py/node_data.py
+++ b/ros_bt_py/ros_bt_py/node_data.py
@@ -28,7 +28,17 @@
import rclpy
import rclpy.logging
+from ros_bt_py.custom_types import (
+ FilePath,
+ RosActionName,
+ RosActionType,
+ RosServiceName,
+ RosServiceType,
+ RosTopicName,
+ RosTopicType,
+)
from ros_bt_py.helpers import json_encode
+from ros_bt_py.ros_helpers import get_interface_name
def from_string(data_type, string_value, static=False):
@@ -104,8 +114,24 @@ def set(self, new_value):
if self._static and self.updated:
raise Exception("Trying to overwrite data in static NodeData object")
if not isinstance(new_value, self.data_type) and new_value is not None:
+ # Convert str based params to the FilePath or Ros...Name format.
+ if self.data_type in [
+ RosServiceName,
+ RosTopicName,
+ RosActionName,
+ FilePath,
+ ] and isinstance(new_value, str):
+ new_value = self.data_type(new_value)
+ # Convert Ros...Type from type variables!
+ elif self.data_type in [
+ RosServiceType,
+ RosActionType,
+ RosTopicType,
+ ] and isinstance(new_value, type):
+ new_value_type = get_interface_name(new_value)
+ new_value = self.data_type(new_value_type)
# Silently convert ints to float
- if self.data_type == float and isinstance(new_value, int):
+ elif self.data_type == float and isinstance(new_value, int):
new_value = float(new_value)
else:
if type(new_value) is dict and "py/type" in new_value:
diff --git a/ros_bt_py/ros_bt_py/nodes/getters.py b/ros_bt_py/ros_bt_py/nodes/getters.py
index 1ce8fce..7ef18f9 100644
--- a/ros_bt_py/ros_bt_py/nodes/getters.py
+++ b/ros_bt_py/ros_bt_py/nodes/getters.py
@@ -376,6 +376,7 @@ def _do_tick(self):
if self.inputs.is_updated("object"):
try:
+ #TODO Maybe it would be nice to allow for calling 0-argument functions this way?
self.outputs["attr"] = rgetattr(
self.inputs["object"], self.options["attr_name"]
)
diff --git a/ros_bt_py/ros_bt_py/package_manager.py b/ros_bt_py/ros_bt_py/package_manager.py
index 9632398..aa59257 100644
--- a/ros_bt_py/ros_bt_py/package_manager.py
+++ b/ros_bt_py/ros_bt_py/package_manager.py
@@ -39,7 +39,7 @@
import rosidl_runtime_py
import rosidl_runtime_py.utilities
-from ros_bt_py_interfaces.msg import Message, Messages, Package, Packages, Tree
+from ros_bt_py_interfaces.msg import MessageTypes, Package, Packages, Tree
from ros_bt_py_interfaces.srv import (
GetMessageFields,
SaveTree,
@@ -184,34 +184,32 @@ def publish_message_list(self):
)
return
- messages = []
+ message_types = MessageTypes()
- packages = list(ament_index_python.get_packages_with_prefixes().keys())
+ packages = list(rosidl_runtime_py.get_interface_packages().keys())
for package, package_messages in rosidl_runtime_py.get_message_interfaces(
packages
).items():
for message in package_messages:
- messages.append(
- Message(msg=package + "/" + message, service=False, action=False)
+ message_types.topics.append(
+ package + "/" + message
)
for package, package_services in rosidl_runtime_py.get_service_interfaces(
packages
).items():
for service in package_services:
- messages.append(
- Message(msg=package + "/" + service, service=True, action=False)
+ message_types.services.append(
+ package + "/" + service
)
for package, package_actions in rosidl_runtime_py.get_action_interfaces(
packages
).items():
for action in package_actions:
- messages.append(
- Message(msg=package + "/" + action, service=False, action=True)
+ message_types.actions.append(
+ package + "/" + action
)
- msg = Messages()
- msg.messages = messages
- self.message_list_pub.publish(msg)
+ self.message_list_pub.publish(message_types)
def get_message_fields(
self, request: GetMessageFields.Request, response: GetMessageFields.Response
diff --git a/ros_bt_py/ros_bt_py/ros_helpers.py b/ros_bt_py/ros_bt_py/ros_helpers.py
index cd29147..c317f9c 100644
--- a/ros_bt_py/ros_bt_py/ros_helpers.py
+++ b/ros_bt_py/ros_bt_py/ros_helpers.py
@@ -28,8 +28,11 @@
import inspect
import rclpy.logging
+from rclpy import action
+from rclpy.node import Node, Publisher
from ros_bt_py.exceptions import BehaviorTreeException
+from ros_bt_py_interfaces.msg import MessageChannel, MessageChannels
class LoggerLevel(object):
@@ -48,6 +51,21 @@ def __init__(self, enum_value=""):
self.enum_value = enum_value
+def get_interface_name(msg_metaclass: type) -> str:
+ """
+ Extract the interface name from a ROS2 message metaclass.
+
+ :param msg_metaclass: The ROS2 message metaclass.
+
+ :returns: The interface name in the format 'package_name/message_type/message_name'.
+ """
+ module_parts = msg_metaclass.__module__.split(".")
+ package_name = module_parts[0]
+ message_type = module_parts[-2] # Extract 'msg', 'srv', or 'action'
+ message_name = msg_metaclass.__name__
+ return f"{package_name}/{message_type}/{message_name}"
+
+
def get_message_constant_fields(message_class):
"""Return all constant fields of a message as a list."""
if inspect.isclass(message_class):
@@ -62,3 +80,16 @@ def get_message_constant_fields(message_class):
return members
else:
raise BehaviorTreeException(f"{message_class} is not a ROS Message")
+
+
+def publish_message_channels(node: Node, publisher: Publisher):
+ """Return all known topic-, service-, and action-names."""
+ msg = MessageChannels()
+ # Types are returned as 1?-element lists, so we need to unpack them
+ for name, [interface, *_] in node.get_topic_names_and_types():
+ msg.topics.append(MessageChannel(name=name, type=interface))
+ for name, [interface, *_] in node.get_service_names_and_types():
+ msg.services.append(MessageChannel(name=name, type=interface))
+ for name, [interface, *_] in action.get_action_names_and_types(node):
+ msg.actions.append(MessageChannel(name=name, type=interface))
+ publisher.publish(msg)
diff --git a/ros_bt_py/ros_bt_py/ros_nodes/action.py b/ros_bt_py/ros_bt_py/ros_nodes/action.py
index b6275ca..7b23863 100644
--- a/ros_bt_py/ros_bt_py/ros_nodes/action.py
+++ b/ros_bt_py/ros_bt_py/ros_nodes/action.py
@@ -35,6 +35,7 @@
from rclpy.callback_groups import ReentrantCallbackGroup
from rclpy.time import Time
+from ros_bt_py.custom_types import RosActionName, RosActionType
from ros_bt_py_interfaces.msg import Node as NodeMsg
from ros_bt_py_interfaces.msg import UtilityBounds
@@ -60,7 +61,7 @@ class ActionStates(Enum):
@define_bt_node(
NodeConfig(
options={
- "action_name": str,
+ "action_name": RosActionName,
"wait_for_action_server_seconds": float,
"timeout_seconds": float,
"fail_if_not_available": bool,
@@ -147,7 +148,7 @@ def set_action_attributes(self):
self._feedback_type = "ENTER_FEEDBACK_TYPE"
self._result_type = "ENTER_RESULT_TYPE"
- self._action_name = self.options["action_name"]
+ self._action_name = self.options["action_name"].name
def set_input(self):
pass
@@ -468,8 +469,8 @@ def _do_calculate_utility(self):
NodeConfig(
version="0.1.0",
options={
- "action_type": type,
- "action_name": str,
+ "action_type": RosActionType,
+ "action_name": RosActionName,
"wait_for_action_server_seconds": float,
"timeout_seconds": float,
"fail_if_not_available": bool,
@@ -526,47 +527,25 @@ def __init__(
node_inputs = {}
node_outputs = {}
- self._action_name = self.options["action_name"]
- self._action_type = self.options["action_type"]
-
- try:
- self._goal_type = getattr(self.options["action_type"], "Goal")
-
- if inspect.isclass(self._goal_type):
- msg = self._goal_type()
- for field in msg._fields_and_field_types:
- node_inputs[field] = type(getattr(msg, field))
- else:
- node_inputs["in"] = self.options["action_type"]
- except AttributeError:
- node_inputs["in"] = self.options["action_type"]
- self.logwarn(f"Non message type passed to: {self.name}")
-
- try:
- self._result_type = getattr(self.options["action_type"], "Result")
- if inspect.isclass(self._result_type):
- msg = self._result_type()
- for field in msg._fields_and_field_types:
- node_outputs["result_" + field] = type(getattr(msg, field))
- else:
- node_outputs["result_out"] = self.options["action_type"]
- except AttributeError:
- self._result_type = Int64()
- node_outputs["result_data"] = self.options["action_type"]
- self.logwarn(f"Non message type passed to: {self.name}")
-
- try:
- self._feedback_type = getattr(self.options["action_type"], "Feedback")
- if inspect.isclass(self._feedback_type):
- msg = self._feedback_type()
- for field in msg._fields_and_field_types:
- node_outputs["feedback_" + field] = type(getattr(msg, field))
- else:
- node_outputs["feedback_out"] = self.options["action_type"]
- except AttributeError:
- self._feedback_type = Int64()
- node_outputs["feedback_data"] = self.options["action_type"]
- self.logwarn(f"Non message type passed to: {self.name}")
+ self._action_name = self.options["action_name"].name
+ self._action_type = self.options["action_type"].get_type_obj()
+
+ self._goal_type = self._action_type.Goal
+ self._result_type = self._action_type.Result
+ self._feedback_type = self._action_type.Feedback
+
+ goal_msg = self._goal_type()
+ for field in goal_msg._fields_and_field_types:
+ node_inputs[field] = type(getattr(goal_msg, field))
+
+ result_msg = self._result_type()
+ for field in result_msg._fields_and_field_types:
+ node_outputs["result_" + field] = type(getattr(result_msg, field))
+
+ feedback_msg = self._feedback_type()
+ for field in feedback_msg._fields_and_field_types:
+ node_outputs["feedback_" + field] = type(getattr(feedback_msg, field))
+
self._register_node_data(source_map=node_inputs, target_map=self.inputs)
self._register_node_data(source_map=node_outputs, target_map=self.outputs)
diff --git a/ros_bt_py/ros_bt_py/ros_nodes/message_converters.py b/ros_bt_py/ros_bt_py/ros_nodes/message_converters.py
index 68e333c..49f55dc 100644
--- a/ros_bt_py/ros_bt_py/ros_nodes/message_converters.py
+++ b/ros_bt_py/ros_bt_py/ros_nodes/message_converters.py
@@ -29,6 +29,7 @@
from typing import Optional, Dict
+from ros_bt_py.custom_types import RosTopicType
from ros_bt_py_interfaces.msg import Node as NodeMsg
from rclpy.node import Node
@@ -41,8 +42,8 @@
@define_bt_node(
NodeConfig(
version="0.1.0",
- options={"input_type": type},
- inputs={"in": OptionRef("input_type")},
+ options={"input_type": RosTopicType},
+ inputs={},
outputs={},
max_children=0,
)
@@ -68,41 +69,34 @@ def __init__(
simulate_tick=simulate_tick,
)
- node_outputs = {}
+ self._message_type = self.options["input_type"].get_type_obj()
- self.passthrough = True
+ node_inputs = {"in": self._message_type}
+ node_outputs = {}
- if inspect.isclass(self.options["input_type"]):
- try:
- msg = self.options["input_type"]()
- for field in msg._fields_and_field_types:
- node_outputs[field] = type(getattr(msg, field))
- self.passthrough = False
- except AttributeError:
- node_outputs["out"] = self.options["input_type"]
- self.logwarn(f"Non message type passed to: {self.name}")
- else:
- node_outputs["out"] = self.options["input_type"]
+ msg = self._message_type()
+ for field in msg._fields_and_field_types:
+ node_outputs[field] = type(getattr(msg, field))
self.node_config.extend(
- NodeConfig(options={}, inputs={}, outputs=node_outputs, max_children=0)
+ NodeConfig(
+ options={}, inputs=node_inputs, outputs=node_outputs, max_children=0
+ )
)
+ self._register_node_data(source_map=node_inputs, target_map=self.inputs)
self._register_node_data(source_map=node_outputs, target_map=self.outputs)
def _do_setup(self):
return NodeMsg.IDLE
def _do_tick(self):
- if self.passthrough:
- self.outputs["out"] = self.inputs["in"]
- else:
- for field in self.outputs:
- value = getattr(self.inputs["in"], field)
- if type(value) == tuple and self.outputs.get_type(field) == list:
- self.outputs[field] = list(value)
- else:
- self.outputs[field] = value
+ for field in self.outputs:
+ value = getattr(self.inputs["in"], field)
+ if type(value) == tuple and self.outputs.get_type(field) == list:
+ self.outputs[field] = list(value)
+ else:
+ self.outputs[field] = value
return NodeMsg.SUCCEEDED
def _do_untick(self):
@@ -118,9 +112,9 @@ def _do_reset(self):
@define_bt_node(
NodeConfig(
version="0.1.0",
- options={"output_type": type},
+ options={"output_type": RosTopicType},
inputs={},
- outputs={"out": OptionRef("output_type")},
+ outputs={},
max_children=0,
)
)
@@ -154,41 +148,34 @@ def __init__(
simulate_tick=simulate_tick,
)
- node_inputs = {}
+ self._message_type = self.options["output_type"].get_type_obj()
- self.passthrough = True
+ node_inputs = {}
+ node_outputs = {"out": self._message_type}
- if inspect.isclass(self.options["output_type"]):
- try:
- msg = self.options["output_type"]()
- for field in msg._fields_and_field_types:
- node_inputs[field] = type(getattr(msg, field))
- self.passthrough = False
- except AttributeError:
- node_inputs["in"] = self.options["output_type"]
- self.logwarn(f"Non message type passed to: {self.name}")
- else:
- node_inputs["in"] = self.options["output_type"]
+ msg = self._message_type()
+ for field in msg._fields_and_field_types:
+ node_inputs[field] = type(getattr(msg, field))
self.node_config.extend(
- NodeConfig(options={}, inputs=node_inputs, outputs={}, max_children=0)
+ NodeConfig(
+ options={}, inputs=node_inputs, outputs=node_outputs, max_children=0
+ )
)
self._register_node_data(source_map=node_inputs, target_map=self.inputs)
+ self._register_node_data(source_map=node_outputs, target_map=self.outputs)
def _do_setup(self):
return NodeMsg.IDLE
def _do_tick(self):
- if self.passthrough:
- self.outputs["out"] = self.inputs["in"]
- else:
- msg = self.options["output_type"]()
+ msg = self._message_type()
- for field in msg._fields_and_field_types:
- setattr(msg, field, self.inputs[field])
+ for field in msg._fields_and_field_types:
+ setattr(msg, field, self.inputs[field])
- self.outputs["out"] = msg
+ self.outputs["out"] = msg
return NodeMsg.SUCCEEDED
def _do_untick(self):
diff --git a/ros_bt_py/ros_bt_py/ros_nodes/messages_from_dict.py b/ros_bt_py/ros_bt_py/ros_nodes/messages_from_dict.py
index e71dfea..df5eef8 100644
--- a/ros_bt_py/ros_bt_py/ros_nodes/messages_from_dict.py
+++ b/ros_bt_py/ros_bt_py/ros_nodes/messages_from_dict.py
@@ -26,31 +26,70 @@
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
"""BT nodes to convert Dicts to ROS messages of a specific type."""
-from ros_bt_py_interfaces.msg import Node as NodeMsg
+
+from typing import Dict, Optional
+
+from rclpy.node import Node
from rosidl_runtime_py.set_message import set_message_fields
from ros_bt_py.node import Leaf, define_bt_node
from ros_bt_py.node_config import NodeConfig, OptionRef
+from ros_bt_py.custom_types import RosTopicType
+from ros_bt_py.debug_manager import DebugManager
+from ros_bt_py.subtree_manager import SubtreeManager
+
+from ros_bt_py_interfaces.msg import Node as NodeMsg
+
@define_bt_node(
NodeConfig(
version="0.1.0",
- options={"message_type": type},
+ options={"message_type": RosTopicType},
inputs={"dict": dict},
- outputs={"message": OptionRef("message_type")},
+ outputs={},
max_children=0,
)
)
class MessageFromDict(Leaf):
"""Fill a ROS message with the values from `dict`."""
+ def __init__(
+ self,
+ options: Optional[Dict] = None,
+ debug_manager: Optional[DebugManager] = None,
+ subtree_manager: Optional[SubtreeManager] = None,
+ name: Optional[str] = None,
+ ros_node: Optional[Node] = None,
+ succeed_always: bool = False,
+ simulate_tick: bool = False,
+ ):
+ super(MessageFromDict, self).__init__(
+ options=options,
+ debug_manager=debug_manager,
+ subtree_manager=subtree_manager,
+ name=name,
+ ros_node=ros_node,
+ succeed_always=succeed_always,
+ simulate_tick=simulate_tick,
+ )
+
+ self._message_type = self.options["message_type"].get_type_obj()
+
+ node_outputs = {"message": self._message_type}
+
+ self.node_config.extend(
+ NodeConfig(options={}, inputs={}, outputs=node_outputs, max_children=0)
+ )
+
+ self._register_node_data(source_map=node_outputs, target_map=self.outputs)
+
def _do_setup(self):
pass
def _do_tick(self):
if self.inputs.is_updated("dict") or self.state == NodeMsg.IDLE:
- message = self.options["message_type"]()
+ message = self._message_type()
try:
set_message_fields(
message,
@@ -62,7 +101,7 @@ def _do_tick(self):
TypeError,
) as ex:
self.logerr(
- f"Error populating message of type {self.options['message_type'].__name__}: "
+ f"Error populating message of type {self._message_type.__name__}: "
f"{str(ex)}"
)
return NodeMsg.FAILED
@@ -81,20 +120,50 @@ def _do_untick(self):
@define_bt_node(
NodeConfig(
version="0.9.0",
- options={"message_type": type, "dict": dict},
+ options={"message_type": RosTopicType, "dict": dict},
inputs={},
- outputs={"message": OptionRef("message_type")},
+ outputs={},
max_children=0,
)
)
class MessageFromConstDict(Leaf):
"""Fill a ROS message with the values from `dict`."""
+ def __init__(
+ self,
+ options: Optional[Dict] = None,
+ debug_manager: Optional[DebugManager] = None,
+ subtree_manager: Optional[SubtreeManager] = None,
+ name: Optional[str] = None,
+ ros_node: Optional[Node] = None,
+ succeed_always: bool = False,
+ simulate_tick: bool = False,
+ ):
+ super(MessageFromConstDict, self).__init__(
+ options=options,
+ debug_manager=debug_manager,
+ subtree_manager=subtree_manager,
+ name=name,
+ ros_node=ros_node,
+ succeed_always=succeed_always,
+ simulate_tick=simulate_tick,
+ )
+
+ self._message_type = self.options["message_type"].get_type_obj()
+
+ node_outputs = {"message": self._message_type}
+
+ self.node_config.extend(
+ NodeConfig(options={}, inputs={}, outputs=node_outputs, max_children=0)
+ )
+
+ self._register_node_data(source_map=node_outputs, target_map=self.outputs)
+
def _do_setup(self):
pass
def _do_tick(self):
- message = self.options["message_type"]()
+ message = self._message_type()
try:
set_message_fields(
message,
@@ -103,7 +172,7 @@ def _do_tick(self):
self.outputs["message"] = message
except (TypeError, AttributeError) as ex:
self.logerr(
- f"Error populating message of type {self.options['message_type'].__name__}: "
+ f"Error populating message of type {self._message_type.__name__}: "
f"{str(ex)}"
)
return NodeMsg.FAILED
diff --git a/ros_bt_py/ros_bt_py/ros_nodes/service.py b/ros_bt_py/ros_bt_py/ros_nodes/service.py
index 04d0035..b1caf81 100644
--- a/ros_bt_py/ros_bt_py/ros_nodes/service.py
+++ b/ros_bt_py/ros_bt_py/ros_nodes/service.py
@@ -32,6 +32,7 @@
from rclpy.duration import Duration
from rclpy.time import Time
+from ros_bt_py.custom_types import RosServiceName, RosServiceType
from ros_bt_py_interfaces.msg import Node as NodeMsg
from ros_bt_py_interfaces.msg import UtilityBounds
@@ -51,7 +52,7 @@
NodeConfig(
version="0.1.0",
options={
- "service_type": type,
+ "service_type": RosServiceType,
"wait_for_response_seconds": float,
},
inputs={
@@ -102,33 +103,22 @@ def __init__(
simulate_tick=simulate_tick,
)
+ self._service_type = self.options["service_type"].get_type_obj()
+
+ self._request_type = self._service_type.Request
+ self._response_type = self._service_type.Response
+
node_inputs = {}
node_outputs = {}
- try:
- self._request_type = getattr(self.options["service_type"], "Request")
- if inspect.isclass(self._request_type):
- msg = self._request_type()
- for field in msg._fields_and_field_types:
- node_inputs[field] = type(getattr(msg, field))
- self.passthrough = False
- else:
- node_inputs["in"] = self.options["service_type"]
- except AttributeError:
- node_inputs["in"] = self.options["service_type"]
- self.logwarn(f"Non message type passed to: {self.name}")
-
- try:
- self._response_type = getattr(self.options["service_type"], "Response")
- if inspect.isclass(self._response_type):
- msg = self._response_type()
- for field in msg._fields_and_field_types:
- node_outputs[field] = type(getattr(msg, field))
- self.passthrough = False
- else:
- node_outputs["out"] = self.options["service_type"]
- except AttributeError:
- node_outputs["out"] = self.options["service_type"]
- self.logwarn(f"Non message type passed to: {self.name}")
+
+ request_msg = self._request_type()
+ for field in request_msg._fields_and_field_types:
+ node_inputs[field] = type(getattr(request_msg, field))
+
+ response_msg = self._response_type()
+ for field in response_msg._fields_and_field_types:
+ node_outputs[field] = type(getattr(response_msg, field))
+
self.node_config.extend(
NodeConfig(
@@ -180,7 +170,7 @@ def _do_tick(self):
if self._service_client is None:
if self.has_ros_node:
self._service_client = self.ros_node.create_client(
- self.options["service_type"],
+ self._service_type,
self.inputs["service_name"],
callback_group=ReentrantCallbackGroup(),
)
@@ -284,8 +274,8 @@ def _do_calculate_utility(self):
NodeConfig(
version="0.1.0",
options={
- "service_type": type,
- "service_name": str,
+ "service_type": RosServiceType,
+ "service_name": RosServiceName,
"wait_for_service_seconds": float,
},
inputs={},
@@ -297,13 +287,36 @@ def _do_calculate_utility(self):
class WaitForService(Leaf):
"""Wait for a service to be available, fails if this wait times out."""
+ def __init__(
+ self,
+ options = None,
+ debug_manager = None,
+ subtree_manager = None,
+ name = None,
+ ros_node = None,
+ succeed_always = False,
+ simulate_tick = False
+ ):
+ super().__init__(
+ options,
+ debug_manager,
+ subtree_manager,
+ name,
+ ros_node,
+ succeed_always,
+ simulate_tick
+ )
+
+ self._service_type = self.options["service_type"].get_type_obj()
+ self._service_name = self.options["service_name"].name
+
def _do_setup(self):
if not self.has_ros_node:
self.logerr("Not ROS node reference available!")
raise BehaviorTreeException("No ROS node reference available!")
self._service_client = self.ros_node.create_client(
- self.options["service_name"], self.options["service_type"]
+ self._service_name, self._service_type
)
self._last_service_call_time: Optional[Time] = None
@@ -346,7 +359,7 @@ def _do_shutdown(self):
@define_bt_node(
NodeConfig(
version="0.1.0",
- options={"service_type": type, "wait_for_service_seconds": float},
+ options={"service_type": RosServiceType, "wait_for_service_seconds": float},
inputs={"service_name": str},
outputs={},
max_children=0,
@@ -356,6 +369,28 @@ def _do_shutdown(self):
class WaitForServiceInput(Leaf):
"""Wait for a service to be available, fails if this wait times out."""
+ def __init__(
+ self,
+ options = None,
+ debug_manager = None,
+ subtree_manager = None,
+ name = None,
+ ros_node = None,
+ succeed_always = False,
+ simulate_tick = False
+ ):
+ super().__init__(
+ options,
+ debug_manager,
+ subtree_manager,
+ name,
+ ros_node,
+ succeed_always,
+ simulate_tick
+ )
+
+ self._service_type = self.options["service_type"].get_type_obj()
+
def _do_setup(self):
if not self.has_ros_node:
self.logerr("Not ROS node reference available!")
@@ -374,7 +409,7 @@ def _do_tick(self):
if self._service_client is None:
self._service_client = self.ros_node.create_client(
- self.inputs["service_name"], self.options["service_type"]
+ self.inputs["service_name"], self._service_type
)
if self._service_client.service_is_ready():
@@ -414,7 +449,7 @@ def _do_shutdown(self):
@define_bt_node(
NodeConfig(
options={
- "service_name": str,
+ "service_name": RosServiceName,
"wait_for_service_seconds": float,
"wait_for_response_seconds": float,
"fail_if_not_available": bool,
@@ -499,7 +534,7 @@ def __init__(
simulate_tick=simulate_tick,
)
self._service_client: Optional[Client] = None
- self._service_name = self.options["service_name"]
+ self._service_name = self.options["service_name"].name
self.set_service_type()
# Sets all outputs none (define output key while overwriting)
@@ -617,7 +652,7 @@ def _do_tick(self):
).nanoseconds / 1e9
if seconds_since_call > self.options["wait_for_response_seconds"]:
self.loginfo(
- f"Service call to {self.options['service_name']} with request "
+ f"Service call to {self._service_name} with request "
f"{self._last_request} timed out"
)
self._service_request_future.cancel()
@@ -651,14 +686,14 @@ def _do_shutdown(self):
def _do_calculate_utility(self):
if not self.has_ros_node or self._service_client is None:
self.logdebug(
- f"Unable to check for service {self.options['service_name']}: "
+ f"Unable to check for service {self._service_name}: "
"No ros node available!"
)
return UtilityBounds(can_execute=False)
if self._service_client.service_is_ready():
self.logdebug(
- f"Found service {self.options['service_name']} with correct type, returning "
+ f"Found service {self._service_name} with correct type, returning "
"filled out UtilityBounds"
)
return UtilityBounds(
@@ -669,15 +704,15 @@ def _do_calculate_utility(self):
has_upper_bound_failure=True,
)
- self.logdebug(f"Service {self.options['service_name']} is unavailable")
+ self.logdebug(f"Service {self._service_name} is unavailable")
return UtilityBounds(can_execute=False)
@define_bt_node(
NodeConfig(
options={
- "service_name": str,
- "service_type": type,
+ "service_name": RosServiceName,
+ "service_type": RosServiceType,
"wait_for_service_seconds": float,
"wait_for_response_seconds": float,
"fail_if_not_available": bool,
@@ -733,33 +768,23 @@ def __init__(
simulate_tick=simulate_tick,
)
+ self._service_type = self.options["service_type"].get_type_obj()
+ self._service_name = self.options["service_name"].name
+
+ self._request_type = self._service_type.Request
+ self._response_type = self._service_type.Response
+
node_inputs = {}
node_outputs = {}
- try:
- self._request_type = getattr(self.options["service_type"], "Request")
- if inspect.isclass(self._request_type):
- msg = self._request_type()
- for field in msg._fields_and_field_types:
- node_inputs[field] = type(getattr(msg, field))
- self.passthrough = False
- else:
- node_inputs["in"] = self.options["service_type"]
- except AttributeError:
- node_inputs["in"] = self.options["service_type"]
- self.logwarn(f"Non message type passed to: {self.name}")
-
- try:
- self._response_type = getattr(self.options["service_type"], "Response")
- if inspect.isclass(self._response_type):
- msg = self._response_type()
- for field in msg._fields_and_field_types:
- node_outputs[field] = type(getattr(msg, field))
- self.passthrough = False
- else:
- node_outputs["out"] = self.options["service_type"]
- except AttributeError:
- node_outputs["out"] = self.options["service_type"]
- self.logwarn(f"Non message type passed to: {self.name}")
+
+ request_msg = self._request_type()
+ for field in request_msg._fields_and_field_types:
+ node_inputs[field] = type(getattr(request_msg, field))
+
+ response_msg = self._response_type()
+ for field in response_msg._fields_and_field_types:
+ node_outputs[field] = type(getattr(response_msg, field))
+
self.node_config.extend(
NodeConfig(
@@ -805,11 +830,12 @@ def _do_tick(self):
return NodeMsg.RUNNING
+ #TODO Can't this be in `_do_setup`?
if self._service_client is None:
if self.has_ros_node:
self._service_client = self.ros_node.create_client(
- self.options["service_type"],
- self.options["service_name"],
+ self._service_type,
+ self._service_name,
callback_group=ReentrantCallbackGroup(),
)
else:
@@ -848,7 +874,7 @@ def _do_tick(self):
if seconds_since_call > self.options["wait_for_response_seconds"]:
self.logerr(
- f"Service call to {self.options['service_name']} with request "
+ f"Service call to {self._service_name} with request "
f"{self._last_request} timed out after {seconds_since_call} seconds"
)
self._service_request_future.cancel()
@@ -885,14 +911,14 @@ def _do_shutdown(self):
def _do_calculate_utility(self):
if not self.has_ros_node or self._service_client is None:
self.loginfo(
- f"Unable to check for service {self.options['service_name']}, "
+ f"Unable to check for service {self._service_name}, "
"ros node available!"
)
return UtilityBounds()
if self._service_client.service_is_ready():
self.loginfo(
- f"Found service {self.options['service_name']} with correct type, returning "
+ f"Found service {self._service_name} with correct type, returning "
"filled out UtilityBounds"
)
return UtilityBounds(
@@ -903,5 +929,5 @@ def _do_calculate_utility(self):
has_upper_bound_failure=True,
)
- self.loginfo(f"Service {self.options['service_name']} is unavailable")
+ self.loginfo(f"Service {self._service_name} is unavailable")
return UtilityBounds(can_execute=False)
diff --git a/ros_bt_py/ros_bt_py/ros_nodes/subtree.py b/ros_bt_py/ros_bt_py/ros_nodes/subtree.py
index e134f98..287756e 100644
--- a/ros_bt_py/ros_bt_py/ros_nodes/subtree.py
+++ b/ros_bt_py/ros_bt_py/ros_nodes/subtree.py
@@ -41,11 +41,13 @@
from ros_bt_py.node import Node as BTNode
from ros_bt_py.node_config import NodeConfig
+from ros_bt_py.custom_types import FilePath
+
@define_bt_node(
NodeConfig(
version="0.2.0",
- options={"subtree_path": str, "use_io_nodes": bool},
+ options={"subtree_path": FilePath, "use_io_nodes": bool},
inputs={},
outputs={"load_success": bool, "load_error_msg": str},
max_children=0,
@@ -111,7 +113,7 @@ def load_subtree(self) -> None:
response = self.manager.load_tree(
request=LoadTree.Request(
tree=Tree(
- path=self.options["subtree_path"],
+ path=self.options["subtree_path"].path,
name=self.name,
)
),
diff --git a/ros_bt_py/ros_bt_py/ros_nodes/topic.py b/ros_bt_py/ros_bt_py/ros_nodes/topic.py
index ca71ff1..b14e614 100644
--- a/ros_bt_py/ros_bt_py/ros_nodes/topic.py
+++ b/ros_bt_py/ros_bt_py/ros_nodes/topic.py
@@ -25,8 +25,9 @@
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
-from typing import Optional
+from typing import Dict, Optional
+from rclpy.node import Node
from rclpy.qos import (
QoSDurabilityPolicy,
QoSProfile,
@@ -41,20 +42,23 @@
from ros_bt_py.exceptions import BehaviorTreeException
from ros_bt_py.node import Leaf, define_bt_node
from ros_bt_py.node_config import NodeConfig, OptionRef
+from ros_bt_py.custom_types import RosTopicName, RosTopicType
+from ros_bt_py.debug_manager import DebugManager
+from ros_bt_py.subtree_manager import SubtreeManager
@define_bt_node(
NodeConfig(
version="0.1.0",
options={
- "topic_type": type,
- "topic_name": str,
+ "topic_type": RosTopicType,
+ "topic_name": RosTopicName,
"reliable": bool,
"transient_local": bool,
"depth": int,
},
inputs={},
- outputs={"message": OptionRef("topic_type")},
+ outputs={},
max_children=0,
)
)
@@ -69,6 +73,37 @@ class TopicSubscriber(Leaf):
This node never returns FAILED.
"""
+ def __init__(
+ self,
+ options: Optional[Dict] = None,
+ debug_manager: Optional[DebugManager] = None,
+ subtree_manager: Optional[SubtreeManager] = None,
+ name: Optional[str] = None,
+ ros_node: Optional[Node] = None,
+ succeed_always: bool = False,
+ simulate_tick: bool = False,
+ ):
+ super(TopicSubscriber, self).__init__(
+ options=options,
+ debug_manager=debug_manager,
+ subtree_manager=subtree_manager,
+ name=name,
+ ros_node=ros_node,
+ succeed_always=succeed_always,
+ simulate_tick=simulate_tick,
+ )
+
+ self._topic_type = self.options["topic_type"].get_type_obj()
+ self._topic_name = self.options["topic_name"].name
+
+ node_outputs = {"message": self._topic_type}
+
+ self.node_config.extend(
+ NodeConfig(options={}, inputs={}, outputs=node_outputs, max_children=0)
+ )
+
+ self._register_node_data(source_map=node_outputs, target_map=self.outputs)
+
_lock = Lock()
_subscriber = None
@@ -91,8 +126,8 @@ def _do_setup(self):
reliability=reliability_policy, history=durability_policy, depth=depth
)
self._subscriber = self.ros_node.create_subscription(
- msg_type=self.options["topic_type"],
- topic=self.options["topic_name"],
+ msg_type=self._topic_type,
+ topic=self._topic_name,
callback=self._callback,
qos_profile=self._qos_profile,
)
@@ -133,11 +168,11 @@ def _do_calculate_utility(self):
if not self.has_ros_node:
return UtilityBounds(can_execute=False)
- resolved_topic = self.ros_node.resolve_topic_name(self.options["topic_name"])
+ resolved_topic = self.ros_node.resolve_topic_name(self._topic_name)
for endpoint in self.ros_node.get_publishers_info_by_topic(resolved_topic):
if (
- endpoint.topic_type == self.options["topic_type"]
+ endpoint.topic_type == self._topic_type
and endpoint.qos_profile == self._qos_profile
):
# if the topic we want exists, we can do our job, so
@@ -156,15 +191,15 @@ def _do_calculate_utility(self):
NodeConfig(
version="0.1.0",
options={
- "topic_type": type,
- "topic_name": str,
+ "topic_type": RosTopicType,
+ "topic_name": RosTopicName,
"memory_delay": float,
"reliable": bool,
"transient_local": bool,
"depth": int,
},
inputs={},
- outputs={"message": OptionRef("topic_type")},
+ outputs={},
max_children=0,
)
)
@@ -180,6 +215,38 @@ class TopicMemorySubscriber(Leaf):
This node never returns RUNNING.
"""
+ def __init__(
+ self,
+ options: Optional[Dict] = None,
+ debug_manager: Optional[DebugManager] = None,
+ subtree_manager: Optional[SubtreeManager] = None,
+ name: Optional[str] = None,
+ ros_node: Optional[Node] = None,
+ succeed_always: bool = False,
+ simulate_tick: bool = False,
+ ):
+ super(TopicMemorySubscriber, self).__init__(
+ options=options,
+ debug_manager=debug_manager,
+ subtree_manager=subtree_manager,
+ name=name,
+ ros_node=ros_node,
+ succeed_always=succeed_always,
+ simulate_tick=simulate_tick,
+ )
+
+ self._topic_type = self.options["topic_type"].get_type_obj()
+ self._topic_name = self.options["topic_name"].name
+
+ node_outputs = {"message": self._topic_type}
+
+ self.node_config.extend(
+ NodeConfig(options={}, inputs={}, outputs=node_outputs, max_children=0)
+ )
+
+ self._register_node_data(source_map=node_outputs, target_map=self.outputs)
+
+
_lock = Lock()
_subscriber = None
@@ -208,8 +275,8 @@ def _do_setup(self):
reliability=reliability_policy, history=durability_policy, depth=depth
)
self._subscriber = self.ros_node.create_subscription(
- msg_type=self.options["topic_type"],
- topic=self.options["topic_name"],
+ msg_type=self._topic_type,
+ topic=self._topic_name,
callback=self._callback,
qos_profile=self._qos_profile,
)
@@ -263,11 +330,11 @@ def _do_calculate_utility(self):
if not self.has_ros_node:
return UtilityBounds(can_execute=False)
- resolved_topic = self.ros_node.resolve_topic_name(self.options["topic_name"])
+ resolved_topic = self.ros_node.resolve_topic_name(self._topic_name)
for endpoint in self.ros_node.get_publishers_info_by_topic(resolved_topic):
if (
- endpoint.topic_type == self.options["topic_type"]
+ endpoint.topic_type == self._topic_type
and endpoint.qos_profile == self._qos_profile
):
# if the topic we want exists, we can do our job, so
@@ -286,19 +353,52 @@ def _do_calculate_utility(self):
NodeConfig(
version="1.0.0",
options={
- "topic_type": type,
- "topic_name": str,
+ "topic_type": RosTopicType,
+ "topic_name": RosTopicName,
"reliable": bool,
"transient_local": bool,
"depth": int,
},
- inputs={"message": OptionRef("topic_type")},
+ inputs={},
outputs={},
max_children=0,
)
)
class TopicPublisher(Leaf):
+
_publisher = None
+
+ def __init__(
+ self,
+ options: Optional[Dict] = None,
+ debug_manager: Optional[DebugManager] = None,
+ subtree_manager: Optional[SubtreeManager] = None,
+ name: Optional[str] = None,
+ ros_node: Optional[Node] = None,
+ succeed_always: bool = False,
+ simulate_tick: bool = False,
+ ):
+ super(TopicPublisher, self).__init__(
+ options=options,
+ debug_manager=debug_manager,
+ subtree_manager=subtree_manager,
+ name=name,
+ ros_node=ros_node,
+ succeed_always=succeed_always,
+ simulate_tick=simulate_tick,
+ )
+
+ self._topic_type = self.options["topic_type"].get_type_obj()
+ self._topic_name = self.options["topic_name"].name
+
+ node_inputs = {"message": self._topic_type}
+
+ self.node_config.extend(
+ NodeConfig(options={}, inputs=node_inputs, outputs={}, max_children=0)
+ )
+
+ self._register_node_data(source_map=node_inputs, target_map=self.inputs)
+
def _do_setup(self):
if not self.has_ros_node:
error_msg = f"{self.name} does not have a refrence to a ROS node!"
@@ -322,8 +422,8 @@ def _do_setup(self):
)
self._publisher = self.ros_node.create_publisher(
- msg_type=self.options["topic_type"],
- topic=self.options["topic_name"],
+ msg_type=self._topic_type,
+ topic=self._topic_name,
qos_profile=self._qos_profile,
)
return NodeMsg.IDLE
diff --git a/ros_bt_py/ros_bt_py/tree_node.py b/ros_bt_py/ros_bt_py/tree_node.py
index 8e49688..92aa9c2 100755
--- a/ros_bt_py/ros_bt_py/tree_node.py
+++ b/ros_bt_py/ros_bt_py/tree_node.py
@@ -46,9 +46,10 @@
from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus
from ros_bt_py.parameters import tree_node_parameters
from ros_bt_py_interfaces.msg import (
+ MessageChannels,
Tree,
SubtreeInfo,
- Messages,
+ MessageTypes,
Packages,
)
from ros_bt_py_interfaces.srv import (
@@ -88,6 +89,9 @@
from ros_bt_py.subtree_manager import SubtreeManager
from ros_bt_py.package_manager import PackageManager
+from ros_bt_py.ros_helpers import publish_message_channels
+from functools import partial
+
class TreeNode(Node):
"""ROS node running a single behavior tree."""
@@ -141,7 +145,7 @@ def init_publisher(self):
)
self.ros_diagnostics_pub = self.create_publisher(
DiagnosticArray,
- "/diagnostics",
+ "/diagnostics", #TODO Should this be '~/diagnostics'?
callback_group=self.publisher_callback_group,
qos_profile=QoSProfile(
reliability=QoSReliabilityPolicy.RELIABLE,
@@ -154,8 +158,8 @@ def init_publisher(self):
def init_package_manager(self, params: tree_node_parameters.Params):
self.get_logger().info("initializing package manager...")
self.message_list_pub = self.create_publisher(
- Messages,
- "~/messages",
+ MessageTypes,
+ "~/message_types",
callback_group=self.publisher_callback_group,
qos_profile=QoSProfile(
reliability=QoSReliabilityPolicy.RELIABLE,
@@ -370,6 +374,27 @@ def init_tree_manager(self, params: tree_node_parameters.Params):
self.get_logger().info("initialized tree manager")
+ def init_channels_publisher(self):
+ self.message_channels_pub = self.create_publisher(
+ MessageChannels,
+ "~/message_channels",
+ callback_group=self.publisher_callback_group,
+ qos_profile=QoSProfile(
+ reliability=QoSReliabilityPolicy.RELIABLE,
+ durability=QoSDurabilityPolicy.VOLATILE,
+ history=QoSHistoryPolicy.KEEP_LAST,
+ depth=1,
+ ),
+ )
+ self.publish_channels_timer = self.create_timer(
+ 10.0,
+ partial(
+ publish_message_channels,
+ self,
+ self.message_channels_pub,
+ ),
+ )
+
def load_default_tree(self, params: tree_node_parameters.Params):
if params.default_tree.load_default_tree:
self.get_logger().info(
@@ -426,6 +451,7 @@ def main(argv=None):
tree_node.init_package_manager(params=params)
tree_node.init_tree_manager(params=params)
tree_node.load_default_tree(params=params)
+ tree_node.init_channels_publisher()
executor = MultiThreadedExecutor(num_threads=3)
executor.add_node(tree_node)
diff --git a/ros_bt_py/tests/ros_nodes/test_fields_to_message.py b/ros_bt_py/tests/ros_nodes/test_fields_to_message.py
index 285a86f..630a040 100644
--- a/ros_bt_py/tests/ros_nodes/test_fields_to_message.py
+++ b/ros_bt_py/tests/ros_nodes/test_fields_to_message.py
@@ -28,7 +28,7 @@
from typing import Dict
import pytest
-from std_srvs.srv import SetBool
+from ros_bt_py.custom_types import RosTopicType
from ros_bt_py.ros_nodes.message_converters import FieldsToMessage
from ros_bt_py_interfaces.msg import Node as NodeMsg, UtilityBounds
@@ -36,9 +36,9 @@
@pytest.mark.parametrize(
"message,fields",
[
- (SetBool.Request, {"data": False}),
+ (RosTopicType("std_msgs/msg/Bool"), {"data": False}),
(
- UtilityBounds,
+ RosTopicType("ros_bt_py_interfaces/msg/UtilityBounds"),
{
"can_execute": False,
"has_upper_bound_success": False,
@@ -53,7 +53,7 @@
),
],
)
-def test_node_success(message: type, fields: Dict[str, type]):
+def test_node_success(message: RosTopicType, fields: Dict[str, type]):
unavailable_service = FieldsToMessage(
options={
"output_type": message,
diff --git a/ros_bt_py/tests/ros_nodes/test_message_from_dict.py b/ros_bt_py/tests/ros_nodes/test_message_from_dict.py
index 3c94433..8c8e2d4 100644
--- a/ros_bt_py/tests/ros_nodes/test_message_from_dict.py
+++ b/ros_bt_py/tests/ros_nodes/test_message_from_dict.py
@@ -26,9 +26,9 @@
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
import pytest
+from ros_bt_py.custom_types import RosTopicType
from ros_bt_py.ros_nodes.messages_from_dict import MessageFromDict
-from std_msgs.msg import Int64, String
-from std_srvs.srv import SetBool
+from std_msgs.msg import Int64, String, Bool
from ros_bt_py_interfaces.srv import ChangeTreeName
from ros_bt_py_interfaces.msg import Node as NodeMsg
@@ -36,9 +36,9 @@
@pytest.mark.parametrize(
"message, message_dict",
[
- (Int64, {"data": 667}),
- (String, {"data": "this is a test string"}),
- (SetBool.Request, {"data": True}),
+ (RosTopicType("std_msgs/msg/Int64"), {"data": 667}),
+ (RosTopicType("std_msgs/msg/String"), {"data": "this is a test string"}),
+ (RosTopicType("std_msgs/msg/Bool"), {"data": True}),
],
)
def test_node_success(message, message_dict):
@@ -59,9 +59,9 @@ def test_node_success(message, message_dict):
@pytest.mark.parametrize(
"message, message_dict",
[
- (Int64, {"data": 667}),
- (String, {"data": "this is a test string"}),
- (SetBool.Request, {"data": True}),
+ (RosTopicType("std_msgs/msg/Int64"), {"data": 667}),
+ (RosTopicType("std_msgs/msg/String"), {"data": "this is a test string"}),
+ (RosTopicType("std_msgs/msg/Bool"), {"data": True}),
],
)
def test_node_untick(message, message_dict):
@@ -94,9 +94,9 @@ def test_node_untick(message, message_dict):
@pytest.mark.parametrize(
"message, message_dict",
[
- (Int64, {"data": 667}),
- (String, {"data": "this is a test string"}),
- (SetBool.Request, {"data": True}),
+ (RosTopicType("std_msgs/msg/Int64"), {"data": 667}),
+ (RosTopicType("std_msgs/msg/String"), {"data": "this is a test string"}),
+ (RosTopicType("std_msgs/msg/Bool"), {"data": True}),
],
)
def test_node_reset(message, message_dict):
@@ -127,7 +127,7 @@ def test_node_reset(message, message_dict):
@pytest.mark.parametrize(
- "message, message_dict", [(ChangeTreeName.Request, {"tequila": False})]
+ "message, message_dict", [(RosTopicType("std_msgs/msg/Bool"), {"tequila": False})]
)
def test_node_failure(message, message_dict):
node = MessageFromDict(options={"message_type": message})
diff --git a/ros_bt_py/tests/ros_nodes/test_message_from_dict_const.py b/ros_bt_py/tests/ros_nodes/test_message_from_dict_const.py
index 0bf5c91..80a1c6d 100644
--- a/ros_bt_py/tests/ros_nodes/test_message_from_dict_const.py
+++ b/ros_bt_py/tests/ros_nodes/test_message_from_dict_const.py
@@ -26,9 +26,9 @@
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
import pytest
+from ros_bt_py.custom_types import RosTopicType
from ros_bt_py.ros_nodes.messages_from_dict import MessageFromConstDict
-from std_msgs.msg import Int64, String
-from std_srvs.srv import SetBool
+from std_msgs.msg import Int64, String, Bool
from ros_bt_py_interfaces.srv import ChangeTreeName
from ros_bt_py_interfaces.msg import Node as NodeMsg
@@ -36,9 +36,9 @@
@pytest.mark.parametrize(
"message, message_dict",
[
- (Int64, {"data": 667}),
- (String, {"data": "this is a test string"}),
- (SetBool.Request, {"data": True}),
+ (RosTopicType("std_msgs/msg/Int64"), {"data": 667}),
+ (RosTopicType("std_msgs/msg/String"), {"data": "this is a test string"}),
+ (RosTopicType("std_msgs/msg/Bool"), {"data": True}),
],
)
def test_node_success(message, message_dict):
@@ -58,9 +58,9 @@ def test_node_success(message, message_dict):
@pytest.mark.parametrize(
"message, message_dict",
[
- (Int64, {"data": 667}),
- (String, {"data": "this is a test string"}),
- (SetBool.Request, {"data": True}),
+ (RosTopicType("std_msgs/msg/Int64"), {"data": 667}),
+ (RosTopicType("std_msgs/msg/String"), {"data": "this is a test string"}),
+ (RosTopicType("std_msgs/msg/Bool"), {"data": True}),
],
)
def test_node_untick(message, message_dict):
@@ -92,9 +92,9 @@ def test_node_untick(message, message_dict):
@pytest.mark.parametrize(
"message, message_dict",
[
- (Int64, {"data": 667}),
- (String, {"data": "this is a test string"}),
- (SetBool.Request, {"data": True}),
+ (RosTopicType("std_msgs/msg/Int64"), {"data": 667}),
+ (RosTopicType("std_msgs/msg/String"), {"data": "this is a test string"}),
+ (RosTopicType("std_msgs/msg/Bool"), {"data": True}),
],
)
def test_node_reset(message, message_dict):
@@ -124,7 +124,7 @@ def test_node_reset(message, message_dict):
@pytest.mark.parametrize(
- "message, message_dict", [(ChangeTreeName.Request, {"tequila": False})]
+ "message, message_dict", [(RosTopicType("std_msgs/msg/Bool"), {"tequila": False})]
)
def test_node_failure(message, message_dict):
node = MessageFromConstDict(options={"message_type": message, "dict": message_dict})
diff --git a/ros_bt_py/tests/ros_nodes/test_message_to_fields.py b/ros_bt_py/tests/ros_nodes/test_message_to_fields.py
index 3fda908..08c85d7 100644
--- a/ros_bt_py/tests/ros_nodes/test_message_to_fields.py
+++ b/ros_bt_py/tests/ros_nodes/test_message_to_fields.py
@@ -29,6 +29,7 @@
import pytest
from std_srvs.srv import SetBool
+from ros_bt_py.custom_types import RosTopicType
from ros_bt_py.ros_nodes.message_converters import MessageToFields
from ros_bt_py_interfaces.msg import Node as NodeMsg, UtilityBounds
@@ -36,9 +37,9 @@
@pytest.mark.parametrize(
"message,fields",
[
- (SetBool.Request, {"data": False}),
+ (RosTopicType("std_msgs/msg/Bool"), {"data": False}),
(
- UtilityBounds,
+ RosTopicType("ros_bt_py_interfaces/msg/UtilityBounds"),
{
"can_execute": False,
"has_upper_bound_success": False,
@@ -61,7 +62,7 @@ def test_node_success(message: type, fields: Dict[str, type]):
)
unavailable_service.setup()
assert unavailable_service.state == NodeMsg.IDLE
- unavailable_service.inputs["in"] = message()
+ unavailable_service.inputs["in"] = message.get_type_obj()()
unavailable_service.tick()
assert unavailable_service.state == NodeMsg.SUCCEED
assert unavailable_service.outputs.__len__() == len(fields)
diff --git a/ros_bt_py/tests/ros_nodes/test_service.py b/ros_bt_py/tests/ros_nodes/test_service.py
index 11a3cf5..2b4a221 100644
--- a/ros_bt_py/tests/ros_nodes/test_service.py
+++ b/ros_bt_py/tests/ros_nodes/test_service.py
@@ -29,6 +29,7 @@
import unittest.mock as mock
from std_srvs.srv import SetBool
+from ros_bt_py.custom_types import RosServiceName, RosServiceType
from ros_bt_py.ros_nodes.service import Service
from rclpy.time import Time
from ros_bt_py_interfaces.msg import Node as NodeMsg, UtilityBounds
@@ -52,8 +53,8 @@ def test_node_success(ros_mock, client_mock, future_mock, clock_mock):
unavailable_service = Service(
options={
- "service_name": "this_service_does_not_exist",
- "service_type": SetBool,
+ "service_name": RosServiceName(name="this_service_does_not_exist"),
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
"wait_for_service_seconds": 5.0,
"fail_if_not_available": True,
@@ -99,8 +100,8 @@ def test_node_failure(ros_mock, client_mock, future_mock, clock_mock):
unavailable_service = Service(
options={
- "service_name": "this_service_does_not_exist",
- "service_type": SetBool,
+ "service_name": RosServiceName(name="this_service_does_not_exist"),
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
"wait_for_service_seconds": 5.0,
"fail_if_not_available": True,
@@ -133,8 +134,8 @@ def test_node_timeout(ros_mock, client_mock, future_mock, clock_mock):
unavailable_service = Service(
options={
- "service_name": "this_service_does_not_exist",
- "service_type": SetBool,
+ "service_name": RosServiceName(name="this_service_does_not_exist"),
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
"wait_for_service_seconds": 5.0,
"fail_if_not_available": True,
@@ -177,8 +178,8 @@ def test_node_reset_shutdown(ros_mock, client_mock, future_mock, clock_mock):
unavailable_service = Service(
options={
- "service_name": "this_service_does_not_exist",
- "service_type": SetBool,
+ "service_name": RosServiceName(name="this_service_does_not_exist"),
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
"wait_for_service_seconds": 5.0,
"fail_if_not_available": True,
@@ -230,8 +231,8 @@ def test_node_reset(ros_mock, client_mock, future_mock, clock_mock):
unavailable_service = Service(
options={
- "service_name": "this_service_does_not_exist",
- "service_type": SetBool,
+ "service_name": RosServiceName(name="this_service_does_not_exist"),
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
"wait_for_service_seconds": 5.0,
"fail_if_not_available": True,
@@ -283,8 +284,8 @@ def test_node_no_ros():
with pytest.raises(BehaviorTreeException):
unavailable_service = Service(
options={
- "service_name": "this_service_does_not_exist",
- "service_type": SetBool,
+ "service_name": RosServiceName(name="this_service_does_not_exist"),
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
"wait_for_service_seconds": 5.0,
"fail_if_not_available": True,
@@ -319,8 +320,8 @@ def test_node_untick(ros_mock, client_mock, future_mock, clock_mock):
unavailable_service = Service(
options={
- "service_name": "this_service_does_not_exist",
- "service_type": SetBool,
+ "service_name": RosServiceName(name="this_service_does_not_exist"),
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
"wait_for_service_seconds": 5.0,
"fail_if_not_available": True,
@@ -364,8 +365,8 @@ def test_node_utility_no_ros(ros_mock, client_mock, future_mock, clock_mock):
unavailable_service = Service(
options={
- "service_name": "this_service_does_not_exist",
- "service_type": SetBool,
+ "service_name": RosServiceName(name="this_service_does_not_exist"),
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
"wait_for_service_seconds": 5.0,
"fail_if_not_available": True,
@@ -377,8 +378,8 @@ def test_node_utility_no_ros(ros_mock, client_mock, future_mock, clock_mock):
unavailable_service_2 = Service(
options={
- "service_name": "this_service_does_not_exist",
- "service_type": SetBool,
+ "service_name": RosServiceName(name="this_service_does_not_exist"),
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
"wait_for_service_seconds": 5.0,
"fail_if_not_available": True,
@@ -412,8 +413,8 @@ def test_node_utility(ros_mock, client_mock, future_mock, clock_mock):
unavailable_service = Service(
options={
- "service_name": "this_service_does_not_exist",
- "service_type": SetBool,
+ "service_name": RosServiceName(name="this_service_does_not_exist"),
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
"wait_for_service_seconds": 5.0,
"fail_if_not_available": True,
@@ -465,8 +466,8 @@ def test_node_simulate_tick(ros_mock, client_mock, future_mock, clock_mock):
unavailable_service = Service(
options={
- "service_name": "this_service_does_not_exist",
- "service_type": SetBool,
+ "service_name": RosServiceName(name="this_service_does_not_exist"),
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
"wait_for_service_seconds": 5.0,
"fail_if_not_available": True,
diff --git a/ros_bt_py/tests/ros_nodes/test_service_input.py b/ros_bt_py/tests/ros_nodes/test_service_input.py
index ad3e553..e977913 100644
--- a/ros_bt_py/tests/ros_nodes/test_service_input.py
+++ b/ros_bt_py/tests/ros_nodes/test_service_input.py
@@ -29,6 +29,7 @@
import unittest.mock as mock
from std_srvs.srv import SetBool
+from ros_bt_py.custom_types import RosServiceType
from ros_bt_py.ros_nodes.service import ServiceInput
from rclpy.time import Time
from ros_bt_py_interfaces.msg import Node as NodeMsg, UtilityBounds
@@ -50,10 +51,9 @@ def test_node_success(self, ros_mock, client_mock, future_mock, clock_mock):
ros_mock.create_client.return_value = client_mock
clock_mock.now.side_effect = [Time(seconds=0), Time(seconds=1), Time(seconds=2)]
ros_mock.get_clock.return_value = clock_mock
-
unavailable_service = ServiceInput(
options={
- "service_type": SetBool,
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
},
ros_node=ros_mock,
@@ -94,7 +94,7 @@ def test_node_failure(self, ros_mock, client_mock, future_mock, clock_mock):
unavailable_service = ServiceInput(
options={
- "service_type": SetBool,
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
},
ros_node=ros_mock,
@@ -125,7 +125,7 @@ def test_node_timeout(self, ros_mock, client_mock, future_mock, clock_mock):
unavailable_service = ServiceInput(
options={
- "service_type": SetBool,
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
},
ros_node=ros_mock,
@@ -166,7 +166,7 @@ def test_node_reset_shutdown(self, ros_mock, client_mock, future_mock, clock_moc
unavailable_service = ServiceInput(
options={
- "service_type": SetBool,
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
},
ros_node=ros_mock,
@@ -219,7 +219,7 @@ def test_node_reset(self, ros_mock, client_mock, future_mock, clock_mock):
unavailable_service = ServiceInput(
options={
- "service_type": SetBool,
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
},
ros_node=ros_mock,
@@ -270,7 +270,7 @@ def test_node_no_ros(self):
with pytest.raises(BehaviorTreeException):
unavailable_service = ServiceInput(
options={
- "service_type": SetBool,
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
},
ros_node=None,
@@ -302,7 +302,7 @@ def test_node_no_ros_2(self, ros_mock, client_mock, future_mock, clock_mock):
unavailable_service = ServiceInput(
options={
- "service_type": SetBool,
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
},
ros_node=ros_mock,
@@ -340,7 +340,7 @@ def test_node_name_change(self, ros_mock, client_mock, future_mock, clock_mock):
unavailable_service = ServiceInput(
options={
- "service_type": SetBool,
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
},
ros_node=ros_mock,
@@ -382,7 +382,7 @@ def test_node_untick(self, ros_mock, client_mock, future_mock, clock_mock):
unavailable_service = ServiceInput(
options={
- "service_type": SetBool,
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
},
ros_node=ros_mock,
@@ -423,7 +423,7 @@ def test_node_utility_no_ros(self, ros_mock, client_mock, future_mock, clock_moc
unavailable_service = ServiceInput(
options={
- "service_type": SetBool,
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
},
ros_node=None,
@@ -433,7 +433,7 @@ def test_node_utility_no_ros(self, ros_mock, client_mock, future_mock, clock_moc
unavailable_service_2 = ServiceInput(
options={
- "service_type": SetBool,
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
},
ros_node=ros_mock,
@@ -467,7 +467,7 @@ def test_node_utility(self, ros_mock, client_mock, future_mock, clock_mock):
unavailable_service = ServiceInput(
options={
- "service_type": SetBool,
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
},
ros_node=ros_mock,
@@ -517,7 +517,7 @@ def test_node_simulate_tick(self, ros_mock, client_mock, future_mock, clock_mock
unavailable_service = ServiceInput(
options={
- "service_type": SetBool,
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_response_seconds": 5.0,
},
ros_node=ros_mock,
diff --git a/ros_bt_py/tests/ros_nodes/test_wait_for_service.py b/ros_bt_py/tests/ros_nodes/test_wait_for_service.py
index 8f591df..e73c946 100644
--- a/ros_bt_py/tests/ros_nodes/test_wait_for_service.py
+++ b/ros_bt_py/tests/ros_nodes/test_wait_for_service.py
@@ -29,6 +29,7 @@
import unittest.mock as mock
from std_srvs.srv import SetBool
+from ros_bt_py.custom_types import RosServiceName, RosServiceType
from ros_bt_py.ros_nodes.service import WaitForService
from rclpy.time import Time
from ros_bt_py_interfaces.msg import Node as NodeMsg
@@ -46,8 +47,8 @@ def test_node_success(ros_mock, client_mock, clock_mock):
unavailable_service = WaitForService(
options={
- "service_name": "this_service_does_not_exist",
- "service_type": SetBool,
+ "service_name": RosServiceName("this_service_does_not_exist"),
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_service_seconds": 5.0,
},
ros_node=ros_mock,
@@ -80,8 +81,8 @@ def test_node_failure(ros_mock, client_mock, clock_mock):
unavailable_service = WaitForService(
options={
- "service_name": "this_service_does_not_exist",
- "service_type": SetBool,
+ "service_name": RosServiceName("this_service_does_not_exist"),
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_service_seconds": 5.0,
},
ros_node=ros_mock,
@@ -118,8 +119,8 @@ def test_node_reset(ros_mock, client_mock, clock_mock):
unavailable_service = WaitForService(
options={
- "service_name": "this_service_does_not_exist",
- "service_type": SetBool,
+ "service_name": RosServiceName("this_service_does_not_exist"),
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_service_seconds": 5.0,
},
ros_node=ros_mock,
@@ -148,8 +149,8 @@ def test_node_no_ros():
with pytest.raises(BehaviorTreeException):
unavailable_service = WaitForService(
options={
- "service_name": "this_service_does_not_exist",
- "service_type": SetBool,
+ "service_name": RosServiceName("this_service_does_not_exist"),
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_service_seconds": 5.0,
},
ros_node=None,
@@ -176,8 +177,8 @@ def test_node_untick(ros_mock, client_mock, clock_mock):
unavailable_service = WaitForService(
options={
- "service_name": "this_service_does_not_exist",
- "service_type": SetBool,
+ "service_name": RosServiceName("this_service_does_not_exist"),
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_service_seconds": 5.0,
},
ros_node=ros_mock,
@@ -216,11 +217,10 @@ def test_node_simulate_tick(ros_mock, client_mock, clock_mock):
Time(seconds=4),
]
ros_mock.get_clock.return_value = clock_mock
-
unavailable_service = WaitForService(
options={
- "service_name": "this_service_does_not_exist",
- "service_type": SetBool,
+ "service_name": RosServiceName("this_service_does_not_exist"),
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_service_seconds": 5.0,
},
ros_node=ros_mock,
diff --git a/ros_bt_py/tests/ros_nodes/test_wait_for_service_input.py b/ros_bt_py/tests/ros_nodes/test_wait_for_service_input.py
index 97ae4e6..e32952f 100644
--- a/ros_bt_py/tests/ros_nodes/test_wait_for_service_input.py
+++ b/ros_bt_py/tests/ros_nodes/test_wait_for_service_input.py
@@ -28,7 +28,7 @@
import pytest
import unittest.mock as mock
-from std_srvs.srv import SetBool
+from ros_bt_py.custom_types import RosServiceName, RosServiceType
from ros_bt_py.ros_nodes.service import WaitForServiceInput
from rclpy.time import Time
from ros_bt_py_interfaces.msg import Node as NodeMsg
@@ -45,7 +45,10 @@ def test_node_success(ros_mock, client_mock, clock_mock):
ros_mock.get_clock.return_value = clock_mock
unavailable_service = WaitForServiceInput(
- options={"service_type": SetBool, "wait_for_service_seconds": 5.0},
+ options={
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
+ "wait_for_service_seconds": 5.0,
+ },
ros_node=ros_mock,
)
@@ -76,7 +79,10 @@ def test_node_failure(ros_mock, client_mock, clock_mock):
ros_mock.get_clock.return_value = clock_mock
unavailable_service = WaitForServiceInput(
- options={"service_type": SetBool, "wait_for_service_seconds": 5.0},
+ options={
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
+ "wait_for_service_seconds": 5.0,
+ },
ros_node=ros_mock,
)
@@ -111,7 +117,10 @@ def test_node_reset(ros_mock, client_mock, clock_mock):
ros_mock.get_clock.return_value = clock_mock
unavailable_service = WaitForServiceInput(
- options={"service_type": SetBool, "wait_for_service_seconds": 5.0},
+ options={
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
+ "wait_for_service_seconds": 5.0,
+ },
ros_node=ros_mock,
)
@@ -138,7 +147,10 @@ def test_node_reset(ros_mock, client_mock, clock_mock):
def test_node_no_ros():
with pytest.raises(BehaviorTreeException):
unavailable_service = WaitForServiceInput(
- options={"service_type": SetBool, "wait_for_service_seconds": 5.0},
+ options={
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
+ "wait_for_service_seconds": 5.0,
+ },
ros_node=None,
)
@@ -162,7 +174,10 @@ def test_node_untick(ros_mock, client_mock, clock_mock):
ros_mock.get_clock.return_value = clock_mock
unavailable_service = WaitForServiceInput(
- options={"service_type": SetBool, "wait_for_service_seconds": 5.0},
+ options={
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
+ "wait_for_service_seconds": 5.0,
+ },
ros_node=ros_mock,
)
@@ -200,10 +215,9 @@ def test_node_simulate_tick(ros_mock, client_mock, clock_mock):
Time(seconds=4),
]
ros_mock.get_clock.return_value = clock_mock
-
unavailable_service = WaitForServiceInput(
options={
- "service_type": SetBool,
+ "service_type": RosServiceType("std_srvs/srv/SetBool"),
"wait_for_service_seconds": 5.0,
},
ros_node=ros_mock,
diff --git a/ros_bt_py_interfaces/CMakeLists.txt b/ros_bt_py_interfaces/CMakeLists.txt
index cb283ff..10f7c02 100644
--- a/ros_bt_py_interfaces/CMakeLists.txt
+++ b/ros_bt_py_interfaces/CMakeLists.txt
@@ -50,8 +50,6 @@ rosidl_generate_interfaces(${PROJECT_NAME}
"msg/CapabilityIOBridgeData.msg"
"msg/SubtreeInfo.msg"
"msg/DocumentedNode.msg"
- "msg/Message.msg"
- "msg/Messages.msg"
"msg/Node.msg"
"msg/NodeData.msg"
"msg/NodeDataLocation.msg"
@@ -65,6 +63,9 @@ rosidl_generate_interfaces(${PROJECT_NAME}
"msg/Tree.msg"
"msg/TreeDataUpdate.msg"
"msg/UtilityBounds.msg"
+ "msg/MessageChannel.msg"
+ "msg/MessageChannels.msg"
+ "msg/MessageTypes.msg"
"srv/AddNode.srv"
"srv/AddNodeAtIndex.srv"
diff --git a/ros_bt_py_interfaces/msg/Messages.msg b/ros_bt_py_interfaces/msg/MessageChannel.msg
similarity index 95%
rename from ros_bt_py_interfaces/msg/Messages.msg
rename to ros_bt_py_interfaces/msg/MessageChannel.msg
index 571010c..2212da0 100644
--- a/ros_bt_py_interfaces/msg/Messages.msg
+++ b/ros_bt_py_interfaces/msg/MessageChannel.msg
@@ -1,4 +1,4 @@
-# Copyright 2023 FZI Forschungszentrum Informatik
+# Copyright 2024 FZI Forschungszentrum Informatik
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions are met:
@@ -25,4 +25,6 @@
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
-Message[] messages
+
+string name
+string type
\ No newline at end of file
diff --git a/ros_bt_py_interfaces/msg/MessageChannels.msg b/ros_bt_py_interfaces/msg/MessageChannels.msg
new file mode 100644
index 0000000..c8f88cc
--- /dev/null
+++ b/ros_bt_py_interfaces/msg/MessageChannels.msg
@@ -0,0 +1,31 @@
+# Copyright 2024 FZI Forschungszentrum Informatik
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions are met:
+#
+# * Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+#
+# * Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in the
+# documentation and/or other materials provided with the distribution.
+#
+# * Neither the name of the FZI Forschungszentrum Informatik nor the names of its
+# contributors may be used to endorse or promote products derived from
+# this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
+# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+
+MessageChannel[] topics
+MessageChannel[] services
+MessageChannel[] actions
\ No newline at end of file
diff --git a/ros_bt_py_interfaces/msg/Message.msg b/ros_bt_py_interfaces/msg/MessageTypes.msg
similarity index 96%
rename from ros_bt_py_interfaces/msg/Message.msg
rename to ros_bt_py_interfaces/msg/MessageTypes.msg
index 00e9953..1133fd6 100644
--- a/ros_bt_py_interfaces/msg/Message.msg
+++ b/ros_bt_py_interfaces/msg/MessageTypes.msg
@@ -25,6 +25,6 @@
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
-string msg
-bool service
-bool action
+string[] topics
+string[] services
+string[] actions