Public Member Functions | Public Attributes
hrl_generic_arms.hrl_arm_template.HRLArmKinematics Class Reference

Abstract class containing kinematics interfaces for an arm. More...

List of all members.

Public Member Functions

def __init__
def FK
 Returns FK for the last link in the kinematic chain.
def FK_vanilla
 Returns FK for the last link in the kinematic chain.
def IK
 Computes IK for the tooltip.
def IK_vanilla
 Computes IK for the last link in the kinematic chain.
def jacobian
 Computes Jacobian in the arm's frame given joint angles at the specified position.
def jacobian_vanilla
 Computes Jacobian in the arm's frame given joint angles at the specified position.
def set_arm_base
 Sets the offset of the first link in the kinematic chain.
def set_tooltip
 Sets the offset of the tool from the last link in the kinematic chain.

Public Attributes

 arm_base_pos
 arm_base_rot
 n_jts
 tooltip_pos
 tooltip_rot

Detailed Description

Abstract class containing kinematics interfaces for an arm.

Definition at line 83 of file hrl_arm_template.py.


Constructor & Destructor Documentation

def hrl_generic_arms.hrl_arm_template.HRLArmKinematics.__init__ (   self,
  n_jts,
  arm_base_pos = np.matrix([0.]*3).T,
  arm_base_rot = np.matrix(np.eye(3)),
  tool_pos = np.matrix([0.]*3).T,
  tool_rot = np.matrix(np.eye(3)) 
)
Parameters:
n_jtsNumber of joints of the arm
tool_posPostion offset of the tool from the last link in the kinematic chain
tool_rotRotation offset of the tool from the last link in the kinematic chain

Definition at line 88 of file hrl_arm_template.py.


Member Function Documentation

def hrl_generic_arms.hrl_arm_template.HRLArmKinematics.FK (   self,
  q,
  link_number = None 
)

Returns FK for the last link in the kinematic chain.

Must be implemented by child class

Parameters:
qJoint angles in radians
link_numberLink in the kinematic chain to return FK for 0 represents the ground frame, 1 returns the first link's frame, ... n_jts + 1 (and None) returns the tooltip's frame
Returns:
pos (3x1) np matrix, rot (3x3) np matrix

Definition at line 134 of file hrl_arm_template.py.

def hrl_generic_arms.hrl_arm_template.HRLArmKinematics.FK_vanilla (   self,
  q,
  link_number = None 
)

Returns FK for the last link in the kinematic chain.

Must be implemented by child class.

Parameters:
qJoint angles in radians
link_numberLink in the kinematic chain to return FK for 0 represents the ground frame, 1 returns the first link's frame, ... n_jts + 1 returns the tooltip's frame
Returns:
pos (3x1) np matrix, rot (3x3) np matrix

Definition at line 103 of file hrl_arm_template.py.

def hrl_generic_arms.hrl_arm_template.HRLArmKinematics.IK (   self,
  pos,
  rot,
  q_guess = None 
)

Computes IK for the tooltip.

The desired location is first transformed back into the last link's frame and IK is performed on that location.

Parameters:
posDesired link position (3x1 np matrix)
rotDesired link rotation (3x3 np matrix)
q_guessEstimate of the desired joint angles which seeds the IK solver

Definition at line 160 of file hrl_arm_template.py.

def hrl_generic_arms.hrl_arm_template.HRLArmKinematics.IK_vanilla (   self,
  pos,
  rot,
  q_guess = None 
)

Computes IK for the last link in the kinematic chain.

Must be implemented by child class.

Parameters:
posDesired link position (3x1 np matrix)
rotDesired link rotation (3x3 np matrix)
q_guessEstimate of the desired joint angles which seeds the IK solver

Definition at line 112 of file hrl_arm_template.py.

Computes Jacobian in the arm's frame given joint angles at the specified position.

Parameters:
qJoint angles for Jacobian
posPosition at which the Jacobian is centered. If None, the tooltip location from FK is used.
Returns:
Jacobian 6xN np matrix

Definition at line 173 of file hrl_arm_template.py.

Computes Jacobian in the arm's frame given joint angles at the specified position.

Must be implemented by child class.

Parameters:
qJoint angles for Jacobian
posPosition at which the Jacobian is centered. If None, the tooltip location from FK is used.
Returns:
Jacobian 6xN np matrix

Definition at line 122 of file hrl_arm_template.py.

def hrl_generic_arms.hrl_arm_template.HRLArmKinematics.set_arm_base (   self,
  arm_base_pos,
  arm_base_rot = np.matrix(np.eye(3)) 
)

Sets the offset of the first link in the kinematic chain.

Parameters:
arm_base_posPostion offset of the first link in the kinematic chain
arm_base_rotRotation offset of the first link in the kinematic chain

Definition at line 182 of file hrl_arm_template.py.

def hrl_generic_arms.hrl_arm_template.HRLArmKinematics.set_tooltip (   self,
  tool_pos,
  tool_rot = np.matrix(np.eye(3)) 
)

Sets the offset of the tool from the last link in the kinematic chain.

Parameters:
tool_posPostion offset of the tool from the last link in the kinematic chain
tool_rotRotation offset of the tool from the last link in the kinematic chain

Definition at line 190 of file hrl_arm_template.py.


Member Data Documentation

Definition at line 182 of file hrl_arm_template.py.

Definition at line 182 of file hrl_arm_template.py.

Definition at line 88 of file hrl_arm_template.py.

Definition at line 190 of file hrl_arm_template.py.

Definition at line 190 of file hrl_arm_template.py.


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


hrl_generic_arms
Author(s): Kelsey Hawkins
autogenerated on Wed Nov 27 2013 11:53:37