Skip to content

Commit

Permalink
Fix API in tests
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Oct 31, 2024
1 parent f5c4bff commit 3bf0c20
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 5 deletions.
6 changes: 4 additions & 2 deletions pose_broadcaster/test/test_load_pose_broadcaster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,10 @@ TEST(TestLoadPoseBroadcaster, load_controller)
std::shared_ptr<rclcpp::Executor> executor =
std::make_shared<rclcpp::executors::SingleThreadedExecutor>();

controller_manager::ControllerManager cm{
executor, ros2_control_test_assets::minimal_robot_urdf, true, "test_controller_manager"};
controller_manager::ControllerManager cm(
std::make_unique<hardware_interface::ResourceManager>(
ros2_control_test_assets::minimal_robot_urdf),
executor, "test_controller_manager");

const std::string test_file_path =
std::string{TEST_FILES_DIRECTORY} + "/pose_broadcaster_params.yaml";
Expand Down
4 changes: 1 addition & 3 deletions pose_broadcaster/test/test_pose_broadcaster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,7 @@ void PoseBroadcasterTest::TearDown() { pose_broadcaster_.reset(nullptr); }
void PoseBroadcasterTest::SetUpPoseBroadcaster()
{
ASSERT_EQ(
pose_broadcaster_->init(
"test_pose_broadcaster", "", 0, "", pose_broadcaster_->define_custom_node_options()),
controller_interface::return_type::OK);
pose_broadcaster_->init("test_pose_broadcaster"), controller_interface::return_type::OK);

std::vector<LoanedStateInterface> state_interfaces;
state_interfaces.emplace_back(pose_position_x_);
Expand Down

0 comments on commit 3bf0c20

Please sign in to comment.