8 #include <kdl/chain.hpp>
9 #include <kdl/chainfksolverpos_recursive.hpp>
10 #include <kdl/frames.hpp>
11 #include <kdl/solveri.hpp>
12 #include <kdl/tree.hpp>
20 case franka::Frame::kJoint1:
return 1;
21 case franka::Frame::kJoint2:
return 2;
22 case franka::Frame::kJoint3:
return 3;
23 case franka::Frame::kJoint4:
return 4;
24 case franka::Frame::kJoint5:
return 5;
25 case franka::Frame::kJoint6:
return 6;
26 case franka::Frame::kJoint7:
return 7;
27 case franka::Frame::kFlange:
return 8;
28 case franka::Frame::kEndEffector:
return 9;
29 case franka::Frame::kStiffness:
return 10;
39 Eigen::Matrix<double, 6, 6> mat = jacobian.data * jacobian.data.transpose();
40 Eigen::JacobiSVD<Eigen::MatrixXd> svd(mat, Eigen::ComputeFullU | Eigen::ComputeFullV);
41 double critical = svd.singularValues().tail(1)(0);
50 case KDL::SolverI::E_NOERROR:
return "No error";
break;
51 case KDL::SolverI::E_NO_CONVERGE:
return "Failed to converge";
break;
52 case KDL::SolverI::E_UNDEFINED:
return "Undefined value";
break;
53 case KDL::SolverI::E_DEGRADED:
return "Converged but degraded solution";
break;
54 #if ROS_VERSION_MINIMUM(1, 15, 0)
56 case KDL::SolverI::E_NOT_UP_TO_DATE:
return "Internal data structures not up to date with Chain";
break;
57 case KDL::SolverI::E_SIZE_MISMATCH:
return "The size of the input does not match the internal state";
break;
58 case KDL::SolverI::E_MAX_ITERATIONS_EXCEEDED:
return "The maximum number of iterations is exceeded";
break;
59 case KDL::SolverI::E_OUT_OF_RANGE:
return "The requested index is out of range";
break;
60 case KDL::SolverI::E_NOT_IMPLEMENTED:
return "The requested function is not yet implemented";
break;
61 case KDL::SolverI::E_SVD_FAILED:
return "SVD failed";
break;
63 default:
return "UNKNOWN ERROR";
68 const std::string& root,
69 const std::string& tip,
70 double singularity_threshold)
71 : singularity_threshold_(singularity_threshold) {
74 throw std::invalid_argument(
"Cannot construct KDL tree from URDF");
77 if (not tree.getChain(root, tip, this->chain_)) {
78 throw std::invalid_argument(
"Cannot find chain within URDF tree from root '" + root +
79 "' to tip '" + tip +
"'. Do these links exist?");
82 ROS_INFO_STREAM(
"KDL Model initialized for chain from '" << root <<
"' -> '" << tip <<
"'");
86 const std::array<double, 16>& transform,
90 t.matrix() = Eigen::Matrix4d(transform.data());
92 chain.addSegment(KDL::Segment(
name, KDL::Joint(KDL::Joint::None),
f));
96 const std::array<double, 3>& center_of_mass,
98 const std::array<double, 9>& inertia,
101 KDL::RotationalInertia ki;
102 std::copy(center_of_mass.begin(), center_of_mass.end(), std::begin(kc.data));
103 std::copy(inertia.begin(), inertia.end(), std::begin(ki.data));
105 chain.addSegment(KDL::Segment(
name, KDL::Joint(KDL::Joint::None), KDL::Frame(KDL::Vector::Zero()),
106 KDL::RigidBodyInertia(
mass, kc, ki)));
111 const std::array<double, 7>& q,
112 const std::array<double, 16>& F_T_EE,
113 const std::array<double, 16>& EE_T_K)
119 KDL::Chain chain = this->
chain_;
123 KDL::ChainFkSolverPos_recursive solver(chain);
125 kq.data = Eigen::Matrix<double, 7, 1>(q.data());
128 if (
error != KDL::SolverI::E_NOERROR) {
129 throw std::logic_error(
"KDL forward kinematics pose calculation failed with error: " +
135 std::array<double, 16>
result;
136 Eigen::MatrixXd::Map(&
result[0], 4, 4) = p.matrix();
143 const std::array<double, 7>& q,
144 const std::array<double, 16>& F_T_EE,
145 const std::array<double, 16>& EE_T_K)
149 kq.data = Eigen::Matrix<double, 7, 1>(q.data());
152 KDL::Chain chain = this->
chain_;
156 KDL::ChainJntToJacSolver solver(chain);
159 int error = solver.JntToJac(kq, J, seg);
160 if (
error != KDL::SolverI::E_NOERROR) {
161 throw std::logic_error(
"KDL zero jacobian calculation failed with error: " +
strError(
error));
165 KDL::Frame
f = KDL::Frame::Identity();
166 auto transform =
pose(frame, q, F_T_EE, EE_T_K);
168 t.matrix() = Eigen::Matrix4d(transform.data());
171 J.changeBase(
f.M.Inverse());
178 std::array<double, 42>
result;
179 Eigen::MatrixXd::Map(&
result[0], 6, 7) = J.data;
186 const std::array<double, 7>& q,
187 const std::array<double, 16>& F_T_EE,
188 const std::array<double, 16>& EE_T_K)
192 kq.data = Eigen::Matrix<double, 7, 1>(q.data());
195 KDL::Chain chain = this->
chain_;
199 KDL::ChainJntToJacSolver solver(chain);
202 if (
error != KDL::SolverI::E_NOERROR) {
203 throw std::logic_error(
"KDL zero jacobian calculation failed with error: " +
strError(
error));
211 std::array<double, 42>
result;
212 Eigen::MatrixXd::Map(&
result[0], 6, 7) = J.data;
218 const std::array<double, 7>& q,
219 const std::array<double, 9>& I_total,
221 const std::array<double, 3>& F_x_Ctotal)
224 KDL::JntSpaceInertiaMatrix M(7);
225 kq.data = Eigen::Matrix<double, 7, 1>(q.data());
227 KDL::Chain chain = this->
chain_;
228 augmentFrame(
"load", F_x_Ctotal, m_total, I_total, chain);
229 KDL::ChainDynParam solver(chain, KDL::Vector(0, 0, -9.81));
231 int error = solver.JntToMass(kq, M);
232 if (
error != KDL::SolverI::E_NOERROR) {
233 throw std::logic_error(
"KDL mass calculation failed with error: " +
strError(
error));
236 std::array<double, 49>
result;
237 Eigen::MatrixXd::Map(&
result[0], 7, 7) = M.data;
243 const std::array<double, 7>& q,
244 const std::array<double, 7>& dq,
245 const std::array<double, 9>& I_total,
247 const std::array<double, 3>& F_x_Ctotal)
249 KDL::JntArray kq, kdq, kc(7);
250 kq.data = Eigen::Matrix<double, 7, 1>(q.data());
251 kdq.data = Eigen::Matrix<double, 7, 1>(dq.data());
253 KDL::Chain chain = this->
chain_;
254 augmentFrame(
"load", F_x_Ctotal, m_total, I_total, chain);
255 KDL::ChainDynParam solver(chain, KDL::Vector(0, 0, -9.81));
257 int error = solver.JntToCoriolis(kq, kdq, kc);
258 if (
error != KDL::SolverI::E_NOERROR) {
259 throw std::logic_error(
"KDL coriolis calculation failed with error: " +
strError(
error));
262 std::array<double, 7>
result;
263 Eigen::VectorXd::Map(&
result[0], kc.data.size()) = kc.data;
269 const std::array<double, 7>& q,
271 const std::array<double, 3>& F_x_Ctotal,
272 const std::array<double, 3>& gravity_earth)
const {
273 KDL::JntArray kq, kg(7);
274 KDL::Vector grav(gravity_earth[0], gravity_earth[1], gravity_earth[2]);
275 kq.data = Eigen::Matrix<double, 7, 1>(q.data());
277 KDL::Chain chain = this->
chain_;
278 augmentFrame(
"load", F_x_Ctotal, m_total, {1, 0, 0, 0, 1, 0, 0, 0, 1}, chain);
279 KDL::ChainDynParam solver(chain, grav);
281 int error = solver.JntToGravity(kq, kg);
282 if (
error != KDL::SolverI::E_NOERROR) {
283 throw std::logic_error(
"KDL gravity calculation failed with error: " +
strError(
error));
286 std::array<double, 7>
result;
287 Eigen::VectorXd::Map(&
result[0], kg.data.size()) = kg.data;