Skip to content
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -596,11 +596,11 @@ class Ros2ControlManager : public moveit_controller_manager::MoveItControllerMan
dependency_map_reverse_.clear();
for (auto& controller : result->controller)
{
if (controller.chain_connections.size() > 1)
if (isActive(controller) && controller.chain_connections.size() > 1)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't have a way to verify this so any test you could add would be extremely helpful.

Example scenario:

arm_1_JTC active
arm_2_JTC active
arm_3_chained inactive or active

Can you confirm that when controller = arm_1_JTC, controller.chain_connections.size() == 0
and when controller = arm_3_chained, controller.chain_connections.size() == 1?

{
RCLCPP_ERROR_STREAM(getLogger(),
"Controller with name %s chains to more than one controller. Chaining to more than "
"one controller is not supported.");
"Controller with name " << controller.name << " chains to more than one controller. "
"Chaining to more than one controller is not supported.");
return false;
}
for (const auto& chained_controller : controller.chain_connections)
Expand Down