WUT Velma robot API
Public Member Functions | Public Attributes | List of all members
velma_kinematics.velma_ik_geom.KinematicsSolverLWR4 Class Reference

Kinematics solver (FK, IK) for Kuka LWR 4+. More...

Public Member Functions

def __init__ (self)
 Initialization. More...
 
def getLimits (self)
 
def getDebug (self, key)
 Get some debug information after solving inverse kinematics. More...
 
def calculateIk (self, T_A0_A7d, elbow_circle_angle, flip_shoulder, flip_elbow, flip_ee)
 Calculate inverse kinematics (IK) for Kuka LWR 4+. More...
 
def calculateIkSet (self, T_A0_A7d, elbow_circle_angles)
 Calculate inverse kinematics (IK) for Kuka LWR 4+. More...
 
def calculateFk (self, q)
 Calculate forward kinematics (FK) for Kuka LWR 4+. More...
 

Public Attributes

 m_lim_lo
 
 m_lim_up
 

Detailed Description

Kinematics solver (FK, IK) for Kuka LWR 4+.

Definition at line 49 of file velma_ik_geom.py.

Constructor & Destructor Documentation

◆ __init__()

def velma_kinematics.velma_ik_geom.KinematicsSolverLWR4.__init__ (   self)

Initialization.

Definition at line 54 of file velma_ik_geom.py.

Member Function Documentation

◆ calculateFk()

def velma_kinematics.velma_ik_geom.KinematicsSolverLWR4.calculateFk (   self,
  q 
)

Calculate forward kinematics (FK) for Kuka LWR 4+.

Parameters
q7-tuple: arm configuration.
Returns
PyKDL.Frame: pose of the last link wrt. the first link of the arm.

Definition at line 298 of file velma_ik_geom.py.

◆ calculateIk()

def velma_kinematics.velma_ik_geom.KinematicsSolverLWR4.calculateIk (   self,
  T_A0_A7d,
  elbow_circle_angle,
  flip_shoulder,
  flip_elbow,
  flip_ee 
)

Calculate inverse kinematics (IK) for Kuka LWR 4+.

Parameters
T_A0_A7dPyKDL.Frame: pose of the end-effector (the last link) wrt. the base of arm (the first link).
elbow_circle_anglefloat: IK parameter.
flip_shoulderbool: IK parameter.
flip_elbowbool: IK parameter.
flip_eebool: IK parameter.
Returns
7-tuple: arm configuration or a tuple of Nones, if the solution does not exist.

Definition at line 244 of file velma_ik_geom.py.

◆ calculateIkSet()

def velma_kinematics.velma_ik_geom.KinematicsSolverLWR4.calculateIkSet (   self,
  T_A0_A7d,
  elbow_circle_angles 
)

Calculate inverse kinematics (IK) for Kuka LWR 4+.

Parameters
T_A0_A7dPyKDL.Frame: pose of the end-effector (the last link) wrt. the base of arm (the first link).
elbow_circle_angleslist of float: list of values for IK parameter: elbow_circle_angle (
See also
calculateIk).
Returns
list of 7-tuples: arm configurations.

Definition at line 273 of file velma_ik_geom.py.

◆ getDebug()

def velma_kinematics.velma_ik_geom.KinematicsSolverLWR4.getDebug (   self,
  key 
)

Get some debug information after solving inverse kinematics.

Parameters
keystring: one of values: 'T_A0_A6d', 'pt_shoulder', 'elbow_pt'.
Returns
Value for the given key or None, if the key does not exist.

Definition at line 72 of file velma_ik_geom.py.

◆ getLimits()

def velma_kinematics.velma_ik_geom.KinematicsSolverLWR4.getLimits (   self)

Definition at line 69 of file velma_ik_geom.py.

Member Data Documentation

◆ m_lim_lo

velma_kinematics.velma_ik_geom.KinematicsSolverLWR4.m_lim_lo

Definition at line 66 of file velma_ik_geom.py.

◆ m_lim_up

velma_kinematics.velma_ik_geom.KinematicsSolverLWR4.m_lim_up

Definition at line 67 of file velma_ik_geom.py.


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