Hybrid planner container with duplicate node name
Description
The hybrid_planning_container is duplicated when creating a ComposableNodeContainer. It's seen related to the global planner node. The node name is not duplicated when I remove the global planner from the container.
Your environment
- ROS Distro: Humble
- OS Version: Ubuntu 22.04
- Source build. origin/humble
- Cyclone DDS
Steps to reproduce
ros2 launch moveit_hybrid_planning hybrid_planning_demo.launch.py ros2 node list
Expected behaviour
Only one node with the name hybrid_planning_container
Actual behaviour
The composable container node is duplicated.
Thanks for reporting this, I'll look into it
@sjahr, I noticed that the local planner and global planner nodes don't have the option automatically_declare_parameters_from_overrides() enabled. The Moveit tutorial states that parameters need this option to work correctly. Is it an error, or that's the way the hybrid planner should work?
Both node constructors have a rclcpp::NodeOption variable, but I couldn't find where it's called on the Moveit source repository.
I think this option should be enabled by default to ease the use of the hybrid planner. I could use the same parameters as move_group node.
I think this issue is related to a launch_ros problem.
This issue is being labeled as stale because it has been open 45 days with no activity. It will be automatically closed after another 45 days without follow-ups.
This issue was closed because it has been stalled for 45 days with no activity.
@sjahr, I noticed that the local planner and global planner nodes don't have the option
automatically_declare_parameters_from_overrides()enabled. The Moveit tutorial states that parameters need this option to work correctly. Is it an error, or that's the way the hybrid planner should work?Both node constructors have a rclcpp::NodeOption variable, but I couldn't find where it's called on the Moveit source repository.
I think this option should be enabled by default to ease the use of the hybrid planner. I could use the same parameters as move_group node.
Hello, I also work on this problem currently. Have you figure out why automatically_declare_parameters_from_overrides do not set true? I have tried to enable it, but the node will crash when boot up. Any information will be highly appreciated. Thanks!
Hello @frankchan12138!
I decided to just fork the Moveit repository and change the hybrid planner. I was able to make the parameters work correctly. It was also important to change how it handles feedback from the local and global planner as it will crash if any non-empty feedback is received.
The fork with these changes are on my company's private repository. I want to open an pull request for these changes when they are propely tested.
But to answer you now, these changes are required:
File: local_planner_component.cpp
LocalPlannerComponent::LocalPlannerComponent(const rclcpp::NodeOptions& options):
node_(NULL),
state_(LocalPlannerState::UNCONFIGURED),
local_planner_feedback_(NULL)
{
rclcpp::NodeOptions moveit_options = options;
moveit_options.automatically_declare_parameters_from_overrides(true);
node_ = std::make_shared<rclcpp::Node>("local_planner_component", moveit_options);
state_ = LocalPlannerState::UNCONFIGURED;
local_planner_feedback_ = std::make_shared<moveit_msgs::action::LocalPlanner::Feedback>();
if (!this->initialize())
{
throw std::runtime_error("Failed to initialize local planner component");
}
RCLCPP_INFO_STREAM(node_->get_logger(), "Created local planner component");
}
FIle: global_planner_component.cpp
GlobalPlannerComponent::GlobalPlannerComponent(const rclcpp::NodeOptions& options)
{
rclcpp::NodeOptions moveit_options = options;
moveit_options.automatically_declare_parameters_from_overrides(true);
node_ = std::make_shared<rclcpp::Node>("global_planner_component", moveit_options);
RCLCPP_INFO_STREAM(LOGGER, "Created global planner component");
if (!initializeGlobalPlanner())
{
throw std::runtime_error("Failed to initialize Global Planner Component");
}
}
I hope it helps!
Hello @Mat198 , Thanks for reply. I modified the code as your advice, and it still do not work properly. Later I modified moveit_planning_pipeline.cpp according to the output log and finally run it successfully. the moveit_planning_pipeline.cpp initialize function should comment the re-declare_parameter s which have been declared before(according to log). In my case, I commented all the parameter apart from moveit_controller_manager like the following code.
bool MoveItPlanningPipeline::initialize(const rclcpp::Node::SharedPtr& node)
{
// Trajectory Execution Functionality (required by the MoveItPlanningPipeline but not used within hybrid planning)
if(!node->has_parameter("moveit_controller_manager")){
node->declare_parameter<std::string>("moveit_controller_manager", UNDEFINED);
}
node_ptr_ = node;
// Initialize MoveItCpp API
moveit_cpp::MoveItCpp::Options moveit_cpp_options(node);
moveit_cpp_ = std::make_shared<moveit_cpp::MoveItCpp>(node, moveit_cpp_options);
return true;
}