robot_models
Robot models.
- robotblockset.robot_models.invkin_model_panda_valid(self, x: ndarray, q7: float, q_initial: ndarray, tcp: ndarray, closest: bool = True) Tuple[ndarray, ...][source]
Check if the inverse kinematics solution is valid for the given end-effector pose and joint angle q7.
if the joint angle q7 is within the valid range, it computes the inverse kinematics solution, otherwise it finds the closest valid joint configuration.
- Parameters:
x (np.ndarray) – The end-effector pose as a 4x4 transformation matrix.
q7 (float) – The joint angle for the 7th joint (end-effector rotation around the z-axis).
q0 (np.ndarray) – The initial joint positions.
tcp (TCPType) – The tool_center_point transformation matrix.
closest (bool, optional) – If True, find the closest valid joint configuration. Default is True.
- Returns:
A tuple containing the valid joint configurations for the given end-effector pose and joint angle q7.
- Return type:
Tuple[np.ndarray, …]
- robotblockset.robot_models.invkin_model_panda(self, x: ndarray, q7: float, q_initial: ndarray, tcp: ndarray, closest: bool = True) Tuple[ndarray, ...][source]
Calculate the inverse kinematics solution the given end-effector pose and joint angle q7.
- Parameters:
x (np.ndarray) – The end-effector pose as a 4x4 transformation matrix.
q7 (float) – The joint angle for the 7th joint (end-effector rotation around the z-axis).
q0 (np.ndarray) – The initial joint positions.
tcp (TCPType) – The tool_center_point transformation matrix.
closest (bool, optional) – If True, find the closest valid joint configuration. Default is True.
- Returns:
A tuple containing the valid joint configurations for the given end-effector pose and joint angle q7.
- Return type:
Tuple[np.ndarray, …]
- robotblockset.robot_models.kinmodel_panda_reduced_pos(q: ndarray, out: str = 'x') Tuple[ndarray, ndarray] | Tuple[ndarray, ndarray, ndarray][source]
Abstract method to compute the forward kinematics of the robot.
This function implements a reduced 5-DoF kinematic model of the Franka Emika Panda manipulator, where only the translational motion of the Tool Center Point (TCP) is considered. The TCP is treated as a point (pointer), and the end-effector orientation is not used for control purposes. The model is intended for applications where the mobile base or higher-level controller depends solely on the TCP position, such as local vector-field-based base–manipulator control.
- Parameters:
q (np.ndarray) – Joint angles of the first five Panda joints, used as input to the reduced kinematic model.
out (str, optional) – Output format selector. Depending on the value, the function returns the TCP position or a homogeneous transformation with translation only. By default “x”.
- Returns:
The computed reduced kinematic output. This is typically the Cartesian position of the TCP (pointer) and, if requested, the associated geometric Jacobian with respect to the first five joints.
- Return type:
tuple
- robotblockset.robot_models.kinmodel_panda(q: ndarray, tcp: ndarray | None = None, out: str = 'x') list[source]
Compute forward kinematics and Jacobian for the robot.
- Parameters:
q (np.ndarray) – Joint angles/positions.
tcp (TCPType, optional) – Tool centre point (optional).
out (str, optional) – Output form (optional).
- Returns:
p (np.array) – Position of the end effector.
R (np.array) – Rotation matrix of the end effector.
J (np.array) – Jacobian matrix (6 x nj).
- robotblockset.robot_models.kinmodel_ur10(q: ndarray, tcp: ndarray | None = None, out: str = 'x') list[source]
Compute forward kinematics and Jacobian for the robot.
- Parameters:
q (np.ndarray) – Joint angles/positions.
tcp (TCPType, optional) – Tool centre point (optional).
out (str, optional) – Output form (optional).
- Returns:
p (np.array) – Position of the end effector.
R (np.array) – Rotation matrix of the end effector.
J (np.array) – Jacobian matrix (6 x nj).
- robotblockset.robot_models.kinmodel_ur10e(q: ndarray, tcp: ndarray | None = None, out: str = 'x') list[source]
Compute forward kinematics and Jacobian for the robot.
- Parameters:
q (np.ndarray) – Joint angles/positions.
tcp (TCPType, optional) – Tool centre point (optional).
out (str, optional) – Output form (optional).
- Returns:
p (np.array) – Position of the end effector.
R (np.array) – Rotation matrix of the end effector.
J (np.array) – Jacobian matrix (6 x nj).
- robotblockset.robot_models.kinmodel_ur5(q: ndarray, tcp: ndarray | None = None, out: str = 'x') list[source]
Compute forward kinematics and Jacobian for the robot.
- Parameters:
q (np.ndarray) – Joint angles/positions.
tcp (TCPType, optional) – Tool centre point (optional).
out (str, optional) – Output form (optional).
- Returns:
p (np.array) – Position of the end effector.
R (np.array) – Rotation matrix of the end effector.
J (np.array) – Jacobian matrix (6 x nj).
- robotblockset.robot_models.kinmodel_ur5e(q: ndarray, tcp: ndarray | None = None, out: str = 'x') list[source]
Compute forward kinematics and Jacobian for the robot.
- Parameters:
q (np.ndarray) – Joint angles/positions.
tcp (TCPType, optional) – Tool centre point (optional).
out (str, optional) – Output form (optional).
- Returns:
p (np.array) – Position of the end effector.
R (np.array) – Rotation matrix of the end effector.
J (np.array) – Jacobian matrix (6 x nj).
- robotblockset.robot_models.kinmodel_iiwa(q: ndarray, tcp: ndarray | None = None, out: str = 'x') list[source]
Compute forward kinematics and Jacobian for the robot.
- Parameters:
q (np.ndarray) – Joint angles/positions.
tcp (TCPType, optional) – Tool centre point (optional).
out (str, optional) – Output form (optional).
- Returns:
p (np.array) – Position of the end effector.
R (np.array) – Rotation matrix of the end effector.
J (np.array) – Jacobian matrix (6 x nj).
- robotblockset.robot_models.kinmodel_lwr(q: ndarray, tcp: ndarray | None = None, out: str = 'x') list[source]
Compute forward kinematics and Jacobian for the robot.
- Parameters:
q (np.ndarray) – Joint angles/positions.
tcp (TCPType, optional) – Tool centre point (optional).
out (str, optional) – Output form (optional).
- Returns:
p (np.array) – Position of the end effector.
R (np.array) – Rotation matrix of the end effector.
J (np.array) – Jacobian matrix (6 x nj).
- robotblockset.robot_models.kinmodel_dh_7dof(q: ndarray, DH: dict, tcp: ndarray | None = None, out: str = 'x') list[source]
Compute forward kinematics and Jacobian for the 7 DOF robot with revolute joints.
- Parameters:
q (np.ndarray) – Joint angles/positions.
DH (dict) – DH parameters: ‘a’, ‘alpha’, ‘d’, ‘theta’.
tcp (TCPType, optional) – Tool centre point (optional).
out (str, optional) – Output form (optional).
- Returns:
p (np.ndarray) – Position of the end effector.
R (np.ndarray) – Rotation matrix of the end effector (3, 3).
J (np.ndarray) – Jacobian matrix (6, nj).
- robotblockset.robot_models.kinmodel_dh_6dof(q: ndarray, DH: dict, tcp: ndarray | None = None, out: str = 'x') list[source]
Compute forward kinematics and Jacobian for the 6 DOF robot with revolute joints.
- Parameters:
q (np.ndarray) – Joint angles/positions.
DH (dict) – DH parameters: ‘a’, ‘alpha’, ‘d’, ‘theta’.
tcp (TCPType, optional) – Tool centre point (optional).
out (str, optional) – Output form (optional).
- Returns:
p (np.ndarray) – Position of the end effector.
R (np.ndarray) – Rotation matrix of the end effector (3, 3).
J (np.ndarray) – Jacobian matrix (6, nj).
- robotblockset.robot_models.kinmodel_crx20(q: ndarray, tcp: ndarray | None = None, out: str = 'x') list[source]
Compute forward kinematics and Jacobian for the Fanuc CRX20ia_l.
- Parameters:
q (np.ndarray) – Joint angles/positions.
tcp (TCPType, optional) – Tool centre point (optional).
out (str, optional) – Output form (optional).
- Returns:
p (np.ndarray) – Position of the end effector.
R (np.ndarray) – Rotation matrix of the end effector (3, 3).
J (np.ndarray) – Jacobian matrix (6, nj).
- robotblockset.robot_models.kinmodel_hc20(q: ndarray, tcp: ndarray | None = None, out: str = 'x') list[source]
Compute forward kinematics and Jacobian for the Yaskawa HC20.
- Parameters:
q (np.ndarray) – Joint angles/positions.
tcp (TCPType, optional) – Tool centre point (optional).
out (str, optional) – Output form (optional).
- Returns:
p (np.ndarray) – Position of the end effector.
R (np.ndarray) – Rotation matrix of the end effector (3, 3).
J (np.ndarray) – Jacobian matrix (6, nj).
- robotblockset.robot_models.kinmodel_z1_DH(q: ndarray, tcp: ndarray = None, out: str = 'x') list[source]
Compute forward kinematics and Jacobian for the Unitree z1.
- Parameters:
q (np.ndarray) – Joint angles/positions.
tcp (np.ndarray, optional) – Tool centre point (optional).
out (str, optional) – Output form (optional).
- Returns:
p (np.ndarray) – Position of the end effector.
R (np.ndarray) – Rotation matrix of the end effector (3, 3).
J (np.ndarray) – Jacobian matrix (6, nj).
- robotblockset.robot_models.kinmodel_z1(q: ndarray, tcp: ndarray = None, out: str = 'x') list[source]
Compute forward kinematics and Jacobian for the Z! MJCF.
- Parameters:
q (np.ndarray) – Joint angles/positions.
tcp (np.ndarray, optional) – Tool centre point (optional).
out (str, optional) – Output form (optional).
- Returns:
p (np.ndarray) – Position of the end effector.
R (np.ndarray) – Rotation matrix of the end effector (3, 3).
J (np.ndarray) – Jacobian matrix (6, nj).
Functions
|
Calculate the inverse kinematics solution the given end-effector pose and joint angle q7. |
|
Check if the inverse kinematics solution is valid for the given end-effector pose and joint angle q7. |
|
Compute forward kinematics and Jacobian for the Fanuc CRX20ia_l. |
|
Compute forward kinematics and Jacobian for the 6 DOF robot with revolute joints. |
|
Compute forward kinematics and Jacobian for the 7 DOF robot with revolute joints. |
|
Compute forward kinematics and Jacobian for the Yaskawa HC20. |
|
Compute forward kinematics and Jacobian for the robot. |
|
Compute forward kinematics and Jacobian for the robot. |
|
Compute forward kinematics and Jacobian for the robot. |
|
Abstract method to compute the forward kinematics of the robot. |
|
Compute forward kinematics and Jacobian for the robot. |
|
Compute forward kinematics and Jacobian for the robot. |
|
Compute forward kinematics and Jacobian for the robot. |
|
Compute forward kinematics and Jacobian for the robot. |
|
Compute forward kinematics and Jacobian for the Z! MJCF. |
|
Compute forward kinematics and Jacobian for the Unitree z1. |