Skip to content

Commit

Permalink
Fix dependencies for source build (#1533)
Browse files Browse the repository at this point in the history
* 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 9884b11.
  • Loading branch information
christophfroehlich authored May 11, 2024
1 parent ac5dfb4 commit e260049
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 1 deletion.
3 changes: 2 additions & 1 deletion controller_interface/test/test_controller_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,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);
Expand Down
1 change: 1 addition & 0 deletions joint_limits/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
<depend>rclcpp_lifecycle</depend>
<depend>urdf</depend>

<test_depend>launch_ros</test_depend>
<test_depend>launch_testing_ament_cmake</test_depend>
<test_depend>ament_cmake_gtest</test_depend>

Expand Down

0 comments on commit e260049

Please sign in to comment.