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. |
|
Manages the trajectory execution. |
- 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.
- get_trajactory_execution_manager()
Returns the trajectory execution manager.
- 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
- process_attached_collision_object()
Apply an attached collision object msg to the planning scene.
- Args:
attached_collision_object_msg (moveit_msgs.msg.AttachedCollisionObject): The attached collision object to apply to the planning scene.
- process_collision_object()
Apply a collision object to the planning scene.
- Args:
collision_object_msg (moveit_msgs.msg.CollisionObject): The collision object to apply to the planning scene.
- read_only()
Returns a read-only context manager for the planning scene.
- read_write()
Returns a read-write context manager for the planning scene.
- request_planning_scene_state()
Request the planning scene.
- Parameters
service_name (str) – The name of the service to call.
- 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.
- update_frame_transforms()
Update the transforms for the frames that are not part of the kinematic model using tf.
Examples of these frames are the “map” and “odom_combined” transforms. This function is automatically called when data that uses transforms is received. However, this function should also be called before starting a planning request, for example.
- wait_for_current_robot_state()
Waits for the current robot state to be received.
- class moveit.planning.TrajectoryExecutionManager
Manages the trajectory execution.
- are_controllers_active()
Check if a set of controllers are active
- clear()
Clear the trajectories to execute.
- enable_execution_duration_monitoring()
Enable or disable the monitoring of trajectory execution duration.
If a controller takes longer than expected, the trajectory is canceled.
- ensure_active_controller()
Make sure a particular controller is active.
If manage_controllers_ is false and the controllers that happen to be active to not include the one specified as argument, this function fails.
- ensure_active_controllers()
Make sure a particular set of controllers are active.
If manage_controllers_ is false and the controllers that happen to be active to not include the ones specified as argument, this function fails.
- ensure_active_controllers_for_group()
Make sure the active controllers are such that trajectories that actuate joints in the specified group can be executed.
If manage_controllers_ is false and the controllers that happen to be active do not cover the joints in the group to be actuated, this function fails.
- ensure_active_controllers_for_joints()
Make sure the active controllers are such that trajectories that actuate joints in the specified set can be executed.
If manage_controllers_ is false and the controllers that happen to be active do not cover the joints to be actuated, this function fails.
- is_controller_active()
Check if a controller is active.
- is_managing_controllers()
If this function returns true, then this instance of the manager is allowed to load/unload/switch controllers.
- process_event()
Execute a named event (e.g., ‘stop’).
- push()
Add a trajectory for future execution. Optionally specify a controller to use for the trajectory.
If no controller is specified, a default is used.
Add a trajectory for future execution. Optionally specify a controller to use for the trajectory.
If no controller is specified, a default is used.
Add a trajectory for future execution.
Optionally specify a set of controllers to consider using for the trajectory. Multiple controllers can be used simultaneously to execute the different parts of the trajectory. If multiple controllers can be used, preference is given to the already loaded ones. If no controller is specified, a default is used.
Add a trajectory for future execution.
Optionally specify a set of controllers to consider using for the trajectory. Multiple controllers can be used simultaneously to execute the different parts of the trajectory. If multiple controllers can be used, preference is given to the already loaded ones. If no controller is specified, a default is used.
- set_allowed_execution_duration_scaling()
When determining the expected duration of a trajectory, this multiplicative factor is applied to get the allowed duration of execution.
- set_allowed_goal_duration_margin()
When determining the expected duration of a trajectory, this additional margin s applied after scalign to allow more than the expected execution time before triggering trajectory cancel.
- set_allowed_start_tolerance()
Set joint-value tolerance for validating trajectory’s start point against current robot state.
- set_execution_velocity_scaling()
Before sending a trajectory to a controller, scale the velocities by the factor specified.
By default, this is 1.0
- set_wait_for_trajectory_completion()
Enable or disable waiting for trajectory completion.
- stop_execution()
Stop whatever executions are active, if any.