23 #include "libKinematics.h" 75 parameters.push_back(joint);
114 for (
int i = 0; i < dom; ++i) {
121 for (
int i = 0; i < dom; ++i) {
128 for (
int i = 0; i < dom; ++i) {
140 for (
int i = 0; i < dom; ++i) {
149 for (
int i = 0; i < dom; ++i) {
165 version.push_back(0);
166 version.push_back(1);
167 version.push_back(0);
174 for (
int i = 0; i < v.
length; ++i) {
175 version.push_back(v.
data[i]);
186 tcpOff.
data[0] = (float) xoff;
187 tcpOff.
data[1] = (float) yoff;
188 tcpOff.
data[2] = (float) zoff;
189 tcpOff.
data[3] = (float) psioff;
197 getCoordinates(position[0], position[1], position[2], position[3], position[4], position[5]);
200 void CikBase::IKCalculate(
double X,
double Y,
double Z,
double phi,
double theta,
double psi, std::vector<int>::iterator solution_iter) {
207 std::vector<double>
pose(6);
215 std::vector<int> actualPosition;
229 pose.
data[0] = (float) (X / 1000);
230 pose.
data[1] = (float) (Y / 1000);
231 pose.
data[2] = (float) (Z / 1000);
232 pose.
data[3] = (float) phi;
233 pose.
data[4] = (float) theta;
234 pose.
data[5] = (float) psi;
239 for(
int i = 0; i < nOfMot; ++i) {
242 actualPosition.
length = nOfMot;
247 kin_IK(&pose, &prev, &ikangle, maxBisection);
258 for(
int i = 0; i < nOfMot; ++i) {
259 *solution_iter = ikenc.
data[i];
266 void CikBase::IKCalculate(
double X,
double Y,
double Z,
double phi,
double theta,
double psi, std::vector<int>::iterator solution_iter,
const std::vector<int>& actualPosition) {
273 std::vector<double>
pose(6);
289 pose.
data[0] = (float) (X / 1000);
290 pose.
data[1] = (float) (Y / 1000);
291 pose.
data[2] = (float) (Z / 1000);
292 pose.
data[3] = (float) phi;
293 pose.
data[4] = (float) theta;
294 pose.
data[5] = (float) psi;
298 for(
int i = 0; i < nOfMot; ++i) {
299 actPos.
data[i] = actualPosition.at(i);
306 int error =
kin_IK(&pose, &prev, &ikangle, maxBisection);
319 for(
int i = 0; i < nOfMot; ++i) {
320 *solution_iter = ikenc.
data[i];
327 void CikBase::IKGoto(
double X,
double Y,
double Z,
double Al,
double Be,
double Ga,
bool wait,
int tolerance,
long timeout) {
344 IKCalculate( X, Y, Z, Al, Be, Ga, solution.begin(), act_pos );
345 moveRobotToEnc( solution.begin(), solution.end(), wait, tolerance, timeout);
349 void CikBase::getCoordinates(
double& x,
double& y,
double& z,
double& phi,
double& theta,
double& psi,
bool refreshEncoders) {
364 std::vector<double>
pose(6);
380 for(
int i = 0; i < nOfMot; ++i) {
390 x = pose.
data[0] * 1000;
391 y = pose.
data[1] * 1000;
392 z = pose.
data[2] * 1000;
394 theta = pose.
data[4];
411 for(
int i = 0; i < nOfMot; ++i) {
412 actPos.
data[i] = encs.at(i);
420 pos.push_back(pose.
data[0] * 1000);
421 pos.push_back(pose.
data[1] * 1000);
422 pos.push_back(pose.
data[2] * 1000);
423 pos.push_back(pose.
data[3]);
424 pos.push_back(pose.
data[4]);
425 pos.push_back(pose.
data[5]);
429 void CikBase::moveRobotTo(
double x,
double y,
double z,
double phi,
double theta,
double psi,
const bool waitUntilReached,
const int waitTimeout) {
430 IKGoto(x, y, z, phi, theta, psi, waitUntilReached, 100, waitTimeout);
433 void CikBase::moveRobotTo(std::vector<double> coordinates,
const bool waitUntilReached,
const int waitTimeout) {
434 IKGoto(coordinates.at(0), coordinates.at(1), coordinates.at(2), coordinates.at(3), coordinates.at(4), coordinates.at(5), waitUntilReached, 100, waitTimeout);
void setTcpOffset(double xoff, double yoff, double zoff, double psioff)
char modelName[255]
model name
std::unique_ptr< KNI::KatanaKinematics > _kinematicsImpl
CKatBase * base
base katana
int kin_K4D2mDHAng(FloatVector *angleK4D, FloatVector *angleMDH)
int kin_IK(FloatVector *pose, FloatVector *prev, FloatVector *angle, int maxBisection)
int kin_setAngRan(FloatVector *angleRange)
double arr_segment[4]
length of the Katana segments
bool _kinematicsIsInitialized
int kin_setEncOff(IntVector *encOffset)
int kin_getVersion(IntVector *version)
int kin_setType(int type)
CMotBase * arr
array of motors
int kin_setLinkLen(FloatVector *links)
TKatEFF * GetEFF()
Get a pointer to the desired structure.
std::vector< KinematicParameters > parameter_container
void getCoordinates(double &x, double &y, double &z, double &phi, double &theta, double &psi, bool refreshEncoders=true)
int kin_DK(FloatVector *angle, FloatVector *pose)
int getMotorEncoders(short number, bool refreshEncoders=true) const
const TKatMOT * GetMOT()
Get a pointer to the desired structure.
void recvMPS()
read all motor positions simultaneously
Inverse Kinematics structure of the endeffektor.
[MOT] every motor's attributes
int mKinematics
The kinematics implementation: 0 for Analytical, 1 for RobAnaGuess.
void getKinematicsVersion(std::vector< int > &version)
FloatVector FloatVector int maxBisection
int kin_setEPC(IntVector *epc)
int kin_setRotDir(IntVector *rotDir)
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...
int kin_setTcpOff(FloatVector *tcpOffset)
void moveRobotTo(double x, double y, double z, double phi, double theta, double psi, bool waitUntilReached=false, int waitTimeout=TM_ENDLESS)
const TMotInit * GetInitialParameters()
int kin_enc2rad(IntVector *enc, FloatVector *angle)
int kin_rad2enc(FloatVector *angle, IntVector *enc)
int kin_setAngOff(FloatVector *angleOffset)
short getNumberOfMotors() const
void IKCalculate(double X, double Y, double Z, double Al, double Be, double Ga, std::vector< int >::iterator solution_iter)
void DKApos(double *position)
void moveRobotToEnc(std::vector< int >::const_iterator start, std::vector< int >::const_iterator end, bool waitUntilReached=false, int encTolerance=100, int waitTimeout=0)
std::vector< double > metrics
To store metrics, 'aka' the length's of the different segments of the robot.
const TKatGNL * GetGNL()
Get a pointer to the desired structure.
void IKGoto(double X, double Y, double Z, double Al, double Be, double Ga, bool wait=false, int tolerance=100, long timeout=TM_ENDLESS)