From 9d67f139bc7f69d104710e4e996a044c9cc592bb Mon Sep 17 00:00:00 2001 From: Surya! Date: Wed, 19 Nov 2025 00:53:17 +0530 Subject: [PATCH] Rename joint_reference_interfaces to reference_interface_names (#2008) (cherry picked from commit 6ddb0b40acbdbf19b4427294469860c94ce96781) # Conflicts: # ackermann_steering_controller/test/test_ackermann_steering_controller.cpp # ackermann_steering_controller/test/test_ackermann_steering_controller.hpp # ackermann_steering_controller/test/test_ackermann_steering_controller_preceding.cpp # bicycle_steering_controller/test/test_bicycle_steering_controller.cpp # bicycle_steering_controller/test/test_bicycle_steering_controller.hpp # bicycle_steering_controller/test/test_bicycle_steering_controller_preceding.cpp # steering_controllers_library/test/test_steering_controllers_library.cpp # steering_controllers_library/test/test_steering_controllers_library.hpp # tricycle_steering_controller/test/test_tricycle_steering_controller.cpp # tricycle_steering_controller/test/test_tricycle_steering_controller.hpp # tricycle_steering_controller/test/test_tricycle_steering_controller_preceding.cpp --- .../test_ackermann_steering_controller.cpp | 24 +++++++++++++++++-- .../test_ackermann_steering_controller.hpp | 6 +++++ ...ckermann_steering_controller_preceding.cpp | 14 +++++++++-- .../test/test_bicycle_steering_controller.cpp | 24 +++++++++++++++++-- .../test/test_bicycle_steering_controller.hpp | 6 +++++ ..._bicycle_steering_controller_preceding.cpp | 14 +++++++++-- .../test_steering_controllers_library.cpp | 14 +++++++++-- .../test_steering_controllers_library.hpp | 4 ++++ .../test_tricycle_steering_controller.cpp | 24 +++++++++++++++++++ .../test_tricycle_steering_controller.hpp | 6 +++++ ...tricycle_steering_controller_preceding.cpp | 14 +++++++++++ 11 files changed, 140 insertions(+), 10 deletions(-) diff --git a/ackermann_steering_controller/test/test_ackermann_steering_controller.cpp b/ackermann_steering_controller/test/test_ackermann_steering_controller.cpp index de45accc0a..5757a76298 100644 --- a/ackermann_steering_controller/test/test_ackermann_steering_controller.cpp +++ b/ackermann_steering_controller/test/test_ackermann_steering_controller.cpp @@ -86,14 +86,24 @@ TEST_F(AckermannSteeringControllerTest, check_exported_interfaces) // check ref itfs auto reference_interfaces = controller_->export_reference_interfaces(); - ASSERT_EQ(reference_interfaces.size(), joint_reference_interfaces_.size()); - for (size_t i = 0; i < joint_reference_interfaces_.size(); ++i) + ASSERT_EQ(reference_interfaces.size(), reference_interface_names_.size()); + for (size_t i = 0; i < reference_interface_names_.size(); ++i) { +<<<<<<< HEAD const std::string ref_itf_name = std::string(controller_->get_node()->get_name()) + "/" + joint_reference_interfaces_[i]; EXPECT_EQ(reference_interfaces[i].get_name(), ref_itf_name); EXPECT_EQ(reference_interfaces[i].get_prefix_name(), controller_->get_node()->get_name()); EXPECT_EQ(reference_interfaces[i].get_interface_name(), joint_reference_interfaces_[i]); +======= + const std::string ref_itf_prefix_name = + std::string(controller_->get_node()->get_name()) + "/" + reference_interface_names_[i]; + EXPECT_EQ( + reference_interfaces[i]->get_name(), + ref_itf_prefix_name + "/" + hardware_interface::HW_IF_VELOCITY); + EXPECT_EQ(reference_interfaces[i]->get_prefix_name(), ref_itf_prefix_name); + EXPECT_EQ(reference_interfaces[i]->get_interface_name(), hardware_interface::HW_IF_VELOCITY); +>>>>>>> 6ddb0b4 (Rename joint_reference_interfaces to reference_interface_names (#2008)) } } @@ -187,8 +197,13 @@ TEST_F(AckermannSteeringControllerTest, test_update_logic) controller_->command_interfaces_[CMD_STEER_LEFT_WHEEL].get_value(), 1.4179821977774734, COMMON_THRESHOLD); +<<<<<<< HEAD EXPECT_FALSE(std::isnan((*(controller_->input_ref_.readFromRT()))->twist.linear.x)); EXPECT_EQ(controller_->reference_interfaces_.size(), joint_reference_interfaces_.size()); +======= + EXPECT_FALSE(std::isnan(controller_->input_ref_.get().twist.linear.x)); + EXPECT_EQ(controller_->reference_interfaces_.size(), reference_interface_names_.size()); +>>>>>>> 6ddb0b4 (Rename joint_reference_interfaces to reference_interface_names (#2008)) for (const auto & interface : controller_->reference_interfaces_) { EXPECT_TRUE(std::isnan(interface)); @@ -227,8 +242,13 @@ TEST_F(AckermannSteeringControllerTest, test_update_logic_chained) controller_->command_interfaces_[STATE_STEER_LEFT_WHEEL].get_value(), 1.4179821977774734, COMMON_THRESHOLD); +<<<<<<< HEAD EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromRT()))->twist.linear.x)); EXPECT_EQ(controller_->reference_interfaces_.size(), joint_reference_interfaces_.size()); +======= + EXPECT_TRUE(std::isnan(controller_->input_ref_.get().twist.linear.x)); + EXPECT_EQ(controller_->reference_interfaces_.size(), reference_interface_names_.size()); +>>>>>>> 6ddb0b4 (Rename joint_reference_interfaces to reference_interface_names (#2008)) for (const auto & interface : controller_->reference_interfaces_) { EXPECT_TRUE(std::isnan(interface)); diff --git a/ackermann_steering_controller/test/test_ackermann_steering_controller.hpp b/ackermann_steering_controller/test/test_ackermann_steering_controller.hpp index 389cb67f2e..c2bfaf8b1c 100644 --- a/ackermann_steering_controller/test/test_ackermann_steering_controller.hpp +++ b/ackermann_steering_controller/test/test_ackermann_steering_controller.hpp @@ -302,9 +302,15 @@ class AckermannSteeringControllerFixture : public ::testing::Test double front_wheels_radius_ = 0.45; double rear_wheels_radius_ = 0.45; +<<<<<<< HEAD std::array joint_state_values_ = {0.5, 0.5, 0.0, 0.0}; std::array joint_command_values_ = {1.1, 3.3, 2.2, 4.4}; std::array joint_reference_interfaces_ = {"linear/velocity", "angular/velocity"}; +======= + std::array joint_state_values_ = {{0.5, 0.5, 0.0, 0.0}}; + std::array joint_command_values_ = {{1.1, 3.3, 2.2, 4.4}}; + std::array reference_interface_names_ = {{"linear", "angular"}}; +>>>>>>> 6ddb0b4 (Rename joint_reference_interfaces to reference_interface_names (#2008)) std::string steering_interface_name_ = "position"; // defined in setup std::string traction_interface_name_ = ""; diff --git a/ackermann_steering_controller/test/test_ackermann_steering_controller_preceding.cpp b/ackermann_steering_controller/test/test_ackermann_steering_controller_preceding.cpp index 54ee7e4062..ea39c9aaf7 100644 --- a/ackermann_steering_controller/test/test_ackermann_steering_controller_preceding.cpp +++ b/ackermann_steering_controller/test/test_ackermann_steering_controller_preceding.cpp @@ -88,14 +88,24 @@ TEST_F(AckermannSteeringControllerTest, check_exported_interfaces) // check ref itfs auto reference_interfaces = controller_->export_reference_interfaces(); - ASSERT_EQ(reference_interfaces.size(), joint_reference_interfaces_.size()); - for (size_t i = 0; i < joint_reference_interfaces_.size(); ++i) + ASSERT_EQ(reference_interfaces.size(), reference_interface_names_.size()); + for (size_t i = 0; i < reference_interface_names_.size(); ++i) { +<<<<<<< HEAD const std::string ref_itf_name = std::string(controller_->get_node()->get_name()) + "/" + joint_reference_interfaces_[i]; EXPECT_EQ(reference_interfaces[i].get_name(), ref_itf_name); EXPECT_EQ(reference_interfaces[i].get_prefix_name(), controller_->get_node()->get_name()); EXPECT_EQ(reference_interfaces[i].get_interface_name(), joint_reference_interfaces_[i]); +======= + const std::string ref_itf_prefix_name = + std::string(controller_->get_node()->get_name()) + "/" + reference_interface_names_[i]; + EXPECT_EQ( + reference_interfaces[i]->get_name(), + ref_itf_prefix_name + "/" + hardware_interface::HW_IF_VELOCITY); + EXPECT_EQ(reference_interfaces[i]->get_prefix_name(), ref_itf_prefix_name); + EXPECT_EQ(reference_interfaces[i]->get_interface_name(), hardware_interface::HW_IF_VELOCITY); +>>>>>>> 6ddb0b4 (Rename joint_reference_interfaces to reference_interface_names (#2008)) } } diff --git a/bicycle_steering_controller/test/test_bicycle_steering_controller.cpp b/bicycle_steering_controller/test/test_bicycle_steering_controller.cpp index a06aabbd20..a45134c248 100644 --- a/bicycle_steering_controller/test/test_bicycle_steering_controller.cpp +++ b/bicycle_steering_controller/test/test_bicycle_steering_controller.cpp @@ -70,14 +70,24 @@ TEST_F(BicycleSteeringControllerTest, check_exported_interfaces) // check ref itfs auto reference_interfaces = controller_->export_reference_interfaces(); - ASSERT_EQ(reference_interfaces.size(), joint_reference_interfaces_.size()); - for (size_t i = 0; i < joint_reference_interfaces_.size(); ++i) + ASSERT_EQ(reference_interfaces.size(), reference_interface_names_.size()); + for (size_t i = 0; i < reference_interface_names_.size(); ++i) { +<<<<<<< HEAD const std::string ref_itf_name = std::string(controller_->get_node()->get_name()) + "/" + joint_reference_interfaces_[i]; EXPECT_EQ(reference_interfaces[i].get_name(), ref_itf_name); EXPECT_EQ(reference_interfaces[i].get_prefix_name(), controller_->get_node()->get_name()); EXPECT_EQ(reference_interfaces[i].get_interface_name(), joint_reference_interfaces_[i]); +======= + const std::string ref_itf_prefix_name = + std::string(controller_->get_node()->get_name()) + "/" + reference_interface_names_[i]; + EXPECT_EQ( + reference_interfaces[i]->get_name(), + ref_itf_prefix_name + "/" + hardware_interface::HW_IF_VELOCITY); + EXPECT_EQ(reference_interfaces[i]->get_prefix_name(), ref_itf_prefix_name); + EXPECT_EQ(reference_interfaces[i]->get_interface_name(), hardware_interface::HW_IF_VELOCITY); +>>>>>>> 6ddb0b4 (Rename joint_reference_interfaces to reference_interface_names (#2008)) } } @@ -163,8 +173,13 @@ TEST_F(BicycleSteeringControllerTest, test_update_logic) controller_->command_interfaces_[CMD_STEER_WHEEL].get_value(), 1.4179821977774734, COMMON_THRESHOLD); +<<<<<<< HEAD EXPECT_FALSE(std::isnan((*(controller_->input_ref_.readFromRT()))->twist.linear.x)); EXPECT_EQ(controller_->reference_interfaces_.size(), joint_reference_interfaces_.size()); +======= + EXPECT_FALSE(std::isnan(controller_->input_ref_.get().twist.linear.x)); + EXPECT_EQ(controller_->reference_interfaces_.size(), reference_interface_names_.size()); +>>>>>>> 6ddb0b4 (Rename joint_reference_interfaces to reference_interface_names (#2008)) for (const auto & interface : controller_->reference_interfaces_) { EXPECT_TRUE(std::isnan(interface)); @@ -195,8 +210,13 @@ TEST_F(BicycleSteeringControllerTest, test_update_logic_chained) controller_->command_interfaces_[CMD_STEER_WHEEL].get_value(), 1.4179821977774734, COMMON_THRESHOLD); +<<<<<<< HEAD EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromRT()))->twist.linear.x)); EXPECT_EQ(controller_->reference_interfaces_.size(), joint_reference_interfaces_.size()); +======= + EXPECT_TRUE(std::isnan(controller_->input_ref_.get().twist.linear.x)); + EXPECT_EQ(controller_->reference_interfaces_.size(), reference_interface_names_.size()); +>>>>>>> 6ddb0b4 (Rename joint_reference_interfaces to reference_interface_names (#2008)) for (const auto & interface : controller_->reference_interfaces_) { EXPECT_TRUE(std::isnan(interface)); diff --git a/bicycle_steering_controller/test/test_bicycle_steering_controller.hpp b/bicycle_steering_controller/test/test_bicycle_steering_controller.hpp index d88939c4e1..de46b9f3e2 100644 --- a/bicycle_steering_controller/test/test_bicycle_steering_controller.hpp +++ b/bicycle_steering_controller/test/test_bicycle_steering_controller.hpp @@ -267,9 +267,15 @@ class BicycleSteeringControllerFixture : public ::testing::Test double front_wheels_radius_ = 0.45; double rear_wheels_radius_ = 0.45; +<<<<<<< HEAD std::array joint_state_values_ = {3.3, 0.5}; std::array joint_command_values_ = {1.1, 2.2}; std::array joint_reference_interfaces_ = {"linear/velocity", "angular/velocity"}; +======= + std::array joint_state_values_ = {{3.3, 0.5}}; + std::array joint_command_values_ = {{1.1, 2.2}}; + std::array reference_interface_names_ = {{"linear", "angular"}}; +>>>>>>> 6ddb0b4 (Rename joint_reference_interfaces to reference_interface_names (#2008)) std::string steering_interface_name_ = "position"; // defined in setup diff --git a/bicycle_steering_controller/test/test_bicycle_steering_controller_preceding.cpp b/bicycle_steering_controller/test/test_bicycle_steering_controller_preceding.cpp index 7b22541e3e..0983896fbb 100644 --- a/bicycle_steering_controller/test/test_bicycle_steering_controller_preceding.cpp +++ b/bicycle_steering_controller/test/test_bicycle_steering_controller_preceding.cpp @@ -74,14 +74,24 @@ TEST_F(BicycleSteeringControllerTest, check_exported_interfaces) // check ref itfs auto reference_interfaces = controller_->export_reference_interfaces(); - ASSERT_EQ(reference_interfaces.size(), joint_reference_interfaces_.size()); - for (size_t i = 0; i < joint_reference_interfaces_.size(); ++i) + ASSERT_EQ(reference_interfaces.size(), reference_interface_names_.size()); + for (size_t i = 0; i < reference_interface_names_.size(); ++i) { +<<<<<<< HEAD const std::string ref_itf_name = std::string(controller_->get_node()->get_name()) + "/" + joint_reference_interfaces_[i]; EXPECT_EQ(reference_interfaces[i].get_name(), ref_itf_name); EXPECT_EQ(reference_interfaces[i].get_prefix_name(), controller_->get_node()->get_name()); EXPECT_EQ(reference_interfaces[i].get_interface_name(), joint_reference_interfaces_[i]); +======= + const std::string ref_itf_prefix_name = + std::string(controller_->get_node()->get_name()) + "/" + reference_interface_names_[i]; + EXPECT_EQ( + reference_interfaces[i]->get_name(), + ref_itf_prefix_name + "/" + hardware_interface::HW_IF_VELOCITY); + EXPECT_EQ(reference_interfaces[i]->get_prefix_name(), ref_itf_prefix_name); + EXPECT_EQ(reference_interfaces[i]->get_interface_name(), hardware_interface::HW_IF_VELOCITY); +>>>>>>> 6ddb0b4 (Rename joint_reference_interfaces to reference_interface_names (#2008)) } } diff --git a/steering_controllers_library/test/test_steering_controllers_library.cpp b/steering_controllers_library/test/test_steering_controllers_library.cpp index f4e72361ac..53b1c169c2 100644 --- a/steering_controllers_library/test/test_steering_controllers_library.cpp +++ b/steering_controllers_library/test/test_steering_controllers_library.cpp @@ -68,14 +68,24 @@ TEST_F(SteeringControllersLibraryTest, check_exported_interfaces) // check ref itfs auto reference_interfaces = controller_->export_reference_interfaces(); - ASSERT_EQ(reference_interfaces.size(), joint_reference_interfaces_.size()); - for (size_t i = 0; i < joint_reference_interfaces_.size(); ++i) + ASSERT_EQ(reference_interfaces.size(), reference_interface_names_.size()); + for (size_t i = 0; i < reference_interface_names_.size(); ++i) { +<<<<<<< HEAD const std::string ref_itf_name = std::string(controller_->get_node()->get_name()) + "/" + joint_reference_interfaces_[i]; EXPECT_EQ(reference_interfaces[i].get_name(), ref_itf_name); EXPECT_EQ(reference_interfaces[i].get_prefix_name(), controller_->get_node()->get_name()); EXPECT_EQ(reference_interfaces[i].get_interface_name(), joint_reference_interfaces_[i]); +======= + const std::string ref_itf_prefix_name = + std::string(controller_->get_node()->get_name()) + "/" + reference_interface_names_[i]; + EXPECT_EQ(reference_interfaces[i]->get_prefix_name(), ref_itf_prefix_name); + EXPECT_EQ( + reference_interfaces[i]->get_name(), + ref_itf_prefix_name + "/" + hardware_interface::HW_IF_VELOCITY); + EXPECT_EQ(reference_interfaces[i]->get_interface_name(), hardware_interface::HW_IF_VELOCITY); +>>>>>>> 6ddb0b4 (Rename joint_reference_interfaces to reference_interface_names (#2008)) } } diff --git a/steering_controllers_library/test/test_steering_controllers_library.hpp b/steering_controllers_library/test/test_steering_controllers_library.hpp index 97a3bb3867..f840890b8b 100644 --- a/steering_controllers_library/test/test_steering_controllers_library.hpp +++ b/steering_controllers_library/test/test_steering_controllers_library.hpp @@ -323,10 +323,14 @@ class SteeringControllersLibraryFixture : public ::testing::Test double front_wheels_radius_ = 0.45; double rear_wheels_radius_ = 0.45; +<<<<<<< HEAD std::array joint_state_values_ = {0.5, 0.5, 0.0, 0.0}; std::array joint_command_values_ = {1.1, 3.3, 2.2, 4.4}; std::array joint_reference_interfaces_ = {"linear/velocity", "angular/velocity"}; +======= + std::array reference_interface_names_ = {{"linear", "angular"}}; +>>>>>>> 6ddb0b4 (Rename joint_reference_interfaces to reference_interface_names (#2008)) std::string steering_interface_name_ = "position"; // defined in setup std::string traction_interface_name_ = ""; diff --git a/tricycle_steering_controller/test/test_tricycle_steering_controller.cpp b/tricycle_steering_controller/test/test_tricycle_steering_controller.cpp index ad7f80607f..1329907750 100644 --- a/tricycle_steering_controller/test/test_tricycle_steering_controller.cpp +++ b/tricycle_steering_controller/test/test_tricycle_steering_controller.cpp @@ -77,6 +77,7 @@ TEST_F(TricycleSteeringControllerTest, check_exported_interfaces) EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL); // check ref itfs +<<<<<<< HEAD auto ref_if_conf = controller_->export_reference_interfaces(); ASSERT_EQ(ref_if_conf.size(), joint_reference_interfaces_.size()); for (size_t i = 0; i < joint_reference_interfaces_.size(); ++i) @@ -86,6 +87,19 @@ TEST_F(TricycleSteeringControllerTest, check_exported_interfaces) EXPECT_EQ(ref_if_conf[i].get_name(), ref_itf_name); EXPECT_EQ(ref_if_conf[i].get_prefix_name(), controller_->get_node()->get_name()); EXPECT_EQ(ref_if_conf[i].get_interface_name(), joint_reference_interfaces_[i]); +======= + auto reference_interfaces = controller_->export_reference_interfaces(); + ASSERT_EQ(reference_interfaces.size(), reference_interface_names_.size()); + for (size_t i = 0; i < reference_interface_names_.size(); ++i) + { + const std::string ref_itf_prefix_name = + std::string(controller_->get_node()->get_name()) + "/" + reference_interface_names_[i]; + EXPECT_EQ(reference_interfaces[i]->get_prefix_name(), ref_itf_prefix_name); + EXPECT_EQ( + reference_interfaces[i]->get_name(), + ref_itf_prefix_name + "/" + hardware_interface::HW_IF_VELOCITY); + EXPECT_EQ(reference_interfaces[i]->get_interface_name(), hardware_interface::HW_IF_VELOCITY); +>>>>>>> 6ddb0b4 (Rename joint_reference_interfaces to reference_interface_names (#2008)) } } @@ -175,8 +189,13 @@ TEST_F(TricycleSteeringControllerTest, test_update_logic) controller_->command_interfaces_[CMD_STEER_WHEEL].get_value(), 1.4179821977774734, COMMON_THRESHOLD); +<<<<<<< HEAD EXPECT_FALSE(std::isnan((*(controller_->input_ref_.readFromRT()))->twist.linear.x)); EXPECT_EQ(controller_->reference_interfaces_.size(), joint_reference_interfaces_.size()); +======= + EXPECT_FALSE(std::isnan(controller_->input_ref_.get().twist.linear.x)); + EXPECT_EQ(controller_->reference_interfaces_.size(), reference_interface_names_.size()); +>>>>>>> 6ddb0b4 (Rename joint_reference_interfaces to reference_interface_names (#2008)) for (const auto & interface : controller_->reference_interfaces_) { EXPECT_TRUE(std::isnan(interface)); @@ -212,8 +231,13 @@ TEST_F(TricycleSteeringControllerTest, test_update_logic_chained) controller_->command_interfaces_[CMD_STEER_WHEEL].get_value(), 1.4179821977774734, COMMON_THRESHOLD); +<<<<<<< HEAD EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromRT()))->twist.linear.x)); EXPECT_EQ(controller_->reference_interfaces_.size(), joint_reference_interfaces_.size()); +======= + EXPECT_TRUE(std::isnan(controller_->input_ref_.get().twist.linear.x)); + EXPECT_EQ(controller_->reference_interfaces_.size(), reference_interface_names_.size()); +>>>>>>> 6ddb0b4 (Rename joint_reference_interfaces to reference_interface_names (#2008)) for (const auto & interface : controller_->reference_interfaces_) { EXPECT_TRUE(std::isnan(interface)); diff --git a/tricycle_steering_controller/test/test_tricycle_steering_controller.hpp b/tricycle_steering_controller/test/test_tricycle_steering_controller.hpp index db3a2f4b99..815aeaee8d 100644 --- a/tricycle_steering_controller/test/test_tricycle_steering_controller.hpp +++ b/tricycle_steering_controller/test/test_tricycle_steering_controller.hpp @@ -282,12 +282,18 @@ class TricycleSteeringControllerFixture : public ::testing::Test double wheelbase_ = 3.24644; double wheel_track_ = 1.212121; +<<<<<<< HEAD double front_wheels_radius_ = 0.45; double rear_wheels_radius_ = 0.45; std::array joint_state_values_ = {0.5, 0.5, 0.0}; std::array joint_command_values_ = {1.1, 3.3, 2.2}; std::array joint_reference_interfaces_ = {"linear/velocity", "angular/velocity"}; +======= + std::array joint_state_values_{{0.5, 0.5, 0.0}}; + std::array joint_command_values_{{1.1, 3.3, 2.2}}; + std::array reference_interface_names_{{"linear", "angular"}}; +>>>>>>> 6ddb0b4 (Rename joint_reference_interfaces to reference_interface_names (#2008)) std::string steering_interface_name_ = "position"; // defined in setup std::string traction_interface_name_ = ""; diff --git a/tricycle_steering_controller/test/test_tricycle_steering_controller_preceding.cpp b/tricycle_steering_controller/test/test_tricycle_steering_controller_preceding.cpp index 2c9981a486..4db1b27ce8 100644 --- a/tricycle_steering_controller/test/test_tricycle_steering_controller_preceding.cpp +++ b/tricycle_steering_controller/test/test_tricycle_steering_controller_preceding.cpp @@ -80,6 +80,7 @@ TEST_F(TricycleSteeringControllerTest, check_exported_interfaces) EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL); // check ref itfs +<<<<<<< HEAD auto ref_if_conf = controller_->export_reference_interfaces(); ASSERT_EQ(ref_if_conf.size(), joint_reference_interfaces_.size()); for (size_t i = 0; i < joint_reference_interfaces_.size(); ++i) @@ -89,6 +90,19 @@ TEST_F(TricycleSteeringControllerTest, check_exported_interfaces) EXPECT_EQ(ref_if_conf[i].get_name(), ref_itf_name); EXPECT_EQ(ref_if_conf[i].get_prefix_name(), controller_->get_node()->get_name()); EXPECT_EQ(ref_if_conf[i].get_interface_name(), joint_reference_interfaces_[i]); +======= + auto reference_interfaces = controller_->export_reference_interfaces(); + ASSERT_EQ(reference_interfaces.size(), reference_interface_names_.size()); + for (size_t i = 0; i < reference_interface_names_.size(); ++i) + { + const std::string ref_itf_prefix_name = + std::string(controller_->get_node()->get_name()) + "/" + reference_interface_names_[i]; + EXPECT_EQ(reference_interfaces[i]->get_prefix_name(), ref_itf_prefix_name); + EXPECT_EQ( + reference_interfaces[i]->get_name(), + ref_itf_prefix_name + "/" + hardware_interface::HW_IF_VELOCITY); + EXPECT_EQ(reference_interfaces[i]->get_interface_name(), hardware_interface::HW_IF_VELOCITY); +>>>>>>> 6ddb0b4 (Rename joint_reference_interfaces to reference_interface_names (#2008)) } }