AnalyticalInverseKinematics.inverse_kinematics

AnalyticalInverseKinematics.inverse_kinematics(robot, frame_WCF, start_configuration=None, group=None, options=None)[source]

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

The IK for 6-axis industrial robots returns by default 8 possible solutions. These solutions have an order. That means that if you call IK on two subsequent frames and compare the 8 configurations of the first frame with the 8 configurations of the second frame at their respective indices, then these configurations are “close” to one another. For this reason, for certain use cases, e.g. for cartesian path planning, it makes sense to keep the order of solutions. This can be achieved by setting the optional parameter keep_order to True. The configurations that are in collision or outside joint boundaries are then not removed from the list of solutions, they are set to None.

Parameters:
robotcompas_fab.robots.Robot

The robot instance for which inverse kinematics is being calculated.

frame_WCF: :class:`compas.geometry.Frame`

The frame to calculate the inverse for.

start_configuration: :class:`compas_fab.robots.Configuration`, optional

The start_configuration of the robot.

group: str, optional

The planning group used for determining the end effector and labeling the start_configuration. Defaults to the robot’s main planning group.

options: dict

Dictionary containing the following key-value pairs:

  • "solver": (str) The solver to use to calculate IK.

  • "check_collision": (str, optional ) When True, checks if the robot is in collision. Defaults to False.

  • "keep_order": (str, optional ) When False, removes the None- solutions. Defaults to False.

Yields:
tuple of list

A tuple of 2 elements containing a list of joint positions and a list of matching joint names. If "keep_order" is True this list contains also None, None

Raises:
ValueError

If the solver to solve the kinematics has not been passed.

Notes

This will only work with robots that have 6 revolute joints.