Robot.inverse_kinematics

Robot.inverse_kinematics(frame_WCF, start_configuration=None, group=None, avoid_collisions=True, constraints=None, attempts=8, attached_collision_meshes=None, return_full_configuration=False)[source]

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

Parameters
  • frame (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 init configuration.

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

  • 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.

  • attempts (int, optional) – The maximum number of inverse kinematic attempts. Defaults to 8.

  • attached_collision_meshes (list of compas_fab.robots.AttachedCollisionMesh) – Defaults to None.

  • return_full_configuration (bool) – If True, returns a full configuration with all joint values specified, including passive ones if available.

Raises

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

Returns

compas_fab.robots.Configuration – The planning group’s configuration.

Examples

>>> frame_WCF = Frame([0.3, 0.1, 0.5], [1, 0, 0], [0, 1, 0])
>>> start_configuration = robot.zero_configuration()
>>> group = robot.main_group_name
>>> robot.inverse_kinematics(frame_WCF, start_configuration, group)                 
Configuration((4.045, 5.130, -2.174, -6.098, -5.616, 6.283), (0, 0, 0, 0, 0, 0))