54 void _initKinematics();
58 CikBase() : _kinematicsIsInitialized(false) { };
65 void getKinematicsVersion(std::vector<int>& version);
72 void setTcpOffset(
double xoff,
double yoff,
double zoff,
double psioff);
76 void DKApos(
double* position);
82 void getCoordinates(
double& x,
double& y,
double& z,
double& phi,
double& theta,
double& psi,
bool refreshEncoders =
true);
85 void getCoordinatesFromEncoders(std::vector<double>&
pose,
const std::vector<int>& encs);
90 void IKCalculate(
double X,
96 std::vector<int>::iterator solution_iter);
101 void IKCalculate(
double X,
107 std::vector<int>::iterator solution_iter,
108 const std::vector<int>& actualPosition );
112 void IKGoto(
double X,
124 void moveRobotTo(
double x,
130 bool waitUntilReached =
false,
int waitTimeout =
TM_ENDLESS);
136 void moveRobotTo( std::vector<double> coordinates,
bool waitUntilReached =
false,
int waitTimeout =
TM_ENDLESS);
std::unique_ptr< KNI::KatanaKinematics > _kinematicsImpl
bool _kinematicsIsInitialized
Extended Katana class with additional functions.
#define TM_ENDLESS
timeout symbol for 'endless' waiting