sot-talos-balance  2.0.5
Collection of dynamic-graph entities aimed at implementing balance control on talos.
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 <dynamic-graph/all-commands.h>
20 #include <dynamic-graph/factory.h>
21 
22 #include <Eigen/Core>
23 #include <sot/core/debug.hh>
24 #include <sot/core/stop-watch.hh>
25 
26 namespace dynamicgraph {
27 namespace sot {
28 namespace talos_balance {
29 namespace dg = ::dynamicgraph;
30 using namespace dg;
31 using namespace dg::command;
32 
33 // Size to be aligned "-------------------------------------------------------"
34 #define PROFILE_QUATTOEULER_COMPUTATION \
35  "QuatToEuler computation "
36 
37 #define INPUT_SIGNALS m_quaternionSIN
38 
39 #define OUTPUT_SIGNALS m_eulerSOUT
40 
43 typedef QuatToEuler EntityClassName;
44 
45 /* --- DG FACTORY ---------------------------------------------------- */
46 DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(QuatToEuler, "QuatToEuler");
47 
48 /* ------------------------------------------------------------------- */
49 /* --- CONSTRUCTION -------------------------------------------------- */
50 /* ------------------------------------------------------------------- */
51 QuatToEuler::QuatToEuler(const std::string& name)
52  : Entity(name),
53  CONSTRUCT_SIGNAL_IN(quaternion, dynamicgraph::Vector),
54  CONSTRUCT_SIGNAL_OUT(euler, dynamicgraph::Vector, INPUT_SIGNALS) {
55  Entity::signalRegistration(INPUT_SIGNALS << OUTPUT_SIGNALS);
56 
57  /* Commands. */
58  addCommand("init",
59  makeCommandVoid0(*this, &QuatToEuler::init,
60  docCommandVoid0("Initialize the entity.")));
61 }
62 
63 /* ------------------------------------------------------------------- */
64 /* --- SIGNALS ------------------------------------------------------- */
65 /* ------------------------------------------------------------------- */
66 
68  const dynamicgraph::Vector& input = m_quaternionSIN(iter);
69  const size_t sz = input.size();
70  if ((size_t)(s.size()) != (sz - 1)) s.resize(sz - 1);
71 
72  getProfiler().start(PROFILE_QUATTOEULER_COMPUTATION);
73 
74  const Eigen::Map<const Eigen::Quaterniond> quat(input.segment<4>(3).data());
75 
76  s.head<3>() = input.head<3>();
77 
78  Eigen::Vector3d euler = quat.toRotationMatrix().eulerAngles(2, 1, 0);
79  s[3] = euler[2];
80  s[4] = euler[1];
81  s[5] = euler[0];
82 
83  if (sz > 7) s.tail(sz - 7) = input.tail(sz - 7);
84 
85  getProfiler().stop(PROFILE_QUATTOEULER_COMPUTATION);
86 
87  return s;
88 }
89 
90 /* --- COMMANDS ---------------------------------------------------------- */
91 
92 /* ------------------------------------------------------------------- */
93 /* --- ENTITY -------------------------------------------------------- */
94 /* ------------------------------------------------------------------- */
95 
96 void QuatToEuler::display(std::ostream& os) const {
97  os << "QuatToEuler " << getName();
98  try {
99  getProfiler().report_all(3, os);
100  } catch (ExceptionSignal e) {
101  }
102 }
103 
104 } // namespace talos_balance
105 } // namespace sot
106 } // namespace dynamicgraph
sot_talos_balance.test.appli_admittance_end_effector.sot
sot
Definition: appli_admittance_end_effector.py:117
dynamicgraph
Definition: treeview.dox:24
PROFILE_QUATTOEULER_COMPUTATION
#define PROFILE_QUATTOEULER_COMPUTATION
Definition: quat-to-euler.cpp:34
sot_talos_balance.test.test_admittance_end_effector.input
input
Definition: test_admittance_end_effector.py:11
dynamicgraph::sot::talos_balance::DEFINE_SIGNAL_OUT_FUNCTION
DEFINE_SIGNAL_OUT_FUNCTION(dq, dynamicgraph::Vector)
Definition: admittance-controller-end-effector.cpp:210
OUTPUT_SIGNALS
#define OUTPUT_SIGNALS
Definition: quat-to-euler.cpp:39
dynamicgraph::sot::talos_balance::QuatToEuler::QuatToEuler
EIGEN_MAKE_ALIGNED_OPERATOR_NEW QuatToEuler(const std::string &name)
Definition: quat-to-euler.cpp:51
quat-to-euler.hh
INPUT_SIGNALS
#define INPUT_SIGNALS
Definition: quat-to-euler.cpp:37
dynamicgraph::sot::talos_balance::math::Vector
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: fwd.hh:36
dynamicgraph::sot::talos_balance::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(AdmittanceControllerEndEffector, "AdmittanceControllerEndEffector")
dynamicgraph::sot::talos_balance::QuatToEuler::init
void init()
Definition: quat-to-euler.hh:63
dynamicgraph::sot::talos_balance::EntityClassName
AdmittanceControllerEndEffector EntityClassName
Definition: admittance-controller-end-effector.cpp:46
sot_talos_balance.test.appli_dcm_zmp_control.name
name
Definition: appli_dcm_zmp_control.py:298
dynamicgraph::sot::talos_balance::QuatToEuler::display
virtual void display(std::ostream &os) const
Definition: quat-to-euler.cpp:96