Skip to content

Commit

Permalink
ResourceManager doesn't always log an error on shutdown anymore (#867)
Browse files Browse the repository at this point in the history
Co-authored-by: Christopher Wecht <[email protected]>
Co-authored-by: Denis Štogl <[email protected]>
  • Loading branch information
3 people authored Dec 6, 2022
1 parent f58d407 commit 89e6598
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 14 deletions.
2 changes: 1 addition & 1 deletion hardware_interface/src/resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -266,7 +266,7 @@ class ResourceStorage
{
bool result = trigger_and_print_hardware_state_transition(
std::bind(&HardwareT::shutdown, &hardware), "shutdown", hardware.get_name(),
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED);
lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED);

if (result)
{
Expand Down
28 changes: 15 additions & 13 deletions hardware_interface/test/test_resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ class TestableResourceManager : public hardware_interface::ResourceManager
}
};

void set_components_state(
std::vector<hardware_interface::return_type> set_components_state(
TestableResourceManager & rm, const std::vector<std::string> & components, const uint8_t state_id,
const std::string & state_name)
{
Expand All @@ -87,49 +87,52 @@ void set_components_state(
{
int_components = {"TestActuatorHardware", "TestSensorHardware", "TestSystemHardware"};
}
std::vector<hardware_interface::return_type> results;
for (const auto & component : int_components)
{
rclcpp_lifecycle::State state(state_id, state_name);
rm.set_component_state(component, state);
const auto result = rm.set_component_state(component, state);
results.push_back(result);
}
return results;
}

auto configure_components =
[](TestableResourceManager & rm, const std::vector<std::string> & components = {})
{
set_components_state(
return set_components_state(
rm, components, lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
hardware_interface::lifecycle_state_names::INACTIVE);
};

auto activate_components =
[](TestableResourceManager & rm, const std::vector<std::string> & components = {})
{
set_components_state(
return set_components_state(
rm, components, lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
hardware_interface::lifecycle_state_names::ACTIVE);
};

auto deactivate_components =
[](TestableResourceManager & rm, const std::vector<std::string> & components = {})
{
set_components_state(
return set_components_state(
rm, components, lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
hardware_interface::lifecycle_state_names::INACTIVE);
};

auto cleanup_components =
[](TestableResourceManager & rm, const std::vector<std::string> & components = {})
{
set_components_state(
return set_components_state(
rm, components, lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
hardware_interface::lifecycle_state_names::UNCONFIGURED);
};

auto shutdown_components =
[](TestableResourceManager & rm, const std::vector<std::string> & components = {})
{
set_components_state(
return set_components_state(
rm, components, lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED,
hardware_interface::lifecycle_state_names::FINALIZED);
};
Expand Down Expand Up @@ -534,7 +537,7 @@ TEST_F(ResourceManagerTest, lifecycle_all_resources)
hardware_interface::lifecycle_state_names::UNCONFIGURED);
}

configure_components(rm);
ASSERT_THAT(configure_components(rm), ::testing::Each(hardware_interface::return_type::OK));
{
auto status_map = rm.get_components_status();
EXPECT_EQ(
Expand All @@ -557,7 +560,7 @@ TEST_F(ResourceManagerTest, lifecycle_all_resources)
hardware_interface::lifecycle_state_names::INACTIVE);
}

activate_components(rm);
ASSERT_THAT(activate_components(rm), ::testing::Each(hardware_interface::return_type::OK));
{
auto status_map = rm.get_components_status();
EXPECT_EQ(
Expand All @@ -580,7 +583,7 @@ TEST_F(ResourceManagerTest, lifecycle_all_resources)
hardware_interface::lifecycle_state_names::ACTIVE);
}

deactivate_components(rm);
ASSERT_THAT(deactivate_components(rm), ::testing::Each(hardware_interface::return_type::OK));
{
auto status_map = rm.get_components_status();
EXPECT_EQ(
Expand All @@ -603,7 +606,7 @@ TEST_F(ResourceManagerTest, lifecycle_all_resources)
hardware_interface::lifecycle_state_names::INACTIVE);
}

cleanup_components(rm);
ASSERT_THAT(cleanup_components(rm), ::testing::Each(hardware_interface::return_type::OK));
{
auto status_map = rm.get_components_status();
EXPECT_EQ(
Expand All @@ -626,7 +629,7 @@ TEST_F(ResourceManagerTest, lifecycle_all_resources)
hardware_interface::lifecycle_state_names::UNCONFIGURED);
}

shutdown_components(rm);
ASSERT_THAT(shutdown_components(rm), ::testing::Each(hardware_interface::return_type::OK));
{
auto status_map = rm.get_components_status();
EXPECT_EQ(
Expand Down Expand Up @@ -838,7 +841,6 @@ TEST_F(ResourceManagerTest, lifecycle_individual_resources)
hardware_interface::lifecycle_state_names::FINALIZED);
}

// TODO(destogl): Watch-out this fails in output, why is this not caught?!!!
shutdown_components(rm, {TEST_SENSOR_HARDWARE_NAME});
{
auto status_map = rm.get_components_status();
Expand Down

0 comments on commit 89e6598

Please sign in to comment.