Skip to content
Closed
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
23 changes: 13 additions & 10 deletions controller_manager/test/test_ros2_control_node_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,13 +30,13 @@

import pytest
import unittest
import os
import launch_testing
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

do we use this?


from ament_index_python.packages import get_package_share_directory, get_package_prefix
from launch import LaunchDescription
from launch_testing.actions import ReadyToTest
import launch_testing.markers
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think we still need this for @pytest.mark.launch_test?

import launch_ros.actions
from launch.substitutions import PathSubstitution
from launch_ros.substitutions import FindPackageShare

import rclpy
from controller_manager.test_utils import (
Expand All @@ -50,8 +50,10 @@
@pytest.mark.launch_test
def generate_test_description():

robot_controllers = os.path.join(
get_package_prefix("controller_manager"), "test", "test_ros2_control_node.yaml"
robot_controllers = (
PathSubstitution(FindPackageShare("controller_manager"))
/ "test"
/ "test_ros2_control_node.yaml"
)

control_node = launch_ros.actions.Node(
Expand All @@ -63,12 +65,13 @@ def generate_test_description():
],
output="both",
)
# Get URDF, without involving xacro
urdf = os.path.join(
get_package_share_directory("ros2_control_test_assets"),
"urdf",
"test_hardware_components.urdf",

urdf = (
PathSubstitution(FindPackageShare("ros2_control_test_assets"))
/ "urdf"
/ "test_hardware_components.urdf"
)

with open(urdf) as infp:
robot_description_content = infp.read()
robot_description = {"robot_description": robot_description_content}
Expand Down