@@ -201,7 +201,7 @@ class AdmittanceControllerTest : public ::testing::Test
201201
202202 for (auto i = 0u ; i < joint_command_values_.size (); ++i)
203203 {
204- command_itfs_.emplace_back (hardware_interface::CommandInterface (
204+ command_itfs_.emplace_back (std::make_shared< hardware_interface::CommandInterface> (
205205 joint_names_[i], command_interface_types_[0 ], &joint_command_values_[i]));
206206 command_ifs.emplace_back (command_itfs_.back ());
207207 }
@@ -216,7 +216,7 @@ class AdmittanceControllerTest : public ::testing::Test
216216
217217 for (auto i = 0u ; i < joint_state_values_.size (); ++i)
218218 {
219- state_itfs_.emplace_back (hardware_interface::StateInterface (
219+ state_itfs_.emplace_back (std::make_shared< hardware_interface::StateInterface> (
220220 joint_names_[i], state_interface_types_[0 ], &joint_state_values_[i]));
221221 state_ifs.emplace_back (state_itfs_.back ());
222222 }
@@ -226,7 +226,7 @@ class AdmittanceControllerTest : public ::testing::Test
226226
227227 for (auto i = 0u ; i < fts_state_names_.size (); ++i)
228228 {
229- state_itfs_.emplace_back (hardware_interface::StateInterface (
229+ state_itfs_.emplace_back (std::make_shared< hardware_interface::StateInterface> (
230230 ft_sensor_name_, fts_itf_names[i], &fts_state_values_[i]));
231231 state_ifs.emplace_back (state_itfs_.back ());
232232 }
@@ -397,8 +397,8 @@ class AdmittanceControllerTest : public ::testing::Test
397397 std::array<double , 6 > fts_state_values_ = {0.0 , 0.0 , 0.0 , 0.0 , 0.0 , 0.0 };
398398 std::vector<std::string> fts_state_names_;
399399
400- std::vector<hardware_interface::StateInterface> state_itfs_;
401- std::vector<hardware_interface::CommandInterface> command_itfs_;
400+ std::vector<std::shared_ptr< hardware_interface::StateInterface> > state_itfs_;
401+ std::vector<std::shared_ptr< hardware_interface::CommandInterface> > command_itfs_;
402402
403403 // Test related parameters
404404 std::unique_ptr<TestableAdmittanceController> controller_;
0 commit comments