pymoveit_mtc.core.PipelinePlanner

class PipelinePlanner(self: pymoveit_mtc.core.PipelinePlanner, pipeline: str = 'ompl')

Bases: PlannerInterface

Plan using MoveIt’s PlanningPipeline

from moveit.task_constructor import core

# Create and configure a planner instance
pipelinePlanner = core.PipelinePlanner()
pipelinePlanner.planner = 'PRMkConfigDefault'
pipelinePlanner.num_planning_attempts = 10

Methods

Attributes

display_motion_plans

Publish generated solutions via a topic

goal_joint_tolerance

Tolerance for reaching joint goals

goal_orientation_tolerance

Tolerance for reaching orientation goals

goal_position_tolerance

Tolerance for reaching position goals

max_acceleration_scaling_factor

Reduce the maximum acceleration by scaling between (0,1]

max_velocity_scaling_factor

Reduce the maximum velocity by scaling between (0,1]

num_planning_attempts

Number of planning attempts

planner

Planner ID

properties

Properties of the planner

publish_planning_requests

Publish motion planning requests via a topic

workspace_parameters

Specifies workspace box to be used for Cartesian sampling

property display_motion_plans

Publish generated solutions via a topic

Type:

bool

property goal_joint_tolerance

Tolerance for reaching joint goals

Type:

float

property goal_orientation_tolerance

Tolerance for reaching orientation goals

Type:

float

property goal_position_tolerance

Tolerance for reaching position goals

Type:

float

property max_acceleration_scaling_factor

Reduce the maximum acceleration by scaling between (0,1]

Type:

float

property max_velocity_scaling_factor

Reduce the maximum velocity by scaling between (0,1]

Type:

float

property num_planning_attempts

Number of planning attempts

Type:

int

property planner

Planner ID

Type:

str

property properties

Properties of the planner

property publish_planning_requests

Publish motion planning requests via a topic

Type:

bool

property workspace_parameters

Specifies workspace box to be used for Cartesian sampling

Type:

WorkspaceParameters