sot-talos-balance  1.7.0
euler-to-quat.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_EULERTOQUAT_COMPUTATION "EulerToQuat computation "
38 
39 #define INPUT_SIGNALS m_eulerSIN
40 
41 #define OUTPUT_SIGNALS m_quaternionSOUT
42 
45  typedef EulerToQuat EntityClassName;
46 
47  /* --- DG FACTORY ---------------------------------------------------- */
49  "EulerToQuat");
50 
51  /* ------------------------------------------------------------------- */
52  /* --- CONSTRUCTION -------------------------------------------------- */
53  /* ------------------------------------------------------------------- */
54  EulerToQuat::EulerToQuat(const std::string& name)
55  : Entity(name)
56  , CONSTRUCT_SIGNAL_IN(euler, dynamicgraph::Vector)
57  , CONSTRUCT_SIGNAL_OUT(quaternion, dynamicgraph::Vector, INPUT_SIGNALS)
58  {
59  Entity::signalRegistration( INPUT_SIGNALS << OUTPUT_SIGNALS );
60 
61  /* Commands. */
62  addCommand("init", makeCommandVoid0(*this, &EulerToQuat::init, docCommandVoid0("Initialize the entity.")));
63  }
64 
65  /* ------------------------------------------------------------------- */
66  /* --- SIGNALS ------------------------------------------------------- */
67  /* ------------------------------------------------------------------- */
68 
70  {
71  const dynamicgraph::Vector & input = m_eulerSIN(iter);
72  const size_t sz = input.size();
73  if((size_t)(s.size())!=(sz+1))
74  s.resize(sz+1);
75 
76  getProfiler().start(PROFILE_EULERTOQUAT_COMPUTATION);
77 
78  const Eigen::Vector3d & euler = input.segment<3>(3);
79 
80  const double roll = euler[0];
81  const double pitch = euler[1];
82  const double yaw = euler[2];
83 
84  Eigen::Quaterniond quat;
85  quat = Eigen::AngleAxisd(yaw, Eigen::Vector3d::UnitZ())
86  * Eigen::AngleAxisd(pitch, Eigen::Vector3d::UnitY())
87  * Eigen::AngleAxisd(roll, Eigen::Vector3d::UnitX());
88 
89  s.head<3>() = input.head<3>();
90 
91  s.segment<4>(3) = quat.coeffs();
92 
93  if(sz>6)
94  s.tail(sz-6) = input.tail(sz-6);
95 
96  getProfiler().stop(PROFILE_EULERTOQUAT_COMPUTATION);
97 
98  return s;
99  }
100 
101  /* --- COMMANDS ---------------------------------------------------------- */
102 
103  /* ------------------------------------------------------------------- */
104  /* --- ENTITY -------------------------------------------------------- */
105  /* ------------------------------------------------------------------- */
106 
107  void EulerToQuat::display(std::ostream& os) const
108  {
109  os << "EulerToQuat " << getName();
110  try
111  {
112  getProfiler().report_all(3, os);
113  }
114  catch (ExceptionSignal e) {}
115  }
116 
117  } // namespace talos_balance
118  } // namespace sot
119 } // namespace dynamicgraph
120 
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: math/fwd.hh:40
#define INPUT_SIGNALS
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(AdmittanceControllerEndEffector, "AdmittanceControllerEndEffector")
virtual void display(std::ostream &os) const
#define PROFILE_EULERTOQUAT_COMPUTATION
#define OUTPUT_SIGNALS
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EulerToQuat(const std::string &name)