Skip to content

Commit

Permalink
Parameterize tests on rmw implementation
Browse files Browse the repository at this point in the history
Signed-off-by: Jacob Perron <[email protected]>
  • Loading branch information
jacobperron committed Apr 15, 2020
1 parent 5b0da73 commit 6643e55
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions ros2param/test/test_verb_dump.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
import pytest

import rclpy
from rclpy.utilities import get_available_rmw_implementations

from ros2cli.node.strategy import NodeStrategy

Expand All @@ -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}
Expand Down

0 comments on commit 6643e55

Please sign in to comment.