Skip to content

Commit 0164264

Browse files
committed
Add logic to Ros2ControlManager to match ros2_control
Signed-off-by: Paul Gesel <paul.gesel@picknik.ai>
1 parent 9922704 commit 0164264

File tree

1 file changed

+82
-18
lines changed

1 file changed

+82
-18
lines changed

moveit_plugins/moveit_ros_control_interface/src/controller_manager_plugin.cpp

+82-18
Original file line numberDiff line numberDiff line change
@@ -119,8 +119,11 @@ class Ros2ControlManager : public moveit_controller_manager::MoveItControllerMan
119119
rclcpp::Client<controller_manager_msgs::srv::ListControllers>::SharedPtr list_controllers_service_;
120120
rclcpp::Client<controller_manager_msgs::srv::SwitchController>::SharedPtr switch_controller_service_;
121121

122-
// Chained controllers have dependencies (other controllers which must be running)
122+
// Chained controllers have dependent controllers (other controllers which must be started if the chained controller is started)
123123
std::unordered_map<std::string /* controller name */, std::vector<std::string> /* dependencies */> dependency_map_;
124+
// Controllers may have preceding chained controllers (other chained controllers which must be shutdown if the controller is shutdown)
125+
std::unordered_map<std::string /* controller name */, std::vector<std::string> /* reverse dependencies */>
126+
dependency_map_reverse_;
124127

125128
/**
126129
* \brief Check if given controller is active
@@ -370,35 +373,91 @@ class Ros2ControlManager : public moveit_controller_manager::MoveItControllerMan
370373
return c;
371374
}
372375

376+
static void simplifyControllerActivationDeactivation(std::vector<std::string>& activate_controllers,
377+
std::vector<std::string>& deactivate_controllers)
378+
{
379+
// Convert vectors to sets for uniqueness
380+
std::unordered_set set1(activate_controllers.begin(), activate_controllers.end());
381+
std::unordered_set set2(deactivate_controllers.begin(), deactivate_controllers.end());
382+
383+
// Find common elements
384+
std::unordered_set<std::string> common;
385+
for (const auto& str : set1)
386+
{
387+
if (set2.count(str))
388+
{
389+
common.insert(str);
390+
}
391+
}
392+
393+
// Remove common elements from both sets
394+
for (const auto& str : common)
395+
{
396+
set1.erase(str);
397+
set2.erase(str);
398+
}
399+
400+
// Convert sets back to vectors
401+
activate_controllers.assign(set1.begin(), set1.end());
402+
deactivate_controllers.assign(set2.begin(), set2.end());
403+
}
404+
373405
/**
374406
* \brief Filter lists for managed controller and computes switching set.
375407
* Stopped list might be extended by unsupported controllers that claim needed resources
376-
* @param activate vector of controllers to be activated
377-
* @param deactivate vector of controllers to be deactivated
408+
* @param activate_base vector of controllers to be activated
409+
* @param deactivate_base vector of controllers to be deactivated
378410
* @return true if switching succeeded
379411
*/
380412
bool switchControllers(const std::vector<std::string>& activate_base,
381413
const std::vector<std::string>& deactivate_base) override
382414
{
383-
// add controller dependencies
384-
std::vector<std::string> activate = activate_base;
385-
std::vector<std::string> deactivate = deactivate_base;
386-
for (auto controllers : { &activate, &deactivate })
387-
{
388-
auto queue = *controllers;
415+
// add_all_dependencies traverses the provided dependency map and appends the results to the controllers vector.
416+
auto add_all_dependencies = [](const std::unordered_map<std::string, std::vector<std::string>>& dependencies,
417+
const std::function<bool(const std::string&)>& should_include,
418+
std::vector<std::string>& controllers) {
419+
auto queue = controllers;
389420
while (!queue.empty())
390421
{
391422
auto controller = queue.back();
392-
controller.erase(0, 1);
423+
if (controller.size() > 1 && controller[0] == '/')
424+
{
425+
// Remove leading / from controller name
426+
controller.erase(0, 1);
427+
}
393428
queue.pop_back();
394-
for (const auto& dependency : dependency_map_[controller])
429+
if (dependencies.find(controller) == dependencies.end())
430+
{
431+
continue;
432+
}
433+
for (const auto& dependency : dependencies.at(controller))
395434
{
396435
queue.push_back(dependency);
397-
controllers->push_back("/" + dependency);
436+
if (should_include(dependency))
437+
{
438+
controllers.push_back("/" + dependency);
439+
}
398440
}
399441
}
400-
}
401-
// activation dependencies must be started first, but they are processed last, so the order needs to be flipped
442+
};
443+
444+
std::vector<std::string> activate = activate_base;
445+
add_all_dependencies(
446+
dependency_map_,
447+
[this](const std::string& dependency) {
448+
return active_controllers_.find(dependency) == active_controllers_.end();
449+
},
450+
activate);
451+
std::vector<std::string> deactivate = deactivate_base;
452+
add_all_dependencies(
453+
dependency_map_reverse_,
454+
[this](const std::string& dependency) {
455+
return active_controllers_.find(dependency) != active_controllers_.end();
456+
},
457+
deactivate);
458+
459+
// The dependencies for chained controller activation must be started first, but they are processed last, so the
460+
// order needs to be flipped
402461
std::reverse(activate.begin(), activate.end());
403462

404463
std::scoped_lock<std::mutex> lock(controllers_mutex_);
@@ -471,6 +530,11 @@ class Ros2ControlManager : public moveit_controller_manager::MoveItControllerMan
471530
}
472531
}
473532

533+
// ROS2 Control expects simplified controller activation/deactivation.
534+
// E.g. a controller should not be stopped and started at the same time, rather it should be removed from both the
535+
// activation and deactivation request.
536+
simplifyControllerActivationDeactivation(request->activate_controllers, request->deactivate_controllers);
537+
474538
// Setting level to STRICT means that the controller switch will only be committed if all controllers are
475539
// successfully activated or deactivated.
476540
request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
@@ -502,6 +566,9 @@ class Ros2ControlManager : public moveit_controller_manager::MoveItControllerMan
502566
{
503567
controller_name_map[result->controller[i].name] = i;
504568
}
569+
570+
dependency_map_.clear();
571+
dependency_map_reverse_.clear();
505572
for (auto& controller : result->controller)
506573
{
507574
if (controller.chain_connections.size() > 1)
@@ -511,14 +578,11 @@ class Ros2ControlManager : public moveit_controller_manager::MoveItControllerMan
511578
"one controller is not supported.");
512579
return false;
513580
}
514-
dependency_map_[controller.name].clear();
515581
for (const auto& chained_controller : controller.chain_connections)
516582
{
517583
auto ind = controller_name_map[chained_controller.name];
518584
dependency_map_[controller.name].push_back(chained_controller.name);
519-
std::copy(result->controller[ind].required_command_interfaces.begin(),
520-
result->controller[ind].required_command_interfaces.end(),
521-
std::back_inserter(controller.required_command_interfaces));
585+
dependency_map_reverse_[chained_controller.name].push_back(controller.name);
522586
std::copy(result->controller[ind].reference_interfaces.begin(),
523587
result->controller[ind].reference_interfaces.end(),
524588
std::back_inserter(controller.required_command_interfaces));

0 commit comments

Comments
 (0)