48namespace planning_pipeline_interfaces
55typedef std::function<bool(
const PlanResponsesContainer& plan_responses_container,
56 const std::vector<::planning_interface::MotionPlanRequest>& plan_requests)>
64 const std::vector<::planning_interface::MotionPlanResponse>& solutions)>
74 const ::planning_interface::MotionPlanRequest& motion_plan_request,
76 const std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr>& planning_pipelines);
93 const std::vector<::planning_interface::MotionPlanRequest>& motion_plan_requests,
95 const std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr>& planning_pipelines,
108std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr>
110 const moveit::core::RobotModelConstPtr& robot_model,
const rclcpp::Node::SharedPtr& node,
111 const std::string& parameter_namespace = std::string());
::planning_interface::MotionPlanResponse planWithSinglePipeline(const ::planning_interface::MotionPlanRequest &motion_plan_request, const ::planning_scene::PlanningSceneConstPtr &planning_scene, const std::unordered_map< std::string, planning_pipeline::PlanningPipelinePtr > &planning_pipelines)
Function to calculate the MotionPlanResponse for a given MotionPlanRequest and a PlanningScene.
std::unordered_map< std::string, planning_pipeline::PlanningPipelinePtr > createPlanningPipelineMap(const std::vector< std::string > &pipeline_names, const moveit::core::RobotModelConstPtr &robot_model, const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace=std::string())
Utility function to create a map of named planning pipelines.
std::function< bool(const PlanResponsesContainer &plan_responses_container, const std::vector<::planning_interface::MotionPlanRequest > &plan_requests)> StoppingCriterionFunction
A stopping criterion callback function for the parallel planning API of planning component.
const std::vector<::planning_interface::MotionPlanResponse > planWithParallelPipelines(const std::vector<::planning_interface::MotionPlanRequest > &motion_plan_requests, const ::planning_scene::PlanningSceneConstPtr &planning_scene, const std::unordered_map< std::string, planning_pipeline::PlanningPipelinePtr > &planning_pipelines, const StoppingCriterionFunction &stopping_criterion_callback=nullptr, const SolutionSelectionFunction &solution_selection_function=nullptr)
Function to solve multiple planning problems in parallel threads with multiple planning pipelines at ...
std::function<::planning_interface::MotionPlanResponse(const std::vector<::planning_interface::MotionPlanResponse > &solutions)> SolutionSelectionFunction
A solution callback function type for the parallel planning API of planning component.
Main namespace for MoveIt.
This namespace includes the central class for representing planning contexts.
Response to a planning query.