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_QUATTOEULER_COMPUTATION \
35 "QuatToEuler computation "
37 #define INPUT_SIGNALS m_quaternionSIN
39 #define OUTPUT_SIGNALS m_eulerSOUT
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::Map<const Eigen::Quaterniond> quat(
input.segment<4>(3).data());
76 s.head<3>() =
input.head<3>();
78 Eigen::Vector3d euler = quat.toRotationMatrix().eulerAngles(2, 1, 0);
83 if (sz > 7) s.tail(sz - 7) =
input.tail(sz - 7);
97 os <<
"QuatToEuler " << getName();
99 getProfiler().report_all(3, os);
100 }
catch (ExceptionSignal e) {