19 #include <dynamic-graph/all-commands.h>
20 #include <dynamic-graph/command-bind.h>
21 #include <dynamic-graph/factory.h>
23 #include <sot/core/debug.hh>
25 #include "sot/core/stop-watch.hh"
29 namespace talos_balance {
30 namespace dg = ::dynamicgraph;
32 using namespace dg::command;
35 #define PROFILE_SIMPLE_CONTROLLER_6D_DX_REF_COMPUTATION \
36 "SimpleController6d: v_ref computation "
38 #define INPUT_SIGNALS m_KpSIN << m_xSIN << m_x_desSIN << m_v_desSIN
40 #define OUTPUT_SIGNALS m_v_refSOUT
59 m_initSucceeded(false) {
65 docCommandVoid0(
"Initialize the entity.")));
70 template <
typename Derived>
73 M << 0, -v[2], v[1], v[2], 0, -v[0], -v[1], v[0], 0;
82 if (!m_initSucceeded) {
83 SEND_WARNING_STREAM_MSG(
84 "Cannot compute signal v_ref before initialization!");
87 if (s.size() != 6) s.resize(6);
93 const MatrixHomogeneous&
x = m_xSIN(iter);
94 const MatrixHomogeneous& x_des = m_x_desSIN(iter);
98 const Eigen::Vector3d e_O =
99 0.5 * (
x.linear().col(0).cross(x_des.linear().col(0)) +
100 x.linear().col(1).cross(x_des.linear().col(1)) +
101 x.linear().col(2).cross(x_des.linear().col(2)));
103 const Eigen::Matrix3d L =
104 -0.5 * (skew(x_des.linear().col(0)) * skew(
x.linear().col(0)) +
105 skew(x_des.linear().col(1)) * skew(
x.linear().col(1)) +
106 skew(x_des.linear().col(2)) * skew(
x.linear().col(2)));
108 Eigen::Matrix<double, 6, 1> dv_ref;
112 x.linear().transpose() *
113 Kp.head<3>().cwiseProduct(x_des.translation() -
x.translation());
116 x.linear().transpose() * L.inverse() *
Kp.tail<3>().cwiseProduct(e_O);
118 if (m_v_desSIN.isPlugged()) {
137 os <<
"SimpleController6d " << getName();
139 getProfiler().report_all(3, os);
140 }
catch (ExceptionSignal e) {