Hand Kinematics
- class dexrobot_kinematics.hand.LeftHandKinematics(urdf_path: Path | None = None, config_path: Path | None = None)[source]
Bases:
HandKinematicsBase
Class for left hand kinematics calculations
- class dexrobot_kinematics.hand.RightHandKinematics(urdf_path: Path | None = None, config_path: Path | None = None)[source]
Bases:
HandKinematicsBase
Class for right hand kinematics calculations
HandKinematicsBase
- class dexrobot_kinematics.hand.base.HandKinematicsBase(handedness: str, config_path: Path)[source]
Bases:
object
Base class for hand kinematics calculations
- forward_kinematics(joint_angles: Dict[str, float], base_pose: Pose | None = None, frame: str = 'hand', end_effector: str = 'fingerpad') Dict[str, Pose] [source]
Compute forward kinematics for all fingers
- Parameters:
joint_angles – Current joint angles
base_pose – Optional base pose of the hand, used to transform output pose when frame is ‘world’
frame – Reference frame (‘hand’ or ‘world’)
end_effector – Target frame type (‘fingerpad’ or ‘fingertip’)
- Returns:
Dictionary of finger poses in specified frame
- inverse_kinematics_finger(finger: str, target_pos: Position, base_pose: Pose | None = None, frame: str = 'hand', end_effector: str = 'fingerpad', initial_guess: Dict[str, float] | None = None) Tuple[Dict[str, float], bool] [source]
Solve IK for a single finger
- Parameters:
finger – Target finger name
target_pos – Target position
base_pose – Optional base pose of the hand, used to transform target when frame is ‘world’
frame – Reference frame (‘hand’ or ‘world’)
end_effector – Target frame type (‘fingerpad’ or ‘fingertip’)
initial_guess – Initial joint angles
- Returns:
Tuple of (joint angles, success flag)
- inverse_kinematics_grasp(finger_targets: Dict[str, Position], base_pose: Pose | None = None, frame: str = 'hand', end_effector: str = 'fingerpad', initial_guess: Dict[str, float] | None = None) Tuple[Dict[str, float], bool] [source]
Solve IK for multiple fingers simultaneously.
- Parameters:
finger_targets – Target positions for each finger
base_pose – Optional base pose of the hand, used to transform target when frame is ‘world
frame – Reference frame (‘hand’ or ‘world’)
end_effector – Target frame type (‘fingerpad’ or ‘fingertip’)
initial_guess – Initial joint angles
- Returns:
Tuple of (joint angles for all fingers, success flag)
IK Solver
- class dexrobot_kinematics.hand.ik_solver.HandIKSolver(robot: RobotWrapper, handedness: str, target_frame: str, config_path: Path, eps: float = 0.0001, max_iter: int = 200, damping: float = 0.01, dt: float = 1)[source]
Bases:
object
A Pinocchio-based IK solver for robotic hand that handles joint limits and finger joint synchronization
- solve(target_pos: Position, initial_q: ndarray | None = None, orientation_weight: float = 0.0) Tuple[ndarray, bool] [source]
Solve inverse kinematics
- Parameters:
target_pos – Target end-effector position
initial_q – Initial joint configuration
orientation_weight – Weight for orientation constraint
- Returns:
Tuple of (final joint configuration, success flag)