From bd24d4c307d465df41a47f3c86ffb5225217e810 Mon Sep 17 00:00:00 2001 From: rafal-gorecki Date: Fri, 26 Apr 2024 12:07:31 +0200 Subject: [PATCH] typo --- .../test/test_diff_drive_controller.cpp | 15 +++++++-------- 1 file changed, 7 insertions(+), 8 deletions(-) diff --git a/diff_drive_controller/test/test_diff_drive_controller.cpp b/diff_drive_controller/test/test_diff_drive_controller.cpp index 527d595ea6..dc6f5ee106 100644 --- a/diff_drive_controller/test/test_diff_drive_controller.cpp +++ b/diff_drive_controller/test/test_diff_drive_controller.cpp @@ -257,6 +257,8 @@ TEST_F(TestDiffDriveController, configure_succeeds_when_wheels_are_specified) TEST_F(TestDiffDriveController, TfPrefixNamespaceParams) { + std::string odom_id = "odom"; + std::string base_link_id = "base_link"; const std::vector test_cases = { {"", "", ""}, {"/", "", ""}, @@ -270,18 +272,15 @@ TEST_F(TestDiffDriveController, TfPrefixNamespaceParams) for (const auto & test_case : test_cases) { - std::string odom_id = "odom"; - std::string base_link_id = "base_link"; - std::vector params = { - rclcpp::Parameter("tf_frame_prefix", test_case.tf_prefix), - rclcpp::Parameter("odom_frame_id", odom_id), - rclcpp::Parameter("base_frame_id", base_link_id), - } + rclcpp::Parameter("tf_frame_prefix", rclcpp::ParameterValue(test_case.tf_prefix)), + rclcpp::Parameter("odom_frame_id", rclcpp::ParameterValue(odom_id)), + rclcpp::Parameter("base_frame_id", rclcpp::ParameterValue(base_link_id)), + }; ASSERT_EQ( - InitController(parameters = params, ns = test_case.ns), + InitController(left_wheel_names, right_wheel_names, params, test_case.ns), controller_interface::return_type::OK); ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);