Skip to content

Commit

Permalink
Remove separate test launch file
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Jul 22, 2024
1 parent d4540d1 commit f3d69c8
Show file tree
Hide file tree
Showing 3 changed files with 18 additions and 58 deletions.
2 changes: 1 addition & 1 deletion controller_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -211,7 +211,7 @@ if(BUILD_TESTING)
)

find_package(ament_cmake_pytest REQUIRED)
install(FILES test/test_ros2_control_node.yaml test/cm.launch.py
install(FILES test/test_ros2_control_node.yaml
DESTINATION test)
ament_add_pytest_test(test_ros2_control_node test/test_ros2_control_node_launch.py)
endif()
Expand Down
45 changes: 0 additions & 45 deletions controller_manager/test/cm.launch.py

This file was deleted.

29 changes: 17 additions & 12 deletions controller_manager/test/test_ros2_control_node_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,36 +28,41 @@
#
# Author: Christoph Froehlich

import os
import pytest
import unittest
import time

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import PathJoinSubstitution
from launch_ros.substitutions import FindPackageShare
from launch_testing.actions import ReadyToTest

import launch_testing.markers
import rclpy
import launch_ros.actions
from rclpy.node import Node


# Executes the given launch file and checks if all nodes can be started
@pytest.mark.launch_test
def generate_test_description():

launch_include = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(
get_package_share_directory("controller_manager"),
"../../test/cm.launch.py",
)
),
robot_controllers = PathJoinSubstitution(
[
FindPackageShare("controller_manager"),
"test",
"test_ros2_control_node.yaml",
]
)

return LaunchDescription([launch_include, ReadyToTest()])
control_node = launch_ros.actions.Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_controllers],
output="both",
)

return LaunchDescription([control_node, ReadyToTest()])


# This is our test fixture. Each method is a test case.
Expand Down

0 comments on commit f3d69c8

Please sign in to comment.