From 6f1836b82a38ca0976a9fc7c705dca55df9c2f11 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Sat, 11 May 2024 19:48:19 +0200 Subject: [PATCH] Fix dependencies for source build (#1533) * Don't use std::system call inside test * Give launch_ros as explicit dependency * Test the source build on this branch * Revert "Test the source build on this branch" This reverts commit 9884b112257fc2626d1d03ba523d02247c6f258e. (cherry picked from commit e2600490481092ba2709c5ac9cb1b36b1032a4bc) --- controller_interface/test/test_controller_interface.cpp | 3 ++- joint_limits/package.xml | 1 + 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/controller_interface/test/test_controller_interface.cpp b/controller_interface/test/test_controller_interface.cpp index f27fc43283..567efe52ff 100644 --- a/controller_interface/test/test_controller_interface.cpp +++ b/controller_interface/test/test_controller_interface.cpp @@ -82,7 +82,8 @@ TEST(TestableControllerInterface, setting_update_rate_in_configure) ASSERT_EQ(controller.get_update_rate(), 2812u); // Test updating of update_rate parameter - EXPECT_EQ(std::system("ros2 param set /testable_controller_interface update_rate 623"), 0); + auto res = controller.get_node()->set_parameter(rclcpp::Parameter("update_rate", 623)); + EXPECT_EQ(res.successful, true); // Keep the same update rate until transition from 'UNCONFIGURED' TO 'INACTIVE' does not happen controller.configure(); // No transition so the update rate should stay intact ASSERT_NE(controller.get_update_rate(), 623u); diff --git a/joint_limits/package.xml b/joint_limits/package.xml index 312a0d3f45..f1d1cdfc77 100644 --- a/joint_limits/package.xml +++ b/joint_limits/package.xml @@ -17,6 +17,7 @@ rclcpp rclcpp_lifecycle + launch_ros launch_testing_ament_cmake ament_cmake_gtest