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