pykin.robots package
Submodules
pykin.robots.bimanual module
- class pykin.robots.bimanual.Bimanual(fname: str, offset=None)[source]
Bases:
pykin.robots.robot.Robot
Initializes a bimanual robot simulation object.
- Parameters
fname (str) – path to the urdf file.
offset (Transform) – robot init offset
- property active_joint_names
- property arm_type
Return arm type If number of eef_name is two, return tuple type(“right”, “left) otherwise, return list type([“right] or [“left”])
- Returns
arm types (tuple or list)
- property base_name
- compute_eef_pose(transformations)[source]
Compute end effector’s pose
- Parameters
transformations (OrderedDict) –
- Returns
vals(dict)
- property eef_name
- inverse_kin(current_joints, target_pose, method='LM', maxIter=1000)[source]
Returns joint angles obtained by computing IK
- Parameters
current_joints (sequence of float) – input joint angles
target_pose (np.array) – goal pose to achieve
method (str) – two methods to calculate IK (LM: Levenberg-marquardt, NR: Newton-raphson)
maxIter (int) – Maximum number of calculation iterations
- Returns
target joint angles
- Return type
joints (np.array)
pykin.robots.robot module
- class pykin.robots.robot.Robot(fname=None, offset=None)[source]
Bases:
pykin.models.urdf_model.URDFModel
Initializes a robot object, as defined by a single corresponding robot URDF
- Parameters
fname (str) – path to the urdf file.
offset (Transform) – robot init offset
- property active_joint_names
- property base_name
- compute_pose_error(target_HT=array([[1.0, 0.0, 0.0, 0.0], [0.0, 1.0, 0.0, 0.0], [0.0, 0.0, 1.0, 0.0], [0.0, 0.0, 0.0, 1.0]]), result_HT=array([[1.0, 0.0, 0.0, 0.0], [0.0, 1.0, 0.0, 0.0], [0.0, 0.0, 1.0, 0.0], [0.0, 0.0, 0.0, 1.0]]))[source]
Computes pose(homogeneous transform) error
- Parameters
target_HT (np.array) – target homogeneous transform
result_HT (np.array) – result homogeneous transform
- Returns
error (np.array)
- property eef_name
- property frame
- property offset
pykin.robots.single_arm module
- class pykin.robots.single_arm.SingleArm(fname: str, offset=None)[source]
Bases:
pykin.robots.robot.Robot
Initializes a single-armed robot simulation object.
- Parameters
fname (str) – path to the urdf file.
offset (Transform) – robot init offset
- property active_joint_names
- property base_name
- compute_eef_pose(transformations)[source]
Compute end effector’s pose
- Parameters
transformations (OrderedDict) –
- Returns
vals(dict)
- property eef_name
- inverse_kin(current_joints, target_pose, method='LM', maxIter=1000)[source]
Returns joint angles obtained by computing IK
- Parameters
current_joints (sequence of float) – input joint angles
target_pose (np.array) – goal pose to achieve
method (str) – two methods to calculate IK (LM: Levenberg-marquardt, NR: Newton-raphson)
maxIter (int) – Maximum number of calculation iterations
- Returns
target joint angles
- Return type
joints (np.array)