Skip to content

Commit

Permalink
Fix controller_manager_plugin for multi controllers managers
Browse files Browse the repository at this point in the history
  • Loading branch information
JafarAbdi committed Nov 6, 2024
1 parent cdaf638 commit f97a22c
Showing 1 changed file with 3 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -258,13 +258,12 @@ class Ros2ControlManager : public moveit_controller_manager::MoveItControllerMan
Ros2ControlManager(const std::string& ns)
: ns_(ns), loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
{
RCLCPP_INFO_STREAM(getLogger(), "Started moveit_ros_control_interface::Ros2ControlManager for namespace " << ns_);
}

void initialize(const rclcpp::Node::SharedPtr& node) override
{
node_ = node;
if (!ns_.empty())
if (ns_.empty())
{
if (!node_->has_parameter("ros_control_namespace"))
{
Expand All @@ -275,11 +274,8 @@ class Ros2ControlManager : public moveit_controller_manager::MoveItControllerMan
node_->get_parameter<std::string>("ros_control_namespace", ns_);
}
}
else if (node->has_parameter("ros_control_namespace"))
{
node_->get_parameter<std::string>("ros_control_namespace", ns_);
RCLCPP_INFO_STREAM(getLogger(), "Namespace for controller manager was specified, namespace: " << ns_);
}
RCLCPP_INFO_STREAM(getLogger(),
"Initialized moveit_ros_control_interface::Ros2ControlManager for namespace " << ns_);

list_controllers_service_ = node_->create_client<controller_manager_msgs::srv::ListControllers>(
getAbsName("controller_manager/list_controllers"));
Expand Down

0 comments on commit f97a22c

Please sign in to comment.