VrepPlanner.plan_motion

VrepPlanner.plan_motion(*args, **kwargs)[source]

Finds a path plan to move the selected robot from its current position to the goal_constraints.

Args:

robot (compas_fab.robots.Robot): The robot instance for which the motion plan is being calculated. goal_constraints (Frame): Target or goal frame. start_configuration (None): Unused parameter. group (int): Integer referencing the desired robot group. options (dict): Dictionary containing the following key-values pairs:

  • "metric_values": (list of float) List containing one value per configurable joint. Each value ranges from 0 to 1, where 1 indicates the axis/joint is blocked and cannot move during inverse kinematic solving.

  • "collision_meshes": (list of compas.datastructures.Mesh) Collision meshes to be taken into account when calculating the motion plan. Defaults to None.

  • "planner_id": (str) Name of the planner to use. Defaults to rrtconnect.

  • "trials": (int) Number of search trials to run. Defaults to 1.

  • "resolution": (float) Validity checking resolution. This value is specified as a fraction of the space’s extent. Defaults to 0.02.

  • "gantry_joint_limits": (list of float) List of 6 floats defining the upper/lower limits of gantry joints. Use this if you want to restrict the working area of the path planner.

  • "arm_joint_limits": (list of float) List of 12 floats defining the upper/lower limits of arm joints. Use this if you want to restrict the working area of the path planner.

  • "shallow_state_search": (bool) True to search only a minimum of valid states before searching a path, False to search states intensively.

  • "optimize_path_length": (bool) True to search the path with minimal total length among all trials, False to return the first valid path found. It only affects the output if trials > 1.

  • "log": (Logger) Logger object to aid debugging. Default to None.

Returns:

list: List of Configuration objects representing the collision-free path to the goal_constraint.