diff --git a/admittance_controller/test/test_admittance_controller.hpp b/admittance_controller/test/test_admittance_controller.hpp index 7dca2e2010..5a17f05102 100644 --- a/admittance_controller/test/test_admittance_controller.hpp +++ b/admittance_controller/test/test_admittance_controller.hpp @@ -201,7 +201,7 @@ class AdmittanceControllerTest : public ::testing::Test for (auto i = 0u; i < joint_command_values_.size(); ++i) { - command_itfs_.emplace_back(hardware_interface::CommandInterface( + command_itfs_.emplace_back(std::make_shared( joint_names_[i], command_interface_types_[0], &joint_command_values_[i])); command_ifs.emplace_back(command_itfs_.back()); } @@ -216,7 +216,7 @@ class AdmittanceControllerTest : public ::testing::Test for (auto i = 0u; i < joint_state_values_.size(); ++i) { - state_itfs_.emplace_back(hardware_interface::StateInterface( + state_itfs_.emplace_back(std::make_shared( joint_names_[i], state_interface_types_[0], &joint_state_values_[i])); state_ifs.emplace_back(state_itfs_.back()); } @@ -226,7 +226,7 @@ class AdmittanceControllerTest : public ::testing::Test for (auto i = 0u; i < fts_state_names_.size(); ++i) { - state_itfs_.emplace_back(hardware_interface::StateInterface( + state_itfs_.emplace_back(std::make_shared( ft_sensor_name_, fts_itf_names[i], &fts_state_values_[i])); state_ifs.emplace_back(state_itfs_.back()); } @@ -397,8 +397,8 @@ class AdmittanceControllerTest : public ::testing::Test std::array fts_state_values_ = {0.0, 0.0, 0.0, 0.0, 0.0, 0.0}; std::vector fts_state_names_; - std::vector state_itfs_; - std::vector command_itfs_; + std::vector> state_itfs_; + std::vector> command_itfs_; // Test related parameters std::unique_ptr controller_; diff --git a/gripper_controllers/test/test_gripper_controllers.hpp b/gripper_controllers/test/test_gripper_controllers.hpp index 3e9750a603..b002aaf9c4 100644 --- a/gripper_controllers/test/test_gripper_controllers.hpp +++ b/gripper_controllers/test/test_gripper_controllers.hpp @@ -57,9 +57,12 @@ class GripperControllerTest : public ::testing::Test std::vector joint_states_ = {1.1, 2.1}; std::vector joint_commands_ = {3.1}; - StateInterface joint_1_pos_state_{joint_name_, HW_IF_POSITION, &joint_states_[0]}; - StateInterface joint_1_vel_state_{joint_name_, HW_IF_VELOCITY, &joint_states_[1]}; - CommandInterface joint_1_pos_cmd_{joint_name_, HW_IF_POSITION, &joint_commands_[0]}; + std::shared_ptr joint_1_pos_state_ = + std::make_shared(joint_name_, HW_IF_POSITION, &joint_states_[0]); + std::shared_ptr joint_1_vel_state_ = + std::make_shared(joint_name_, HW_IF_VELOCITY, &joint_states_[1]); + std::shared_ptr joint_1_pos_cmd_ = + std::make_shared(joint_name_, HW_IF_POSITION, &joint_commands_[0]); }; #endif // TEST_GRIPPER_CONTROLLERS_HPP_