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_POSEQUATERNIONTOMATRIXHOMO_COMPUTATION \
35 "PoseQuaternionToMatrixHomo computation "
37 #define INPUT_SIGNALS m_sinSIN
39 #define OUTPUT_SIGNALS m_soutSOUT
47 "PoseQuaternionToMatrixHomo");
55 CONSTRUCT_SIGNAL_OUT(sout, MatrixHomogeneous,
INPUT_SIGNALS) {
61 docCommandVoid0(
"Initialize the entity.")));
73 const Eigen::Map<const Eigen::Quaterniond>
q(vect.segment<4>(3).data());
75 s.translation() = vect.head<3>();
76 s.linear() =
q.toRotationMatrix();
90 os <<
"PoseQuaternionToMatrixHomo " << getName();
92 getProfiler().report_all(3, os);
93 }
catch (ExceptionSignal e) {
EIGEN_MAKE_ALIGNED_OPERATOR_NEW PoseQuaternionToMatrixHomo(const std::string &name)
virtual void display(std::ostream &os) const
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
AdmittanceControllerEndEffector EntityClassName
DEFINE_SIGNAL_OUT_FUNCTION(dq, dynamicgraph::Vector)
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(AdmittanceControllerEndEffector, "AdmittanceControllerEndEffector")
#define PROFILE_POSEQUATERNIONTOMATRIXHOMO_COMPUTATION