sot-talos-balance  2.0.5
Collection of dynamic-graph entities aimed at implementing balance control on talos.
state-transformation.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/command-bind.h>
21 #include <dynamic-graph/factory.h>
22 
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_STATETRANSFORMATION_Q_COMPUTATION \
35  "State transformation q computation "
36 #define PROFILE_STATETRANSFORMATION_V_COMPUTATION \
37  "State transformation v computation "
38 
39 #define INPUT_SIGNALS m_referenceFrameSIN << m_q_inSIN << m_v_inSIN
40 
41 #define OUTPUT_SIGNALS m_qSOUT << m_vSOUT
42 
45 typedef StateTransformation EntityClassName;
46 
47 /* --- DG FACTORY ---------------------------------------------------- */
48 DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(StateTransformation, "StateTransformation");
49 
50 /* ------------------------------------------------------------------- */
51 /* --- CONSTRUCTION -------------------------------------------------- */
52 /* ------------------------------------------------------------------- */
54  : Entity(name),
55  CONSTRUCT_SIGNAL_IN(referenceFrame, MatrixHomogeneous),
56  CONSTRUCT_SIGNAL_IN(q_in, dynamicgraph::Vector),
57  CONSTRUCT_SIGNAL_IN(v_in, dynamicgraph::Vector),
58  CONSTRUCT_SIGNAL_OUT(q, dynamicgraph::Vector,
59  m_referenceFrameSIN << m_q_inSIN),
60  CONSTRUCT_SIGNAL_OUT(v, dynamicgraph::Vector,
61  m_referenceFrameSIN << m_v_inSIN),
62  m_initSucceeded(false) {
63  Entity::signalRegistration(INPUT_SIGNALS << OUTPUT_SIGNALS);
64 
65  /* Commands. */
66  addCommand("init",
67  makeCommandVoid0(*this, &StateTransformation::init,
68  docCommandVoid0("Initialize the entity.")));
69 }
70 
72 
73 /* ------------------------------------------------------------------- */
74 /* --- SIGNALS ------------------------------------------------------- */
75 /* ------------------------------------------------------------------- */
76 
78  const dynamicgraph::Vector& input = m_q_inSIN(iter);
79  const size_t sz = input.size();
80  if ((size_t)(s.size()) != sz) s.resize(sz);
81 
82  getProfiler().start(PROFILE_STATETRANSFORMATION_Q_COMPUTATION);
83 
84  const MatrixHomogeneous& referenceFrame = m_referenceFrameSIN(iter);
85 
86  // convert q base to homogeneous matrix
87  const Eigen::Vector3d& euler = input.segment<3>(3);
88 
89  const double roll = euler[0];
90  const double pitch = euler[1];
91  const double yaw = euler[2];
92 
93  Eigen::Quaterniond quat;
94  quat = Eigen::AngleAxisd(yaw, Eigen::Vector3d::UnitZ()) *
95  Eigen::AngleAxisd(pitch, Eigen::Vector3d::UnitY()) *
96  Eigen::AngleAxisd(roll, Eigen::Vector3d::UnitX());
97 
98  MatrixHomogeneous M;
99  M.linear() = quat.toRotationMatrix();
100  M.translation() = input.head<3>();
101 
102  // Convert the matrix
103  MatrixHomogeneous res = referenceFrame * M;
104 
105  // Write the result
106  s.head<3>() = res.translation();
107 
108  s.segment<3>(3) = res.linear().eulerAngles(2, 1, 0).reverse();
109 
110  if (sz > 6) s.tail(sz - 6) = input.tail(sz - 6);
111 
112  getProfiler().stop(PROFILE_STATETRANSFORMATION_Q_COMPUTATION);
113 
114  return s;
115 }
116 
118  const dynamicgraph::Vector& input = m_v_inSIN(iter);
119  const size_t sz = input.size();
120  if ((size_t)(s.size()) != sz) s.resize(sz);
121 
122  getProfiler().start(PROFILE_STATETRANSFORMATION_V_COMPUTATION);
123 
124  const MatrixHomogeneous& referenceFrame = m_referenceFrameSIN(iter);
125 
126  // Write the result
127  s.head<3>() = referenceFrame.linear() * input.head<3>();
128 
129  s.segment<3>(3) = referenceFrame.linear() * input.segment<3>(3);
130 
131  if (sz > 6) s.tail(sz - 6) = input.tail(sz - 6);
132 
133  getProfiler().stop(PROFILE_STATETRANSFORMATION_V_COMPUTATION);
134 
135  return s;
136 }
137 
138 /* --- COMMANDS ---------------------------------------------------------- */
139 
140 /* ------------------------------------------------------------------- */
141 /* --- ENTITY -------------------------------------------------------- */
142 /* ------------------------------------------------------------------- */
143 
144 void StateTransformation::display(std::ostream& os) const {
145  os << "StateTransformation " << getName();
146  try {
147  getProfiler().report_all(3, os);
148  } catch (ExceptionSignal e) {
149  }
150 }
151 } // namespace talos_balance
152 } // namespace sot
153 } // namespace dynamicgraph
sot_talos_balance.test.appli_admittance_end_effector.q
list q
Definition: appli_admittance_end_effector.py:30
sot_talos_balance.test.appli_admittance_end_effector.sot
sot
Definition: appli_admittance_end_effector.py:117
dynamicgraph
Definition: treeview.dox:24
INPUT_SIGNALS
#define INPUT_SIGNALS
Definition: state-transformation.cpp:39
sot_talos_balance.test.test_admittance_end_effector.input
input
Definition: test_admittance_end_effector.py:11
dynamicgraph::sot::talos_balance::StateTransformation::display
virtual void display(std::ostream &os) const
Definition: state-transformation.cpp:144
dynamicgraph::sot::talos_balance::StateTransformation::m_initSucceeded
bool m_initSucceeded
Definition: state-transformation.hh:81
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: state-transformation.cpp:41
PROFILE_STATETRANSFORMATION_V_COMPUTATION
#define PROFILE_STATETRANSFORMATION_V_COMPUTATION
Definition: state-transformation.cpp:36
state-transformation.hh
dynamicgraph::sot::talos_balance::math::Vector
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: fwd.hh:36
dynamicgraph::sot::talos_balance::StateTransformation::init
void init()
Definition: state-transformation.cpp:71
PROFILE_STATETRANSFORMATION_Q_COMPUTATION
#define PROFILE_STATETRANSFORMATION_Q_COMPUTATION
Definition: state-transformation.cpp:34
dynamicgraph::sot::talos_balance::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(AdmittanceControllerEndEffector, "AdmittanceControllerEndEffector")
dynamicgraph::sot::talos_balance::EntityClassName
AdmittanceControllerEndEffector EntityClassName
Definition: admittance-controller-end-effector.cpp:46
dynamicgraph::sot::talos_balance::StateTransformation::StateTransformation
EIGEN_MAKE_ALIGNED_OPERATOR_NEW StateTransformation(const std::string &name)
Definition: state-transformation.cpp:53
sot_talos_balance.test.appli_dcm_zmp_control.name
name
Definition: appli_dcm_zmp_control.py:298