sot-talos-balance  2.0.5
Collection of dynamic-graph entities aimed at implementing balance control on talos.
joint-position-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 #define PROFILE_JOINTPOSITIONCONTROLLER_DQREF_COMPUTATION \
35  "JointPositionController: dqRef computation "
36 
37 #define INPUT_SIGNALS m_KpSIN << m_stateSIN << m_qDesSIN << m_dqDesSIN
38 
39 #define OUTPUT_SIGNALS m_dqRefSOUT
40 
43 typedef JointPositionController EntityClassName;
44 
45 /* --- DG FACTORY ---------------------------------------------------- */
46 DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(JointPositionController,
47  "JointPositionController");
48 
49 /* ------------------------------------------------------------------- */
50 /* --- CONSTRUCTION -------------------------------------------------- */
51 /* ------------------------------------------------------------------- */
53  : Entity(name),
54  CONSTRUCT_SIGNAL_IN(Kp, dynamicgraph::Vector),
55  CONSTRUCT_SIGNAL_IN(state, dynamicgraph::Vector),
56  CONSTRUCT_SIGNAL_IN(qDes, dynamicgraph::Vector),
57  CONSTRUCT_SIGNAL_IN(dqDes, dynamicgraph::Vector),
58  CONSTRUCT_SIGNAL_OUT(dqRef, dynamicgraph::Vector, INPUT_SIGNALS),
59  m_initSucceeded(false) {
60  Entity::signalRegistration(INPUT_SIGNALS << OUTPUT_SIGNALS);
61 
62  /* Commands. */
63  addCommand("init", makeCommandVoid1(*this, &JointPositionController::init,
64  docCommandVoid1("Initialize the entity.",
65  "Control gains")));
66 }
67 
68 void JointPositionController::init(const unsigned& n) {
69  if (n < 1) return SEND_MSG("n must be at least 1", MSG_TYPE_ERROR);
70  if (!m_KpSIN.isPlugged())
71  return SEND_MSG("Init failed: signal Kp is not plugged", MSG_TYPE_ERROR);
72  if (!m_stateSIN.isPlugged())
73  return SEND_MSG("Init failed: signal q is not plugged", MSG_TYPE_ERROR);
74  if (!m_qDesSIN.isPlugged())
75  return SEND_MSG("Init failed: signal qDes is not plugged", MSG_TYPE_ERROR);
76  if (!m_dqDesSIN.isPlugged())
77  return SEND_MSG("Init failed: signal dqDes is not plugged", MSG_TYPE_ERROR);
78 
79  m_n = n;
80  m_initSucceeded = true;
81 }
82 
83 /* ------------------------------------------------------------------- */
84 /* --- SIGNALS ------------------------------------------------------- */
85 /* ------------------------------------------------------------------- */
86 
88  if (!m_initSucceeded) {
89  SEND_WARNING_STREAM_MSG(
90  "Cannot compute signal dqRef before initialization!");
91  return s;
92  }
93  if (s.size() != m_n) s.resize(m_n);
94 
96 
97  const Vector& state = m_stateSIN(iter);
98  const Vector& qDes = m_qDesSIN(iter);
99  const Vector& dqDes = m_dqDesSIN(iter);
100  const Vector& Kp = m_KpSIN(iter);
101 
102  assert(state.size() == m_n + 6 && "Unexpected size of signal state");
103  assert(qDes.size() == m_n && "Unexpected size of signal qDes");
104  assert(dqDes.size() == m_n && "Unexpected size of signal dqDes");
105  assert(Kp.size() == m_n && "Unexpected size of signal Kp");
106 
107  s = dqDes + Kp.cwiseProduct(qDes - state.tail(m_n));
108 
110 
111  return s;
112 }
113 
114 /* --- COMMANDS ---------------------------------------------------------- */
115 
116 /* ------------------------------------------------------------------- */
117 /* --- ENTITY -------------------------------------------------------- */
118 /* ------------------------------------------------------------------- */
119 
120 void JointPositionController::display(std::ostream& os) const {
121  os << "JointPositionController " << getName();
122  try {
123  getProfiler().report_all(3, os);
124  } catch (ExceptionSignal e) {
125  }
126 }
127 } // namespace talos_balance
128 } // namespace sot
129 } // namespace dynamicgraph
dynamicgraph::sot::talos_balance::JointPositionController::init
void init(const unsigned &n)
Definition: joint-position-controller.cpp:68
INPUT_SIGNALS
#define INPUT_SIGNALS
Definition: joint-position-controller.cpp:37
sot_talos_balance.test.appli_admittance_end_effector.sot
sot
Definition: appli_admittance_end_effector.py:117
dynamicgraph
Definition: treeview.dox:24
dynamicgraph::sot::talos_balance::JointPositionController::m_n
int m_n
Definition: joint-position-controller.hh:77
dynamicgraph::sot::talos_balance::JointPositionController::m_initSucceeded
bool m_initSucceeded
Definition: joint-position-controller.hh:79
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.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
OUTPUT_SIGNALS
#define OUTPUT_SIGNALS
Definition: joint-position-controller.cpp:39
dynamicgraph::sot::talos_balance::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(AdmittanceControllerEndEffector, "AdmittanceControllerEndEffector")
dynamicgraph::sot::talos_balance::JointPositionController::JointPositionController
EIGEN_MAKE_ALIGNED_OPERATOR_NEW JointPositionController(const std::string &name)
Definition: joint-position-controller.cpp:52
joint-position-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
PROFILE_JOINTPOSITIONCONTROLLER_DQREF_COMPUTATION
#define PROFILE_JOINTPOSITIONCONTROLLER_DQREF_COMPUTATION
Definition: joint-position-controller.cpp:34
dynamicgraph::sot::talos_balance::JointPositionController::display
virtual void display(std::ostream &os) const
Definition: joint-position-controller.cpp:120