@@ -1089,26 +1089,26 @@ TEST(TestComponentInterfaces, dummy_sensor_default_interface_export)
10891089 EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
10901090 EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
10911091
1092- auto state_interfaces = sensor_hw.export_state_interfaces ();
1092+ auto state_interfaces = sensor_hw.on_export_state_interfaces ();
10931093 ASSERT_EQ (1u , state_interfaces.size ());
1094- EXPECT_EQ (" joint1/voltage" , state_interfaces[0 ]. get_name ());
1095- EXPECT_EQ (" voltage" , state_interfaces[0 ]. get_interface_name ());
1096- EXPECT_EQ (" joint1" , state_interfaces[0 ]. get_prefix_name ());
1097- EXPECT_TRUE (std::isnan (state_interfaces[0 ]. get_value ()));
1094+ EXPECT_EQ (" joint1/voltage" , state_interfaces[0 ]-> get_name ());
1095+ EXPECT_EQ (" voltage" , state_interfaces[0 ]-> get_interface_name ());
1096+ EXPECT_EQ (" joint1" , state_interfaces[0 ]-> get_prefix_name ());
1097+ EXPECT_TRUE (std::isnan (state_interfaces[0 ]-> get_value ()));
10981098
10991099 // Not updated because is is UNCONFIGURED
11001100 sensor_hw.read (TIME, PERIOD);
1101- EXPECT_TRUE (std::isnan (state_interfaces[0 ]. get_value ()));
1101+ EXPECT_TRUE (std::isnan (state_interfaces[0 ]-> get_value ()));
11021102
11031103 // Updated because is is INACTIVE
11041104 state = sensor_hw.configure ();
11051105 EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, state.id ());
11061106 EXPECT_EQ (hardware_interface::lifecycle_state_names::INACTIVE, state.label ());
1107- EXPECT_EQ (0.0 , state_interfaces[0 ]. get_value ());
1107+ EXPECT_EQ (0.0 , state_interfaces[0 ]-> get_value ());
11081108
11091109 // It can read now
11101110 sensor_hw.read (TIME, PERIOD);
1111- EXPECT_EQ (0x666 , state_interfaces[0 ]. get_value ());
1111+ EXPECT_EQ (0x666 , state_interfaces[0 ]-> get_value ());
11121112}
11131113
11141114TEST (TestComponentInterfaces, dummy_sensor_default_read_error_behavior)
@@ -1124,7 +1124,7 @@ TEST(TestComponentInterfaces, dummy_sensor_default_read_error_behavior)
11241124 const hardware_interface::HardwareInfo voltage_sensor_res = control_resources[0 ];
11251125 auto state = sensor_hw.initialize (voltage_sensor_res);
11261126
1127- auto state_interfaces = sensor_hw.export_state_interfaces ();
1127+ auto state_interfaces = sensor_hw.on_export_state_interfaces ();
11281128 // Updated because is is INACTIVE
11291129 state = sensor_hw.configure ();
11301130 state = sensor_hw.activate ();
@@ -1146,7 +1146,7 @@ TEST(TestComponentInterfaces, dummy_sensor_default_read_error_behavior)
11461146
11471147 // activate again and expect reset values
11481148 state = sensor_hw.configure ();
1149- EXPECT_EQ (state_interfaces[0 ]. get_value (), 0.0 );
1149+ EXPECT_EQ (state_interfaces[0 ]-> get_value (), 0.0 );
11501150
11511151 state = sensor_hw.activate ();
11521152 EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, state.id ());
@@ -1277,32 +1277,32 @@ TEST(TestComponentInterfaces, dummy_actuator_default)
12771277 EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id ());
12781278 EXPECT_EQ (hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label ());
12791279
1280- auto state_interfaces = actuator_hw.export_state_interfaces ();
1280+ auto state_interfaces = actuator_hw.on_export_state_interfaces ();
12811281 ASSERT_EQ (2u , state_interfaces.size ());
1282- EXPECT_EQ (" joint1/position" , state_interfaces[0 ]. get_name ());
1283- EXPECT_EQ (hardware_interface::HW_IF_POSITION, state_interfaces[0 ]. get_interface_name ());
1284- EXPECT_EQ (" joint1" , state_interfaces[0 ]. get_prefix_name ());
1285- EXPECT_EQ (" joint1/velocity" , state_interfaces[1 ]. get_name ());
1286- EXPECT_EQ (hardware_interface::HW_IF_VELOCITY, state_interfaces[1 ]. get_interface_name ());
1287- EXPECT_EQ (" joint1" , state_interfaces[1 ]. get_prefix_name ());
1288-
1289- auto command_interfaces = actuator_hw.export_command_interfaces ();
1282+ EXPECT_EQ (" joint1/position" , state_interfaces[0 ]-> get_name ());
1283+ EXPECT_EQ (hardware_interface::HW_IF_POSITION, state_interfaces[0 ]-> get_interface_name ());
1284+ EXPECT_EQ (" joint1" , state_interfaces[0 ]-> get_prefix_name ());
1285+ EXPECT_EQ (" joint1/velocity" , state_interfaces[1 ]-> get_name ());
1286+ EXPECT_EQ (hardware_interface::HW_IF_VELOCITY, state_interfaces[1 ]-> get_interface_name ());
1287+ EXPECT_EQ (" joint1" , state_interfaces[1 ]-> get_prefix_name ());
1288+
1289+ auto command_interfaces = actuator_hw.on_export_command_interfaces ();
12901290 ASSERT_EQ (1u , command_interfaces.size ());
1291- EXPECT_EQ (" joint1/velocity" , command_interfaces[0 ]. get_name ());
1292- EXPECT_EQ (hardware_interface::HW_IF_VELOCITY, command_interfaces[0 ]. get_interface_name ());
1293- EXPECT_EQ (" joint1" , command_interfaces[0 ]. get_prefix_name ());
1291+ EXPECT_EQ (" joint1/velocity" , command_interfaces[0 ]-> get_name ());
1292+ EXPECT_EQ (hardware_interface::HW_IF_VELOCITY, command_interfaces[0 ]-> get_interface_name ());
1293+ EXPECT_EQ (" joint1" , command_interfaces[0 ]-> get_prefix_name ());
12941294
12951295 double velocity_value = 1.0 ;
1296- command_interfaces[0 ]. set_value (velocity_value); // velocity
1296+ command_interfaces[0 ]-> set_value (velocity_value); // velocity
12971297 ASSERT_EQ (hardware_interface::return_type::ERROR, actuator_hw.write (TIME, PERIOD));
12981298
12991299 // Noting should change because it is UNCONFIGURED
13001300 for (auto step = 0u ; step < 10 ; ++step)
13011301 {
13021302 ASSERT_EQ (hardware_interface::return_type::ERROR, actuator_hw.read (TIME, PERIOD));
13031303
1304- ASSERT_TRUE (std::isnan (state_interfaces[0 ]. get_value ())); // position value
1305- ASSERT_TRUE (std::isnan (state_interfaces[1 ]. get_value ())); // velocity
1304+ ASSERT_TRUE (std::isnan (state_interfaces[0 ]-> get_value ())); // position value
1305+ ASSERT_TRUE (std::isnan (state_interfaces[1 ]-> get_value ())); // velocity
13061306
13071307 ASSERT_EQ (hardware_interface::return_type::ERROR, actuator_hw.write (TIME, PERIOD));
13081308 }
@@ -1316,8 +1316,8 @@ TEST(TestComponentInterfaces, dummy_actuator_default)
13161316 {
13171317 ASSERT_EQ (hardware_interface::return_type::OK, actuator_hw.read (TIME, PERIOD));
13181318
1319- EXPECT_EQ (step * velocity_value, state_interfaces[0 ]. get_value ()); // position value
1320- EXPECT_EQ (step ? velocity_value : 0 , state_interfaces[1 ]. get_value ()); // velocity
1319+ EXPECT_EQ (step * velocity_value, state_interfaces[0 ]-> get_value ()); // position value
1320+ EXPECT_EQ (step ? velocity_value : 0 , state_interfaces[1 ]-> get_value ()); // velocity
13211321
13221322 ASSERT_EQ (hardware_interface::return_type::OK, actuator_hw.write (TIME, PERIOD));
13231323 }
@@ -1331,8 +1331,8 @@ TEST(TestComponentInterfaces, dummy_actuator_default)
13311331 {
13321332 ASSERT_EQ (hardware_interface::return_type::OK, actuator_hw.read (TIME, PERIOD));
13331333
1334- EXPECT_EQ ((10 + step) * velocity_value, state_interfaces[0 ]. get_value ()); // position value
1335- EXPECT_EQ (velocity_value, state_interfaces[1 ]. get_value ()); // velocity
1334+ EXPECT_EQ ((10 + step) * velocity_value, state_interfaces[0 ]-> get_value ()); // position value
1335+ EXPECT_EQ (velocity_value, state_interfaces[1 ]-> get_value ()); // velocity
13361336
13371337 ASSERT_EQ (hardware_interface::return_type::OK, actuator_hw.write (TIME, PERIOD));
13381338 }
@@ -1346,8 +1346,8 @@ TEST(TestComponentInterfaces, dummy_actuator_default)
13461346 {
13471347 ASSERT_EQ (hardware_interface::return_type::ERROR, actuator_hw.read (TIME, PERIOD));
13481348
1349- EXPECT_EQ (20 * velocity_value, state_interfaces[0 ]. get_value ()); // position value
1350- EXPECT_EQ (0 , state_interfaces[1 ]. get_value ()); // velocity
1349+ EXPECT_EQ (20 * velocity_value, state_interfaces[0 ]-> get_value ()); // position value
1350+ EXPECT_EQ (0 , state_interfaces[1 ]-> get_value ()); // velocity
13511351
13521352 ASSERT_EQ (hardware_interface::return_type::ERROR, actuator_hw.write (TIME, PERIOD));
13531353 }
0 commit comments