rclpy.subscription module

class rclpy.subscription.MessageInfo

Bases: TypedDict

publication_sequence_number: int | None
publisher_gid: dict | None
received_timestamp: int
reception_sequence_number: int | None
source_timestamp: int
class rclpy.subscription.Subscription(subscription_impl: rpyutils.import_c_library.Subscription.~MsgT, msg_type: ~typing.Type[~rclpy.type_support.MsgT], topic: str, callback: ~typing.Callable[[~rclpy.type_support.MsgT], None] | ~typing.Callable[[~rclpy.type_support.MsgT, ~rclpy.subscription.MessageInfo], None], callback_group: ~rclpy.callback_groups.CallbackGroup, qos_profile: rclpy.qos.QoSProfile, raw: bool, event_callbacks: ~rclpy.event_handler.SubscriptionEventCallbacks)

Bases: Generic[MsgT]

Create a container for a ROS subscription.

Warning

Users should not create a subscription with this constructor, instead they should call Node.create_subscription().

Parameters:
  • subscription_implSubscription wrapping the underlying rcl_subscription_t object.

  • msg_type – The type of ROS messages the subscription will subscribe to.

  • topic – The name of the topic the subscription will subscribe to.

  • callback – A user-defined callback function that is called when a message is received by the subscription.

  • callback_group – The callback group for the subscription. If None, then the nodes default callback group is used.

  • qos_profile – The quality of service profile to apply to the subscription.

  • raw – If True, then received messages will be stored in raw binary representation.

class CallbackType(*values)

Bases: Enum

MessageOnly = 0
WithMessageInfo = 1
property callback: Callable[[MsgT], None] | Callable[[MsgT, MessageInfo], None]
destroy() None

Destroy a container for a ROS subscription.

Warning

Users should not destroy a subscription with this method, instead they should call Node.destroy_subscription().

get_content_filter() ContentFilterOptions

Get the filter expression and expression parameters for the subscription.

Returns:

ContentFilterOptions object containing the filter expression and expression parameters.

Raises:

RCLError if internal error occurred when calling the rcl function.

get_publisher_count() int

Get the number of publishers that this subscription has.

property handle: rpyutils.import_c_library.Subscription.~MsgT
property is_cft_enabled: bool

Check if content filtering is enabled for the subscription.

property logger_name: str

Get the name of the logger associated with the node of the subscription.

set_content_filter(filter_expression: str, expression_parameters: list[str]) None

Set the filter expression and expression parameters for the subscription.

Parameters:
  • filter_expression – The filter expression to set.

  • expression_parameters – The expression parameters to set.

Raises:

RCLError if internal error occurred when calling the rcl function.

property topic_name: str