Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
pykdl_utils.joint_kinematics.JointKinematics Class Reference

Kinematics class which subscribes to the /joint_states topic, recording the current joint states for the kinematic chain designated. More...

Inheritance diagram for pykdl_utils.joint_kinematics.JointKinematics:
Inheritance graph
[legend]

List of all members.

Public Member Functions

def __init__
 Constructor.
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 get_joint_angles
 Returns the current joint angle positions.
def get_joint_efforts
 Returns the current joint efforts.
def get_joint_velocities
 Returns the current joint velocities.
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 wait_for_joint_angles
 Wait until we have found the current joint angles.
def wrap_angles
 Returns joint angles for continuous joints to a range [0, 2*PI)

Public Attributes

 joint_types

Private Member Functions

def _joint_state_cb
 Joint angles listener callback.

Private Attributes

 _joint_angles
 _joint_efforts
 _joint_state_inds
 _joint_velocities

Detailed Description

Kinematics class which subscribes to the /joint_states topic, recording the current joint states for the kinematic chain designated.

Definition at line 54 of file joint_kinematics.py.


Constructor & Destructor Documentation

def pykdl_utils.joint_kinematics.JointKinematics.__init__ (   self,
  urdf,
  base_link,
  end_link,
  kdl_tree = None,
  timeout = 1. 
)

Constructor.

Parameters:
urdfURDF object of robot.
base_linkName of the root link of the kinematic chain.
end_linkName of the end link of the kinematic chain.
kdl_treeOptional KDL.Tree object to use. If None, one will be generated from the URDF.
timeoutTime in seconds to wait for the /joint_states topic.

Definition at line 63 of file joint_kinematics.py.


Member Function Documentation

Joint angles listener callback.

Definition at line 77 of file joint_kinematics.py.

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 174 of file joint_kinematics.py.

Returns the current effective end effector force.

Definition at line 191 of file joint_kinematics.py.

def pykdl_utils.joint_kinematics.JointKinematics.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 141 of file joint_kinematics.py.

Returns the current joint angle positions.

Parameters:
wrappedIf False returns the raw encoded positions, if True returns the angles with the forearm and wrist roll in the range -pi to pi

Definition at line 109 of file joint_kinematics.py.

Returns the current joint efforts.

Definition at line 128 of file joint_kinematics.py.

Returns the current joint velocities.

Definition at line 120 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 163 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 152 of file joint_kinematics.py.

Wait until we have found the current joint angles.

Parameters:
timeoutTime at which we break if we haven't recieved the angles.

Definition at line 92 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 185 of file joint_kinematics.py.


Member Data Documentation

Definition at line 63 of file joint_kinematics.py.

Definition at line 63 of file joint_kinematics.py.

Definition at line 63 of file joint_kinematics.py.

Definition at line 63 of file joint_kinematics.py.

Reimplemented from pykdl_utils.kdl_kinematics.KDLKinematics.

Definition at line 185 of file joint_kinematics.py.


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


pykdl_utils
Author(s): Kelsey Hawkins / kphawkins@gatech.edu, Advisor: Prof. Charlie Kemp (Healthcare Robotics Lab at Georgia Tech)
autogenerated on Wed Nov 27 2013 11:37:37