moveit.planning
Python bindings for moveit_cpp functionalities.
Classes
A context manager that locks the planning scene for reading. |
|
A context manager that locks the planning scene for reading and writing. |
|
The MoveItPy class is the main interface to the MoveIt Python API. |
|
Planner parameters provided with a MotionPlanRequest. |
|
Planner parameters provided with a MotionPlanRequest. |
|
Represents a joint model group and motion plans corresponding to this joint model group. |
|
Maintains the internal state of the planning scene. |
- class moveit.planning.LockedPlanningSceneContextManagerRO
A context manager that locks the planning scene for reading.
- class moveit.planning.LockedPlanningSceneContextManagerRW
A context manager that locks the planning scene for reading and writing.
- class moveit.planning.MoveItPy
The MoveItPy class is the main interface to the MoveIt Python API. It is a wrapper around the MoveIt C++ API.
- execute()
Execute a trajectory (planning group is inferred from robot trajectory object).
- get_planning_component()
Creates a planning component instance. :Parameters: planning_component_name (str) – The name of the planning component.
- Returns
moveit_py.planning.PlanningComponent
– A planning component instance corresponding to the provided plan component name.
- get_planning_scene_monitor()
Returns the planning scene monitor.
- get_robot_model()
Returns robot model.
- shutdown()
Shutdown the moveit_cpp node.
- class moveit.planning.MultiPipelinePlanRequestParameters
Planner parameters provided with a MotionPlanRequest.
- property multi_plan_request_parameters
- class moveit.planning.PlanRequestParameters
Planner parameters provided with a MotionPlanRequest.
- property max_acceleration_scaling_factor
The maximum scaling factor that can be used.
- Type
float
- property max_velocity_scaling_factor
The maximum velocity scaling factor that can be used.
- Type
float
- property planner_id
The planner id to use.
- Type
str
- property planning_attempts
The number of planning attempts to make.
- Type
int
- property planning_pipeline
The planning pipeline to use.
- Type
str
- property planning_time
The amount of time to spend planning.
- Type
float
- class moveit.planning.PlanningComponent
Represents a joint model group and motion plans corresponding to this joint model group.
- get_named_target_state_values()
dict: The joint values for targets specified by name.
- get_start_state()
Returns the current start state for the planning component.
- property named_target_states
The names of the named robot states available as targets.
- Type
list of str
- plan()
Plan a motion plan using the current start and goal states.
- Parameters
plan_parameters (moveit_py.core.PlanParameters) – The parameters to use for planning.
- property planning_group_name
The name of the planning group to plan for.
- Type
str
- set_goal_state()
Set the goal state for the planning component.
- Parameters
configuration_name (str) – The name of the configuration to set the goal to.
robot_state (moveit_py.core.RobotState) – The state to set the goal to.
pose_stamped_msg (geometry_msgs.msg.PoseStamped) – A PoseStamped ros message.
pose_link (str) – The name of the link for which the pose constraint is specified.
motion_plan_constraints (list) – The motion plan constraints to set the goal to.
- set_path_constraints()
Set the path constraints generated from a moveit msg Constraints.
- Parameters
path_constraints (moveit_msgs.msg.Constraints) – The path constraints.
- set_start_state()
Set the start state of the plan to the given robot state.
- Parameters
configuration_name (str) – The name of the configuration to use as the start state.
robot_state (
moveit_msgs.msg.RobotState
) – The robot state to use as the start state.
- set_start_state_to_current_state()
Set the start state of the plan to the current state of the robot.
- set_workspace()
Specify the workspace bounding box. The box is specified in the planning frame (i.e. relative to the robot root link start position). The workspace applies only to the root joint of a mobile robot (driving base, quadrotor) and does not limit the workspace of a robot arm.
- Parameters
min_x (float) – The minimum x value of the workspace.
min_y (float) – The minimum y value of the workspace.
min_z (float) – The minimum z value of the workspace.
max_x (float) – The maximum x value of the workspace.
max_y (float) – The maximum y value of the workspace.
max_z (float) – The maximum z value of the workspace.
- unset_workspace()
Remove the workspace bounding box from planning.
- class moveit.planning.PlanningSceneMonitor
Maintains the internal state of the planning scene.
- clear_octomap()
Clears the octomap.
- property name
The name of this planning scene monitor.
- Type
str
- read_only()
Returns a read-only context manager for the planning scene.
- read_write()
Returns a read-write context manager for the planning scene.
- start_scene_monitor()
Starts the scene monitor.
- start_state_monitor()
Starts the state monitor.
- stop_scene_monitor()
Stops the scene monitor.
- stop_state_monitor()
Stops the state monitor.
- wait_for_current_robot_state()
Waits for the current robot state to be received.