#include <pipeline_planner.h>
|
| void | init (const moveit::core::RobotModelConstPtr &robot_model) override |
| |
| | PipelinePlanner (const planning_pipeline::PlanningPipelinePtr &planning_pipeline) |
| |
| | PipelinePlanner (const std::string &pipeline="ompl") |
| |
| Result | plan (const planning_scene::PlanningSceneConstPtr &from, const moveit::core::LinkModel &link, const Eigen::Isometry3d &offset, const Eigen::Isometry3d &target, const moveit::core::JointModelGroup *jmg, double timeout, robot_trajectory::RobotTrajectoryPtr &result, const moveit_msgs::Constraints &path_constraints=moveit_msgs::Constraints()) override |
| | plan trajectory from current robot state to Cartesian target, such that pose(link)*offset == target More...
|
| |
| Result | plan (const planning_scene::PlanningSceneConstPtr &from, const planning_scene::PlanningSceneConstPtr &to, const core::JointModelGroup *jmg, double timeout, robot_trajectory::RobotTrajectoryPtr &result, const moveit_msgs::Constraints &path_constraints=moveit_msgs::Constraints()) override |
| | plan trajectory between to robot states More...
|
| |
| void | setPlannerId (const std::string &planner) |
| |
| | PlannerInterface () |
| |
| PropertyMap & | properties () |
| |
| const PropertyMap & | properties () const |
| |
| void | setMaxAccelerationScalingFactor (double factor) |
| |
| void | setMaxVelocityScalingFactor (double factor) |
| |
| void | setProperty (const std::string &name, const boost::any &value) |
| |
| void | setTimeout (double timeout) |
| |
| void | setTimeParameterization (const trajectory_processing::TimeParameterizationPtr &tp) |
| |
| virtual | ~PlannerInterface () |
| |
|
| static planning_pipeline::PlanningPipelinePtr | create (const moveit::core::RobotModelConstPtr &model) |
| |
| static planning_pipeline::PlanningPipelinePtr | create (const Specification &spec) |
| |
Use MoveIt's PlanningPipeline to plan a trajectory between to scenes
Definition at line 56 of file pipeline_planner.h.
◆ PipelinePlanner() [1/2]
| moveit::task_constructor::solvers::PipelinePlanner::PipelinePlanner |
( |
const std::string & |
pipeline = "ompl" | ) |
|
◆ PipelinePlanner() [2/2]
| moveit::task_constructor::solvers::PipelinePlanner::PipelinePlanner |
( |
const planning_pipeline::PlanningPipelinePtr & |
planning_pipeline | ) |
|
◆ create() [1/2]
| static planning_pipeline::PlanningPipelinePtr moveit::task_constructor::solvers::PipelinePlanner::create |
( |
const moveit::core::RobotModelConstPtr & |
model | ) |
|
|
inlinestatic |
◆ create() [2/2]
| planning_pipeline::PlanningPipelinePtr moveit::task_constructor::solvers::PipelinePlanner::create |
( |
const Specification & |
spec | ) |
|
|
static |
◆ init()
| void moveit::task_constructor::solvers::PipelinePlanner::init |
( |
const moveit::core::RobotModelConstPtr & |
robot_model | ) |
|
|
overridevirtual |
◆ plan() [1/3]
| PlannerInterface::Result moveit::task_constructor::solvers::PipelinePlanner::plan |
( |
const planning_scene::PlanningSceneConstPtr & |
from, |
|
|
const moveit::core::LinkModel & |
link, |
|
|
const Eigen::Isometry3d & |
offset, |
|
|
const Eigen::Isometry3d & |
target, |
|
|
const moveit::core::JointModelGroup * |
jmg, |
|
|
double |
timeout, |
|
|
robot_trajectory::RobotTrajectoryPtr & |
result, |
|
|
const moveit_msgs::Constraints & |
path_constraints = moveit_msgs::Constraints() |
|
) |
| |
|
overridevirtual |
◆ plan() [2/3]
◆ plan() [3/3]
| PlannerInterface::Result moveit::task_constructor::solvers::PipelinePlanner::plan |
( |
const planning_scene::PlanningSceneConstPtr & |
from, |
|
|
const planning_scene::PlanningSceneConstPtr & |
to, |
|
|
const core::JointModelGroup * |
jmg, |
|
|
double |
timeout, |
|
|
robot_trajectory::RobotTrajectoryPtr & |
result, |
|
|
const moveit_msgs::Constraints & |
path_constraints = moveit_msgs::Constraints() |
|
) |
| |
|
overridevirtual |
◆ setPlannerId()
| void moveit::task_constructor::solvers::PipelinePlanner::setPlannerId |
( |
const std::string & |
planner | ) |
|
|
inline |
◆ pipeline_name_
| std::string moveit::task_constructor::solvers::PipelinePlanner::pipeline_name_ |
|
protected |
◆ planner_
| planning_pipeline::PlanningPipelinePtr moveit::task_constructor::solvers::PipelinePlanner::planner_ |
|
protected |
The documentation for this class was generated from the following files: