|  | 
| 12 | 12 | # See the License for the specific language governing permissions and | 
| 13 | 13 | # limitations under the License. | 
| 14 | 14 | 
 | 
| 15 |  | - | 
| 16 | 15 | import base64 | 
| 17 |  | -from typing import Optional, Type, Union, cast | 
|  | 16 | +from typing import Any, OrderedDict, Type, cast | 
| 18 | 17 | 
 | 
| 19 | 18 | import cv2 | 
| 20 | 19 | import numpy as np | 
| 21 |  | -import rclpy | 
| 22 |  | -import rclpy.executors | 
| 23 |  | -import rclpy.node | 
| 24 |  | -import rclpy.time | 
|  | 20 | +import rosidl_runtime_py.convert | 
|  | 21 | +import rosidl_runtime_py.set_message | 
|  | 22 | +import rosidl_runtime_py.utilities | 
| 25 | 23 | import sensor_msgs.msg | 
| 26 | 24 | from cv_bridge import CvBridge | 
| 27 |  | -from rclpy.duration import Duration | 
| 28 |  | -from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy | 
| 29 |  | -from rclpy.node import Node | 
| 30 |  | -from rclpy.qos import QoSProfile | 
| 31 |  | -from rclpy.signals import SignalHandlerGuardCondition | 
| 32 |  | -from rclpy.utilities import timeout_sec_to_nsec | 
| 33 | 25 | from rosidl_parser.definition import NamespacedType | 
| 34 | 26 | from rosidl_runtime_py.import_message import import_message_from_namespaced_type | 
| 35 | 27 | from rosidl_runtime_py.utilities import get_namespaced_type | 
| 36 |  | -from tf2_ros import Buffer, LookupException, TransformListener, TransformStamped | 
|  | 28 | + | 
|  | 29 | + | 
|  | 30 | +def ros2_message_to_dict(message: Any) -> OrderedDict[str, Any]: | 
|  | 31 | +    """Convert any ROS2 message into a dictionary. | 
|  | 32 | +
 | 
|  | 33 | +    Args: | 
|  | 34 | +        message: A ROS2 message instance | 
|  | 35 | +
 | 
|  | 36 | +    Returns: | 
|  | 37 | +        A dictionary representation of the message | 
|  | 38 | +
 | 
|  | 39 | +    Raises: | 
|  | 40 | +        TypeError: If the input is not a valid ROS2 message | 
|  | 41 | +    """ | 
|  | 42 | +    msg_dict: OrderedDict[str, Any] = rosidl_runtime_py.convert.message_to_ordereddict( | 
|  | 43 | +        message | 
|  | 44 | +    )  # type: ignore | 
|  | 45 | +    return msg_dict | 
| 37 | 46 | 
 | 
| 38 | 47 | 
 | 
| 39 | 48 | def import_message_from_str(msg_type: str) -> Type[object]: | 
| @@ -101,81 +110,3 @@ def convert_ros_img_to_base64(msg: sensor_msgs.msg.Image) -> str: | 
| 101 | 110 |         cv_image = cv2.cvtColor(cv_image, cv2.COLOR_BGR2RGB) | 
| 102 | 111 |         image_data = cv2.imencode(".png", cv_image)[1].tostring()  # type: ignore | 
| 103 | 112 |         return base64.b64encode(image_data).decode("utf-8")  # type: ignore | 
| 104 |  | - | 
| 105 |  | - | 
| 106 |  | -# Copied from https://github.com/ros2/rclpy/blob/jazzy/rclpy/rclpy/wait_for_message.py, to support humble | 
| 107 |  | -def wait_for_message( | 
| 108 |  | -    msg_type: Type[object], | 
| 109 |  | -    node: "Node", | 
| 110 |  | -    topic: str, | 
| 111 |  | -    *, | 
| 112 |  | -    qos_profile: Union[QoSProfile, int] = 1, | 
| 113 |  | -    time_to_wait: float = -1, | 
| 114 |  | -) -> tuple[bool, Optional[object]]: | 
| 115 |  | -    """ | 
| 116 |  | -    Wait for the next incoming message. | 
| 117 |  | -
 | 
| 118 |  | -    :param msg_type: message type | 
| 119 |  | -    :param node: node to initialize the subscription on | 
| 120 |  | -    :param topic: topic name to wait for message | 
| 121 |  | -    :param qos_profile: QoS profile to use for the subscription | 
| 122 |  | -    :param time_to_wait: seconds to wait before returning | 
| 123 |  | -    :returns: (True, msg) if a message was successfully received, (False, None) if message | 
| 124 |  | -        could not be obtained or shutdown was triggered asynchronously on the context. | 
| 125 |  | -    """ | 
| 126 |  | -    context = node.context | 
| 127 |  | -    wait_set = _rclpy.WaitSet(1, 1, 0, 0, 0, 0, context.handle) | 
| 128 |  | -    wait_set.clear_entities() | 
| 129 |  | - | 
| 130 |  | -    sub = node.create_subscription( | 
| 131 |  | -        msg_type, topic, lambda _: None, qos_profile=qos_profile | 
| 132 |  | -    ) | 
| 133 |  | -    try: | 
| 134 |  | -        wait_set.add_subscription(sub.handle) | 
| 135 |  | -        sigint_gc = SignalHandlerGuardCondition(context=context) | 
| 136 |  | -        wait_set.add_guard_condition(sigint_gc.handle) | 
| 137 |  | - | 
| 138 |  | -        timeout_nsec = timeout_sec_to_nsec(time_to_wait) | 
| 139 |  | -        wait_set.wait(timeout_nsec) | 
| 140 |  | - | 
| 141 |  | -        subs_ready = wait_set.get_ready_entities("subscription") | 
| 142 |  | -        guards_ready = wait_set.get_ready_entities("guard_condition") | 
| 143 |  | - | 
| 144 |  | -        if guards_ready: | 
| 145 |  | -            if sigint_gc.handle.pointer in guards_ready: | 
| 146 |  | -                return False, None | 
| 147 |  | - | 
| 148 |  | -        if subs_ready: | 
| 149 |  | -            if sub.handle.pointer in subs_ready: | 
| 150 |  | -                msg_info = sub.handle.take_message(sub.msg_type, sub.raw) | 
| 151 |  | -                if msg_info is not None: | 
| 152 |  | -                    return True, msg_info[0] | 
| 153 |  | -    finally: | 
| 154 |  | -        # TODO(boczekbartek): uncomment when rclpy resolves: https://github.com/ros2/rclpy/issues/1142 | 
| 155 |  | -        # node.destroy_subscription(sub) | 
| 156 |  | -        pass | 
| 157 |  | - | 
| 158 |  | -    return False, None | 
| 159 |  | - | 
| 160 |  | - | 
| 161 |  | -def get_transform( | 
| 162 |  | -    node: rclpy.node.Node, | 
| 163 |  | -    target_frame: str, | 
| 164 |  | -    source_frame: str, | 
| 165 |  | -    timeout_sec: float = 5.0, | 
| 166 |  | -) -> TransformStamped: | 
| 167 |  | -    tf_buffer = Buffer(node=node) | 
| 168 |  | -    tf_listener = TransformListener(tf_buffer, node) | 
| 169 |  | - | 
| 170 |  | -    transform: Optional[TransformStamped] = tf_buffer.lookup_transform( | 
| 171 |  | -        target_frame, source_frame, rclpy.time.Time(), timeout=Duration(seconds=3) | 
| 172 |  | -    ) | 
| 173 |  | - | 
| 174 |  | -    tf_listener.unregister() | 
| 175 |  | - | 
| 176 |  | -    if transform is None: | 
| 177 |  | -        raise LookupException( | 
| 178 |  | -            f"Could not find transform from {source_frame} to {target_frame} in {timeout_sec} seconds" | 
| 179 |  | -        ) | 
| 180 |  | - | 
| 181 |  | -    return transform | 
0 commit comments