Exemplo n.º 1
0
    def test_subscription_constructor(self):
        callbacks = SubscriptionEventCallbacks()
        liveliness_callback = Mock()
        deadline_callback = Mock()
        message_callback = Mock()

        # No arg
        subscription = self.node.create_subscription(EmptyMsg, 'test_topic', message_callback, 10)
        self.assertEqual(len(subscription.event_handlers), 0)
        self.node.destroy_subscription(subscription)

        # Arg with no callbacks
        subscription = self.node.create_subscription(
            EmptyMsg, 'test_topic', message_callback, 10, event_callbacks=callbacks)
        self.assertEqual(len(subscription.event_handlers), 0)
        self.node.destroy_subscription(subscription)

        # Arg with one of the callbacks
        callbacks.deadline = deadline_callback
        subscription = self.node.create_subscription(
            EmptyMsg, 'test_topic', message_callback, 10, event_callbacks=callbacks)
        self.assertEqual(len(subscription.event_handlers), 1)
        self.node.destroy_subscription(subscription)

        # Arg with both callbacks
        callbacks.liveliness = liveliness_callback
        subscription = self.node.create_subscription(
            EmptyMsg, 'test_topic', message_callback, 10, event_callbacks=callbacks)
        self.assertEqual(len(subscription.event_handlers), 2)
        self.node.destroy_subscription(subscription)
Exemplo n.º 2
0
    def test_subscription_constructor(self):
        callbacks = SubscriptionEventCallbacks()
        liveliness_callback = Mock()
        deadline_callback = Mock()
        message_callback = Mock()
        incompatible_qos_callback = Mock()
        expected_num_event_handlers = 1

        # No arg
        subscription = self.node.create_subscription(EmptyMsg, self.topic_name,
                                                     message_callback, 10)
        self.assertEqual(len(subscription.event_handlers),
                         expected_num_event_handlers)
        self.node.destroy_subscription(subscription)

        # Arg with no callbacks
        subscription = self.node.create_subscription(EmptyMsg,
                                                     self.topic_name,
                                                     message_callback,
                                                     10,
                                                     event_callbacks=callbacks)
        self.assertEqual(len(subscription.event_handlers),
                         expected_num_event_handlers)
        self.node.destroy_subscription(subscription)

        # Arg with one of the callbacks
        callbacks.deadline = deadline_callback
        expected_num_event_handlers += 1
        subscription = self.node.create_subscription(EmptyMsg,
                                                     self.topic_name,
                                                     message_callback,
                                                     10,
                                                     event_callbacks=callbacks)
        self.assertEqual(len(subscription.event_handlers),
                         expected_num_event_handlers)
        self.node.destroy_subscription(subscription)

        # Arg with two callbacks
        callbacks.liveliness = liveliness_callback
        expected_num_event_handlers += 1
        subscription = self.node.create_subscription(EmptyMsg,
                                                     self.topic_name,
                                                     message_callback,
                                                     10,
                                                     event_callbacks=callbacks)
        self.assertEqual(len(subscription.event_handlers),
                         expected_num_event_handlers)
        self.node.destroy_subscription(subscription)

        # Arg with three callbacks
        callbacks.incompatible_qos = incompatible_qos_callback
        subscription = self.node.create_subscription(EmptyMsg,
                                                     self.topic_name,
                                                     message_callback,
                                                     10,
                                                     event_callbacks=callbacks)
        self.assertEqual(len(subscription.event_handlers), 3)
        self.node.destroy_subscription(subscription)
Exemplo n.º 3
0
def subscriber(node: Node,
               topic_name: str,
               message_type: MsgType,
               callback: Callable[[MsgType], Any],
               qos_profile: QoSProfile,
               report_lost_messages: bool,
               future=None,
               timeout=None) -> Optional[str]:
    """Initialize a node with a single subscription and spin."""
    event_callbacks = None
    if report_lost_messages:
        event_callbacks = SubscriptionEventCallbacks(
            message_lost=message_lost_event_callback)
    try:
        node.create_subscription(message_type,
                                 topic_name,
                                 callback,
                                 qos_profile,
                                 event_callbacks=event_callbacks)
    except UnsupportedEventTypeError:
        assert report_lost_messages
        print(f"The rmw implementation '{get_rmw_implementation_identifier()}'"
              ' does not support reporting lost messages')

    rclpy.spin_until_future_complete(node, future, timeout)

    if future is not None:
        if not future.done():
            node.get_logger().info('Timeout occured')
Exemplo n.º 4
0
def main(args=None):
    parsed_args = parse_args()
    rclpy.init(args=args)

    topic = 'qos_deadline_chatter'
    deadline = Duration(seconds=parsed_args.deadline / 1000.0)

    qos_profile = QoSProfile(depth=10, deadline=deadline)

    subscription_callbacks = SubscriptionEventCallbacks(
        deadline=lambda event: get_logger('Listener').info(str(event)))
    listener = Listener(topic,
                        qos_profile,
                        event_callbacks=subscription_callbacks)

    publisher_callbacks = PublisherEventCallbacks(
        deadline=lambda event: get_logger('Talker').info(str(event)))
    talker = Talker(topic, qos_profile, event_callbacks=publisher_callbacks)

    publish_for_seconds = parsed_args.publish_for / 1000.0
    pause_for_seconds = parsed_args.pause_for / 1000.0
    pause_timer = talker.create_timer(  # noqa: F841
        publish_for_seconds, lambda: talker.pause_for(pause_for_seconds))

    executor = SingleThreadedExecutor()
    executor.add_node(listener)
    executor.add_node(talker)
    try:
        executor.spin()
    except KeyboardInterrupt:
        pass
    except ExternalShutdownException:
        sys.exit(1)
    finally:
        rclpy.try_shutdown()
Exemplo n.º 5
0
    def subscribe_and_spin(
        self,
        node: Node,
        topic_name: str,
        message_type: MsgType,
        qos_profile: QoSProfile,
        no_report_lost_messages: bool,
        raw: bool
    ) -> Optional[str]:
        """Initialize a node with a single subscription and spin."""
        event_callbacks = None
        if not no_report_lost_messages:
            event_callbacks = SubscriptionEventCallbacks(
                message_lost=_message_lost_event_callback)
        try:
            node.create_subscription(
                message_type,
                topic_name,
                self._subscriber_callback,
                qos_profile,
                event_callbacks=event_callbacks,
                raw=raw)
        except UnsupportedEventTypeError:
            assert not no_report_lost_messages
            node.create_subscription(
                message_type,
                topic_name,
                self._subscriber_callback,
                qos_profile,
                event_callbacks=None,
                raw=raw)

        rclpy.spin(node)
Exemplo n.º 6
0
    def __init__(self):

        qos = QoSProfile(depth=10)
        qos.durability = DurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL

        custom_callback = lambda event: print("Custom Incompatible Callback!")
        callbacks = SubscriptionEventCallbacks()
        callbacks.incompatible_qos = custom_callback

        super().__init__('minimal_subscriber')
        self.subscription = self.create_subscription(
            String,
            'topic',
            self.listener_callback,
            qos,
            event_callbacks=callbacks)
Exemplo n.º 7
0
def main(args=None):
    parsed_args = parse_args()
    rclpy.init(args=args)

    topic = 'qos_liveliness_chatter'
    liveliness_lease_duration = Duration(
        seconds=parsed_args.liveliness_lease_duration / 1000.0)
    liveliness_policy = POLICY_MAP[parsed_args.policy]

    qos_profile = QoSProfile(
        depth=10,
        liveliness=liveliness_policy,
        liveliness_lease_duration=liveliness_lease_duration)

    subscription_callbacks = SubscriptionEventCallbacks(
        liveliness=lambda event: get_logger('Listener').info(str(event)))
    listener = Listener(topic,
                        qos_profile,
                        event_callbacks=subscription_callbacks)

    publisher_callbacks = PublisherEventCallbacks(
        liveliness=lambda event: get_logger('Talker').info(str(event)))
    talker = Talker(topic,
                    qos_profile,
                    event_callbacks=publisher_callbacks,
                    assert_node_period=parsed_args.node_assert_period / 1000.0,
                    assert_topic_period=parsed_args.topic_assert_period /
                    1000.0)

    executor = SingleThreadedExecutor()

    def kill_talker():
        if liveliness_policy == QoSLivelinessPolicy.RMW_QOS_POLICY_LIVELINESS_AUTOMATIC:
            executor.remove_node(talker)
            talker.destroy_node()
        elif liveliness_policy == QoSLivelinessPolicy.RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_NODE:
            talker.stop()
        elif liveliness_policy == QoSLivelinessPolicy.RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC:
            talker.stop()
        kill_timer.cancel()

    if parsed_args.kill_publisher_after > 0:
        kill_timer = listener.create_timer(  # noqa: F841
            parsed_args.kill_publisher_after / 1000.0, kill_talker)

    executor.add_node(listener)
    executor.add_node(talker)
    executor.spin()

    rclpy.shutdown()
Exemplo n.º 8
0
    def __init__(self):
        """Create a MessageLostListener."""
        super().__init__('message_lost_listener')

        # Create an object describing the event handlers that will
        # be registered in the subscription.
        # In this case, only a handler for a message lost event is registered.
        event_callbacks = SubscriptionEventCallbacks(
            message_lost=self._message_lost_event_callback)
        # Create a subscription, passing the previously created event handlers.
        self.subscription = self.create_subscription(
            Image,
            'message_lost_chatter',
            self._message_callback,
            1,
            event_callbacks=event_callbacks)
Exemplo n.º 9
0
def subscriber(node: Node, topic_name: str, message_type: MsgType,
               callback: Callable[[MsgType], Any],
               qos_profile: QoSProfile) -> Optional[str]:
    """Initialize a node with a single subscription and spin."""
    if message_type is None:
        topic_names_and_types = get_topic_names_and_types(
            node=node, include_hidden_topics=True)
        try:
            expanded_name = expand_topic_name(topic_name, node.get_name(),
                                              node.get_namespace())
        except ValueError as e:
            raise RuntimeError(e)
        try:
            validate_full_topic_name(expanded_name)
        except rclpy.exceptions.InvalidTopicNameException as e:
            raise RuntimeError(e)
        for n, t in topic_names_and_types:
            if n == expanded_name:
                if len(t) > 1:
                    raise RuntimeError(
                        "Cannot echo topic '%s', as it contains more than one type: [%s]"
                        % (topic_name, ', '.join(t)))
                message_type = t[0]
                break
        else:
            raise RuntimeError(
                'Could not determine the type for the passed topic')

    msg_module = get_message(message_type)

    subscription_callbacks = SubscriptionEventCallbacks(
        incompatible_qos=handle_incompatible_qos_event)
    try:
        node.create_subscription(msg_module,
                                 topic_name,
                                 callback,
                                 qos_profile,
                                 event_callbacks=subscription_callbacks)
    except UnsupportedEventTypeError:
        node.create_subscription(msg_module, topic_name, callback, qos_profile)

    rclpy.spin(node)
Exemplo n.º 10
0
def subscriber(node: Node, topic_name: str, message_type: MsgType,
               callback: Callable[[MsgType], Any], qos_profile: QoSProfile,
               report_lost_messages: bool, raw: bool) -> Optional[str]:
    """Initialize a node with a single subscription and spin."""
    event_callbacks = None
    if report_lost_messages:
        event_callbacks = SubscriptionEventCallbacks(
            message_lost=message_lost_event_callback)
    try:
        node.create_subscription(message_type,
                                 topic_name,
                                 callback,
                                 qos_profile,
                                 event_callbacks=event_callbacks,
                                 raw=raw)
    except UnsupportedEventTypeError:
        assert report_lost_messages
        print(f"The rmw implementation '{get_rmw_implementation_identifier()}'"
              ' does not support reporting lost messages')
    rclpy.spin(node)
Exemplo n.º 11
0
    def __init__(
        self,
        subscription_handle: Handle,
        msg_type: MsgType,
        topic: str,
        callback: Callable,
        callback_group: CallbackGroup,
        qos_profile: QoSProfile,
        raw: bool,
        event_callbacks: SubscriptionEventCallbacks,
    ) -> None:
        """
        Create a container for a ROS subscription.

        .. warning:: Users should not create a subscription with this constructor, instead they
           should call :meth:`.Node.create_subscription`.

        :param subscription_handle: :class:`Handle` wrapping the underlying ``rcl_subscription_t``
            object.
        :param msg_type: The type of ROS messages the subscription will subscribe to.
        :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 callback_group: The callback group for the subscription. If ``None``, then the
            nodes default callback group is used.
        :param qos_profile: The quality of service profile to apply to the subscription.
        :param raw: If ``True``, then received messages will be stored in raw binary
            representation.
        """
        self.__handle = subscription_handle
        self.msg_type = msg_type
        self.topic = topic
        self.callback = callback
        self.callback_group = callback_group
        # True when the callback is ready to fire but has not been "taken" by an executor
        self._executor_event = False
        self.qos_profile = qos_profile
        self.raw = raw

        self.event_handlers: QoSEventHandler = event_callbacks.create_event_handlers(
            callback_group, subscription_handle, topic)
Exemplo n.º 12
0
def main(args=None):
    # Argument parsing and usage
    parser = get_parser()
    parsed_args = parser.parse_args()

    # Configuration variables
    qos_policy_name = parsed_args.incompatible_qos_policy_name
    qos_profile_publisher = QoSProfile(depth=10)
    qos_profile_subscription = QoSProfile(depth=10)

    if qos_policy_name == 'durability':
        print('Durability incompatibility selected.\n'
              'Incompatibility condition: publisher durability kind <'
              'subscripition durability kind.\n'
              'Setting publisher durability to: VOLATILE\n'
              'Setting subscription durability to: TRANSIENT_LOCAL\n')
        qos_profile_publisher.durability = \
            QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_VOLATILE
        qos_profile_subscription.durability = \
            QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL
    elif qos_policy_name == 'deadline':
        print(
            'Deadline incompatibility selected.\n'
            'Incompatibility condition: publisher deadline > subscription deadline.\n'
            'Setting publisher durability to: 2 seconds\n'
            'Setting subscription durability to: 1 second\n')
        qos_profile_publisher.deadline = Duration(seconds=2)
        qos_profile_subscription.deadline = Duration(seconds=1)
    elif qos_policy_name == 'liveliness_policy':
        print('Liveliness Policy incompatibility selected.\n'
              'Incompatibility condition: publisher liveliness policy <'
              'subscripition liveliness policy.\n'
              'Setting publisher liveliness policy to: AUTOMATIC\n'
              'Setting subscription liveliness policy to: MANUAL_BY_TOPIC\n')
        qos_profile_publisher.liveliness = \
            QoSLivelinessPolicy.RMW_QOS_POLICY_LIVELINESS_AUTOMATIC
        qos_profile_subscription.liveliness = \
            QoSLivelinessPolicy.RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC
    elif qos_policy_name == 'liveliness_lease_duration':
        print(
            'Liveliness lease duration incompatibility selected.\n'
            'Incompatibility condition: publisher liveliness lease duration >'
            'subscription liveliness lease duration.\n'
            'Setting publisher liveliness lease duration to: 2 seconds\n'
            'Setting subscription liveliness lease duration to: 1 second\n')
        qos_profile_publisher.liveliness_lease_duration = Duration(seconds=2)
        qos_profile_subscription.liveliness_lease_duration = Duration(
            seconds=1)
    elif qos_policy_name == 'reliability':
        print(
            'Reliability incompatibility selected.\n'
            'Incompatibility condition: publisher reliability < subscripition reliability.\n'
            'Setting publisher reliability to: BEST_EFFORT\n'
            'Setting subscription reliability to: RELIABLE\n')
        qos_profile_publisher.reliability = \
            QoSReliabilityPolicy.RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT
        qos_profile_subscription.reliability = \
            QoSReliabilityPolicy.RMW_QOS_POLICY_RELIABILITY_RELIABLE
    else:
        print('{name} not recognised.'.format(name=qos_policy_name))
        parser.print_help()
        return 0

    # Initialization and configuration
    rclpy.init(args=args)
    topic = 'incompatible_qos_chatter'
    num_msgs = 5

    publisher_callbacks = PublisherEventCallbacks(
        incompatible_qos=lambda event: get_logger('Talker').info(str(event)))
    subscription_callbacks = SubscriptionEventCallbacks(
        incompatible_qos=lambda event: get_logger('Listener').info(str(event)))

    try:
        talker = Talker(topic,
                        qos_profile_publisher,
                        event_callbacks=publisher_callbacks,
                        publish_count=num_msgs)
        listener = Listener(topic,
                            qos_profile_subscription,
                            event_callbacks=subscription_callbacks)
    except UnsupportedEventTypeError as exc:
        print()
        print(exc, end='\n\n')
        print('Please try this demo using a different RMW implementation')
        return -1

    executor = SingleThreadedExecutor()
    executor.add_node(listener)
    executor.add_node(talker)

    try:
        while talker.publish_count < num_msgs:
            executor.spin_once()
    except KeyboardInterrupt:
        pass

    rclpy.shutdown()

    return 0