sot-talos-balance  2.0.5
Collection of dynamic-graph entities aimed at implementing balance control on talos.
simple-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 // Size to be aligned "-------------------------------------------------------"
34 
35 #define PROFILE_SIMPLE_ADMITTANCECONTROLLER_QREF_COMPUTATION \
36  "SimpleAdmittanceController: qRef computation "
37 
38 #define PROFILE_SIMPLE_ADMITTANCECONTROLLER_DQREF_COMPUTATION \
39  "SimpleAdmittanceController: dqRef computation "
40 
41 #define INPUT_SIGNALS m_KpSIN << m_stateSIN << m_tauSIN << m_tauDesSIN
42 
43 #define OUTPUT_SIGNALS m_qRefSOUT << m_dqRefSOUT
44 
47 typedef SimpleAdmittanceController EntityClassName;
48 
49 /* --- DG FACTORY ---------------------------------------------------- */
50 DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(SimpleAdmittanceController,
51  "SimpleAdmittanceController");
52 
53 /* ------------------------------------------------------------------- */
54 /* --- CONSTRUCTION -------------------------------------------------- */
55 /* ------------------------------------------------------------------- */
57  : Entity(name),
58  CONSTRUCT_SIGNAL_IN(Kp, dynamicgraph::Vector),
59  CONSTRUCT_SIGNAL_IN(state, dynamicgraph::Vector),
60  CONSTRUCT_SIGNAL_IN(tau, dynamicgraph::Vector),
61  CONSTRUCT_SIGNAL_IN(tauDes, dynamicgraph::Vector),
62  CONSTRUCT_SIGNAL_OUT(dqRef, dynamicgraph::Vector, INPUT_SIGNALS),
63  CONSTRUCT_SIGNAL_OUT(qRef, dynamicgraph::Vector, m_dqRefSOUT),
64  m_useState(false),
65  m_initSucceeded(false) {
66  Entity::signalRegistration(INPUT_SIGNALS << OUTPUT_SIGNALS);
67 
68  /* Commands. */
69  addCommand("init", makeCommandVoid2(
71  docCommandVoid2("Initialize the entity.", "time step",
72  "Number of elements")));
73  addCommand("setPosition",
74  makeCommandVoid1(*this, &SimpleAdmittanceController::setPosition,
75  docCommandVoid1("Set initial reference position.",
76  "Initial position")));
77  addCommand("useExternalState",
78  makeDirectSetter(*this, &m_useState,
79  docDirectSetter("use external state", "bool")));
80  addCommand("isUsingExternalState",
81  makeDirectGetter(*this, &m_useState,
82  docDirectGetter("use external state", "bool")));
83 }
84 
85 void SimpleAdmittanceController::init(const double& dt, const unsigned& n) {
86  if (n < 1) return SEND_MSG("n must be at least 1", MSG_TYPE_ERROR);
87  if (!m_KpSIN.isPlugged())
88  return SEND_MSG("Init failed: signal Kp is not plugged", MSG_TYPE_ERROR);
89  if (!m_tauSIN.isPlugged())
90  return SEND_MSG("Init failed: signal tau is not plugged", MSG_TYPE_ERROR);
91  if (!m_tauDesSIN.isPlugged())
92  return SEND_MSG("Init failed: signal tauDes is not plugged",
93  MSG_TYPE_ERROR);
94 
95  m_n = n;
96  m_dt = dt;
97  m_q.setZero(n);
98  m_initSucceeded = true;
99 }
100 
102  const dynamicgraph::Vector& position)
103 
104 {
105  m_q = position;
106 }
107 
108 /* ------------------------------------------------------------------- */
109 /* --- SIGNALS ------------------------------------------------------- */
110 /* ------------------------------------------------------------------- */
111 
113  if (!m_initSucceeded) {
114  SEND_WARNING_STREAM_MSG(
115  "Cannot compute signal dqRef before initialization!");
116  return s;
117  }
118  if (s.size() != m_n) s.resize(m_n);
119 
121 
122  const Vector& tauDes = m_tauDesSIN(iter);
123  const Vector& tau = m_tauSIN(iter);
124  const Vector& Kp = m_KpSIN(iter);
125 
126  assert(tau.size() == m_n && "Unexpected size of signal tau");
127  assert(tauDes.size() == m_n && "Unexpected size of signal tauDes");
128  assert(Kp.size() == m_n && "Unexpected size of signal Kp");
129 
130  s = Kp.cwiseProduct(tauDes - tau);
131 
133 
134  return s;
135 }
136 
138  if (!m_initSucceeded) {
139  SEND_WARNING_STREAM_MSG(
140  "Cannot compute signal qRef before initialization!");
141  return s;
142  }
143  if (s.size() != m_n) s.resize(m_n);
144 
146 
147  const Vector& dqRef = m_dqRefSOUT(iter);
148 
149  assert(dqRef.size() == m_n && "Unexpected size of signal dqRef");
150 
151  if (m_useState) {
152  if (!m_stateSIN.isPlugged()) {
153  SEND_MSG("Signal state is requested, but is not plugged", MSG_TYPE_ERROR);
154  return s;
155  }
156  const Vector& state = m_stateSIN(iter);
157  assert(state.size() == m_n && "Unexpected size of signal state");
158  m_q = state;
159  }
160 
161  m_q += dqRef * m_dt;
162 
163  s = m_q;
164 
166 
167  return s;
168 }
169 
170 /* --- COMMANDS ---------------------------------------------------------- */
171 
172 /* ------------------------------------------------------------------- */
173 /* --- ENTITY -------------------------------------------------------- */
174 /* ------------------------------------------------------------------- */
175 
176 void SimpleAdmittanceController::display(std::ostream& os) const {
177  os << "SimpleAdmittanceController " << getName();
178  try {
179  getProfiler().report_all(3, os);
180  } catch (ExceptionSignal e) {
181  }
182 }
183 } // namespace talos_balance
184 } // namespace sot
185 } // namespace dynamicgraph
sot_talos_balance.test.appli_admittance_end_effector.sot
sot
Definition: appli_admittance_end_effector.py:117
dynamicgraph::sot::talos_balance::SimpleAdmittanceController::init
void init(const double &dt, const unsigned &n)
Definition: simple-admittance-controller.cpp:85
dynamicgraph
Definition: treeview.dox:24
OUTPUT_SIGNALS
#define OUTPUT_SIGNALS
Definition: simple-admittance-controller.cpp:43
dynamicgraph::sot::talos_balance::SimpleAdmittanceController::m_dt
double m_dt
Definition: simple-admittance-controller.hh:87
dynamicgraph::sot::talos_balance::SimpleAdmittanceController::m_initSucceeded
bool m_initSucceeded
Definition: simple-admittance-controller.hh:84
dynamicgraph::sot::talos_balance::DEFINE_SIGNAL_OUT_FUNCTION
DEFINE_SIGNAL_OUT_FUNCTION(dq, dynamicgraph::Vector)
Definition: admittance-controller-end-effector.cpp:210
sot_talos_balance.test.test_admittance_single_joint.tau
tau
Definition: test_admittance_single_joint.py:20
dynamicgraph::sot::talos_balance::SimpleAdmittanceController::SimpleAdmittanceController
EIGEN_MAKE_ALIGNED_OPERATOR_NEW SimpleAdmittanceController(const std::string &name)
Definition: simple-admittance-controller.cpp:56
simple-admittance-controller.hh
sot_talos_balance.test.appli_admittance_single_joint.Kp
list Kp
Definition: appli_admittance_single_joint.py:33
dynamicgraph::sot::talos_balance::math::Vector
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: fwd.hh:36
PROFILE_SIMPLE_ADMITTANCECONTROLLER_QREF_COMPUTATION
#define PROFILE_SIMPLE_ADMITTANCECONTROLLER_QREF_COMPUTATION
Definition: simple-admittance-controller.cpp:35
sot_talos_balance.test.appli_admittance_single_joint.dt
dt
Definition: appli_admittance_single_joint.py:17
dynamicgraph::sot::talos_balance::SimpleAdmittanceController::m_useState
bool m_useState
Definition: simple-admittance-controller.hh:79
PROFILE_SIMPLE_ADMITTANCECONTROLLER_DQREF_COMPUTATION
#define PROFILE_SIMPLE_ADMITTANCECONTROLLER_DQREF_COMPUTATION
Definition: simple-admittance-controller.cpp:38
dynamicgraph::sot::talos_balance::SimpleAdmittanceController::m_q
dynamicgraph::Vector m_q
Definition: simple-admittance-controller.hh:86
dynamicgraph::sot::talos_balance::SimpleAdmittanceController::display
virtual void display(std::ostream &os) const
Definition: simple-admittance-controller.cpp:176
dynamicgraph::sot::talos_balance::SimpleAdmittanceController::setPosition
void setPosition(const dynamicgraph::Vector &position)
Definition: simple-admittance-controller.cpp:101
dynamicgraph::sot::talos_balance::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(AdmittanceControllerEndEffector, "AdmittanceControllerEndEffector")
dynamicgraph::sot::talos_balance::SimpleAdmittanceController::m_n
int m_n
Definition: simple-admittance-controller.hh:82
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
INPUT_SIGNALS
#define INPUT_SIGNALS
Definition: simple-admittance-controller.cpp:41