Skip to content

Commit

Permalink
update tests to be able to sort on configuring the controller
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Sep 21, 2023
1 parent d77f6f1 commit e654806
Show file tree
Hide file tree
Showing 3 changed files with 15 additions and 112 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -32,33 +32,13 @@ TestChainableController::TestChainableController()
controller_interface::InterfaceConfiguration
TestChainableController::command_interface_configuration() const
{
if (
get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE ||
get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
{
return cmd_iface_cfg_;
}
else
{
throw std::runtime_error(
"Can not get command interface configuration until the controller is configured.");
}
return cmd_iface_cfg_;
}

controller_interface::InterfaceConfiguration
TestChainableController::state_interface_configuration() const
{
if (
get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE ||
get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
{
return state_iface_cfg_;
}
else
{
throw std::runtime_error(
"Can not get state interface configuration until the controller is configured.");
}
return state_iface_cfg_;
}

controller_interface::return_type TestChainableController::update_reference_from_subscribers(
Expand Down
24 changes: 2 additions & 22 deletions controller_manager/test/test_controller/test_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,32 +31,12 @@ TestController::TestController()

controller_interface::InterfaceConfiguration TestController::command_interface_configuration() const
{
if (
get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE ||
get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
{
return cmd_iface_cfg_;
}
else
{
throw std::runtime_error(
"Can not get command interface configuration until the controller is configured.");
}
return cmd_iface_cfg_;
}

controller_interface::InterfaceConfiguration TestController::state_interface_configuration() const
{
if (
get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE ||
get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
{
return state_iface_cfg_;
}
else
{
throw std::runtime_error(
"Can not get state interface configuration until the controller is configured.");
}
return state_iface_cfg_;
}

controller_interface::return_type TestController::update(
Expand Down
79 changes: 11 additions & 68 deletions controller_manager/test/test_controller_manager_srvs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -261,27 +261,28 @@ TEST_F(TestControllerManagerSrvs, list_chained_controllers_srv)
// get controller list after configure
result = call_service_and_wait(*client, request, srv_executor);
ASSERT_EQ(2u, result->controller.size());
// At this stage, the controllers are already reordered
// check chainable controller
ASSERT_EQ(result->controller[0].state, "inactive");
ASSERT_EQ(result->controller[0].claimed_interfaces.size(), 0u);
ASSERT_EQ(result->controller[0].required_command_interfaces.size(), 1u);
ASSERT_EQ(result->controller[0].required_command_interfaces.size(), 3u);
ASSERT_EQ(result->controller[0].required_state_interfaces.size(), 2u);
ASSERT_EQ(result->controller[0].is_chainable, true);
ASSERT_EQ(result->controller[0].is_chainable, false);
ASSERT_EQ(result->controller[0].is_chained, false);
ASSERT_EQ(result->controller[0].reference_interfaces.size(), 2u);
ASSERT_EQ("joint1/position", result->controller[0].reference_interfaces[0]);
ASSERT_EQ("joint1/velocity", result->controller[0].reference_interfaces[1]);
ASSERT_EQ(result->controller[0].reference_interfaces.size(), 0u);
ASSERT_EQ(result->controller[0].chain_connections.size(), 1u);

ASSERT_EQ(result->controller[0].chain_connections.size(), 0u);
// check test controller
ASSERT_EQ(result->controller[1].state, "inactive");
ASSERT_EQ(result->controller[1].claimed_interfaces.size(), 0u);
ASSERT_EQ(result->controller[1].required_command_interfaces.size(), 3u);
ASSERT_EQ(result->controller[1].required_command_interfaces.size(), 1u);
ASSERT_EQ(result->controller[1].required_state_interfaces.size(), 2u);
ASSERT_EQ(result->controller[1].is_chainable, false);
ASSERT_EQ(result->controller[1].is_chainable, true);
ASSERT_EQ(result->controller[1].is_chained, false);
ASSERT_EQ(result->controller[1].reference_interfaces.size(), 0u);
ASSERT_EQ(result->controller[1].chain_connections.size(), 1u);
ASSERT_EQ(result->controller[1].reference_interfaces.size(), 2u);
ASSERT_EQ(result->controller[1].chain_connections.size(), 0u);
ASSERT_EQ("joint1/position", result->controller[1].reference_interfaces[0]);
ASSERT_EQ("joint1/velocity", result->controller[1].reference_interfaces[1]);
// activate controllers
cm_->switch_controller(
{test_chainable_controller::TEST_CONTROLLER_NAME}, {},
Expand Down Expand Up @@ -603,22 +604,6 @@ TEST_F(TestControllerManagerSrvs, list_sorted_chained_controllers)
result = call_service_and_wait(*client, request, srv_executor);
ASSERT_EQ(6u, result->controller.size());

// activate controllers
cm_->switch_controller(
{TEST_CHAINED_CONTROLLER_1}, {},
controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0));
cm_->switch_controller(
{TEST_CHAINED_CONTROLLER_3, TEST_CHAINED_CONTROLLER_5, TEST_CHAINED_CONTROLLER_2,
TEST_CHAINED_CONTROLLER_4},
{}, controller_manager_msgs::srv::SwitchController::Request::STRICT, true,
rclcpp::Duration(0, 0));
cm_->switch_controller(
{test_controller::TEST_CONTROLLER_NAME}, {},
controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0));
// get controller list after activate
result = call_service_and_wait(*client, request, srv_executor);

ASSERT_EQ(6u, result->controller.size());
// reordered controllers
ASSERT_EQ(result->controller[0].name, "test_controller_name");
ASSERT_EQ(result->controller[1].name, TEST_CHAINED_CONTROLLER_5);
Expand Down Expand Up @@ -776,25 +761,6 @@ TEST_F(TestControllerManagerSrvs, list_sorted_complex_chained_controllers)
result = call_service_and_wait(*client, request, srv_executor);
ASSERT_EQ(8u, result->controller.size());

// activate controllers
cm_->switch_controller(
{TEST_CHAINED_CONTROLLER_1}, {},
controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0));
cm_->switch_controller(
{TEST_CHAINED_CONTROLLER_3}, {},
controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0));
cm_->switch_controller(
{TEST_CHAINED_CONTROLLER_6, TEST_CHAINED_CONTROLLER_5, TEST_CHAINED_CONTROLLER_2,
TEST_CHAINED_CONTROLLER_4, TEST_CHAINED_CONTROLLER_7},
{}, controller_manager_msgs::srv::SwitchController::Request::STRICT, true,
rclcpp::Duration(0, 0));
cm_->switch_controller(
{test_controller::TEST_CONTROLLER_NAME}, {},
controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0));
// get controller list after activate
result = call_service_and_wait(*client, request, srv_executor);

ASSERT_EQ(8u, result->controller.size());
// reordered controllers
ASSERT_EQ(result->controller[0].name, "test_controller_name");
ASSERT_EQ(result->controller[1].name, TEST_CHAINED_CONTROLLER_7);
Expand Down Expand Up @@ -1009,29 +975,6 @@ TEST_F(TestControllerManagerSrvs, list_sorted_independent_chained_controllers)
result = call_service_and_wait(*client, request, srv_executor);
ASSERT_EQ(10u, result->controller.size());

// activate controllers
cm_->switch_controller(
{TEST_CHAINED_CONTROLLER_1}, {},
controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0));
cm_->switch_controller(
{TEST_CHAINED_CONTROLLER_4}, {},
controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0));
cm_->switch_controller(
{TEST_CHAINED_CONTROLLER_7}, {},
controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0));
cm_->switch_controller(
{TEST_CHAINED_CONTROLLER_3, TEST_CHAINED_CONTROLLER_5, TEST_CHAINED_CONTROLLER_2,
TEST_CHAINED_CONTROLLER_6, TEST_CHAINED_CONTROLLER_8},
{}, controller_manager_msgs::srv::SwitchController::Request::STRICT, true,
rclcpp::Duration(0, 0));
cm_->switch_controller(
{TEST_CONTROLLER_1, TEST_CONTROLLER_2}, {},
controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0));
// get controller list after activate
result = call_service_and_wait(*client, request, srv_executor);

ASSERT_EQ(10u, result->controller.size());

auto get_ctrl_pos = [result](const std::string & controller_name) -> int
{
auto it = std::find_if(
Expand Down

0 comments on commit e654806

Please sign in to comment.