Skip to content

Commit

Permalink
make compileable
Browse files Browse the repository at this point in the history
  • Loading branch information
mamueluth committed Aug 28, 2024
1 parent 132a5e3 commit 0a61ac5
Show file tree
Hide file tree
Showing 4 changed files with 18 additions and 18 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -135,7 +135,7 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
virtual void import_state_interface_descriptions(const HardwareInfo & hardware_info)
{
auto joint_state_interface_descriptions =
parse_state_interface_descriptions_from_hardware_info(hardware_info.joints);
parse_state_interface_descriptions(hardware_info.joints);
for (const auto & description : joint_state_interface_descriptions)
{
joint_state_interfaces_.insert(std::make_pair(description.get_name(), description));
Expand All @@ -149,7 +149,7 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
virtual void import_command_interface_descriptions(const HardwareInfo & hardware_info)
{
auto joint_command_interface_descriptions =
parse_command_interface_descriptions_from_hardware_info(hardware_info.joints);
parse_command_interface_descriptions(hardware_info.joints);
for (const auto & description : joint_command_interface_descriptions)
{
joint_command_interfaces_.insert(std::make_pair(description.get_name(), description));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -134,7 +134,7 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
virtual void import_state_interface_descriptions(const HardwareInfo & hardware_info)
{
auto sensor_state_interface_descriptions =
parse_state_interface_descriptions_from_hardware_info(hardware_info.sensors);
parse_state_interface_descriptions(hardware_info.sensors);
for (const auto & description : sensor_state_interface_descriptions)
{
sensor_state_interfaces_.insert(std::make_pair(description.get_name(), description));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -138,19 +138,19 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
void import_state_interface_descriptions(const HardwareInfo & hardware_info)
{
auto joint_state_interface_descriptions =
parse_state_interface_descriptions_from_hardware_info(hardware_info.joints);
parse_state_interface_descriptions(hardware_info.joints);
for (const auto & description : joint_state_interface_descriptions)
{
joint_state_interfaces_.insert(std::make_pair(description.get_name(), description));
}
auto sensor_state_interface_descriptions =
parse_state_interface_descriptions_from_hardware_info(hardware_info.sensors);
parse_state_interface_descriptions(hardware_info.sensors);
for (const auto & description : sensor_state_interface_descriptions)
{
sensor_state_interfaces_.insert(std::make_pair(description.get_name(), description));
}
auto gpio_state_interface_descriptions =
parse_state_interface_descriptions_from_hardware_info(hardware_info.gpios);
parse_state_interface_descriptions(hardware_info.gpios);
for (const auto & description : gpio_state_interface_descriptions)
{
gpio_state_interfaces_.insert(std::make_pair(description.get_name(), description));
Expand All @@ -164,13 +164,13 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
void import_command_interface_descriptions(const HardwareInfo & hardware_info)
{
auto joint_command_interface_descriptions =
parse_command_interface_descriptions_from_hardware_info(hardware_info.joints);
parse_command_interface_descriptions(hardware_info.joints);
for (const auto & description : joint_command_interface_descriptions)
{
joint_command_interfaces_.insert(std::make_pair(description.get_name(), description));
}
auto gpio_command_interface_descriptions =
parse_command_interface_descriptions_from_hardware_info(hardware_info.gpios);
parse_command_interface_descriptions(hardware_info.gpios);
for (const auto & description : gpio_command_interface_descriptions)
{
gpio_command_interfaces_.insert(std::make_pair(description.get_name(), description));
Expand Down
20 changes: 10 additions & 10 deletions hardware_interface/test/test_component_interfaces.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1380,7 +1380,7 @@ TEST(TestComponentInterfaces, dummy_actuator_read_error_behavior)
}
ASSERT_EQ(hardware_interface::return_type::ERROR, actuator_hw.read(TIME, PERIOD));

state = actuator_hw.get_state();
state = actuator_hw.get_lifecycle_state();
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::FINALIZED, state.label());

Expand Down Expand Up @@ -1426,7 +1426,7 @@ TEST(TestComponentInterfaces, dummy_actuator_default_read_error_behavior)
}
ASSERT_EQ(hardware_interface::return_type::ERROR, actuator_hw.read(TIME, PERIOD));

state = actuator_hw.get_state();
state = actuator_hw.get_lifecycle_state();
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

Expand Down Expand Up @@ -1513,7 +1513,7 @@ TEST(TestComponentInterfaces, dummy_actuator_write_error_behavior)
}
ASSERT_EQ(hardware_interface::return_type::ERROR, actuator_hw.write(TIME, PERIOD));

state = actuator_hw.get_state();
state = actuator_hw.get_lifecycle_state();
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::FINALIZED, state.label());

Expand Down Expand Up @@ -1558,7 +1558,7 @@ TEST(TestComponentInterfaces, dummy_actuator_default_write_error_behavior)
}
ASSERT_EQ(hardware_interface::return_type::ERROR, actuator_hw.write(TIME, PERIOD));

state = actuator_hw.get_state();
state = actuator_hw.get_lifecycle_state();
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

Expand Down Expand Up @@ -1691,7 +1691,7 @@ TEST(TestComponentInterfaces, dummy_sensor_default_read_error_behavior)
}
ASSERT_EQ(hardware_interface::return_type::ERROR, sensor_hw.read(TIME, PERIOD));

state = sensor_hw.get_state();
state = sensor_hw.get_lifecycle_state();
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

Expand All @@ -1711,7 +1711,7 @@ TEST(TestComponentInterfaces, dummy_sensor_default_read_error_behavior)
}
ASSERT_EQ(hardware_interface::return_type::ERROR, sensor_hw.read(TIME, PERIOD));

state = sensor_hw.get_state();
state = sensor_hw.get_lifecycle_state();
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::FINALIZED, state.label());

Expand Down Expand Up @@ -1777,7 +1777,7 @@ TEST(TestComponentInterfaces, dummy_system_read_error_behavior)
}
ASSERT_EQ(hardware_interface::return_type::ERROR, system_hw.read(TIME, PERIOD));

state = system_hw.get_state();
state = system_hw.get_lifecycle_state();
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::FINALIZED, state.label());

Expand Down Expand Up @@ -1821,7 +1821,7 @@ TEST(TestComponentInterfaces, dummy_system_default_read_error_behavior)
}
ASSERT_EQ(hardware_interface::return_type::ERROR, system_hw.read(TIME, PERIOD));

state = system_hw.get_state();
state = system_hw.get_lifecycle_state();
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

Expand Down Expand Up @@ -1915,7 +1915,7 @@ TEST(TestComponentInterfaces, dummy_system_write_error_behavior)
}
ASSERT_EQ(hardware_interface::return_type::ERROR, system_hw.write(TIME, PERIOD));

state = system_hw.get_state();
state = system_hw.get_lifecycle_state();
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::FINALIZED, state.label());

Expand Down Expand Up @@ -1959,7 +1959,7 @@ TEST(TestComponentInterfaces, dummy_system_default_write_error_behavior)
}
ASSERT_EQ(hardware_interface::return_type::ERROR, system_hw.write(TIME, PERIOD));

state = system_hw.get_state();
state = system_hw.get_lifecycle_state();
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

Expand Down

0 comments on commit 0a61ac5

Please sign in to comment.