Skip to content

Commit b6f32c3

Browse files
saikishordestogl
andauthored
[CM] Set chained controller interfaces 'available' for activated controllers (#1098)
* control reference interface availability based on the controller state * update the docs of the chainable controllers output --------- Co-authored-by: Dr. Denis <denis@stoglrobotics.de>
1 parent 82c82ae commit b6f32c3

File tree

4 files changed

+180
-15
lines changed

4 files changed

+180
-15
lines changed

controller_manager/doc/controller_chaining.rst

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -76,7 +76,9 @@ One can also think of it as an actual chain, you can not add a chain link or bre
7676
Debugging outputs
7777
----------------------------
7878

79-
Flag ``unavailable`` on reference interface does not provide much information about anything at the moment. So don't get confused by it. The reason we have it are internal implementation reasons irelevant for the usage.
79+
- The reference interfaces are ``unavailable`` and ``unclaimed``, when the controller exporting them is in inactive state
80+
- The reference interfaces are ``available`` and ``unclaimed``, when the controller exporting them is in an active state but is not in chained mode with any other controller (The controllers gets its references from the subscriber)
81+
- The reference interfaces are ``available`` and ``claimed``, when the controller exporting them is in active state and also in chained mode with other controllers (The controller gets its references from the controllers it is chained with)
8082

8183

8284
Closing remarks

controller_manager/src/controller_manager.cpp

Lines changed: 15 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -1386,6 +1386,11 @@ void ControllerManager::deactivate_controllers(
13861386
{
13871387
const auto new_state = controller->get_node()->deactivate();
13881388
controller->release_interfaces();
1389+
// if it is a chainable controller, make the reference interfaces unavailable on deactivation
1390+
if (controller->is_chainable())
1391+
{
1392+
resource_manager_->make_controller_reference_interfaces_unavailable(request);
1393+
}
13891394
if (new_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
13901395
{
13911396
RCLCPP_ERROR(
@@ -1419,18 +1424,10 @@ void ControllerManager::switch_chained_mode(
14191424
auto controller = found_it->c;
14201425
if (!is_controller_active(*controller))
14211426
{
1422-
if (controller->set_chained_mode(to_chained_mode))
1423-
{
1424-
if (to_chained_mode)
1425-
{
1426-
resource_manager_->make_controller_reference_interfaces_available(request);
1427-
}
1428-
else
1429-
{
1430-
resource_manager_->make_controller_reference_interfaces_unavailable(request);
1431-
}
1432-
}
1433-
else
1427+
// if it is a chainable controller, make the reference interfaces available on preactivation
1428+
// (This is needed when you activate a couple of chainable controller altogether)
1429+
resource_manager_->make_controller_reference_interfaces_available(request);
1430+
if (!controller->set_chained_mode(to_chained_mode))
14341431
{
14351432
RCLCPP_ERROR(
14361433
get_logger(),
@@ -1567,6 +1564,12 @@ void ControllerManager::activate_controllers(
15671564
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE);
15681565
}
15691566

1567+
// if it is a chainable controller, make the reference interfaces available on activation
1568+
if (controller->is_chainable())
1569+
{
1570+
resource_manager_->make_controller_reference_interfaces_available(request);
1571+
}
1572+
15701573
if (controller->is_async())
15711574
{
15721575
async_controller_threads_.at(controller_name)->activate();

controller_manager/test/test_controller_manager_srvs.cpp

Lines changed: 160 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424
#include "controller_manager/controller_manager.hpp"
2525
#include "controller_manager_msgs/srv/list_controller_types.hpp"
2626
#include "controller_manager_msgs/srv/list_controllers.hpp"
27+
#include "controller_manager_msgs/srv/list_hardware_interfaces.hpp"
2728
#include "controller_manager_msgs/srv/switch_controller.hpp"
2829
#include "lifecycle_msgs/msg/state.hpp"
2930
#include "test_chainable_controller/test_chainable_controller.hpp"
@@ -34,6 +35,7 @@ using ::testing::Return;
3435
using ::testing::UnorderedElementsAre;
3536

3637
using ListControllers = controller_manager_msgs::srv::ListControllers;
38+
using ListHardwareInterfaces = controller_manager_msgs::srv::ListHardwareInterfaces;
3739
using TestController = test_controller::TestController;
3840
using TestChainableController = test_chainable_controller::TestChainableController;
3941

@@ -1553,3 +1555,161 @@ TEST_F(TestControllerManagerSrvs, list_sorted_large_chained_controller_tree)
15531555
}
15541556
RCLCPP_INFO(srv_node->get_logger(), "Check successful!");
15551557
}
1558+
1559+
TEST_F(TestControllerManagerSrvs, list_hardware_interfaces_srv)
1560+
{
1561+
// create server client and request
1562+
rclcpp::executors::SingleThreadedExecutor srv_executor;
1563+
rclcpp::Node::SharedPtr srv_node = std::make_shared<rclcpp::Node>("srv_client");
1564+
srv_executor.add_node(srv_node);
1565+
rclcpp::Client<ListHardwareInterfaces>::SharedPtr client =
1566+
srv_node->create_client<ListHardwareInterfaces>(
1567+
"test_controller_manager/list_hardware_interfaces");
1568+
auto request = std::make_shared<ListHardwareInterfaces::Request>();
1569+
1570+
// create chained controller
1571+
auto test_chained_controller = std::make_shared<TestChainableController>();
1572+
controller_interface::InterfaceConfiguration chained_cmd_cfg = {
1573+
controller_interface::interface_configuration_type::INDIVIDUAL, {"joint1/position"}};
1574+
controller_interface::InterfaceConfiguration chained_state_cfg = {
1575+
controller_interface::interface_configuration_type::INDIVIDUAL,
1576+
{"joint1/position", "joint1/velocity"}};
1577+
test_chained_controller->set_command_interface_configuration(chained_cmd_cfg);
1578+
test_chained_controller->set_state_interface_configuration(chained_state_cfg);
1579+
test_chained_controller->set_reference_interface_names({"joint1/position", "joint1/velocity"});
1580+
// create non-chained controller
1581+
auto test_controller = std::make_shared<TestController>();
1582+
controller_interface::InterfaceConfiguration cmd_cfg = {
1583+
controller_interface::interface_configuration_type::INDIVIDUAL,
1584+
{std::string(test_chainable_controller::TEST_CONTROLLER_NAME) + "/joint1/position",
1585+
std::string(test_chainable_controller::TEST_CONTROLLER_NAME) + "/joint1/velocity",
1586+
"joint2/velocity"}};
1587+
controller_interface::InterfaceConfiguration state_cfg = {
1588+
controller_interface::interface_configuration_type::INDIVIDUAL,
1589+
{"joint1/position", "joint1/velocity"}};
1590+
test_controller->set_command_interface_configuration(cmd_cfg);
1591+
test_controller->set_state_interface_configuration(state_cfg);
1592+
1593+
// add controllers
1594+
cm_->add_controller(
1595+
test_chained_controller, test_chainable_controller::TEST_CONTROLLER_NAME,
1596+
test_chainable_controller::TEST_CONTROLLER_CLASS_NAME);
1597+
cm_->add_controller(
1598+
test_controller, test_controller::TEST_CONTROLLER_NAME,
1599+
test_controller::TEST_CONTROLLER_CLASS_NAME);
1600+
// get hardware interface list before configure and loading
1601+
auto initial_result = call_service_and_wait(*client, request, srv_executor);
1602+
// As there is no controller, so all the interfaces should be available and unclaimed
1603+
for (const auto & cmd_itrf : initial_result->command_interfaces)
1604+
{
1605+
ASSERT_TRUE(cmd_itrf.is_available);
1606+
ASSERT_FALSE(cmd_itrf.is_claimed);
1607+
}
1608+
1609+
// configure controllers
1610+
cm_->configure_controller(test_chainable_controller::TEST_CONTROLLER_NAME);
1611+
cm_->configure_controller(test_controller::TEST_CONTROLLER_NAME);
1612+
1613+
// The interfaces should be same available and unclaimed until we activate the controllers
1614+
auto result = call_service_and_wait(*client, request, srv_executor);
1615+
1616+
ASSERT_EQ(2u, result->command_interfaces.size() - initial_result->command_interfaces.size());
1617+
// There will be no increase in state interfaces
1618+
ASSERT_EQ(0u, result->state_interfaces.size() - initial_result->state_interfaces.size());
1619+
// As there is no controller, so all the interfaces should be available and unclaimed
1620+
for (const auto & cmd_itrf : result->command_interfaces)
1621+
{
1622+
// The controller command interface shouldn't be active until it's controller is active
1623+
if (
1624+
cmd_itrf.name ==
1625+
std::string(test_chainable_controller::TEST_CONTROLLER_NAME) + "/joint1/position" ||
1626+
cmd_itrf.name ==
1627+
std::string(test_chainable_controller::TEST_CONTROLLER_NAME) + "/joint1/velocity")
1628+
{
1629+
ASSERT_FALSE(cmd_itrf.is_available);
1630+
}
1631+
else
1632+
{
1633+
ASSERT_TRUE(cmd_itrf.is_available);
1634+
}
1635+
ASSERT_FALSE(cmd_itrf.is_claimed);
1636+
}
1637+
auto find_interface_in_list = [](const std::string & interface, auto & hw_interface_info)
1638+
{
1639+
return std::find_if(
1640+
hw_interface_info.begin(), hw_interface_info.end(),
1641+
[&](auto info) { return info.name == interface; }) != hw_interface_info.end();
1642+
};
1643+
ASSERT_TRUE(find_interface_in_list(
1644+
std::string(test_chainable_controller::TEST_CONTROLLER_NAME) + "/joint1/position",
1645+
result->command_interfaces));
1646+
ASSERT_TRUE(find_interface_in_list(
1647+
std::string(test_chainable_controller::TEST_CONTROLLER_NAME) + "/joint1/velocity",
1648+
result->command_interfaces));
1649+
1650+
// activate controllers
1651+
cm_->switch_controller(
1652+
{test_chainable_controller::TEST_CONTROLLER_NAME}, {},
1653+
controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0));
1654+
1655+
// On activating this chainable controller, we should see that there are 2 more command interfaces
1656+
// as this chainable controllers exports 2 reference interfaces
1657+
result = call_service_and_wait(*client, request, srv_executor);
1658+
1659+
// There will be no increase upon activation
1660+
ASSERT_EQ(2u, result->command_interfaces.size() - initial_result->command_interfaces.size());
1661+
ASSERT_EQ(0u, result->state_interfaces.size() - initial_result->state_interfaces.size());
1662+
1663+
for (const auto & cmd_itrf : result->command_interfaces)
1664+
{
1665+
ASSERT_TRUE(cmd_itrf.is_available);
1666+
// This interface is claimed by the chainable controller
1667+
if (cmd_itrf.name == "joint1/position")
1668+
{
1669+
EXPECT_TRUE(cmd_itrf.is_claimed);
1670+
}
1671+
else if (
1672+
cmd_itrf.name ==
1673+
std::string(test_chainable_controller::TEST_CONTROLLER_NAME) + "/joint1/position" ||
1674+
cmd_itrf.name ==
1675+
std::string(test_chainable_controller::TEST_CONTROLLER_NAME) + "/joint1/velocity")
1676+
{
1677+
// As these interfaces are exposed by the chainable controller and not yet claimed by other
1678+
// controllers
1679+
ASSERT_FALSE(cmd_itrf.is_claimed);
1680+
}
1681+
else
1682+
{
1683+
// Case for rest of the controllers
1684+
ASSERT_FALSE(cmd_itrf.is_claimed);
1685+
}
1686+
}
1687+
1688+
cm_->switch_controller(
1689+
{test_controller::TEST_CONTROLLER_NAME}, {},
1690+
controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0));
1691+
1692+
// Now as another controller using the interfaces of chainable controller is activated, those
1693+
// interfaces should reflect as claimed
1694+
result = call_service_and_wait(*client, request, srv_executor);
1695+
1696+
for (const auto & cmd_itrf : result->command_interfaces)
1697+
{
1698+
ASSERT_TRUE(cmd_itrf.is_available);
1699+
// This interface is claimed by the chainable controller
1700+
if (
1701+
cmd_itrf.name == "joint1/position" || cmd_itrf.name == "joint2/velocity" ||
1702+
cmd_itrf.name ==
1703+
std::string(test_chainable_controller::TEST_CONTROLLER_NAME) + "/joint1/position" ||
1704+
cmd_itrf.name ==
1705+
std::string(test_chainable_controller::TEST_CONTROLLER_NAME) + "/joint1/velocity")
1706+
{
1707+
ASSERT_TRUE(cmd_itrf.is_claimed);
1708+
}
1709+
else
1710+
{
1711+
// Case for rest of the controllers
1712+
ASSERT_FALSE(cmd_itrf.is_claimed);
1713+
}
1714+
}
1715+
}

controller_manager/test/test_controllers_chaining_with_controller_manager.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -670,14 +670,14 @@ TEST_P(
670670
// PositionController is deactivated --> DiffDrive controller is not in chained mode anymore
671671
DeactivateAndCheckController(
672672
position_tracking_controller, POSITION_TRACKING_CONTROLLER,
673-
POSITION_CONTROLLER_CLAIMED_INTERFACES, 4u);
673+
POSITION_CONTROLLER_CLAIMED_INTERFACES, 4u, true);
674674
EXPECT_TRUE(pid_left_wheel_controller->is_in_chained_mode());
675675
EXPECT_TRUE(pid_right_wheel_controller->is_in_chained_mode());
676676
ASSERT_FALSE(diff_drive_controller->is_in_chained_mode());
677677

678678
// DiffDrive (preceding) controller is activated --> PID controller in chained mode
679679
DeactivateAndCheckController(
680-
diff_drive_controller, DIFF_DRIVE_CONTROLLER, DIFF_DRIVE_CLAIMED_INTERFACES, 8u);
680+
diff_drive_controller, DIFF_DRIVE_CONTROLLER, DIFF_DRIVE_CLAIMED_INTERFACES, 8u, true);
681681
EXPECT_FALSE(pid_left_wheel_controller->is_in_chained_mode());
682682
EXPECT_FALSE(pid_right_wheel_controller->is_in_chained_mode());
683683
ASSERT_FALSE(diff_drive_controller->is_in_chained_mode());

0 commit comments

Comments
 (0)