diff --git a/ros2param/test/test_verb_dump.py b/ros2param/test/test_verb_dump.py index 00e2fd5e8..0704d3fc8 100644 --- a/ros2param/test/test_verb_dump.py +++ b/ros2param/test/test_verb_dump.py @@ -32,6 +32,7 @@ import pytest import rclpy +from rclpy.utilities import get_available_rmw_implementations from ros2cli.node.strategy import NodeStrategy @@ -54,10 +55,9 @@ ' use_sim_time: false\n' ) -# TODO(jacobperron): Enable testing with all RMW implementations when they pass -# @launch_testing.parametrize('rmw_implementation', get_available_rmw_implementations()) + @pytest.mark.rostest -@launch_testing.parametrize('rmw_implementation', ['rmw_fastrtps_cpp']) +@launch_testing.parametrize('rmw_implementation', get_available_rmw_implementations()) def generate_test_description(rmw_implementation): path_to_fixtures = os.path.join(os.path.dirname(__file__), 'fixtures') additional_env = {'RMW_IMPLEMENTATION': rmw_implementation}