Skip to content

Commit

Permalink
Remove old parameter from tests.
Browse files Browse the repository at this point in the history
  • Loading branch information
destogl committed Dec 11, 2023
1 parent ae7279e commit a86bc40
Showing 1 changed file with 4 additions and 62 deletions.
66 changes: 4 additions & 62 deletions controller_manager/test/test_hardware_management_srvs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -205,7 +205,8 @@ class TestControllerManagerHWManagementSrvs : public TestControllerManagerSrvs
TEST_F(TestControllerManagerHWManagementSrvs, list_hardware_components)
{
// Default status after start:
// checks if "configure_components_on_start" and "activate_components_on_start" are correctly read
// checks if "hardware_components_initial_state.unconfigured" and
// "hardware_components_initial_state.inactive" are correctly read

list_hardware_components_and_check(
// actuator, sensor, system
Expand Down Expand Up @@ -391,8 +392,8 @@ class TestControllerManagerHWManagementSrvsWithoutParams

TEST_F(TestControllerManagerHWManagementSrvsWithoutParams, test_default_activation_of_all_hardware)
{
// "configure_components_on_start" and "activate_components_on_start" are not set (empty)
// therefore all hardware components are active
// "hardware_components_initial_state.unconfigured" and "hardware_components_initial_state.inactive"
// are not set (empty). Therefore, all hardware components are active.
list_hardware_components_and_check(
// actuator, sensor, system
std::vector<uint8_t>(
Expand All @@ -412,62 +413,3 @@ TEST_F(TestControllerManagerHWManagementSrvsWithoutParams, test_default_activati
{{false, false, false, false}, {false, false, false, false, false, false, false}}, // system
}));
}

// BEGIN: Remove at the end of 2023
class TestControllerManagerHWManagementSrvsOldParameters
: public TestControllerManagerHWManagementSrvs
{
public:
void SetUp() override
{
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
cm_ = std::make_shared<controller_manager::ControllerManager>(
std::make_unique<hardware_interface::ResourceManager>(), executor_, TEST_CM_NAME);
run_updater_ = false;

cm_->set_parameter(
rclcpp::Parameter("robot_description", ros2_control_test_assets::minimal_robot_urdf));
cm_->set_parameter(rclcpp::Parameter(
"activate_components_on_start", std::vector<std::string>({TEST_ACTUATOR_HARDWARE_NAME})));
cm_->set_parameter(rclcpp::Parameter(
"configure_components_on_start", std::vector<std::string>({TEST_SENSOR_HARDWARE_NAME})));

std::string robot_description = "";
cm_->get_parameter("robot_description", robot_description);
if (robot_description.empty())
{
throw std::runtime_error(
"Unable to initialize resource manager, no robot description found.");
}

cm_->init_resource_manager(robot_description);

SetUpSrvsCMExecutor();
}
};

TEST_F(TestControllerManagerHWManagementSrvsOldParameters, list_hardware_components)
{
// Default status after start:
// checks if "configure_components_on_start" and "activate_components_on_start" are correctly read

list_hardware_components_and_check(
// actuator, sensor, system
std::vector<uint8_t>(
{LFC_STATE::PRIMARY_STATE_ACTIVE, LFC_STATE::PRIMARY_STATE_INACTIVE,
LFC_STATE::PRIMARY_STATE_UNCONFIGURED}),
std::vector<std::string>({ACTIVE, INACTIVE, UNCONFIGURED}),
std::vector<std::vector<std::vector<bool>>>({
// is available
{{true, true}, {true, true, true}}, // actuator
{{}, {true}}, // sensor
{{false, false, false, false}, {false, false, false, false, false, false, false}}, // system
}),
std::vector<std::vector<std::vector<bool>>>({
// is claimed
{{false, false}, {false, false, false}}, // actuator
{{}, {false}}, // sensor
{{false, false, false, false}, {false, false, false, false, false, false, false}}, // system
}));
}
// END: Remove at the end of 2023

0 comments on commit a86bc40

Please sign in to comment.