sot-talos-balance  2.0.5
Collection of dynamic-graph entities aimed at implementing balance control on talos.
ankle-admittance-controller.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 #define PROFILE_ANKLEADMITTANCECONTROLLER_DRP_COMPUTATION \
34  "AnkleAdmittanceController: dRP computation "
35 
36 #define INPUT_SIGNALS m_gainsXYSIN << m_wrenchSIN << m_pRefSIN
37 
38 #define OUTPUT_SIGNALS m_dRPSOUT << m_vDesSOUT
39 
42 typedef AnkleAdmittanceController EntityClassName;
43 
44 /* --- DG FACTORY ---------------------------------------------------- */
45 DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(AnkleAdmittanceController,
46  "AnkleAdmittanceController");
47 
48 /* ------------------------------------------------------------------- */
49 /* --- CONSTRUCTION -------------------------------------------------- */
50 /* ------------------------------------------------------------------- */
52  : Entity(name),
53  CONSTRUCT_SIGNAL_IN(gainsXY, dynamicgraph::Vector),
54  CONSTRUCT_SIGNAL_IN(wrench, dynamicgraph::Vector),
55  CONSTRUCT_SIGNAL_IN(pRef, dynamicgraph::Vector),
56  CONSTRUCT_SIGNAL_OUT(dRP, dynamicgraph::Vector, INPUT_SIGNALS),
57  CONSTRUCT_SIGNAL_OUT(vDes, dynamicgraph::Vector, m_dRPSOUT),
58  m_initSucceeded(false) {
59  Entity::signalRegistration(INPUT_SIGNALS << OUTPUT_SIGNALS);
60 
61  /* Commands. */
62  addCommand("init",
63  makeCommandVoid0(*this, &AnkleAdmittanceController::init,
64  docCommandVoid0("Initialize the entity.")));
65 }
66 
68  ;
69  if (!m_gainsXYSIN.isPlugged())
70  return SEND_MSG("Init failed: signal gainsXY is not plugged",
71  MSG_TYPE_ERROR);
72  if (!m_wrenchSIN.isPlugged())
73  return SEND_MSG("Init failed: signal wrench is not plugged",
74  MSG_TYPE_ERROR);
75  if (!m_pRefSIN.isPlugged())
76  return SEND_MSG("Init failed: signal pRef is not plugged", MSG_TYPE_ERROR);
77 
78  m_initSucceeded = true;
79 }
80 
81 /* ------------------------------------------------------------------- */
82 /* --- SIGNALS ------------------------------------------------------- */
83 /* ------------------------------------------------------------------- */
84 
86  if (!m_initSucceeded) {
87  SEND_WARNING_STREAM_MSG("Can't compute dqRef before initialization!");
88  return s;
89  }
90  if (s.size() != 2) s.resize(2);
91 
93 
94  const Eigen::Vector3d pRef = m_pRefSIN(iter);
95  const Vector& wrench = m_wrenchSIN(iter);
96  const Vector& gainsXY = m_gainsXYSIN(iter);
97 
98  assert(pRef.size() == 3 && "Unexpected size of signal pRef");
99  assert(wrench.size() == 6 && "Unexpected size of signal wrench");
100  assert(gainsXY.size() == 2 && "Unexpected size of signal gainsXY");
101 
102  const Eigen::Vector3d error = wrench.tail<3>() - pRef.cross(wrench.head<3>());
103  Eigen::Vector2d dRP;
104 
105  dRP[0] = gainsXY[0] * error[0];
106  dRP[1] = gainsXY[1] * error[1];
107 
108  s = dRP;
109 
111 
112  return s;
113 }
114 
116  if (!m_initSucceeded) {
117  SEND_WARNING_STREAM_MSG("Can't compute vDes before initialization!");
118  return s;
119  }
120  if (s.size() != 6) s.resize(6);
121 
122  const Vector& dRP = m_dRPSOUT(iter);
123 
124  s.head<3>().setZero();
125  s.segment<2>(3) = dRP;
126  s[5] = 0;
127 
128  return s;
129 }
130 
131 /* --- COMMANDS ---------------------------------------------------------- */
132 
133 /* ------------------------------------------------------------------- */
134 /* --- ENTITY -------------------------------------------------------- */
135 /* ------------------------------------------------------------------- */
136 
137 void AnkleAdmittanceController::display(std::ostream& os) const {
138  os << "AnkleAdmittanceController " << getName();
139  try {
140  getProfiler().report_all(3, os);
141  } catch (ExceptionSignal e) {
142  }
143 }
144 } // namespace talos_balance
145 } // namespace sot
146 } // namespace dynamicgraph
OUTPUT_SIGNALS
#define OUTPUT_SIGNALS
Definition: ankle-admittance-controller.cpp:38
dynamicgraph::sot::talos_balance::AnkleAdmittanceController::display
virtual void display(std::ostream &os) const
Definition: ankle-admittance-controller.cpp:137
sot_talos_balance.test.appli_admittance_end_effector.sot
sot
Definition: appli_admittance_end_effector.py:117
dynamicgraph::sot::talos_balance::AnkleAdmittanceController::init
void init()
Definition: ankle-admittance-controller.cpp:67
dynamicgraph
Definition: treeview.dox:24
PROFILE_ANKLEADMITTANCECONTROLLER_DRP_COMPUTATION
#define PROFILE_ANKLEADMITTANCECONTROLLER_DRP_COMPUTATION
Definition: ankle-admittance-controller.cpp:33
dynamicgraph::sot::talos_balance::AnkleAdmittanceController::AnkleAdmittanceController
EIGEN_MAKE_ALIGNED_OPERATOR_NEW AnkleAdmittanceController(const std::string &name)
Definition: ankle-admittance-controller.cpp:51
dynamicgraph::sot::talos_balance::DEFINE_SIGNAL_OUT_FUNCTION
DEFINE_SIGNAL_OUT_FUNCTION(dq, dynamicgraph::Vector)
Definition: admittance-controller-end-effector.cpp:210
INPUT_SIGNALS
#define INPUT_SIGNALS
Definition: ankle-admittance-controller.cpp:36
dynamicgraph::sot::talos_balance::math::Vector
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: fwd.hh:36
sot_talos_balance.test.script_test_end_effector.wrench
wrench
Definition: script_test_end_effector.py:9
dynamicgraph::sot::talos_balance::AnkleAdmittanceController::m_initSucceeded
bool m_initSucceeded
Definition: ankle-admittance-controller.hh:78
dynamicgraph::sot::talos_balance::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(AdmittanceControllerEndEffector, "AdmittanceControllerEndEffector")
ankle-admittance-controller.hh
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