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

Public Member Functions

def __init__ (self)
 
def link (self)
 
def destLink (self)
 
def numPosDims (self)
 
def numRotDims (self)
 
def setFixedPoint (self, link, plocal, pworld)
 
def setFixedPoints (self, link, plocals, pworlds)
 
def setFixedTransform (self, link, R, t)
 
def setRelativePoint (self, link1, link2, p1, p2)
 
def setRelativePoints (self, link1, link2, p1s, p2s)
 
def setRelativeTransform (self, link, linkTgt, R, t)
 
def setLinks (self, link, link2=-1)
 
def setFreePosition (self)
 
def setFixedPosConstraint (self, tlocal, tworld)
 
def setPlanarPosConstraint (self, tlocal, nworld, oworld)
 
def setLinearPosConstraint (self, tlocal, sworld, dworld)
 
def setFreeRotConstraint (self)
 
def setFixedRotConstraint (self, R)
 
def setAxialRotConstraint (self, alocal, aworld)
 
def getPosition (self)
 
def getPositionDirection (self)
 
def getRotation (self)
 
def getRotationAxis (self)
 
def getTransform (self)
 
def loadString (self, str)
 
def saveString (self)
 

Public Attributes

 this
 

Static Public Attributes

tuple goal = _swig_property(_robotsim.IKObjective_goal_get, _robotsim.IKObjective_goal_set)
 

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

IKObjective::IKObjective() 

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

Member Function Documentation

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

int
IKObjective::destLink() const

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

void
IKObjective::getPosition(double out[3], double out2[3]) const

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

void
IKObjective::getPositionDirection(double out[3]) const

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

void
IKObjective::getRotation(double out[9]) const

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

void
IKObjective::getRotationAxis(double out[3], double out2[3]) const

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

void
IKObjective::getTransform(double out[9], double out2[3]) const

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

int IKObjective::link()
const

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

bool
IKObjective::loadString(const char *str)

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

int
IKObjective::numPosDims() const

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

int
IKObjective::numRotDims() const

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

std::string
IKObjective::saveString() const

Saves the objective to a Klamp't-native formatted string. For a more
readable but verbose format, try the JSON IO routines
loader.toJson/fromJson() 
def klampt.robotsim.IKObjective.setAxialRotConstraint (   self,
  alocal,
  aworld 
)
setAxialRotConstraint(IKObjective self, double const [3] alocal, double const [3] aworld)

void
IKObjective::setAxialRotConstraint(const double alocal[3], const
double aworld[3])

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

void
IKObjective::setFixedPoint(int link, const double plocal[3], const
double pworld[3])

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

void
IKObjective::setFixedPoints(int link, PyObject *plocals, PyObject
*pworlds)

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

void
IKObjective::setFixedPosConstraint(const double tlocal[3], const
double tworld[3])

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

void
IKObjective::setFixedRotConstraint(const double R[9])

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

void
IKObjective::setFixedTransform(int link, const double R[9], const
double t[3])

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

void
IKObjective::setFreePosition()

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

void
IKObjective::setFreeRotConstraint()

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

void
IKObjective::setLinearPosConstraint(const double tlocal[3], const
double sworld[3], const double dworld[3])

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

void
IKObjective::setLinks(int link, int link2=-1)

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

void
IKObjective::setPlanarPosConstraint(const double tlocal[3], const
double nworld[3], double oworld)

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

void
IKObjective::setRelativePoint(int link1, int link2, const double
p1[3], const double p2[3])

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

void
IKObjective::setRelativePoints(int link1, int link2, PyObject *p1s,
PyObject *p2s)

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

void
IKObjective::setRelativeTransform(int link, int linkTgt, const double
R[9], const double t[3])

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

Member Data Documentation

tuple klampt.robotsim.IKObjective.goal = _swig_property(_robotsim.IKObjective_goal_get, _robotsim.IKObjective_goal_set)
static
klampt.robotsim.IKObjective.this

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