File size: 5,149 Bytes
985c397 | 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 | // SPDX-License-Identifier: LGPL-2.1-or-later
/***************************************************************************
* Copyright (c) 2002 Jürgen Riegel <juergen.riegel@web.de> *
* *
* This file is part of the FreeCAD CAx development system. *
* *
* This library is free software; you can redistribute it and/or *
* modify it under the terms of the GNU Library General Public *
* License as published by the Free Software Foundation; either *
* version 2 of the License, or (at your option) any later version. *
* *
* This library is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU Library General Public License for more details. *
* *
* You should have received a copy of the GNU Library General Public *
* License along with this library; see the file COPYING.LIB. If not, *
* write to the Free Software Foundation, Inc., 59 Temple Place, *
* Suite 330, Boston, MA 02111-1307, USA *
* *
***************************************************************************/
#include "kdl_cp/chainfksolverpos_recursive.hpp"
#include "kdl_cp/chainiksolverpos_nr.hpp"
#include "kdl_cp/chainiksolvervel_pinv.hpp"
#include "kdl_cp/frames_io.hpp"
#include "RobotAlgos.h"
using namespace Robot;
using namespace std;
using namespace KDL;
//===========================================================================
// FeatureView
//===========================================================================
RobotAlgos::RobotAlgos() = default;
RobotAlgos::~RobotAlgos() = default;
void RobotAlgos::Test()
{
// Definition of a kinematic chain & add segments to the chain
KDL::Chain chain;
chain.addSegment(Segment(Joint(Joint::RotZ), Frame(Vector(0.0, 0.0, 1.020))));
chain.addSegment(Segment(Joint(Joint::RotX), Frame(Vector(0.0, 0.0, 0.480))));
chain.addSegment(Segment(Joint(Joint::RotX), Frame(Vector(0.0, 0.0, 0.645))));
chain.addSegment(Segment(Joint(Joint::RotZ)));
chain.addSegment(Segment(Joint(Joint::RotX), Frame(Vector(0.0, 0.0, 0.120))));
chain.addSegment(Segment(Joint(Joint::RotZ)));
// Create solver based on kinematic chain
ChainFkSolverPos_recursive fksolver = ChainFkSolverPos_recursive(chain);
// Create joint array
unsigned int nj = chain.getNrOfJoints();
KDL::JntArray jointpositions = JntArray(nj);
// Assign some values to the joint positions
for (unsigned int i = 0; i < nj; i++) {
float myinput;
printf("Enter the position of joint %i: ", i);
int result = scanf("%e", &myinput);
(void)result;
jointpositions(i) = (double)myinput;
}
// Create the frame that will contain the results
KDL::Frame cartpos;
// Calculate forward position kinematics
int kinematics_status;
kinematics_status = fksolver.JntToCart(jointpositions, cartpos);
if (kinematics_status >= 0) {
std::cout << cartpos << std::endl;
printf("%s \n", "Success, thanks KDL!");
}
else {
printf("%s \n", "Error: could not calculate forward kinematics :(");
}
// Creation of the solvers:
ChainFkSolverPos_recursive fksolver1(chain); // Forward position solver
ChainIkSolverVel_pinv iksolver1v(chain); // Inverse velocity solver
ChainIkSolverPos_NR iksolver1(
chain,
fksolver1,
iksolver1v,
100,
1e-6
); // Maximum 100 iterations, stop at accuracy 1e-6
// Creation of jntarrays:
JntArray result(chain.getNrOfJoints());
JntArray q_init(chain.getNrOfJoints());
// Set destination frame
Frame F_dest = cartpos;
iksolver1.CartToJnt(q_init, F_dest, result);
for (unsigned int i = 0; i < nj; i++) {
printf("Axle %i: %f \n", i, result(i));
}
}
namespace Robot
{
KDL::Frame toFrame(const Base::Placement& To)
{
return {
KDL::Rotation::Quaternion(
To.getRotation()[0],
To.getRotation()[1],
To.getRotation()[2],
To.getRotation()[3]
),
KDL::Vector(To.getPosition()[0], To.getPosition()[1], To.getPosition()[2])
};
}
Base::Placement toPlacement(const KDL::Frame& frame)
{
double x;
double y;
double z;
double w;
frame.M.GetQuaternion(x, y, z, w);
return {Base::Vector3d(frame.p[0], frame.p[1], frame.p[2]), Base::Rotation(x, y, z, w)};
}
} // namespace Robot
|