Skip to content

Commit

Permalink
Pass pipeline map by reference
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr committed Apr 20, 2023
1 parent 9be2ab3 commit c0ea5cd
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ class PipelinePlanner : public PlannerInterface
*/
PipelinePlanner(const rclcpp::Node::SharedPtr& node,
const std::unordered_map<std::string, std::string>& pipeline_id_planner_id_map,
const std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr> planning_pipelines =
const std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr>& planning_pipelines =
std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr>(),
const moveit::planning_pipeline_interfaces::StoppingCriterionFunction& stopping_criterion_callback = &moveit::planning_pipeline_interfaces::stopAtFirstSolution,
const moveit::planning_pipeline_interfaces::SolutionSelectionFunction& solution_selection_function = &moveit::planning_pipeline_interfaces::getShortestSolution);
Expand Down
2 changes: 1 addition & 1 deletion core/src/solvers/pipeline_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ PipelinePlanner::PipelinePlanner(const rclcpp::Node::SharedPtr& node, const std:

PipelinePlanner::PipelinePlanner(
const rclcpp::Node::SharedPtr& node, const std::unordered_map<std::string, std::string>& pipeline_id_planner_id_map,
const std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr> planning_pipelines,
const std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr>& planning_pipelines,
const moveit::planning_pipeline_interfaces::StoppingCriterionFunction& stopping_criterion_callback,
const moveit::planning_pipeline_interfaces::SolutionSelectionFunction& solution_selection_function)
: node_(node)
Expand Down

0 comments on commit c0ea5cd

Please sign in to comment.