Skip to content

Commit

Permalink
Clean up test targets (#160)
Browse files Browse the repository at this point in the history
  • Loading branch information
mvukov authored Aug 6, 2023
1 parent a93e1e0 commit 097defd
Show file tree
Hide file tree
Showing 11 changed files with 20 additions and 0 deletions.
2 changes: 2 additions & 0 deletions examples/chatter/tests.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,12 @@
import launch
import launch_ros.actions
import launch_testing.actions
import launch_testing.markers
import rclpy
import std_msgs.msg


@launch_testing.markers.keep_alive
def generate_test_description():
talker_node = launch_ros.actions.Node(executable='chatter/talker',
parameters=[
Expand Down
1 change: 1 addition & 0 deletions examples/lifecycle/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ ros2_launch(

ros2_test(
name = "tests",
size = "small",
launch_file = "tests.py",
nodes = [
":lifecycle_listener",
Expand Down
2 changes: 2 additions & 0 deletions examples/lifecycle/tests.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,11 +20,13 @@
import launch_ros.events.lifecycle
import launch_testing.actions
import launch_testing.asserts
import launch_testing.markers
import lifecycle_msgs.msg

_Transition = lifecycle_msgs.msg.Transition


@launch_testing.markers.keep_alive
def generate_test_description():
talker_node = launch_ros.actions.LifecycleNode(
executable='lifecycle/lifecycle_talker',
Expand Down
2 changes: 2 additions & 0 deletions examples/zero_copy/tests.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,11 @@
import launch_ros.actions
import launch_testing.actions
import launch_testing.asserts
import launch_testing.markers
import zero_copy.roudi


@launch_testing.markers.keep_alive
def generate_test_description():
talker_tests_node = launch_ros.actions.Node(
executable='zero_copy/talker_tests',
Expand Down
1 change: 1 addition & 0 deletions repositories/private/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@ py_binary(

py_test(
name = "tests",
size = "small",
srcs = ["ros2_repo_mappings_tests.py"],
data = ["@com_github_mvukov_rules_ros2//repositories:ros2_repo_mappings.yaml"],
main = "ros2_repo_mappings_tests.py",
Expand Down
1 change: 1 addition & 0 deletions ros2/test/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,7 @@ ros2_cpp_test(

ros2_cpp_test(
name = "generic_publisher_tests",
size = "small",
srcs = ["generic_publisher_tests.cc"],
idl_deps = [
"@ros2_common_interfaces//:std_msgs",
Expand Down
1 change: 1 addition & 0 deletions ros2/test/image_common/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@ load("@com_github_mvukov_rules_ros2//ros2:test.bzl", "ros2_test")

ros2_cpp_test(
name = "image_transport_plugins_tests",
size = "small",
srcs = ["image_transport_plugins_tests.cc"],
set_up_ament = True,
deps = [
Expand Down
5 changes: 5 additions & 0 deletions ros2/test/pluginlib/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ ros2_plugin(

ros2_cpp_test(
name = "tests",
size = "small",
srcs = ["plugin_tests.cc"],
data = [
":square",
Expand All @@ -67,6 +68,7 @@ ros2_cpp_binary(

ros2_py_test(
name = "py_loader_tests",
size = "small",
srcs = [
"py_loader_tests.py",
],
Expand Down Expand Up @@ -96,6 +98,7 @@ ros2_cpp_binary(

sh_test(
name = "ros2_cpp_binary_test",
size = "small",
srcs = ["ros2_cpp_binary_test.sh"],
data = [
":plugin_tests_binary",
Expand All @@ -118,6 +121,7 @@ ros2_py_binary(

sh_test(
name = "ros2_py_library_test",
size = "small",
srcs = [
"ros2_py_binary_test.sh",
],
Expand All @@ -142,6 +146,7 @@ cpp_ament_setup_library(

cc_test(
name = "ament_setup_library_tests",
size = "small",
srcs = ["ament_setup_library_tests.cc"],
deps = [
":polygon_base",
Expand Down
2 changes: 2 additions & 0 deletions ros2/test/rosbag/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@ ros2_bag(
":publisher",
":recorder",
],
tags = ["cpu:2"],
deps = [requirement("pyyaml")],
)
for storage_id in [
Expand All @@ -63,6 +64,7 @@ ros2_bag(

ros2_py_test(
name = "write_to_bag_tests",
size = "small",
srcs = ["write_to_bag_tests.py"],
main = "write_to_bag_tests.py",
set_up_ament = True,
Expand Down
1 change: 1 addition & 0 deletions ros2/test/xacro/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ xacro(

py_test(
name = "tests",
size = "small",
srcs = ["tests.py"],
data = [
":test_include",
Expand Down
2 changes: 2 additions & 0 deletions third_party/foxglove_bridge/tests.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,10 @@
import launch_ros.actions
import launch_testing.actions
import launch_testing.asserts
import launch_testing.markers


@launch_testing.markers.keep_alive
def generate_test_description():
test_node = launch_ros.actions.Node(
executable='third_party/foxglove_bridge/foxglove_bridge_tests',
Expand Down

0 comments on commit 097defd

Please sign in to comment.