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
toTrue
. The configurations that are in collision or outside joint boundaries are then not removed from the list of solutions, they are set toNone
.- 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) – 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 ) WhenTrue
, checksif the robot is in collision. Defaults to
False
."keep_order"
: (str
, optional ) WhenFalse
, removes theNone
- solutions. Defaults toFalse
.
- Yields
tuple
oflist
– A tuple of 2 elements containing a list of joint positions and a list of matching joint names. If"keep_order"
isTrue
this list contains alsoNone
,None
Notes
This will only work with robots that have 6 revolute joints.
:raises ValueError : If the solver to solve the kinematics has not been passed.: