Skip to content

Commit 6039ef8

Browse files
committed
Remove planning pipelines argument
1 parent e11f89c commit 6039ef8

File tree

2 files changed

+0
-9
lines changed

2 files changed

+0
-9
lines changed

core/include/moveit/task_constructor/solvers/pipeline_planner.h

-3
Original file line numberDiff line numberDiff line change
@@ -72,15 +72,12 @@ class PipelinePlanner : public PlannerInterface
7272
/** \brief Constructor
7373
* \param [in] node ROS 2 node
7474
* \param [in] pipeline_id_planner_id_map Map containing pairs of pipeline and plugin names to be used for planning
75-
* \param [in] planning_pipelines Optional: A map with the names and initialized corresponding planning pipelines
7675
* \param [in] stopping_criterion_callback Optional: Callback to decide when to stop parallel planning
7776
* \param [in] solution_selection_function Optional: Callback to choose the best solution from multiple ran pipelines
7877
*/
7978
PipelinePlanner(
8079
const rclcpp::Node::SharedPtr& node,
8180
const std::unordered_map<std::string, std::string>& pipeline_id_planner_id_map,
82-
const std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr>& planning_pipelines =
83-
std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr>(),
8481
const moveit::planning_pipeline_interfaces::StoppingCriterionFunction& stopping_criterion_callback = nullptr,
8582
const moveit::planning_pipeline_interfaces::SolutionSelectionFunction& solution_selection_function =
8683
&moveit::planning_pipeline_interfaces::getShortestSolution);

core/src/solvers/pipeline_planner.cpp

-6
Original file line numberDiff line numberDiff line change
@@ -58,18 +58,12 @@ using PipelineMap = std::unordered_map<std::string, std::string>;
5858

5959
PipelinePlanner::PipelinePlanner(
6060
const rclcpp::Node::SharedPtr& node, const PipelineMap& pipeline_id_planner_id_map,
61-
const std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr>& planning_pipelines,
6261
const moveit::planning_pipeline_interfaces::StoppingCriterionFunction& stopping_criterion_callback,
6362
const moveit::planning_pipeline_interfaces::SolutionSelectionFunction& solution_selection_function)
6463
: node_(node)
6564
, last_successful_planner_("")
6665
, stopping_criterion_callback_(stopping_criterion_callback)
6766
, solution_selection_function_(solution_selection_function) {
68-
// If the pipeline name - pipeline map is passed as constructor argument, use it. Otherwise, it will be created in
69-
// the init(..) function
70-
if (!planning_pipelines.empty()) {
71-
planning_pipelines_ = planning_pipelines;
72-
}
7367
// Declare properties of the MotionPlanRequest
7468
properties().declare<uint>("num_planning_attempts", 1u, "number of planning attempts");
7569
properties().declare<moveit_msgs::msg::WorkspaceParameters>(

0 commit comments

Comments
 (0)