Robot.plan_motion
- Robot.plan_motion(target, start_configuration=None, group=None, options=None)[source]
Calculate a motion path.
- Parameters:
- target
compas_fab.robots.Target
The target to be achieved by the robot at the end of the motion. See Targets and Waypoints.
- start_configuration
compas_robots.Configuration
, optional The robot’s full configuration, i.e. values for all configurable joints of the entire robot, at the starting position. Defaults to the all-zero configuration.
- group
str
, optional The name of the planning group used to define the movable joints. The planning group must match with one of the groups defined in the robot’s semantics. Defaults to the robot’s main planning group.
- options
dict
, optional Dictionary containing the following key-value pairs:
- path_constraints ::
list
ofConstraint
, optional Optional constraints that can be imposed along the solution path. Note that path calculation won’t work if the start_configuration violates these constraints. Defaults to
None
.
- path_constraints ::
- attached_collision_meshes ::
list
ofcompas_fab.robots.AttachedCollisionMesh
Defaults to
None
.
- attached_collision_meshes ::
There are additional options that are specific to the backend in use. Check the API reference of the motion planner backend implementation for more details.
- target
- Returns:
JointTrajectory
The calculated trajectory.
Examples
Using a
FrameTarget
:>>> with RosClient() as client: #: This doctest can pass locally but persistently fails on CI in GitHub. "roslibpy.core.RosTimeoutError: Failed to connect to ROS" ... robot = client.load_robot() ... frame = Frame([0.4, 0.3, 0.4], [0, 1, 0], [0, 0, 1]) ... tolerance_position = 0.001 ... tolerance_orientation = math.radians(1) ... start_configuration = Configuration.from_revolute_values([-0.042, 4.295, 0, -3.327, 4.755, 0.]) ... group = robot.main_group_name ... target = FrameTarget(frame, tolerance_position, tolerance_orientation) ... goal_constraints = robot.constraints_from_frame(frame, tolerance_position, tolerances_axes, group) ... trajectory = robot.plan_motion((target, start_configuration, group, {'planner_id': 'RRTConnect'}) ... print(trajectory.fraction) 1.0
Using a
ConfigurationTarget
:>>> with RosClient() as client: #: This doctest can pass locally but persistently fails on CI in GitHub. "roslibpy.core.RosTimeoutError: Failed to connect to ROS" ... robot = client.load_robot() ... joint_names = robot.get_configurable_joint_names() ... configuration = Configuration.from_revolute_values([0.0, -1.5707, 0.0, -1.5707, 0.0, 0.0], joint_names) ... tolerances_above = [math.radians(5)] * len(configuration.joint_values) ... tolerances_below = [math.radians(5)] * len(configuration.joint_values) ... group = robot.main_group_name ... target = ConfigurationTarget(configuration, tolerances_above, tolerances_below) ... trajectory = robot.plan_motion(target, start_configuration, group, {'planner_id': 'RRTConnect'}) ... print(trajectory.fraction) 1.0