PyBulletPlanner.inverse_kinematics
- PyBulletPlanner.inverse_kinematics(robot, frame_WCF, start_configuration=None, group=None, options=None)[source]
Calculate the robot’s inverse kinematic for a given frame.
- Parameters:
- robot
compas_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
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 determining the end effector and labeling the
start_configuration
. Defaults to the robot’s main planning group.- options: dict, optional
Dictionary containing the following key-value pairs:
"link_name"
: (str
, optional ) Name of the link for which to compute the inverse kinematics. Defaults to the given group’s end effector."semi-constrained"
: (bool
, optional) WhenTrue
, only the position and not the orientation offrame_WCF
will not be considered in the calculation. Defaults toFalse
."enforce_joint_limits"
: (bool
, optional) WhenFalse
, the robot’s joint limits will be ignored in the calculation. Defaults toTrue
."high_accuracy"
: (bool
, optional) WhenTrue
, the solver will iteratively try to approach minimum deviation from the requested target frame. Defaults toTrue
."high_accuracy_threshold"
: (float
, optional) Defines the maximum acceptable distance threshold for the high accuracy solver. Defaults to1e-6
."high_accuracy_max_iter"
: (float
, optional) Defines the maximum number of iterations to use for the high accuracy solver. Defaults to20
."max_results"
: (int
) Maximum number of results to return. Defaults to100
.
- robot
- Yields:
- Raises: