sot-talos-balance  1.5.0
quat-to-euler.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2018, Gepetto team, LAAS-CNRS
3  *
4  * This file is part of sot-talos-balance.
5  * sot-talos-balance is free software: you can redistribute it and/or
6  * modify it under the terms of the GNU Lesser General Public License
7  * as published by the Free Software Foundation, either version 3 of
8  * the License, or (at your option) any later version.
9  * sot-talos-balance is distributed in the hope that it will be
10  * useful, but WITHOUT ANY WARRANTY; without even the implied warranty
11  * of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  * GNU Lesser General Public License for more details. You should
13  * have received a copy of the GNU Lesser General Public License along
14  * with sot-talos-balance. If not, see <http://www.gnu.org/licenses/>.
15  */
16 
18 
19 #include <sot/core/debug.hh>
20 #include <dynamic-graph/factory.h>
21 #include <dynamic-graph/all-commands.h>
22 #include <sot/core/stop-watch.hh>
23 
24 #include <Eigen/Core>
25 
26 namespace dynamicgraph
27 {
28  namespace sot
29  {
30  namespace talos_balance
31  {
32  namespace dg = ::dynamicgraph;
33  using namespace dg;
34  using namespace dg::command;
35 
36 //Size to be aligned "-------------------------------------------------------"
37 #define PROFILE_QUATTOEULER_COMPUTATION "QuatToEuler computation "
38 
39 #define INPUT_SIGNALS m_quaternionSIN
40 
41 #define OUTPUT_SIGNALS m_eulerSOUT
42 
45  typedef QuatToEuler EntityClassName;
46 
47  /* --- DG FACTORY ---------------------------------------------------- */
49  "QuatToEuler");
50 
51  /* ------------------------------------------------------------------- */
52  /* --- CONSTRUCTION -------------------------------------------------- */
53  /* ------------------------------------------------------------------- */
54  QuatToEuler::QuatToEuler(const std::string& name)
55  : Entity(name)
56  , CONSTRUCT_SIGNAL_IN(quaternion, dynamicgraph::Vector)
57  , CONSTRUCT_SIGNAL_OUT(euler, dynamicgraph::Vector, INPUT_SIGNALS)
58  {
59  Entity::signalRegistration( INPUT_SIGNALS << OUTPUT_SIGNALS );
60 
61  /* Commands. */
62  addCommand("init", makeCommandVoid0(*this, &QuatToEuler::init, docCommandVoid0("Initialize the entity.")));
63  }
64 
65  /* ------------------------------------------------------------------- */
66  /* --- SIGNALS ------------------------------------------------------- */
67  /* ------------------------------------------------------------------- */
68 
70  {
71  getProfiler().start(PROFILE_QUATTOEULER_COMPUTATION);
72 
73  const dynamicgraph::Vector & input = m_quaternionSIN(iter);
74 
75  const Eigen::Map<const Eigen::Quaterniond> quat(input.segment<4>(3).data());
76 
77  size_t sz = input.size();
78  s.resize(sz-1);
79 
80  s.head<3>() = input.head<3>();
81 
82  Eigen::Vector3d euler = quat.toRotationMatrix().eulerAngles(2, 1, 0);
83  s[3] = euler[2];
84  s[4] = euler[1];
85  s[5] = euler[0];
86 
87  if(sz>7)
88  s.tail(sz-7) = input.tail(sz-7);
89 
90  getProfiler().stop(PROFILE_QUATTOEULER_COMPUTATION);
91 
92  return s;
93  }
94 
95  /* --- COMMANDS ---------------------------------------------------------- */
96 
97  /* ------------------------------------------------------------------- */
98  /* --- ENTITY -------------------------------------------------------- */
99  /* ------------------------------------------------------------------- */
100 
101  void QuatToEuler::display(std::ostream& os) const
102  {
103  os << "QuatToEuler " << getName();
104  try
105  {
106  getProfiler().report_all(3, os);
107  }
108  catch (ExceptionSignal e) {}
109  }
110 
111  } // namespace talos_balance
112  } // namespace sot
113 } // namespace dynamicgraph
114 
virtual void display(std::ostream &os) const
#define INPUT_SIGNALS
#define PROFILE_QUATTOEULER_COMPUTATION
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: math/fwd.hh:40
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(AdmittanceControllerEndEffector, "AdmittanceControllerEndEffector")
#define OUTPUT_SIGNALS
EIGEN_MAKE_ALIGNED_OPERATOR_NEW QuatToEuler(const std::string &name)