moveit2
The MoveIt Motion Planning Framework for ROS 2.
planning_pipeline_interfaces.hpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2023, PickNik Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of PickNik Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Sebastian Jahr
36  Desc: Functions to create and use a map of PlanningPipelines to solve MotionPlanRequests */
37 
38 #pragma once
39 
45 
46 namespace moveit
47 {
48 namespace planning_pipeline_interfaces
49 {
55 typedef std::function<bool(const PlanResponsesContainer& plan_responses_container,
56  const std::vector<::planning_interface::MotionPlanRequest>& plan_requests)>
58 
63 typedef std::function<::planning_interface::MotionPlanResponse(
64  const std::vector<::planning_interface::MotionPlanResponse>& solutions)>
66 
75  const ::planning_scene::PlanningSceneConstPtr& planning_scene,
76  const std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr>& planning_pipelines);
77 
92 const std::vector<::planning_interface::MotionPlanResponse> planWithParallelPipelines(
93  const std::vector<::planning_interface::MotionPlanRequest>& motion_plan_requests,
94  const ::planning_scene::PlanningSceneConstPtr& planning_scene,
95  const std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr>& planning_pipelines,
96  const StoppingCriterionFunction& stopping_criterion_callback = nullptr,
97  const SolutionSelectionFunction& solution_selection_function = nullptr);
98 
108 std::unordered_map<std::string, planning_pipeline::PlanningPipelinePtr>
109 createPlanningPipelineMap(const std::vector<std::string>& pipeline_names,
110  const moveit::core::RobotModelConstPtr& robot_model, const rclcpp::Node::SharedPtr& node,
111  const std::string& parameter_namespace = std::string());
112 } // namespace planning_pipeline_interfaces
113 } // namespace moveit
::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 &parameter_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.
Definition: exceptions.h:43
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
Response to a planning query.