diff --git a/ackermann_steering_controller/src/ackermann_steering_controller.cpp b/ackermann_steering_controller/src/ackermann_steering_controller.cpp index d9d95bf8b5..4b955f063e 100644 --- a/ackermann_steering_controller/src/ackermann_steering_controller.cpp +++ b/ackermann_steering_controller/src/ackermann_steering_controller.cpp @@ -63,11 +63,13 @@ bool AckermannSteeringController::update_odometry(const rclcpp::Duration & perio else { const double traction_right_wheel_value = - state_interfaces_[STATE_TRACTION_RIGHT_WHEEL].get_value(); + state_interfaces_[STATE_TRACTION_RIGHT_WHEEL].get_value(); const double traction_left_wheel_value = - state_interfaces_[STATE_TRACTION_LEFT_WHEEL].get_value(); - const double steering_right_position = state_interfaces_[STATE_STEER_RIGHT_WHEEL].get_value(); - const double steering_left_position = state_interfaces_[STATE_STEER_LEFT_WHEEL].get_value(); + state_interfaces_[STATE_TRACTION_LEFT_WHEEL].get_value(); + const double steering_right_position = + state_interfaces_[STATE_STEER_RIGHT_WHEEL].get_value(); + const double steering_left_position = + state_interfaces_[STATE_STEER_LEFT_WHEEL].get_value(); if ( std::isfinite(traction_right_wheel_value) && std::isfinite(traction_left_wheel_value) && std::isfinite(steering_right_position) && std::isfinite(steering_left_position)) diff --git a/bicycle_steering_controller/src/bicycle_steering_controller.cpp b/bicycle_steering_controller/src/bicycle_steering_controller.cpp index 95eaf1965c..1e4002cb5b 100644 --- a/bicycle_steering_controller/src/bicycle_steering_controller.cpp +++ b/bicycle_steering_controller/src/bicycle_steering_controller.cpp @@ -60,8 +60,8 @@ bool BicycleSteeringController::update_odometry(const rclcpp::Duration & period) } else { - const double traction_wheel_value = state_interfaces_[STATE_TRACTION_WHEEL].get_value(); - const double steering_position = state_interfaces_[STATE_STEER_AXIS].get_value(); + const double traction_wheel_value = state_interfaces_[STATE_TRACTION_WHEEL].get_value(); + const double steering_position = state_interfaces_[STATE_STEER_AXIS].get_value(); if (std::isfinite(traction_wheel_value) && std::isfinite(steering_position)) { if (params_.position_feedback) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 7843f8d77b..68653b72aa 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -453,7 +453,7 @@ bool JointTrajectoryController::read_state_from_command_interfaces(JointTrajecto { for (size_t index = 0; index < dof_; ++index) { - trajectory_point_interface[index] = joint_interface[index].get().get_value(); + trajectory_point_interface[index] = joint_interface[index].get().get_value(); } }; @@ -461,7 +461,7 @@ bool JointTrajectoryController::read_state_from_command_interfaces(JointTrajecto { return std::find_if( joint_interface.begin(), joint_interface.end(), [](const auto & interface) - { return std::isnan(interface.get().get_value()); }) == joint_interface.end(); + { return std::isnan(interface.get().get_value()); }) == joint_interface.end(); }; // Assign values from the command interfaces as state. Therefore needs check for both. @@ -523,7 +523,7 @@ bool JointTrajectoryController::read_commands_from_command_interfaces( { for (size_t index = 0; index < dof_; ++index) { - trajectory_point_interface[index] = joint_interface[index].get().get_value(); + trajectory_point_interface[index] = joint_interface[index].get().get_value(); } }; @@ -531,7 +531,7 @@ bool JointTrajectoryController::read_commands_from_command_interfaces( { return std::find_if( joint_interface.begin(), joint_interface.end(), [](const auto & interface) - { return std::isnan(interface.get().get_value()); }) == joint_interface.end(); + { return std::isnan(interface.get().get_value()); }) == joint_interface.end(); }; // Assign values from the command interfaces as command. diff --git a/pid_controller/test/test_pid_controller.cpp b/pid_controller/test/test_pid_controller.cpp index 9b53dccb23..e422a4c8fd 100644 --- a/pid_controller/test/test_pid_controller.cpp +++ b/pid_controller/test/test_pid_controller.cpp @@ -67,7 +67,7 @@ TEST_F(PidControllerTest, check_exported_interfaces) ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); auto cmd_if_conf = controller_->command_interface_configuration(); - ASSERT_EQ(cmd_if_conf.names.size(), dof_command_values_.size()); + ASSERT_EQ(cmd_if_conf.names.size(), command_itfs_.size()); for (size_t i = 0; i < cmd_if_conf.names.size(); ++i) { EXPECT_EQ(cmd_if_conf.names[i], dof_names_[i] + "/" + command_interface_); @@ -75,7 +75,7 @@ TEST_F(PidControllerTest, check_exported_interfaces) EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL); auto state_if_conf = controller_->state_interface_configuration(); - ASSERT_EQ(state_if_conf.names.size(), dof_state_values_.size()); + ASSERT_EQ(state_if_conf.names.size(), state_itfs_.size()); size_t si_index = 0; for (const auto & interface : state_interfaces_) { @@ -89,7 +89,7 @@ TEST_F(PidControllerTest, check_exported_interfaces) // check ref itfs auto ref_if_conf = controller_->export_reference_interfaces(); - ASSERT_EQ(ref_if_conf.size(), dof_state_values_.size()); + ASSERT_EQ(ref_if_conf.size(), state_itfs_.size()); size_t ri_index = 0; for (const auto & interface : state_interfaces_) { @@ -97,9 +97,9 @@ TEST_F(PidControllerTest, check_exported_interfaces) { const std::string ref_itf_name = std::string(controller_->get_node()->get_name()) + "/" + dof_name + "/" + interface; - EXPECT_EQ(ref_if_conf[ri_index].get_name(), ref_itf_name); - EXPECT_EQ(ref_if_conf[ri_index].get_prefix_name(), controller_->get_node()->get_name()); - EXPECT_EQ(ref_if_conf[ri_index].get_interface_name(), dof_name + "/" + interface); + EXPECT_EQ(ref_if_conf[ri_index]->get_name(), ref_itf_name); + EXPECT_EQ(ref_if_conf[ri_index]->get_prefix_name(), controller_->get_node()->get_name()); + EXPECT_EQ(ref_if_conf[ri_index]->get_interface_name(), dof_name + "/" + interface); ++ri_index; } } @@ -125,10 +125,12 @@ TEST_F(PidControllerTest, activate_success) EXPECT_TRUE(std::isnan(cmd)); } - EXPECT_EQ(controller_->reference_interfaces_.size(), dof_state_values_.size()); - for (const auto & interface : controller_->reference_interfaces_) + EXPECT_EQ(controller_->reference_interfaces_.size(), state_itfs_.size()); + for (const auto & interface : controller_->ordered_reference_interfaces_) { - EXPECT_TRUE(std::isnan(interface)); + EXPECT_TRUE(interface->operator bool()); + EXPECT_TRUE(interface->holds_value()); + EXPECT_TRUE(std::isnan(interface->get_value())); } } @@ -159,17 +161,17 @@ TEST_F(PidControllerTest, reactivate_success) ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); - ASSERT_TRUE(std::isnan(controller_->reference_interfaces_[0])); + ASSERT_TRUE(std::isnan(controller_->ordered_reference_interfaces_[0]->get_value())); ASSERT_TRUE(std::isnan(controller_->measured_state_values_[0])); - ASSERT_EQ(controller_->command_interfaces_[0].get_value(), 101.101); + ASSERT_EQ(controller_->command_interfaces_[0].get_value(), 101.101); ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS); - ASSERT_TRUE(std::isnan(controller_->reference_interfaces_[0])); + ASSERT_TRUE(std::isnan(controller_->ordered_reference_interfaces_[0]->get_value())); ASSERT_TRUE(std::isnan(controller_->measured_state_values_[0])); - ASSERT_EQ(controller_->command_interfaces_[0].get_value(), 101.101); + ASSERT_EQ(controller_->command_interfaces_[0].get_value(), 101.101); ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); - ASSERT_TRUE(std::isnan(controller_->reference_interfaces_[0])); + ASSERT_TRUE(std::isnan(controller_->ordered_reference_interfaces_[0]->get_value())); ASSERT_TRUE(std::isnan(controller_->measured_state_values_[0])); - ASSERT_EQ(controller_->command_interfaces_[0].get_value(), 101.101); + ASSERT_EQ(controller_->command_interfaces_[0].get_value(), 101.101); ASSERT_EQ( controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), @@ -215,26 +217,31 @@ TEST_F(PidControllerTest, test_update_logic_feedforward_off) ASSERT_FALSE(controller_->is_in_chained_mode()); EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromRT()))->values[0])); EXPECT_EQ(*(controller_->control_mode_.readFromRT()), feedforward_mode_type::OFF); - for (const auto & interface : controller_->reference_interfaces_) + for (const auto & interface : controller_->ordered_reference_interfaces_) { - EXPECT_TRUE(std::isnan(interface)); + EXPECT_TRUE(interface->operator bool()); + EXPECT_TRUE(interface->holds_value()); + EXPECT_TRUE(std::isnan(interface->get_value())); } std::shared_ptr msg = std::make_shared(); msg->dof_names = dof_names_; msg->values.resize(dof_names_.size(), 0.0); - for (size_t i = 0; i < dof_command_values_.size(); ++i) + for (size_t i = 0; i < command_itfs_.size(); ++i) { - msg->values[i] = dof_command_values_[i]; + msg->values[i] = command_itfs_[i].get_value(); } msg->values_dot.resize(dof_names_.size(), std::numeric_limits::quiet_NaN()); controller_->input_ref_.writeFromNonRT(msg); - for (size_t i = 0; i < dof_command_values_.size(); ++i) + for (size_t i = 0; i < command_itfs_.size(); ++i) { EXPECT_FALSE(std::isnan((*(controller_->input_ref_.readFromRT()))->values[i])); - EXPECT_EQ((*(controller_->input_ref_.readFromRT()))->values[i], dof_command_values_[i]); - EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[i])); + EXPECT_EQ( + (*(controller_->input_ref_.readFromRT()))->values[i], command_itfs_[i].get_value()); + EXPECT_TRUE(controller_->ordered_reference_interfaces_[i]->operator bool()); + EXPECT_TRUE(controller_->ordered_reference_interfaces_[i]->holds_value()); + EXPECT_TRUE(std::isnan(controller_->ordered_reference_interfaces_[i]->get_value())); } ASSERT_EQ( @@ -244,8 +251,8 @@ TEST_F(PidControllerTest, test_update_logic_feedforward_off) EXPECT_EQ(*(controller_->control_mode_.readFromRT()), feedforward_mode_type::OFF); EXPECT_EQ( controller_->reference_interfaces_.size(), dof_names_.size() * state_interfaces_.size()); - EXPECT_EQ(controller_->reference_interfaces_.size(), dof_state_values_.size()); - for (size_t i = 0; i < dof_command_values_.size(); ++i) + EXPECT_EQ(controller_->reference_interfaces_.size(), state_itfs_.size()); + for (size_t i = 0; i < command_itfs_.size(); ++i) { EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromRT()))->values[i])); } @@ -264,17 +271,19 @@ TEST_F(PidControllerTest, test_update_logic_feedforward_on) ASSERT_FALSE(controller_->is_in_chained_mode()); EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromRT()))->values[0])); EXPECT_EQ(*(controller_->control_mode_.readFromRT()), feedforward_mode_type::OFF); - for (const auto & interface : controller_->reference_interfaces_) + for (const auto & interface : controller_->ordered_reference_interfaces_) { - EXPECT_TRUE(std::isnan(interface)); + EXPECT_TRUE(interface->operator bool()); + EXPECT_TRUE(interface->holds_value()); + EXPECT_TRUE(std::isnan(interface->get_value())); } std::shared_ptr msg = std::make_shared(); msg->dof_names = dof_names_; msg->values.resize(dof_names_.size(), 0.0); - for (size_t i = 0; i < dof_command_values_.size(); ++i) + for (size_t i = 0; i < command_itfs_.size(); ++i) { - msg->values[i] = dof_command_values_[i]; + msg->values[i] = command_itfs_[i].get_value(); } msg->values_dot.resize(dof_names_.size(), std::numeric_limits::quiet_NaN()); controller_->input_ref_.writeFromNonRT(msg); @@ -282,11 +291,14 @@ TEST_F(PidControllerTest, test_update_logic_feedforward_on) controller_->control_mode_.writeFromNonRT(feedforward_mode_type::ON); EXPECT_EQ(*(controller_->control_mode_.readFromRT()), feedforward_mode_type::ON); - for (size_t i = 0; i < dof_command_values_.size(); ++i) + for (size_t i = 0; i < command_itfs_.size(); ++i) { EXPECT_FALSE(std::isnan((*(controller_->input_ref_.readFromRT()))->values[i])); - EXPECT_EQ((*(controller_->input_ref_.readFromRT()))->values[i], dof_command_values_[i]); - EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[i])); + EXPECT_EQ( + (*(controller_->input_ref_.readFromRT()))->values[i], command_itfs_[i].get_value()); + EXPECT_TRUE(controller_->ordered_reference_interfaces_[i]->operator bool()); + EXPECT_TRUE(controller_->ordered_reference_interfaces_[i]->holds_value()); + EXPECT_TRUE(std::isnan(controller_->ordered_reference_interfaces_[i]->get_value())); } ASSERT_EQ( @@ -296,8 +308,8 @@ TEST_F(PidControllerTest, test_update_logic_feedforward_on) EXPECT_EQ(*(controller_->control_mode_.readFromRT()), feedforward_mode_type::ON); EXPECT_EQ( controller_->reference_interfaces_.size(), dof_names_.size() * state_interfaces_.size()); - EXPECT_EQ(controller_->reference_interfaces_.size(), dof_state_values_.size()); - for (size_t i = 0; i < dof_command_values_.size(); ++i) + EXPECT_EQ(controller_->reference_interfaces_.size(), state_itfs_.size()); + for (size_t i = 0; i < command_itfs_.size(); ++i) { EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromRT()))->values[i])); } @@ -318,18 +330,21 @@ TEST_F(PidControllerTest, test_update_logic_chainable_feedforward_off) std::shared_ptr msg = std::make_shared(); msg->dof_names = dof_names_; msg->values.resize(dof_names_.size(), 0.0); - for (size_t i = 0; i < dof_command_values_.size(); ++i) + for (size_t i = 0; i < command_itfs_.size(); ++i) { - msg->values[i] = dof_command_values_[i]; + msg->values[i] = command_itfs_[i].get_value(); } msg->values_dot.resize(dof_names_.size(), std::numeric_limits::quiet_NaN()); controller_->input_ref_.writeFromNonRT(msg); - for (size_t i = 0; i < dof_command_values_.size(); ++i) + for (size_t i = 0; i < command_itfs_.size(); ++i) { EXPECT_FALSE(std::isnan((*(controller_->input_ref_.readFromRT()))->values[i])); - EXPECT_EQ((*(controller_->input_ref_.readFromRT()))->values[i], dof_command_values_[i]); - EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[i])); + EXPECT_EQ( + (*(controller_->input_ref_.readFromRT()))->values[i], command_itfs_[i].get_value()); + EXPECT_TRUE(controller_->ordered_reference_interfaces_[i]->operator bool()); + EXPECT_TRUE(controller_->ordered_reference_interfaces_[i]->holds_value()); + EXPECT_TRUE(std::isnan(controller_->ordered_reference_interfaces_[i]->get_value())); } ASSERT_EQ( @@ -340,11 +355,12 @@ TEST_F(PidControllerTest, test_update_logic_chainable_feedforward_off) EXPECT_EQ(*(controller_->control_mode_.readFromRT()), feedforward_mode_type::OFF); EXPECT_EQ( controller_->reference_interfaces_.size(), dof_names_.size() * state_interfaces_.size()); - EXPECT_EQ(controller_->reference_interfaces_.size(), dof_state_values_.size()); - for (size_t i = 0; i < dof_command_values_.size(); ++i) + EXPECT_EQ(controller_->reference_interfaces_.size(), state_itfs_.size()); + for (size_t i = 0; i < command_itfs_.size(); ++i) { EXPECT_FALSE(std::isnan((*(controller_->input_ref_.readFromRT()))->values[i])); - EXPECT_EQ((*(controller_->input_ref_.readFromRT()))->values[i], dof_command_values_[i]); + EXPECT_EQ( + (*(controller_->input_ref_.readFromRT()))->values[i], command_itfs_[i].get_value()); } } @@ -364,9 +380,9 @@ TEST_F(PidControllerTest, test_update_logic_chainable_feedforward_on) std::shared_ptr msg = std::make_shared(); msg->dof_names = dof_names_; msg->values.resize(dof_names_.size(), 0.0); - for (size_t i = 0; i < dof_command_values_.size(); ++i) + for (size_t i = 0; i < command_itfs_.size(); ++i) { - msg->values[i] = dof_command_values_[i]; + msg->values[i] = command_itfs_[i].get_value(); } msg->values_dot.resize(dof_names_.size(), std::numeric_limits::quiet_NaN()); controller_->input_ref_.writeFromNonRT(msg); @@ -374,11 +390,14 @@ TEST_F(PidControllerTest, test_update_logic_chainable_feedforward_on) controller_->control_mode_.writeFromNonRT(feedforward_mode_type::ON); EXPECT_EQ(*(controller_->control_mode_.readFromRT()), feedforward_mode_type::ON); - for (size_t i = 0; i < dof_command_values_.size(); ++i) + for (size_t i = 0; i < command_itfs_.size(); ++i) { EXPECT_FALSE(std::isnan((*(controller_->input_ref_.readFromRT()))->values[i])); - EXPECT_EQ((*(controller_->input_ref_.readFromRT()))->values[i], dof_command_values_[i]); - EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[i])); + EXPECT_EQ( + (*(controller_->input_ref_.readFromRT()))->values[i], command_itfs_[i].get_value()); + EXPECT_TRUE(controller_->ordered_reference_interfaces_[i]->operator bool()); + EXPECT_TRUE(controller_->ordered_reference_interfaces_[i]->holds_value()); + EXPECT_TRUE(std::isnan(controller_->ordered_reference_interfaces_[i]->get_value())); } ASSERT_EQ( @@ -389,11 +408,12 @@ TEST_F(PidControllerTest, test_update_logic_chainable_feedforward_on) EXPECT_EQ(*(controller_->control_mode_.readFromRT()), feedforward_mode_type::ON); EXPECT_EQ( controller_->reference_interfaces_.size(), dof_names_.size() * state_interfaces_.size()); - EXPECT_EQ(controller_->reference_interfaces_.size(), dof_state_values_.size()); - for (size_t i = 0; i < dof_command_values_.size(); ++i) + EXPECT_EQ(controller_->reference_interfaces_.size(), state_itfs_.size()); + for (size_t i = 0; i < command_itfs_.size(); ++i) { EXPECT_FALSE(std::isnan((*(controller_->input_ref_.readFromRT()))->values[i])); - EXPECT_EQ((*(controller_->input_ref_.readFromRT()))->values[i], dof_command_values_[i]); + EXPECT_EQ( + (*(controller_->input_ref_.readFromRT()))->values[i], command_itfs_[i].get_value()); } } @@ -460,7 +480,7 @@ TEST_F(PidControllerTest, subscribe_and_get_messages_success) { ASSERT_EQ(msg.dof_states[i].name, dof_names_[i]); EXPECT_TRUE(std::isnan(msg.dof_states[i].reference)); - ASSERT_EQ(msg.dof_states[i].output, dof_command_values_[i]); + ASSERT_EQ(msg.dof_states[i].output, command_itfs_[i].get_value()); } } @@ -485,29 +505,33 @@ TEST_F(PidControllerTest, receive_message_and_publish_updated_status) { ASSERT_EQ(msg.dof_states[i].name, dof_names_[i]); EXPECT_TRUE(std::isnan(msg.dof_states[i].reference)); - ASSERT_EQ(msg.dof_states[i].output, dof_command_values_[i]); + ASSERT_EQ(msg.dof_states[i].output, command_itfs_[i].get_value()); } - for (size_t i = 0; i < controller_->reference_interfaces_.size(); ++i) + for (size_t i = 0; i < controller_->ordered_reference_interfaces_.size(); ++i) { - EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[i])); + EXPECT_TRUE(controller_->ordered_reference_interfaces_[i]->operator bool()); + EXPECT_TRUE(controller_->ordered_reference_interfaces_[i]->holds_value()); + EXPECT_TRUE(std::isnan(controller_->ordered_reference_interfaces_[i]->get_value())); } publish_commands(); controller_->wait_for_commands(executor); - for (size_t i = 0; i < controller_->reference_interfaces_.size(); ++i) + for (size_t i = 0; i < controller_->ordered_reference_interfaces_.size(); ++i) { - EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[i])); + EXPECT_TRUE(controller_->ordered_reference_interfaces_[i]->operator bool()); + EXPECT_TRUE(controller_->ordered_reference_interfaces_[i]->holds_value()); + EXPECT_TRUE(std::isnan(controller_->ordered_reference_interfaces_[i]->get_value())); } ASSERT_EQ( controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - for (size_t i = 0; i < controller_->reference_interfaces_.size(); ++i) + for (size_t i = 0; i < controller_->ordered_reference_interfaces_.size(); ++i) { - ASSERT_EQ(controller_->reference_interfaces_[i], 0.45); + ASSERT_EQ(controller_->ordered_reference_interfaces_[i]->get_value(), 0.45); } subscribe_and_get_messages(msg); @@ -517,7 +541,7 @@ TEST_F(PidControllerTest, receive_message_and_publish_updated_status) { ASSERT_EQ(msg.dof_states[i].name, dof_names_[i]); ASSERT_EQ(msg.dof_states[i].reference, 0.45); - ASSERT_NE(msg.dof_states[i].output, dof_command_values_[i]); + ASSERT_NE(msg.dof_states[i].output, command_itfs_[i].get_value()); } } diff --git a/pid_controller/test/test_pid_controller.hpp b/pid_controller/test/test_pid_controller.hpp index 158b5d9147..6e2e509964 100644 --- a/pid_controller/test/test_pid_controller.hpp +++ b/pid_controller/test/test_pid_controller.hpp @@ -26,6 +26,7 @@ #include #include +#include "hardware_interface/hardware_info.hpp" #include "hardware_interface/loaned_command_interface.hpp" #include "hardware_interface/loaned_state_interface.hpp" #include "pid_controller/pid_controller.hpp" @@ -70,7 +71,7 @@ class TestablePidController : public pid_controller::PidController controller_interface::CallbackReturn on_activate( const rclcpp_lifecycle::State & previous_state) override { - auto ref_itfs = on_export_reference_interfaces(); + auto ref_itfs = export_state_interface_descriptions(); return pid_controller::PidController::on_activate(previous_state); } @@ -111,8 +112,6 @@ class PidControllerFixture : public ::testing::Test dof_names_ = {"joint1"}; command_interface_ = "position"; state_interfaces_ = {"position"}; - dof_state_values_ = {1.1}; - dof_command_values_ = {101.101}; reference_and_state_dof_names_ = {"joint1state"}; // initialize controller @@ -144,8 +143,10 @@ class PidControllerFixture : public ::testing::Test for (size_t i = 0; i < dof_names_.size(); ++i) { - command_itfs_.emplace_back(hardware_interface::CommandInterface( - dof_names_[i], command_interface_, &dof_command_values_[i])); + command_itfs_.emplace_back( + hardware_interface::CommandInterface(hardware_interface::InterfaceDescription( + dof_names_[i], + hardware_interface::InterfaceInfo(command_interface_, "double", "101.101")))); command_ifs.emplace_back(command_itfs_.back()); } @@ -158,7 +159,8 @@ class PidControllerFixture : public ::testing::Test for (const auto & dof_name : dof_names_) { state_itfs_.emplace_back( - hardware_interface::StateInterface(dof_name, interface, &dof_state_values_[index])); + hardware_interface::StateInterface(hardware_interface::InterfaceDescription( + dof_name, hardware_interface::InterfaceInfo(interface, "double", "1.1")))); state_ifs.emplace_back(state_itfs_.back()); ++index; } @@ -264,8 +266,6 @@ class PidControllerFixture : public ::testing::Test std::vector dof_names_; std::string command_interface_; std::vector state_interfaces_; - std::vector dof_state_values_; - std::vector dof_command_values_; std::vector reference_and_state_dof_names_; std::vector state_itfs_; diff --git a/pid_controller/test/test_pid_controller_preceding.cpp b/pid_controller/test/test_pid_controller_preceding.cpp index 498ca633da..9147beab11 100644 --- a/pid_controller/test/test_pid_controller_preceding.cpp +++ b/pid_controller/test/test_pid_controller_preceding.cpp @@ -54,7 +54,7 @@ TEST_F(PidControllerTest, check_exported_interfaces) ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); auto cmd_if_conf = controller_->command_interface_configuration(); - ASSERT_EQ(cmd_if_conf.names.size(), dof_command_values_.size()); + ASSERT_EQ(cmd_if_conf.names.size(), command_itfs_.size()); for (size_t i = 0; i < cmd_if_conf.names.size(); ++i) { EXPECT_EQ(cmd_if_conf.names[i], dof_names_[i] + "/" + command_interface_); @@ -62,7 +62,7 @@ TEST_F(PidControllerTest, check_exported_interfaces) EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL); auto state_if_conf = controller_->state_interface_configuration(); - ASSERT_EQ(state_if_conf.names.size(), dof_state_values_.size()); + ASSERT_EQ(state_if_conf.names.size(), state_itfs_.size()); size_t si_index = 0; for (const auto & interface : state_interfaces_) { @@ -76,7 +76,7 @@ TEST_F(PidControllerTest, check_exported_interfaces) // check ref itfs auto ref_if_conf = controller_->export_reference_interfaces(); - ASSERT_EQ(ref_if_conf.size(), dof_state_values_.size()); + ASSERT_EQ(ref_if_conf.size(), state_itfs_.size()); size_t ri_index = 0; for (const auto & interface : state_interfaces_) { @@ -84,9 +84,9 @@ TEST_F(PidControllerTest, check_exported_interfaces) { const std::string ref_itf_name = std::string(controller_->get_node()->get_name()) + "/" + dof_name + "/" + interface; - EXPECT_EQ(ref_if_conf[ri_index].get_name(), ref_itf_name); - EXPECT_EQ(ref_if_conf[ri_index].get_prefix_name(), controller_->get_node()->get_name()); - EXPECT_EQ(ref_if_conf[ri_index].get_interface_name(), dof_name + "/" + interface); + EXPECT_EQ(ref_if_conf[ri_index]->get_name(), ref_itf_name); + EXPECT_EQ(ref_if_conf[ri_index]->get_prefix_name(), controller_->get_node()->get_name()); + EXPECT_EQ(ref_if_conf[ri_index]->get_interface_name(), dof_name + "/" + interface); ++ri_index; } } diff --git a/steering_controllers_library/include/steering_controllers_library/steering_controllers_library.hpp b/steering_controllers_library/include/steering_controllers_library/steering_controllers_library.hpp index e5414a7f6f..cb27fadf3d 100644 --- a/steering_controllers_library/include/steering_controllers_library/steering_controllers_library.hpp +++ b/steering_controllers_library/include/steering_controllers_library/steering_controllers_library.hpp @@ -104,6 +104,8 @@ class SteeringControllersLibrary : public controller_interface::ChainableControl std::unique_ptr rt_odom_state_publisher_; std::unique_ptr rt_tf_odom_state_publisher_; + std::vector export_state_interface_descriptions() + override; // override methods from ChainableControllerInterface std::vector export_reference_interface_descriptions() override; diff --git a/steering_controllers_library/src/steering_controllers_library.cpp b/steering_controllers_library/src/steering_controllers_library.cpp index 2d034b41d8..cb4bc9ef95 100644 --- a/steering_controllers_library/src/steering_controllers_library.cpp +++ b/steering_controllers_library/src/steering_controllers_library.cpp @@ -311,6 +311,12 @@ SteeringControllersLibrary::state_interface_configuration() const return state_interfaces_config; } +std::vector +SteeringControllersLibrary::export_state_interface_descriptions() +{ + return {}; +} + std::vector SteeringControllersLibrary::export_reference_interface_descriptions() { @@ -368,16 +374,16 @@ controller_interface::return_type SteeringControllersLibrary::update_reference_f { if (!std::isnan(current_ref->twist.linear.x) && !std::isnan(current_ref->twist.angular.z)) { - reference_interfaces_ptrs_[lin_ref_itf_]->set_value(current_ref->twist.linear.x); - reference_interfaces_ptrs_[ang_ref_itf_]->set_value(current_ref->twist.angular.z); + reference_interfaces_[lin_ref_itf_]->set_value(current_ref->twist.linear.x); + reference_interfaces_[ang_ref_itf_]->set_value(current_ref->twist.angular.z); } } else { if (!std::isnan(current_ref->twist.linear.x) && !std::isnan(current_ref->twist.angular.z)) { - reference_interfaces_ptrs_[lin_ref_itf_]->set_value(0.0); - reference_interfaces_ptrs_[ang_ref_itf_]->set_value(0.0); + reference_interfaces_[lin_ref_itf_]->set_value(0.0); + reference_interfaces_[ang_ref_itf_]->set_value(0.0); current_ref->twist.linear.x = std::numeric_limits::quiet_NaN(); current_ref->twist.angular.z = std::numeric_limits::quiet_NaN(); } @@ -397,12 +403,12 @@ controller_interface::return_type SteeringControllersLibrary::update_and_write_c // TODO(destogl): add limiter for the velocities if ( - !std::isnan(reference_interfaces_ptrs_[lin_ref_itf_]->get_value()) && - !std::isnan(reference_interfaces_ptrs_[ang_ref_itf_]->get_value())) + !std::isnan(reference_interfaces_[lin_ref_itf_]->get_value()) && + !std::isnan(reference_interfaces_[ang_ref_itf_]->get_value())) { // store (for open loop odometry) and set commands - last_linear_velocity_ = reference_interfaces_ptrs_[lin_ref_itf_]->get_value(); - last_angular_velocity_ = reference_interfaces_ptrs_[ang_ref_itf_]->get_value(); + last_linear_velocity_ = reference_interfaces_[lin_ref_itf_]->get_value(); + last_angular_velocity_ = reference_interfaces_[ang_ref_itf_]->get_value(); auto [traction_commands, steering_commands] = odometry_.get_commands(last_linear_velocity_, last_angular_velocity_, params_.open_loop); @@ -486,30 +492,30 @@ controller_interface::return_type SteeringControllersLibrary::update_and_write_c if (params_.position_feedback) { controller_state_publisher_->msg_.traction_wheels_position.push_back( - state_interfaces_[i].get_value()); + state_interfaces_[i].get_value()); } else { controller_state_publisher_->msg_.traction_wheels_velocity.push_back( - state_interfaces_[i].get_value()); + state_interfaces_[i].get_value()); } controller_state_publisher_->msg_.linear_velocity_command.push_back( - command_interfaces_[i].get_value()); + command_interfaces_[i].get_value()); } for (size_t i = 0; i < number_of_steering_wheels; ++i) { controller_state_publisher_->msg_.steer_positions.push_back( - state_interfaces_[number_of_traction_wheels + i].get_value()); + state_interfaces_[number_of_traction_wheels + i].get_value()); controller_state_publisher_->msg_.steering_angle_command.push_back( - command_interfaces_[number_of_traction_wheels + i].get_value()); + command_interfaces_[number_of_traction_wheels + i].get_value()); } controller_state_publisher_->unlockAndPublish(); } - reference_interfaces_ptrs_[lin_ref_itf_]->set_value(std::numeric_limits::quiet_NaN()); - reference_interfaces_ptrs_[ang_ref_itf_]->set_value(std::numeric_limits::quiet_NaN()); + reference_interfaces_[lin_ref_itf_]->set_value(std::numeric_limits::quiet_NaN()); + reference_interfaces_[ang_ref_itf_]->set_value(std::numeric_limits::quiet_NaN()); return controller_interface::return_type::OK; } diff --git a/steering_controllers_library/test/test_steering_controllers_library.cpp b/steering_controllers_library/test/test_steering_controllers_library.cpp index 0857626840..c6ab40fd65 100644 --- a/steering_controllers_library/test/test_steering_controllers_library.cpp +++ b/steering_controllers_library/test/test_steering_controllers_library.cpp @@ -91,9 +91,11 @@ TEST_F(SteeringControllersLibraryTest, test_both_update_methods_for_ref_timeout) ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); ASSERT_FALSE(controller_->is_in_chained_mode()); - for (const auto & interface : controller_->reference_interfaces_) + for (const auto & interface : controller_->ordered_reference_interfaces_) { - EXPECT_TRUE(std::isnan(interface)); + EXPECT_TRUE(interface->holds_value()); + EXPECT_TRUE(interface->operator bool()); + EXPECT_TRUE(std::isnan(interface->get_value())); } // set command statically @@ -127,24 +129,25 @@ TEST_F(SteeringControllersLibraryTest, test_both_update_methods_for_ref_timeout) controller_->update(controller_->get_node()->now(), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[0])); - EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[1])); - for (const auto & interface : controller_->reference_interfaces_) + for (const auto & interface : controller_->ordered_reference_interfaces_) { - EXPECT_TRUE(std::isnan(interface)); + EXPECT_TRUE(interface->holds_value()); + EXPECT_TRUE(interface->operator bool()); + EXPECT_TRUE(std::isnan(interface->get_value())); } EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromNonRT()))->twist.linear.x)); EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromNonRT()))->twist.angular.z)); - EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[0])); - for (const auto & interface : controller_->reference_interfaces_) + for (const auto & interface : controller_->ordered_reference_interfaces_) { - EXPECT_TRUE(std::isnan(interface)); + EXPECT_TRUE(interface->holds_value()); + EXPECT_TRUE(interface->operator bool()); + EXPECT_TRUE(std::isnan(interface->get_value())); } for (size_t i = 0; i < controller_->command_interfaces_.size(); ++i) { - EXPECT_EQ(controller_->command_interfaces_[i].get_value(), 0); + EXPECT_EQ(controller_->command_interfaces_[i].get_value(), 0.0); } // case 2 position_feedback = true @@ -168,24 +171,25 @@ TEST_F(SteeringControllersLibraryTest, test_both_update_methods_for_ref_timeout) controller_->update(controller_->get_node()->now(), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[0])); - EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[1])); - for (const auto & interface : controller_->reference_interfaces_) + for (const auto & interface : controller_->ordered_reference_interfaces_) { - EXPECT_TRUE(std::isnan(interface)); + EXPECT_TRUE(interface->holds_value()); + EXPECT_TRUE(interface->operator bool()); + EXPECT_TRUE(std::isnan(interface->get_value())); } EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromNonRT()))->twist.linear.x)); EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromNonRT()))->twist.angular.z)); - EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[0])); - for (const auto & interface : controller_->reference_interfaces_) + for (const auto & interface : controller_->ordered_reference_interfaces_) { - EXPECT_TRUE(std::isnan(interface)); + EXPECT_TRUE(interface->holds_value()); + EXPECT_TRUE(interface->operator bool()); + EXPECT_TRUE(std::isnan(interface->get_value())); } for (size_t i = 0; i < controller_->command_interfaces_.size(); ++i) { - EXPECT_EQ(controller_->command_interfaces_[i].get_value(), 0); + EXPECT_EQ(controller_->command_interfaces_[i].get_value(), 0); } } diff --git a/steering_controllers_library/test/test_steering_controllers_library.hpp b/steering_controllers_library/test/test_steering_controllers_library.hpp index b631eb44d2..09a81312d9 100644 --- a/steering_controllers_library/test/test_steering_controllers_library.hpp +++ b/steering_controllers_library/test/test_steering_controllers_library.hpp @@ -15,8 +15,6 @@ #ifndef TEST_STEERING_CONTROLLERS_LIBRARY_HPP_ #define TEST_STEERING_CONTROLLERS_LIBRARY_HPP_ -#include - #include #include #include @@ -88,7 +86,7 @@ class TestableSteeringControllersLibrary controller_interface::CallbackReturn on_activate( const rclcpp_lifecycle::State & previous_state) override { - auto ref_itfs = on_export_reference_interfaces(); + auto ref_itf_descriptions = export_reference_interface_descriptions(); return steering_controllers_library::SteeringControllersLibrary::on_activate(previous_state); } diff --git a/tricycle_steering_controller/src/tricycle_steering_controller.cpp b/tricycle_steering_controller/src/tricycle_steering_controller.cpp index 03be6b88f0..7d354ab393 100644 --- a/tricycle_steering_controller/src/tricycle_steering_controller.cpp +++ b/tricycle_steering_controller/src/tricycle_steering_controller.cpp @@ -61,10 +61,10 @@ bool TricycleSteeringController::update_odometry(const rclcpp::Duration & period else { const double traction_right_wheel_value = - state_interfaces_[STATE_TRACTION_RIGHT_WHEEL].get_value(); + state_interfaces_[STATE_TRACTION_RIGHT_WHEEL].get_value(); const double traction_left_wheel_value = - state_interfaces_[STATE_TRACTION_LEFT_WHEEL].get_value(); - const double steering_position = state_interfaces_[STATE_STEER_AXIS].get_value(); + state_interfaces_[STATE_TRACTION_LEFT_WHEEL].get_value(); + const double steering_position = state_interfaces_[STATE_STEER_AXIS].get_value(); if ( std::isfinite(traction_right_wheel_value) && std::isfinite(traction_left_wheel_value) && std::isfinite(steering_position)) diff --git a/tricycle_steering_controller/test/test_tricycle_steering_controller.cpp b/tricycle_steering_controller/test/test_tricycle_steering_controller.cpp index 3f2589cb6c..bd45d26b7e 100644 --- a/tricycle_steering_controller/test/test_tricycle_steering_controller.cpp +++ b/tricycle_steering_controller/test/test_tricycle_steering_controller.cpp @@ -75,7 +75,7 @@ TEST_F(TricycleSteeringControllerTest, check_exported_interfaces) EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL); // check ref itfs - auto ref_if_conf = controller_->export_reference_interfaces(); + auto ref_if_conf = controller_->export_reference_interface_descriptions(); ASSERT_EQ(ref_if_conf.size(), joint_reference_interfaces_.size()); for (size_t i = 0; i < joint_reference_interfaces_.size(); ++i) { diff --git a/tricycle_steering_controller/test/test_tricycle_steering_controller.hpp b/tricycle_steering_controller/test/test_tricycle_steering_controller.hpp index 3b7a053937..912c39b157 100644 --- a/tricycle_steering_controller/test/test_tricycle_steering_controller.hpp +++ b/tricycle_steering_controller/test/test_tricycle_steering_controller.hpp @@ -79,7 +79,7 @@ class TestableTricycleSteeringController controller_interface::CallbackReturn on_activate( const rclcpp_lifecycle::State & previous_state) override { - auto ref_itfs = on_export_reference_interfaces(); + auto ref_itfs = export_reference_interface_descriptions(); return tricycle_steering_controller::TricycleSteeringController::on_activate(previous_state); }