|
| 1 | +# ATTENTION: auto generated from C++ code, use `make stubgen` to update! |
| 2 | +""" |
| 3 | +Python bindings for frankik IK/FK |
| 4 | +""" |
| 5 | +from __future__ import annotations |
| 6 | + |
| 7 | +import typing |
| 8 | + |
| 9 | +import numpy |
| 10 | + |
| 11 | +__all__: list[str] = ["fk", "ik", "ik_full"] |
| 12 | + |
| 13 | +def fk( |
| 14 | + q: numpy.ndarray[tuple[typing.Literal[7]], numpy.dtype[numpy.float64]] |
| 15 | +) -> numpy.ndarray[tuple[typing.Literal[4], typing.Literal[4]], numpy.dtype[numpy.float64]]: |
| 16 | + """ |
| 17 | + Compute forward kinematics for Franka Emika Panda robot. |
| 18 | +
|
| 19 | + Args: |
| 20 | + q (Vector7d): Joint angles. |
| 21 | +
|
| 22 | + Returns: |
| 23 | + Eigen::Matrix<double, 4, 4>: End-effector pose. |
| 24 | + """ |
| 25 | + |
| 26 | +def ik( |
| 27 | + O_T_EE: numpy.ndarray[tuple[typing.Literal[4], typing.Literal[4]], numpy.dtype[numpy.float64]], |
| 28 | + q_actual_array: numpy.ndarray[tuple[typing.Literal[7]], numpy.dtype[numpy.float64]] = ..., |
| 29 | + q7: float = 0.7853981633974483, |
| 30 | + is_fr3: bool = False, |
| 31 | +) -> numpy.ndarray[tuple[typing.Literal[7]], numpy.dtype[numpy.float64]]: |
| 32 | + """ |
| 33 | + Compute one inverse kinematics solution for Franka Emika Panda robot. |
| 34 | +
|
| 35 | + Args: |
| 36 | + O_T_EE (Eigen::Matrix<double, 4, 4>): Desired end-effector pose. |
| 37 | + q_actual_array (Vector7d, optional): Current joint angles. Defaults to kQDefault. |
| 38 | + q7 (double, optional): Joint 7 angle. Defaults to M_PI_4. |
| 39 | + is_fr3 (bool, optional): Whether to use FR3 joint limits. Defaults to false. |
| 40 | +
|
| 41 | + Returns: |
| 42 | + Vector7d: One IK solution. NaN if no solution. |
| 43 | + """ |
| 44 | + |
| 45 | +def ik_full( |
| 46 | + O_T_EE: numpy.ndarray[tuple[typing.Literal[4], typing.Literal[4]], numpy.dtype[numpy.float64]], |
| 47 | + q_actual_array: numpy.ndarray[tuple[typing.Literal[7]], numpy.dtype[numpy.float64]] = ..., |
| 48 | + q7: float = 0.7853981633974483, |
| 49 | + is_fr3: bool = False, |
| 50 | +) -> numpy.ndarray[tuple[typing.Literal[4], typing.Literal[7]], numpy.dtype[numpy.float64]]: |
| 51 | + """ |
| 52 | + Compute full inverse kinematics for Franka Emika Panda robot. |
| 53 | +
|
| 54 | + Args: |
| 55 | + O_T_EE (Eigen::Matrix<double, 4, 4>): Desired end-effector pose. |
| 56 | + q_actual_array (Vector7d, optional): Current joint angles. Defaults to kQDefault. |
| 57 | + q7 (double, optional): Joint 7 angle. Defaults to M_PI_4. |
| 58 | + is_fr3 (bool, optional): Whether to use FR3 joint limits. Defaults to false. |
| 59 | +
|
| 60 | + Returns: |
| 61 | + Eigen::Matrix<double, 4, 7>: All possible IK solutions (up to 4). NaN if no solution. |
| 62 | + """ |
| 63 | + |
| 64 | +__version__: str = "0.1" |
0 commit comments