Skip to content

Commit df2d739

Browse files
committed
fix failing tests
1 parent 626412b commit df2d739

File tree

2 files changed

+31
-34
lines changed

2 files changed

+31
-34
lines changed

hardware_interface/test/mock_components/test_generic_system.cpp

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -515,7 +515,6 @@ class TestGenericSystem : public ::testing::Test
515515
<state_interface name="position">
516516
<param name="initial_value">2.78</param>
517517
</state_interface>
518-
<state_interface name="position"/>
519518
<state_interface name="velocity"/>
520519
<state_interface name="acceleration"/>
521520
</joint>
@@ -546,7 +545,6 @@ class TestGenericSystem : public ::testing::Test
546545
<state_interface name="position">
547546
<param name="initial_value">2.78</param>
548547
</state_interface>
549-
<state_interface name="position"/>
550548
<state_interface name="velocity"/>
551549
<state_interface name="acceleration"/>
552550
</joint>
@@ -555,7 +553,6 @@ class TestGenericSystem : public ::testing::Test
555553
<state_interface name="position">
556554
<param name="initial_value">2.78</param>
557555
</state_interface>
558-
<state_interface name="position"/>
559556
<state_interface name="velocity"/>
560557
<state_interface name="acceleration"/>
561558
</joint>

hardware_interface/test/test_component_interfaces.cpp

Lines changed: 31 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -1077,26 +1077,26 @@ TEST(TestComponentInterfaces, dummy_sensor_default_interface_export)
10771077
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
10781078
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
10791079

1080-
auto state_interfaces = sensor_hw.export_state_interfaces();
1080+
auto state_interfaces = sensor_hw.on_export_state_interfaces();
10811081
ASSERT_EQ(1u, state_interfaces.size());
1082-
EXPECT_EQ("joint1/voltage", state_interfaces[0].get_name());
1083-
EXPECT_EQ("voltage", state_interfaces[0].get_interface_name());
1084-
EXPECT_EQ("joint1", state_interfaces[0].get_prefix_name());
1085-
EXPECT_TRUE(std::isnan(state_interfaces[0].get_value()));
1082+
EXPECT_EQ("joint1/voltage", state_interfaces[0]->get_name());
1083+
EXPECT_EQ("voltage", state_interfaces[0]->get_interface_name());
1084+
EXPECT_EQ("joint1", state_interfaces[0]->get_prefix_name());
1085+
EXPECT_TRUE(std::isnan(state_interfaces[0]->get_value()));
10861086

10871087
// Not updated because is is UNCONFIGURED
10881088
sensor_hw.read(TIME, PERIOD);
1089-
EXPECT_TRUE(std::isnan(state_interfaces[0].get_value()));
1089+
EXPECT_TRUE(std::isnan(state_interfaces[0]->get_value()));
10901090

10911091
// Updated because is is INACTIVE
10921092
state = sensor_hw.configure();
10931093
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, state.id());
10941094
EXPECT_EQ(hardware_interface::lifecycle_state_names::INACTIVE, state.label());
1095-
EXPECT_EQ(0.0, state_interfaces[0].get_value());
1095+
EXPECT_EQ(0.0, state_interfaces[0]->get_value());
10961096

10971097
// It can read now
10981098
sensor_hw.read(TIME, PERIOD);
1099-
EXPECT_EQ(0x666, state_interfaces[0].get_value());
1099+
EXPECT_EQ(0x666, state_interfaces[0]->get_value());
11001100
}
11011101

11021102
TEST(TestComponentInterfaces, dummy_sensor_default_read_error_behavior)
@@ -1112,7 +1112,7 @@ TEST(TestComponentInterfaces, dummy_sensor_default_read_error_behavior)
11121112
const hardware_interface::HardwareInfo voltage_sensor_res = control_resources[0];
11131113
auto state = sensor_hw.initialize(voltage_sensor_res);
11141114

1115-
auto state_interfaces = sensor_hw.export_state_interfaces();
1115+
auto state_interfaces = sensor_hw.on_export_state_interfaces();
11161116
// Updated because is is INACTIVE
11171117
state = sensor_hw.configure();
11181118
state = sensor_hw.activate();
@@ -1134,7 +1134,7 @@ TEST(TestComponentInterfaces, dummy_sensor_default_read_error_behavior)
11341134

11351135
// activate again and expect reset values
11361136
state = sensor_hw.configure();
1137-
EXPECT_EQ(state_interfaces[0].get_value(), 0.0);
1137+
EXPECT_EQ(state_interfaces[0]->get_value(), 0.0);
11381138

11391139
state = sensor_hw.activate();
11401140
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, state.id());
@@ -1265,32 +1265,32 @@ TEST(TestComponentInterfaces, dummy_actuator_default)
12651265
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
12661266
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());
12671267

1268-
auto state_interfaces = actuator_hw.export_state_interfaces();
1268+
auto state_interfaces = actuator_hw.on_export_state_interfaces();
12691269
ASSERT_EQ(2u, state_interfaces.size());
1270-
EXPECT_EQ("joint1/position", state_interfaces[0].get_name());
1271-
EXPECT_EQ(hardware_interface::HW_IF_POSITION, state_interfaces[0].get_interface_name());
1272-
EXPECT_EQ("joint1", state_interfaces[0].get_prefix_name());
1273-
EXPECT_EQ("joint1/velocity", state_interfaces[1].get_name());
1274-
EXPECT_EQ(hardware_interface::HW_IF_VELOCITY, state_interfaces[1].get_interface_name());
1275-
EXPECT_EQ("joint1", state_interfaces[1].get_prefix_name());
1276-
1277-
auto command_interfaces = actuator_hw.export_command_interfaces();
1270+
EXPECT_EQ("joint1/position", state_interfaces[0]->get_name());
1271+
EXPECT_EQ(hardware_interface::HW_IF_POSITION, state_interfaces[0]->get_interface_name());
1272+
EXPECT_EQ("joint1", state_interfaces[0]->get_prefix_name());
1273+
EXPECT_EQ("joint1/velocity", state_interfaces[1]->get_name());
1274+
EXPECT_EQ(hardware_interface::HW_IF_VELOCITY, state_interfaces[1]->get_interface_name());
1275+
EXPECT_EQ("joint1", state_interfaces[1]->get_prefix_name());
1276+
1277+
auto command_interfaces = actuator_hw.on_export_command_interfaces();
12781278
ASSERT_EQ(1u, command_interfaces.size());
1279-
EXPECT_EQ("joint1/velocity", command_interfaces[0].get_name());
1280-
EXPECT_EQ(hardware_interface::HW_IF_VELOCITY, command_interfaces[0].get_interface_name());
1281-
EXPECT_EQ("joint1", command_interfaces[0].get_prefix_name());
1279+
EXPECT_EQ("joint1/velocity", command_interfaces[0]->get_name());
1280+
EXPECT_EQ(hardware_interface::HW_IF_VELOCITY, command_interfaces[0]->get_interface_name());
1281+
EXPECT_EQ("joint1", command_interfaces[0]->get_prefix_name());
12821282

12831283
double velocity_value = 1.0;
1284-
command_interfaces[0].set_value(velocity_value); // velocity
1284+
command_interfaces[0]->set_value(velocity_value); // velocity
12851285
ASSERT_EQ(hardware_interface::return_type::ERROR, actuator_hw.write(TIME, PERIOD));
12861286

12871287
// Noting should change because it is UNCONFIGURED
12881288
for (auto step = 0u; step < 10; ++step)
12891289
{
12901290
ASSERT_EQ(hardware_interface::return_type::ERROR, actuator_hw.read(TIME, PERIOD));
12911291

1292-
ASSERT_TRUE(std::isnan(state_interfaces[0].get_value())); // position value
1293-
ASSERT_TRUE(std::isnan(state_interfaces[1].get_value())); // velocity
1292+
ASSERT_TRUE(std::isnan(state_interfaces[0]->get_value())); // position value
1293+
ASSERT_TRUE(std::isnan(state_interfaces[1]->get_value())); // velocity
12941294

12951295
ASSERT_EQ(hardware_interface::return_type::ERROR, actuator_hw.write(TIME, PERIOD));
12961296
}
@@ -1304,8 +1304,8 @@ TEST(TestComponentInterfaces, dummy_actuator_default)
13041304
{
13051305
ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.read(TIME, PERIOD));
13061306

1307-
EXPECT_EQ(step * velocity_value, state_interfaces[0].get_value()); // position value
1308-
EXPECT_EQ(step ? velocity_value : 0, state_interfaces[1].get_value()); // velocity
1307+
EXPECT_EQ(step * velocity_value, state_interfaces[0]->get_value()); // position value
1308+
EXPECT_EQ(step ? velocity_value : 0, state_interfaces[1]->get_value()); // velocity
13091309

13101310
ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.write(TIME, PERIOD));
13111311
}
@@ -1319,8 +1319,8 @@ TEST(TestComponentInterfaces, dummy_actuator_default)
13191319
{
13201320
ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.read(TIME, PERIOD));
13211321

1322-
EXPECT_EQ((10 + step) * velocity_value, state_interfaces[0].get_value()); // position value
1323-
EXPECT_EQ(velocity_value, state_interfaces[1].get_value()); // velocity
1322+
EXPECT_EQ((10 + step) * velocity_value, state_interfaces[0]->get_value()); // position value
1323+
EXPECT_EQ(velocity_value, state_interfaces[1]->get_value()); // velocity
13241324

13251325
ASSERT_EQ(hardware_interface::return_type::OK, actuator_hw.write(TIME, PERIOD));
13261326
}
@@ -1334,8 +1334,8 @@ TEST(TestComponentInterfaces, dummy_actuator_default)
13341334
{
13351335
ASSERT_EQ(hardware_interface::return_type::ERROR, actuator_hw.read(TIME, PERIOD));
13361336

1337-
EXPECT_EQ(20 * velocity_value, state_interfaces[0].get_value()); // position value
1338-
EXPECT_EQ(0, state_interfaces[1].get_value()); // velocity
1337+
EXPECT_EQ(20 * velocity_value, state_interfaces[0]->get_value()); // position value
1338+
EXPECT_EQ(0, state_interfaces[1]->get_value()); // velocity
13391339

13401340
ASSERT_EQ(hardware_interface::return_type::ERROR, actuator_hw.write(TIME, PERIOD));
13411341
}

0 commit comments

Comments
 (0)