6 #include <dynamic-graph/factory.h>
8 #include <sot/core/debug.hh>
13 namespace torque_control {
14 namespace dg = ::dynamicgraph;
16 using namespace dg::command;
19 dg::sot::RefVector q_sot) {
20 assert(q_sot.size() == 6);
21 assert(pos.size() == 3);
22 assert(R.rows() == 3);
23 assert(R.cols() == 3);
26 m = sqrt(R(2, 1) * R(2, 1) + R(2, 2) * R(2, 2));
27 p = atan2(-R(2, 0), m);
28 if (abs(abs(p) - M_PI / 2) < 0.001) {
30 y = -atan2(R(0, 1), R(1, 1));
32 y = atan2(R(1, 0), R(0, 0));
33 r = atan2(R(2, 1), R(2, 2));
46 dg::sot::RefVector q_sot) {
47 assert(q_urdf.size() == 7);
48 assert(q_sot.size() == 6);
50 const double W = q_urdf[6];
51 const double X = q_urdf[3];
52 const double Y = q_urdf[4];
53 const double Z = q_urdf[5];
54 const Eigen::Matrix3d R = Eigen::Quaterniond(W, X, Y, Z).toRotationMatrix();
59 dg::sot::RefVector q_urdf) {
60 assert(q_urdf.size() == 7);
61 assert(q_sot.size() == 6);
63 const double r = q_sot[3];
64 const double p = q_sot[4];
65 const double y = q_sot[5];
66 const Eigen::AngleAxisd rollAngle(r, Eigen::Vector3d::UnitX());
67 const Eigen::AngleAxisd pitchAngle(p, Eigen::Vector3d::UnitY());
68 const Eigen::AngleAxisd yawAngle(y, Eigen::Vector3d::UnitZ());
69 const Eigen::Quaternion<double> quat = yawAngle * pitchAngle * rollAngle;
83 dg::sot::RefVector q_sot) {
84 assert(q_urdf.size() ==
N_JOINTS + 7);
85 assert(q_sot.size() ==
N_JOINTS + 6);
152 dg::sot::RefVector q_urdf) {
153 assert(q_urdf.size() ==
N_JOINTS + 7);
154 assert(q_sot.size() ==
N_JOINTS + 6);
215 dg::sot::RefVector v_sot) {
216 assert(v_urdf.size() ==
N_JOINTS + 6);
217 assert(v_sot.size() ==
N_JOINTS + 6);
218 v_sot.head<6>() = v_urdf.head<6>();
267 dg::sot::RefVector v_urdf) {
268 assert(v_urdf.size() ==
N_JOINTS + 6);
269 assert(v_sot.size() ==
N_JOINTS + 6);
270 v_urdf.head<6>() = v_sot.head<6>();
319 dg::sot::RefVector q_sot) {
323 q_sot[12] = q_urdf[0];
324 q_sot[13] = q_urdf[1];
326 q_sot[14] = q_urdf[2];
327 q_sot[15] = q_urdf[3];
329 q_sot[23] = q_urdf[4];
330 q_sot[24] = q_urdf[5];
331 q_sot[25] = q_urdf[6];
332 q_sot[26] = q_urdf[7];
333 q_sot[27] = q_urdf[8];
334 q_sot[28] = q_urdf[9];
335 q_sot[29] = q_urdf[10];
337 q_sot[16] = q_urdf[11];
338 q_sot[17] = q_urdf[12];
339 q_sot[18] = q_urdf[13];
340 q_sot[19] = q_urdf[14];
341 q_sot[20] = q_urdf[15];
342 q_sot[21] = q_urdf[16];
343 q_sot[22] = q_urdf[17];
345 q_sot[6] = q_urdf[18];
346 q_sot[7] = q_urdf[19];
347 q_sot[8] = q_urdf[20];
348 q_sot[9] = q_urdf[21];
349 q_sot[10] = q_urdf[22];
350 q_sot[11] = q_urdf[23];
352 q_sot[0] = q_urdf[24];
353 q_sot[1] = q_urdf[25];
354 q_sot[2] = q_urdf[26];
355 q_sot[3] = q_urdf[27];
356 q_sot[4] = q_urdf[28];
357 q_sot[5] = q_urdf[29];
362 dg::sot::RefVector q_urdf) {
366 q_urdf[0] = q_sot[12];
367 q_urdf[1] = q_sot[13];
369 q_urdf[2] = q_sot[24];
370 q_urdf[3] = q_sot[25];
372 q_urdf[4] = q_sot[23];
373 q_urdf[5] = q_sot[24];
374 q_urdf[6] = q_sot[25];
375 q_urdf[7] = q_sot[26];
376 q_urdf[8] = q_sot[27];
377 q_urdf[9] = q_sot[28];
378 q_urdf[10] = q_sot[29];
380 q_urdf[11] = q_sot[16];
381 q_urdf[12] = q_sot[17];
382 q_urdf[13] = q_sot[18];
383 q_urdf[14] = q_sot[19];
384 q_urdf[15] = q_sot[20];
385 q_urdf[16] = q_sot[21];
386 q_urdf[17] = q_sot[22];
388 q_urdf[18] = q_sot[6];
389 q_urdf[19] = q_sot[7];
390 q_urdf[20] = q_sot[8];
391 q_urdf[21] = q_sot[9];
392 q_urdf[22] = q_sot[10];
393 q_urdf[23] = q_sot[11];
395 q_urdf[24] = q_sot[0];
396 q_urdf[25] = q_sot[1];
397 q_urdf[26] = q_sot[2];
398 q_urdf[27] = q_sot[3];
399 q_urdf[28] = q_sot[4];
400 q_urdf[29] = q_sot[5];
bool base_sot_to_urdf(dynamicgraph::sot::ConstRefVector q_sot, dynamicgraph::sot::RefVector q_urdf)
bool base_urdf_to_sot(dynamicgraph::sot::ConstRefVector q_urdf, dynamicgraph::sot::RefVector q_sot)
bool velocity_sot_to_urdf(dynamicgraph::sot::ConstRefVector v_sot, dynamicgraph::sot::RefVector v_urdf)
bool joints_urdf_to_sot(dynamicgraph::sot::ConstRefVector q_urdf, dynamicgraph::sot::RefVector q_sot)
bool config_sot_to_urdf(dynamicgraph::sot::ConstRefVector q_sot, dynamicgraph::sot::RefVector q_urdf)
bool velocity_urdf_to_sot(dynamicgraph::sot::ConstRefVector v_urdf, dynamicgraph::sot::RefVector v_sot)
bool base_se3_to_sot(dynamicgraph::sot::ConstRefVector pos, dynamicgraph::sot::ConstRefMatrix R, dynamicgraph::sot::RefVector q_sot)
bool joints_sot_to_urdf(dynamicgraph::sot::ConstRefVector q_sot, dynamicgraph::sot::RefVector q_urdf)
bool config_urdf_to_sot(dynamicgraph::sot::ConstRefVector q_urdf, dynamicgraph::sot::RefVector q_sot)