moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Namespaces | Typedefs | Functions
planning_pipeline_interfaces.hpp File Reference
#include <moveit/planning_pipeline_interfaces/plan_responses_container.hpp>
#include <moveit/planning_interface/planning_response.h>
#include <moveit/planning_interface/planning_request.h>
#include <moveit/planning_pipeline/planning_pipeline.h>
#include <moveit/planning_scene/planning_scene.h>
Include dependency graph for planning_pipeline_interfaces.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  moveit
 Main namespace for MoveIt.
 
namespace  moveit::planning_pipeline_interfaces
 

Typedefs

typedef std::function< bool(const PlanResponsesContainer &plan_responses_container, const std::vector<::planning_interface::MotionPlanRequest > &plan_requests)> moveit::planning_pipeline_interfaces::StoppingCriterionFunction
 A stopping criterion callback function for the parallel planning API of planning component.
 
typedef std::function<::planning_interface::MotionPlanResponse(const std::vector<::planning_interface::MotionPlanResponse > &solutions)> moveit::planning_pipeline_interfaces::SolutionSelectionFunction
 A solution callback function type for the parallel planning API of planning component.
 

Functions

::planning_interface::MotionPlanResponse moveit::planning_pipeline_interfaces::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.
 
const std::vector<::planning_interface::MotionPlanResponsemoveit::planning_pipeline_interfaces::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 the same time.
 
std::unordered_map< std::string, planning_pipeline::PlanningPipelinePtr > moveit::planning_pipeline_interfaces::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.