#include <ikBase.h>
Public Member Functions | |
CikBase () | |
void | DKApos (double *position) |
void | getCoordinates (double &x, double &y, double &z, double &phi, double &theta, double &psi, bool refreshEncoders=true) |
void | getCoordinatesFromEncoders (std::vector< double > &pose, const std::vector< int > &encs) |
Returns the position of the robot corresponting to the given encoders in cartesian coordinates. | |
void | getKinematicsVersion (std::vector< int > &version) |
void | IKCalculate (double X, double Y, double Z, double Al, double Be, double Ga, std::vector< int >::iterator solution_iter) |
void | IKCalculate (double X, double Y, double Z, double Al, double Be, double Ga, std::vector< int >::iterator solution_iter, const std::vector< int > &actualPosition) |
void | IKGoto (double X, double Y, double Z, double Al, double Be, double Ga, bool wait=false, int tolerance=100, long timeout=TM_ENDLESS) |
void | moveRobotTo (double x, double y, double z, double phi, double theta, double psi, bool waitUntilReached=false, int waitTimeout=TM_ENDLESS) |
void | moveRobotTo (std::vector< double > coordinates, bool waitUntilReached=false, int waitTimeout=TM_ENDLESS) |
void | setTcpOffset (double xoff, double yoff, double zoff, double psioff) |
~CikBase () | |
Private Member Functions | |
void | _initKinematics () |
Private Attributes | |
std::unique_ptr < KNI::KatanaKinematics > | _kinematicsImpl |
bool | _kinematicsIsInitialized |
CikBase::CikBase | ( | ) | [inline] |
Definition at line 25 of file ikBase.cpp.
void CikBase::_initKinematics | ( | ) | [private] |
Definition at line 35 of file ikBase.cpp.
void CikBase::DKApos | ( | double * | position | ) |
Returns the current position of the robot in cartesian coordinates.
Definition at line 196 of file ikBase.cpp.
void CikBase::getCoordinates | ( | double & | x, |
double & | y, | ||
double & | z, | ||
double & | phi, | ||
double & | theta, | ||
double & | psi, | ||
bool | refreshEncoders = true |
||
) |
Returns the current position of the robot in cartesian coordinates.
refreshEncoders | With this parameter you can determine if the method reads the actual encoders from the robot or if it will use the cached ones |
Definition at line 349 of file ikBase.cpp.
void CikBase::getCoordinatesFromEncoders | ( | std::vector< double > & | pose, |
const std::vector< int > & | encs | ||
) |
Returns the position of the robot corresponting to the given encoders in cartesian coordinates.
Definition at line 399 of file ikBase.cpp.
void CikBase::getKinematicsVersion | ( | std::vector< int > & | version | ) |
Returns the version number of the kinematics used.
version | vector to write in version (major, minor, revision) |
Definition at line 161 of file ikBase.cpp.
void CikBase::IKCalculate | ( | double | X, |
double | Y, | ||
double | Z, | ||
double | Al, | ||
double | Be, | ||
double | Ga, | ||
std::vector< int >::iterator | solution_iter | ||
) |
Calculates a set of encoders for the given coordinates. This method reads the current encoders from the robot and involves therefore also communication to the robot
Definition at line 200 of file ikBase.cpp.
void CikBase::IKCalculate | ( | double | X, |
double | Y, | ||
double | Z, | ||
double | Al, | ||
double | Be, | ||
double | Ga, | ||
std::vector< int >::iterator | solution_iter, | ||
const std::vector< int > & | actualPosition | ||
) |
Calculates a set of encoders for the given coordinates. For this method you have to pass an actualPosition too. No communication with the robot will be done here.
Definition at line 266 of file ikBase.cpp.
void CikBase::IKGoto | ( | double | X, |
double | Y, | ||
double | Z, | ||
double | Al, | ||
double | Be, | ||
double | Ga, | ||
bool | wait = false , |
||
int | tolerance = 100 , |
||
long | timeout = TM_ENDLESS |
||
) |
Moves to robot to given cartesian coordinates and euler-angles.
Definition at line 327 of file ikBase.cpp.
void CikBase::moveRobotTo | ( | double | x, |
double | y, | ||
double | z, | ||
double | phi, | ||
double | theta, | ||
double | psi, | ||
bool | waitUntilReached = false , |
||
int | waitTimeout = TM_ENDLESS |
||
) |
Moves to robot to given cartesian coordinates and euler-angles.
Reimplemented in CLMBase.
Definition at line 429 of file ikBase.cpp.
void CikBase::moveRobotTo | ( | std::vector< double > | coordinates, |
bool | waitUntilReached = false , |
||
int | waitTimeout = TM_ENDLESS |
||
) |
This method does the same as the one above and is mainly provided for convenience
Reimplemented in CLMBase.
Definition at line 433 of file ikBase.cpp.
void CikBase::setTcpOffset | ( | double | xoff, |
double | yoff, | ||
double | zoff, | ||
double | psioff | ||
) |
Set the offset from the flange to the desired tcp
xoff | offset in x direction of flange coordinate system in m |
yoff | offset in y direction of flange coordinate system in m |
zoff | offset in z direction of flange coordinate system in m |
psioff | angle offset around x-axis of flange coordinate system in rad |
Definition at line 180 of file ikBase.cpp.
std::unique_ptr<KNI::KatanaKinematics> CikBase::_kinematicsImpl [private] |
bool CikBase::_kinematicsIsInitialized [private] |