ros2cli.qos module

ros2cli.qos.add_qos_arguments(parser: ArgumentParser, entity_type: str, default_profile_str: str = 'default', extra_message: str = '') None
ros2cli.qos.choose_qos(node, topic_name: str, qos_args)
ros2cli.qos.profile_configure_short_keys(profile: rclpy.qos.QoSProfile = None, reliability: str | None = None, durability: str | None = None, depth: int | None = None, history: str | None = None, liveliness: str | None = None, liveliness_lease_duration_s: int | None = None) None

Configure a QoSProfile given a profile, and optional overrides.

ros2cli.qos.qos_profile_from_short_keys(preset_profile: str, reliability: str | None = None, durability: str | None = None, depth: int | None = None, history: str | None = None, liveliness: str | None = None, liveliness_lease_duration_s: float | None = None) rclpy.qos.QoSProfile

Construct a QoSProfile given the name of a preset, and optional overrides.