Public Member Functions | |
def | cart_inertia |
Returns the cartesian space mass matrix at the end_link for the given joint angles. | |
def | end_effector_force |
Returns the current effective end effector force. | |
def | forward |
Perform forward kinematics on the current joint angles. | |
def | inertia |
Returns the joint space mass matrix at the end_link for the given joint angles. | |
def | jacobian |
Returns the Jacobian matrix at the end_link from the current joint angles. | |
def | wrap_angles |
Returns joint angles for continuous joints to a range [0, 2*PI) | |
Public Attributes | |
joint_types |
Definition at line 53 of file joint_kinematics.py.
def pykdl_utils.joint_kinematics.JointKinematicsBase.cart_inertia | ( | self, | |
q = None |
|||
) |
Returns the cartesian space mass matrix at the end_link for the given joint angles.
q | List of joint angles. |
Reimplemented from pykdl_utils.kdl_kinematics.KDLKinematics.
Definition at line 94 of file joint_kinematics.py.
Returns the current effective end effector force.
Definition at line 111 of file joint_kinematics.py.
def pykdl_utils.joint_kinematics.JointKinematicsBase.forward | ( | self, | |
q = None , |
|||
end_link = None , |
|||
base_link = None |
|||
) |
Perform forward kinematics on the current joint angles.
q | List of joint angles for the full kinematic chain. If None, the current joint angles are used. |
end_link | Name of the link the pose should be obtained for. |
base_link | Name of the root link frame the end_link should be found in. |
Reimplemented from pykdl_utils.kdl_kinematics.KDLKinematics.
Definition at line 61 of file joint_kinematics.py.
def pykdl_utils.joint_kinematics.JointKinematicsBase.inertia | ( | self, | |
q = None |
|||
) |
Returns the joint space mass matrix at the end_link for the given joint angles.
q | List of joint angles. |
Reimplemented from pykdl_utils.kdl_kinematics.KDLKinematics.
Definition at line 83 of file joint_kinematics.py.
def pykdl_utils.joint_kinematics.JointKinematicsBase.jacobian | ( | self, | |
q = None |
|||
) |
Returns the Jacobian matrix at the end_link from the current joint angles.
q | List of joint angles. If None, the current joint angles are used. |
Definition at line 72 of file joint_kinematics.py.
def pykdl_utils.joint_kinematics.JointKinematicsBase.wrap_angles | ( | self, | |
q | |||
) |
Returns joint angles for continuous joints to a range [0, 2*PI)
q | List of joint angles. |
Definition at line 105 of file joint_kinematics.py.
Reimplemented from pykdl_utils.kdl_kinematics.KDLKinematics.
Definition at line 105 of file joint_kinematics.py.