Klamp't Python Bindings  0.6.2
Public Member Functions | Public Attributes | List of all members
klampt.robotsim.IKObjective Class Reference
Inheritance diagram for klampt.robotsim.IKObjective:

Public Member Functions

def __init__ (self)
def link (self)
def destLink (self)
def numPosDims (self)
def numRotDims (self)
def setFixedPoint (self, args)
def setFixedPoints (self, args)
def setFixedTransform (self, args)
def setRelativePoint (self, args)
def setRelativePoints (self, args)
def setRelativeTransform (self, args)
def setLinks (self, args)
def setFreePosition (self)
def setFixedPosConstraint (self, args)
def setPlanarPosConstraint (self, args)
def setLinearPosConstraint (self, args)
def setFreeRotConstraint (self)
def setFixedRotConstraint (self, args)
def setAxialRotConstraint (self, args)
def getPosition (self)
def getPositionDirection (self)
def getRotation (self)
def getRotationAxis (self)
def getTransform (self)
def loadString (self, args)
def saveString (self)

Public Attributes


Detailed Description

A class defining an inverse kinematic target. Either a link on a robot
can take on a fixed position/orientation in the world frame, or a
relative position/orientation to another frame.

Currently only fixed-point constraints and fixed-transform constraints
are implemented in the Python API.

C++ includes: robotik.h 

Constructor & Destructor Documentation

def klampt.robotsim.IKObjective.__init__ (   self)
__init__(IKObjective self) -> IKObjective

Referenced by klampt.trajectory.HermiteTrajectory.makeSpline().

Member Function Documentation

def klampt.robotsim.IKObjective.destLink (   self)
destLink(IKObjective self) -> int

The index of the destination link, or -1 if fixed to the world. 
def klampt.robotsim.IKObjective.getPosition (   self)
getPosition(IKObjective self)

Returns the local and global position of the position constraint. 
def klampt.robotsim.IKObjective.getPositionDirection (   self)
getPositionDirection(IKObjective self)

For linear and planar constraints, returns the direction. 
def klampt.robotsim.IKObjective.getRotation (   self)
getRotation(IKObjective self)

For fixed rotation constraints, returns the orientation. 
def klampt.robotsim.IKObjective.getRotationAxis (   self)
getRotationAxis(IKObjective self)

For axis rotation constraints, returns the local and global axes. 
def klampt.robotsim.IKObjective.getTransform (   self)
getTransform(IKObjective self)

For fixed-transform constraints, returns the transform (R,T) 
def klampt.robotsim.IKObjective.link (   self)
link(IKObjective self) -> int

The index of the robot link that is constrained. 
def klampt.robotsim.IKObjective.loadString (   self,
loadString(IKObjective self, char const * str) -> bool

Loads the objective from a Klamp't-native formatted string. For a more
readable but verbose format, try the JSON IO routines
def klampt.robotsim.IKObjective.numPosDims (   self)
numPosDims(IKObjective self) -> int

Returns the number of position dimensions constrained (0-3) 
def klampt.robotsim.IKObjective.numRotDims (   self)
numRotDims(IKObjective self) -> int

Returns the number of rotation dimensions constrained (0-3) 
def klampt.robotsim.IKObjective.saveString (   self)
saveString(IKObjective self) -> std::string

Saves the objective to a Klamp't-native formatted string. For a more
readable but verbose format, try the JSON IO routines

References klampt.robotsim._swig_property.

def klampt.robotsim.IKObjective.setAxialRotConstraint (   self,
setAxialRotConstraint(IKObjective self, double const [3] alocal, double const [3] aworld)

Manual: Sets an axial rotation constraint. 
def klampt.robotsim.IKObjective.setFixedPoint (   self,
setFixedPoint(IKObjective self, int link, double const [3] plocal, double const [3] pworld)

Sets a fixed-point constraint. 
def klampt.robotsim.IKObjective.setFixedPoints (   self,
setFixedPoints(IKObjective self, int link, PyObject * plocals, PyObject * pworlds)

Sets a multiple fixed-point constraint. 
def klampt.robotsim.IKObjective.setFixedPosConstraint (   self,
setFixedPosConstraint(IKObjective self, double const [3] tlocal, double const [3] tworld)

Manual: Sets a fixed position constraint. 
def klampt.robotsim.IKObjective.setFixedRotConstraint (   self,
setFixedRotConstraint(IKObjective self, double const [9] R)

Manual: Sets a fixed rotation constraint. 
def klampt.robotsim.IKObjective.setFixedTransform (   self,
setFixedTransform(IKObjective self, int link, double const [9] R, double const [3] t)

Sets a fixed-transform constraint (R,t) 
def klampt.robotsim.IKObjective.setFreePosition (   self)
setFreePosition(IKObjective self)

Manual: Sets a free position constraint. 
def klampt.robotsim.IKObjective.setFreeRotConstraint (   self)
setFreeRotConstraint(IKObjective self)

Manual: Sets a free rotation constraint. 
def klampt.robotsim.IKObjective.setLinearPosConstraint (   self,
setLinearPosConstraint(IKObjective self, double const [3] tlocal, double const [3] sworld, double const [3] dworld)

Manual: Sets a linear position constraint T(link)*tlocal = sworld +
u*dworld for some real value u. 
def klampt.robotsim.IKObjective.setLinks (   self,
setLinks(IKObjective self, int link, int link2=-1)
setLinks(IKObjective self, int link)

Manual construction. 
def klampt.robotsim.IKObjective.setPlanarPosConstraint (   self,
setPlanarPosConstraint(IKObjective self, double const [3] tlocal, double const [3] nworld, double oworld)

Manual: Sets a planar position constraint nworld^T T(link)*tlocal +
oworld = 0. 
def klampt.robotsim.IKObjective.setRelativePoint (   self,
setRelativePoint(IKObjective self, int link1, int link2, double const [3] p1, double const [3] p2)

Sets a fixed-point constraint relative to link2. 
def klampt.robotsim.IKObjective.setRelativePoints (   self,
setRelativePoints(IKObjective self, int link1, int link2, PyObject * p1s, PyObject * p2s)

Sets a multiple fixed-point constraint relative to link2. 
def klampt.robotsim.IKObjective.setRelativeTransform (   self,
setRelativeTransform(IKObjective self, int link, int linkTgt, double const [9] R, double const [3] t)

Sets a fixed-transform constraint (R,t) relative to linkTgt. 

Member Data Documentation


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