@@ -47,20 +47,20 @@ TEST_F(ForceTorqueSensorTest, validate_all_with_default_names)
4747 std::vector<std::string> interface_names = force_torque_sensor_->get_state_interface_names ();
4848
4949 // assign values to force
50- hardware_interface::StateInterface force_x{
51- sensor_name_, fts_interface_names_[0 ], &force_values_[0 ]} ;
52- hardware_interface::StateInterface force_y{
53- sensor_name_, fts_interface_names_[1 ], &force_values_[1 ]} ;
54- hardware_interface::StateInterface force_z{
55- sensor_name_, fts_interface_names_[2 ], &force_values_[2 ]} ;
50+ auto force_x = std::make_shared< hardware_interface::StateInterface>(
51+ sensor_name_, fts_interface_names_[0 ], &force_values_[0 ]) ;
52+ auto force_y = std::make_shared< hardware_interface::StateInterface>(
53+ sensor_name_, fts_interface_names_[1 ], &force_values_[1 ]) ;
54+ auto force_z = std::make_shared< hardware_interface::StateInterface>(
55+ sensor_name_, fts_interface_names_[2 ], &force_values_[2 ]) ;
5656
5757 // assign values to torque
58- hardware_interface::StateInterface torque_x{
59- sensor_name_, fts_interface_names_[3 ], &torque_values_[0 ]} ;
60- hardware_interface::StateInterface torque_y{
61- sensor_name_, fts_interface_names_[4 ], &torque_values_[1 ]} ;
62- hardware_interface::StateInterface torque_z{
63- sensor_name_, fts_interface_names_[5 ], &torque_values_[2 ]} ;
58+ auto torque_x = std::make_shared< hardware_interface::StateInterface>(
59+ sensor_name_, fts_interface_names_[3 ], &torque_values_[0 ]) ;
60+ auto torque_y = std::make_shared< hardware_interface::StateInterface>(
61+ sensor_name_, fts_interface_names_[4 ], &torque_values_[1 ]) ;
62+ auto torque_z = std::make_shared< hardware_interface::StateInterface>(
63+ sensor_name_, fts_interface_names_[5 ], &torque_values_[2 ]) ;
6464
6565 // create local state interface vector
6666 std::vector<hardware_interface::LoanedStateInterface> temp_state_interfaces;
@@ -131,16 +131,16 @@ TEST_F(ForceTorqueSensorTest, validate_all_with_custom_names)
131131 std::vector<std::string> interface_names = force_torque_sensor_->get_state_interface_names ();
132132
133133 // assign values to force.x and force.z
134- hardware_interface::StateInterface force_x{
135- sensor_name_, fts_interface_names_[0 ], &force_values_[0 ]} ;
136- hardware_interface::StateInterface force_z{
137- sensor_name_, fts_interface_names_[2 ], &force_values_[2 ]} ;
134+ auto force_x = std::make_shared< hardware_interface::StateInterface>(
135+ sensor_name_, fts_interface_names_[0 ], &force_values_[0 ]) ;
136+ auto force_z = std::make_shared< hardware_interface::StateInterface>(
137+ sensor_name_, fts_interface_names_[2 ], &force_values_[2 ]) ;
138138
139139 // assign values to torque.y and torque.z
140- hardware_interface::StateInterface torque_y{
141- sensor_name_, fts_interface_names_[4 ], &torque_values_[1 ]} ;
142- hardware_interface::StateInterface torque_z{
143- sensor_name_, fts_interface_names_[5 ], &torque_values_[2 ]} ;
140+ auto torque_y = std::make_shared< hardware_interface::StateInterface>(
141+ sensor_name_, fts_interface_names_[4 ], &torque_values_[1 ]) ;
142+ auto torque_z = std::make_shared< hardware_interface::StateInterface>(
143+ sensor_name_, fts_interface_names_[5 ], &torque_values_[2 ]) ;
144144
145145 // create local state interface vector
146146 std::vector<hardware_interface::LoanedStateInterface> temp_state_interfaces;
@@ -213,20 +213,20 @@ TEST_F(ForceTorqueSensorTest, validate_all_custom_names)
213213 ASSERT_EQ (force_torque_sensor_->interface_names_ [5 ], sensor_name_ + " /" + " torque.z" );
214214
215215 // assign values to force
216- hardware_interface::StateInterface force_x{
217- sensor_name_, fts_interface_names_[0 ], &force_values_[0 ]} ;
218- hardware_interface::StateInterface force_y{
219- sensor_name_, fts_interface_names_[1 ], &force_values_[1 ]} ;
220- hardware_interface::StateInterface force_z{
221- sensor_name_, fts_interface_names_[2 ], &force_values_[2 ]} ;
216+ auto force_x = std::make_shared< hardware_interface::StateInterface>(
217+ sensor_name_, fts_interface_names_[0 ], &force_values_[0 ]) ;
218+ auto force_y = std::make_shared< hardware_interface::StateInterface>(
219+ sensor_name_, fts_interface_names_[1 ], &force_values_[1 ]) ;
220+ auto force_z = std::make_shared< hardware_interface::StateInterface>(
221+ sensor_name_, fts_interface_names_[2 ], &force_values_[2 ]) ;
222222
223223 // assign values to torque
224- hardware_interface::StateInterface torque_x{
225- sensor_name_, fts_interface_names_[3 ], &torque_values_[0 ]} ;
226- hardware_interface::StateInterface torque_y{
227- sensor_name_, fts_interface_names_[4 ], &torque_values_[1 ]} ;
228- hardware_interface::StateInterface torque_z{
229- sensor_name_, fts_interface_names_[5 ], &torque_values_[2 ]} ;
224+ auto torque_x = std::make_shared< hardware_interface::StateInterface>(
225+ sensor_name_, fts_interface_names_[3 ], &torque_values_[0 ]) ;
226+ auto torque_y = std::make_shared< hardware_interface::StateInterface>(
227+ sensor_name_, fts_interface_names_[4 ], &torque_values_[1 ]) ;
228+ auto torque_z = std::make_shared< hardware_interface::StateInterface>(
229+ sensor_name_, fts_interface_names_[5 ], &torque_values_[2 ]) ;
230230
231231 // create local state interface vector
232232 std::vector<hardware_interface::LoanedStateInterface> temp_state_interfaces;
0 commit comments