pymoveit_mtc.stages.ModifyPlanningScene¶
- class ModifyPlanningScene(self: pymoveit_mtc.stages.ModifyPlanningScene, name: str = 'modify planning scene')¶
Bases:
Stage
Apply modifications to the PlanningScene w/o moving the robot
This stage takes the incoming planning scene and applies previously scheduled changes to it, for example:
Modify allowed collision matrix, enabling or disabling collision pairs
Attach or detach objects to robot links
Add or remove objects
For an example, see How-To-Guides.
Methods
Add a CollisionObject to the planning scene
Overloaded function.
Attach an object to a robot link
Attach multiple objects to a robot link
Detach an object from a robot link
Detach multiple objects from a robot link
Initialize the stage once before planning.
Remove a CollisionObject from the planning scene
Reset the Stage.
Overloaded function.
Attributes
Failed Solutions of the stage (read-only)
set of properties forwarded from input to output InterfaceState
Namespace for any markers that are associated to the stage
name of the stage displayed e.g.
PropertyMap of the stage (read-only)
Successful Solutions of the stage (read-only)
Maximally allowed time [s] per computation step
- class PropertyInitializerSource(self: pymoveit_mtc.core.Stage.PropertyInitializerSource, value: int)¶
Bases:
pybind11_object
OR-combinable flags defining a source to initialize a specific property from. Used in pymoveit_mtc.core.PropertyMap
configureInitFrom()
.Members:
PARENT : Inherit properties from parent stage
INTERFACE : Inherit properties from the input InterfaceState
- property name¶
- addObject(self: pymoveit_mtc.stages.ModifyPlanningScene, collision_object: moveit_msgs::CollisionObject_<std::allocator<void> >) None ¶
Add a CollisionObject to the planning scene
- allowCollisions(*args, **kwargs)¶
Overloaded function.
allowCollisions(self: pymoveit_mtc.stages.ModifyPlanningScene, object: str, enable_collision: bool = True) -> None
Allow or disable all collisions involving the given object
allowCollisions(self: pymoveit_mtc.stages.ModifyPlanningScene, first: object, second: object, enable_collision: bool = True) -> None
Allow or disable collisions between links and objects
- attachObject(self: pymoveit_mtc.stages.ModifyPlanningScene, name: str, link: str) None ¶
Attach an object to a robot link
- attachObjects(self: pymoveit_mtc.stages.ModifyPlanningScene, names: object, attach_link: str, attach: bool = True) None ¶
Attach multiple objects to a robot link
- detachObject(self: pymoveit_mtc.stages.ModifyPlanningScene, name: str, link: str) None ¶
Detach an object from a robot link
- detachObjects(self: pymoveit_mtc.stages.ModifyPlanningScene, names: object, attach_link: str) None ¶
Detach multiple objects from a robot link
- property forwarded_properties¶
set of properties forwarded from input to output InterfaceState
- Type:
- init(self: pymoveit_mtc.core.Stage, robot_model: moveit::core::RobotModel) None ¶
Initialize the stage once before planning. Will setup properties configured for initialization from parent.
- property properties¶
PropertyMap of the stage (read-only)
- Type:
- removeObject(self: pymoveit_mtc.stages.ModifyPlanningScene, name: str) None ¶
Remove a CollisionObject from the planning scene
- reset(self: pymoveit_mtc.core.Stage) None ¶
Reset the Stage. Clears all solutions, interfaces and inherited properties
- setCostTerm(*args, **kwargs)¶
Overloaded function.
setCostTerm(self: pymoveit_mtc.core.Stage, arg0: pymoveit_mtc.core.CostTerm) -> None
Specify a CostTerm for calculation of stage costs
setCostTerm(self: pymoveit_mtc.core.Stage, arg0: Callable[[pymoveit_mtc.core.SubTrajectory, str], float]) -> None
Specify a function to calculate trajectory costs
setCostTerm(self: pymoveit_mtc.core.Stage, arg0: Callable[[pymoveit_mtc.core.SubTrajectory], float]) -> None
Specify a function to calculate trajectory costs
- property solutions¶
Successful Solutions of the stage (read-only)