19 #include <dynamic-graph/all-commands.h>
20 #include <dynamic-graph/factory.h>
23 #include <sot/core/debug.hh>
24 #include <sot/core/stop-watch.hh>
28 namespace talos_balance {
29 namespace dg = ::dynamicgraph;
31 using namespace dg::command;
34 #define PROFILE_EULERTOQUAT_COMPUTATION \
35 "EulerToQuat computation "
37 #define INPUT_SIGNALS m_eulerSIN
39 #define OUTPUT_SIGNALS m_quaternionSOUT
60 docCommandVoid0(
"Initialize the entity.")));
69 const size_t sz =
input.size();
70 if ((
size_t)(s.size()) != (sz + 1)) s.resize(sz + 1);
74 const Eigen::Vector3d& euler =
input.segment<3>(3);
76 const double roll = euler[0];
77 const double pitch = euler[1];
78 const double yaw = euler[2];
80 Eigen::Quaterniond quat;
81 quat = Eigen::AngleAxisd(yaw, Eigen::Vector3d::UnitZ()) *
82 Eigen::AngleAxisd(pitch, Eigen::Vector3d::UnitY()) *
83 Eigen::AngleAxisd(roll, Eigen::Vector3d::UnitX());
85 s.head<3>() =
input.head<3>();
87 s.segment<4>(3) = quat.coeffs();
89 if (sz > 6) s.tail(sz - 6) =
input.tail(sz - 6);
103 os <<
"EulerToQuat " << getName();
105 getProfiler().report_all(3, os);
106 }
catch (ExceptionSignal e) {