Robot.inverse_kinematics

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

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

The inverse kinematic solvers are implemented as generators in order to fit both analytic and numerical solver approaches. However, this method abstracts that away and returns one configuration at a time to simplify its usage.

To keep the usefulness of the generator, calls to this method will recall the last retrieved iterator and keep returning results yielded by it, one at a time. This is true only as long as the request is identical to the last one. If the arguments change, the last generator is discarded and the client IK implementation is invoked again.

Parameters:
frame_WCFcompas.geometry.Frame

The frame to calculate the inverse kinematic for.

start_configurationcompas_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: :obj:`str`, optional

The planning group used for calculation. Defaults to the robot’s main planning group.

return_full_configurationbool, optional

If True, returns a full configuration with all joint values specified, including passive ones if available. Defaults to False.

use_attached_tool_framebool, optional

If True and there is a tool attached to the planning group, it will use its TCF instead of the T0CF to calculate IK. Defaults to True.

options: :obj:`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.

Returns:
compas_robots.Configuration

An inverse kinematic solution represented as a configuration.

Raises:
compas_fab.backends.BackendError

If no configuration can be found.

Examples

>>> robot = RobotLibrary.ur5()
>>> 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))