MoveItPlanner.inverse_kinematics

MoveItPlanner.inverse_kinematics(*args, **kwargs)[source]

Calculate the robot’s inverse kinematic for a given frame.

Parameters
  • robot (compas_fab.robots.Robot) – The robot instance for which inverse kinematics is being calculated.

  • frame_WCF (compas.geometry.Frame) – The frame to calculate the inverse for.

  • start_configuration (compas_fab.robots.Configuration, optional) – If passed, the inverse will be calculated such that the calculated joint positions differ the least from the start_configuration. Defaults to the zero configuration.

  • group (str, optional) – The planning group used for calculation. Defaults to the robot’s main planning group.

  • options (dict, optional) – Dictionary containing the following key-value pairs:

    • "base_link": (str) Name of the base link. Defaults to the model’s root link.

    • "avoid_collisions": (bool, optional) Whether or not to avoid collisions. Defaults to True.

    • "constraints": (list of compas_fab.robots.Constraint, optional) A set of constraints that the request must obey. Defaults to None.

    • "timeout": (int, optional) Maximum allowed time for inverse kinematic calculation in seconds. Defaults to 2. This value supersedes the "attempts" argument used before ROS Noetic.

    • "attached_collision_meshes": (list of compas_fab.robots.AttachedCollisionMesh, optional) Defaults to None.

    • "attempts": (int, optional) The maximum number of inverse kinematic attempts. Defaults to 8. This value is ignored on ROS Noetic and newer, use "timeout" instead.

    • "max_results": (int) Maximum number of results to return. Defaults to 100.

Raises

compas_fab.backends.exceptions.BackendError – If no configuration can be found.

Yields

tuple of list – A tuple of 2 elements containing a list of joint positions and a list of matching joint names.