Robot.inverse_kinematics

Robot.inverse_kinematics(frame_WCF, start_configuration=None, group=None, return_full_configuration=False, options=None)[source]

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

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

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

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

  • options (dict, optional) – Dictionary containing the key-value pairs of additional options. The valid options are specific to the backend in use. Check the API reference of the IK backend implementation for more details.

Raises

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

Returns

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))