pykin.kinematics package

Submodules

pykin.kinematics.jacobian module

pykin.kinematics.jacobian.calc_jacobian(frames: list, transformations: dict, jsize: int) numpy.array[source]
Parameters
  • frames (list) – frames to compute jacobian

  • transformations (dict) – transformations from forward kinematics

  • thetas (int) – size of joint space

Returns

return Jacobian

Return type

Jacobian (np.array(6, jsize))

pykin.kinematics.kinematics module

class pykin.kinematics.kinematics.Kinematics(robot_name, offset, active_joint_names=[], base_name='base', eef_name=None)[source]

Bases: object

Class of Kinematics

Parameters
  • robot_name (str) – robot’s name

  • offset (Transform) – robot’s offset

  • active_joint_names (list) – robot’s actuated joints

  • base_name (str) – reference link’s name

  • eef_name (str) – end effector’s name

forward_kinematics(frames, thetas)[source]

Returns transformations obtained by computing fk

Parameters
  • frames (list or Frame()) – robot’s frame for forward kinematics

  • thetas (sequence of float) – input joint angles

Returns

transformations

Return type

transformations (OrderedDict)

inverse_kinematics(**kwargs)

pykin.kinematics.transform module

class pykin.kinematics.transform.Transform(rot=array([1.0, 0.0, 0.0, 0.0]), pos=array([0.0, 0.0, 0.0]))[source]

Bases: object

This class calculates the rotation and translation of a 3D rigid body.

Parameters
  • rot (sequence of float) – The rotation parameter. Give in quaternions or roll pitch yaw.

  • pos (sequence of float) – The translation parameter.

<<<<<<< HEAD
property h_mat
=======
property homogeneous_matrix
>>>>>>> ea49476fc7b0492d09cb4006dd56bb6aba81ff14

Returns: np.array: homogeneous matrix

inverse()[source]
Returns

inverse transform

Return type

Transform

property pos

Returns: np.array: position

property pose

Returns: np.array: pose

property rot

Returns: np.array: rotation (quaternion)

property rotation_matrix

Returns: np.array: rotation matrix

Module contents