Public Member Functions | Public Attributes
pykdl_utils.joint_kinematics.JointKinematicsBase Class Reference
Inheritance diagram for pykdl_utils.joint_kinematics.JointKinematicsBase:
Inheritance graph
[legend]

List of all members.

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

Detailed Description

Definition at line 53 of file joint_kinematics.py.


Member Function Documentation

Returns the cartesian space mass matrix at the end_link for the given joint angles.

Parameters:
qList of joint angles.
Returns:
6x6 np.mat Cartesian inertia matrix or None if the joint angles are not filled.

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.

Parameters:
qList of joint angles for the full kinematic chain. If None, the current joint angles are used.
end_linkName of the link the pose should be obtained for.
base_linkName of the root link frame the end_link should be found in.
Returns:
4x4 numpy.mat homogeneous transformation or None if the joint angles are not filled.

Reimplemented from pykdl_utils.kdl_kinematics.KDLKinematics.

Definition at line 61 of file joint_kinematics.py.

Returns the joint space mass matrix at the end_link for the given joint angles.

Parameters:
qList of joint angles.
Returns:
NxN np.mat Inertia matrix or None if the joint angles are not filled.

Reimplemented from pykdl_utils.kdl_kinematics.KDLKinematics.

Definition at line 83 of file joint_kinematics.py.

Returns the Jacobian matrix at the end_link from the current joint angles.

Parameters:
qList of joint angles. If None, the current joint angles are used.
Returns:
6xN np.mat Jacobian or None if the joint angles are not filled.

Definition at line 72 of file joint_kinematics.py.

Returns joint angles for continuous joints to a range [0, 2*PI)

Parameters:
qList of joint angles.
Returns:
np.array of wrapped joint angles.

Definition at line 105 of file joint_kinematics.py.


Member Data Documentation

Reimplemented from pykdl_utils.kdl_kinematics.KDLKinematics.

Definition at line 105 of file joint_kinematics.py.


The documentation for this class was generated from the following file:


pykdl_utils
Author(s): Kelsey Hawkins
autogenerated on Fri Aug 28 2015 11:05:34