diff --git a/ros2topic/test/test_qos_conversions.py b/ros2topic/test/test_qos_conversions.py index d3a5ebb68..bd41a8e3f 100644 --- a/ros2topic/test/test_qos_conversions.py +++ b/ros2topic/test/test_qos_conversions.py @@ -12,20 +12,29 @@ # See the License for the specific language governing permissions and # limitations under the License. +import pytest import rclpy from ros2topic.api import duration_ns from ros2topic.api import qos_profile_from_short_keys +liveliness_options = [ + ('automatic', rclpy.qos.LivelinessPolicy.AUTOMATIC), + ('system_default', rclpy.qos.LivelinessPolicy.SYSTEM_DEFAULT), + ('manual_by_topic', rclpy.qos.LivelinessPolicy.MANUAL_BY_TOPIC), + ('unknown', rclpy.qos.LivelinessPolicy.UNKNOWN) +] -def test_profile_conversion(): + +@pytest.mark.parametrize('liveliness,expected_liveliness', liveliness_options) +def test_profile_conversion(liveliness, expected_liveliness): profile = qos_profile_from_short_keys( 'sensor_data', reliability='reliable', durability='transient_local', - depth=10, history='keep_last', liveliness='automatic', + depth=10, history='keep_last', liveliness=liveliness, liveliness_lease_duration=duration_ns(1e9)) assert profile.durability == rclpy.qos.QoSDurabilityPolicy.TRANSIENT_LOCAL assert profile.reliability == rclpy.qos.QoSReliabilityPolicy.RELIABLE assert profile.depth == 10 assert profile.history == rclpy.qos.QoSHistoryPolicy.KEEP_LAST - assert profile.liveliness == rclpy.qos.QoSLivelinessPolicy.RMW_QOS_POLICY_LIVELINESS_AUTOMATIC + assert profile.liveliness == expected_liveliness assert profile.liveliness_lease_duration == rclpy.duration.Duration(nanoseconds=1e9)