parameter-server.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2014, Andrea Del Prete, LAAS-CNRS
3  *
4  * This file is part of sot-torque-control.
5  * sot-torque-control 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-torque-control 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-torque-control. If not, see <http://www.gnu.org/licenses/>.
15  */
16 
17 #include <iostream>
18 #include <pinocchio/fwd.hpp>
19 // keep pinocchio before boost
20 
22 #include <dynamic-graph/factory.h>
23 
24 #include <boost/property_tree/ptree.hpp>
25 #include <sot/core/debug.hh>
28 
29 namespace dynamicgraph {
30 namespace sot {
31 namespace dynamicgraph = ::dynamicgraph;
32 using namespace dynamicgraph;
33 using namespace dynamicgraph::command;
34 using namespace std;
35 
36 // Size to be aligned "-------------------------------------------------------"
37 #define PROFILE_PWM_DESIRED_COMPUTATION \
38  "Control manager "
39 #define PROFILE_DYNAMIC_GRAPH_PERIOD \
40  "Control period "
41 
42 #define INPUT_SIGNALS
43 #define OUTPUT_SIGNALS
44 
47 typedef ParameterServer EntityClassName;
48 
49 /* --- DG FACTORY ---------------------------------------------------- */
50 DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(ParameterServer, "ParameterServer");
51 
52 /* ------------------------------------------------------------------- */
53 /* --- CONSTRUCTION -------------------------------------------------- */
54 /* ------------------------------------------------------------------- */
56  : Entity(name),
57  m_robot_util(RefVoidRobotUtil()),
58  m_initSucceeded(false),
59  m_emergency_stop_triggered(false),
60  m_is_first_iter(true),
61  m_iter(0),
62  m_sleep_time(0.0) {
63  //~ Entity::signalRegistration( INPUT_SIGNALS << OUTPUT_SIGNALS);
64 
65  /* Commands. */
66  addCommand("init",
68  docCommandVoid3("Initialize the entity.",
69  "Time period in seconds (double)",
70  "URDF file path (string)",
71  "Robot reference (string)")));
72  addCommand(
73  "init_simple",
75  docCommandVoid1("Initialize the entity.",
76  "Time period in seconds (double)")));
77 
78  addCommand("setNameToId",
81  docCommandVoid2("Set map for a name to an Id",
82  "(string) joint name", "(double) joint id")));
83 
84  addCommand(
85  "setForceNameToForceId",
89  "Set map from a force sensor name to a force sensor Id",
90  "(string) force sensor name", "(double) force sensor id")));
91 
92  addCommand("setJointLimitsFromId",
95  docCommandVoid3("Set the joint limits for a given joint ID",
96  "(double) joint id", "(double) lower limit",
97  "(double) uppper limit")));
98 
99  addCommand(
100  "setForceLimitsFromId",
103  docCommandVoid3("Set the force limits for a given force sensor ID",
104  "(double) force sensor id", "(double) lower limit",
105  "(double) uppper limit")));
106 
107  addCommand(
108  "setJointsUrdfToSot",
110  docCommandVoid1("Map Joints From URDF to SoT.",
111  "Vector of integer for mapping")));
112 
113  addCommand(
114  "setRightFootSoleXYZ",
116  docCommandVoid1("Set the right foot sole 3d position.",
117  "Vector of 3 doubles")));
118  addCommand(
119  "setRightFootForceSensorXYZ",
121  docCommandVoid1("Set the right foot sensor 3d position.",
122  "Vector of 3 doubles")));
123 
124  addCommand("setFootFrameName",
127  docCommandVoid2("Set the Frame Name for the Foot Name.",
128  "(string) Foot name", "(string) Frame name")));
129  addCommand("setHandFrameName",
132  docCommandVoid2("Set the Frame Name for the Hand Name.",
133  "(string) Hand name", "(string) Frame name")));
134  addCommand("setImuJointName",
137  docCommandVoid1("Set the Joint Name wich IMU is attached to.",
138  "(string) Joint name")));
139  addCommand("displayRobotUtil",
142  docCommandVoid0("Display the current robot util data set.")));
143 
144  addCommand(
145  "setParameterBool",
147  *this, &ParameterServer::setParameter<bool>,
148  docCommandVoid2("Set a parameter named ParameterName to value "
149  "ParameterValue (string format).",
150  "(string) ParameterName", "(bool) ParameterValue")));
151  addCommand("setParameterInt",
153  *this, &ParameterServer::setParameter<size_type>,
154  docCommandVoid2("Set a parameter named ParameterName to value "
155  "ParameterValue (string format).",
156  "(string) ParameterName",
157  "(size_type) ParameterValue")));
158  addCommand("setParameterDbl",
160  *this, &ParameterServer::setParameter<double>,
161  docCommandVoid2("Set a parameter named ParameterName to value "
162  "ParameterValue (string format).",
163  "(string) ParameterName",
164  "(double) ParameterValue")));
165 
166  addCommand("setParameter",
168  *this, &ParameterServer::setParameter<std::string>,
169  docCommandVoid2("Set a parameter named ParameterName to value "
170  "ParameterValue (string format).",
171  "(string) ParameterName",
172  "(string) ParameterValue")));
173 
174  addCommand(
175  "getParameter",
176  makeCommandReturnType1(*this, &ParameterServer::getParameter<std::string>,
177  docCommandReturnType1<std::string>(
178  "Return the parameter value for parameter"
179  " named ParameterName.",
180  "(string) ParameterName")));
181 
182  addCommand(
183  "getParameterInt",
184  makeCommandReturnType1(*this, &ParameterServer::getParameter<size_type>,
185  docCommandReturnType1<size_type>(
186  "Return the parameter value for parameter"
187  " named ParameterName.",
188  "(size_type) ParameterName")));
189 
190  addCommand(
191  "getParameterDbl",
192  makeCommandReturnType1(*this, &ParameterServer::getParameter<double>,
193  docCommandReturnType1<double>(
194  "Return the parameter value for parameter"
195  " named ParameterName.",
196  "(double) ParameterName")));
197 
198  addCommand(
199  "getParameterBool",
201  *this, &ParameterServer::getParameter<bool>,
202  docCommandReturnType1<bool>("Return the parameter value for parameter"
203  " named ParameterName.",
204  "(string) ParameterName")));
205 }
206 
207 void ParameterServer::init_simple(const double &dt) {
208  if (dt <= 0.0) return SEND_MSG("Timestep must be positive", MSG_TYPE_ERROR);
209 
210  m_dt = dt;
211 
213  m_initSucceeded = true;
214 
215  std::string localName("robot");
216  std::shared_ptr<std::vector<std::string> > listOfRobots =
218 
219  if (listOfRobots->size() == 1)
220  localName = (*listOfRobots)[0];
221  else {
222  std::ostringstream oss;
223  oss << "No robot registered in the parameter server list";
224  oss << " listOfRobots->size: " << listOfRobots->size();
225  throw ExceptionTools(ExceptionTools::ErrorCodeEnum::PARAMETER_SERVER,
226  oss.str());
227  }
228 
231  } else {
233  }
234 
235  addCommand(
236  "getJointsUrdfToSot",
237  makeDirectGetter(*this, &m_robot_util->m_dgv_urdf_to_sot,
238  docDirectSetter("Display map Joints From URDF to SoT.",
239  "Vector of integer for mapping")));
240 }
241 
242 void ParameterServer::init(const double &dt, const std::string &urdfFile,
243  const std::string &robotRef) {
244  if (dt <= 0.0) return SEND_MSG("Timestep must be positive", MSG_TYPE_ERROR);
245  m_dt = dt;
247  m_initSucceeded = true;
248 
249  std::string localName(robotRef);
252  } else {
254  }
255 
256  m_robot_util->m_urdf_filename = urdfFile;
257 }
258 
259 /* ------------------------------------------------------------------- */
260 /* --- SIGNALS ------------------------------------------------------- */
261 /* ------------------------------------------------------------------- */
262 
263 /* --- COMMANDS ---------------------------------------------------------- */
264 
265 void ParameterServer::setNameToId(const std::string &jointName,
266  const double &jointId) {
267  if (!m_initSucceeded) {
269  "Cannot set joint name from joint id before initialization!");
270  return;
271  }
272  m_robot_util->set_name_to_id(jointName, static_cast<Index>(jointId));
273 }
274 
275 void ParameterServer::setJointLimitsFromId(const double &jointId,
276  const double &lq, const double &uq) {
277  if (!m_initSucceeded) {
279  "Cannot set joints limits from joint id before initialization!");
280  return;
281  }
282 
283  m_robot_util->set_joint_limits_for_id((Index)jointId, lq, uq);
284 }
285 
286 void ParameterServer::setForceLimitsFromId(const double &jointId,
287  const dynamicgraph::Vector &lq,
288  const dynamicgraph::Vector &uq) {
289  if (!m_initSucceeded) {
291  "Cannot set force limits from force id before initialization!");
292  return;
293  }
294 
295  m_robot_util->m_force_util.set_force_id_to_limits((Index)jointId, lq, uq);
296 }
297 
298 void ParameterServer::setForceNameToForceId(const std::string &forceName,
299  const double &forceId) {
300  if (!m_initSucceeded) {
302  "Cannot set force sensor name from force sensor id "
303  " before initialization!");
304  return;
305  }
306 
307  m_robot_util->m_force_util.set_name_to_force_id(forceName,
308  static_cast<Index>(forceId));
309 }
310 
312  if (!m_initSucceeded) {
313  SEND_WARNING_STREAM_MSG("Cannot set mapping to sot before initialization!");
314  return;
315  }
316  m_robot_util->set_urdf_to_sot(urdf_to_sot);
317 }
318 
320  if (!m_initSucceeded) {
322  "Cannot set right foot sole XYZ before initialization!");
323  return;
324  }
325 
326  m_robot_util->m_foot_util.m_Right_Foot_Sole_XYZ = xyz;
327 }
328 
330  const dynamicgraph::Vector &xyz) {
331  if (!m_initSucceeded) {
333  "Cannot set right foot force sensor XYZ before initialization!");
334  return;
335  }
336 
337  m_robot_util->m_foot_util.m_Right_Foot_Force_Sensor_XYZ = xyz;
338 }
339 
340 void ParameterServer::setFootFrameName(const std::string &FootName,
341  const std::string &FrameName) {
342  if (!m_initSucceeded) {
343  SEND_WARNING_STREAM_MSG("Cannot set foot frame name!");
344  return;
345  }
346  if (FootName == "Left")
347  m_robot_util->m_foot_util.m_Left_Foot_Frame_Name = FrameName;
348  else if (FootName == "Right")
349  m_robot_util->m_foot_util.m_Right_Foot_Frame_Name = FrameName;
350  else
351  SEND_WARNING_STREAM_MSG("Did not understand the foot name !" + FootName);
352 }
353 
354 void ParameterServer::setHandFrameName(const std::string &HandName,
355  const std::string &FrameName) {
356  if (!m_initSucceeded) {
357  SEND_WARNING_STREAM_MSG("Cannot set hand frame name!");
358  return;
359  }
360  if (HandName == "Left")
361  m_robot_util->m_hand_util.m_Left_Hand_Frame_Name = FrameName;
362  else if (HandName == "Right")
363  m_robot_util->m_hand_util.m_Right_Hand_Frame_Name = FrameName;
364  else
366  "Available hand names are 'Left' and 'Right', not '" + HandName +
367  "' !");
368 }
369 
370 void ParameterServer::setImuJointName(const std::string &JointName) {
371  if (!m_initSucceeded) {
372  SEND_WARNING_STREAM_MSG("Cannot set IMU joint name!");
373  return;
374  }
375  m_robot_util->m_imu_joint_name = JointName;
376 }
377 
378 void ParameterServer::displayRobotUtil() { m_robot_util->display(std::cout); }
379 
380 /* --- PROTECTED MEMBER METHODS
381  * ---------------------------------------------------------- */
382 
384  std::size_t &id) {
385  // Check if the joint name exists
386  sot::Index jid = m_robot_util->get_id_from_name(name);
387  if (jid < 0) {
388  SEND_MSG("The specified joint name does not exist: " + name,
390  std::stringstream ss;
391  for (long unsigned int it = 0; it < m_robot_util->m_nbJoints; it++)
392  ss << m_robot_util->get_name_from_id(it) << ", ";
393  SEND_MSG("Possible joint names are: " + ss.str(), MSG_TYPE_INFO);
394  return false;
395  }
396  id = (std::size_t)jid;
397  return true;
398 }
399 
400 bool ParameterServer::isJointInRange(std::size_t id, double q) {
401  const JointLimits &JL = m_robot_util->get_joint_limits_from_id((Index)id);
402 
403  double jl = JL.lower;
404  if (q < jl) {
405  SEND_MSG("Desired joint angle " + toString(q) +
406  " is smaller than lower limit: " + toString(jl),
408  return false;
409  }
410  double ju = JL.upper;
411  if (q > ju) {
412  SEND_MSG("Desired joint angle " + toString(q) +
413  " is larger than upper limit: " + toString(ju),
415  return false;
416  }
417  return true;
418 }
419 
420 /* ------------------------------------------------------------------- */
421 /* --- ENTITY -------------------------------------------------------- */
422 /* ------------------------------------------------------------------- */
423 
424 void ParameterServer::display(std::ostream &os) const {
425  os << "ParameterServer " << getName();
426 }
427 } // namespace sot
428 } // namespace dynamicgraph
SEND_MSG
#define SEND_MSG(msg, type)
dynamicgraph::sot::ParameterServer::setRightFootSoleXYZ
void setRightFootSoleXYZ(const dynamicgraph::Vector &)
Definition: parameter-server.cpp:319
dynamicgraph::sot::ParameterServer::m_robot_util
RobotUtilShrPtr m_robot_util
Definition: parameter-server.hh:137
dynamicgraph::sot::ParameterServer::setJointLimitsFromId
void setJointLimitsFromId(const double &jointId, const double &lq, const double &uq)
Definition: parameter-server.cpp:275
dynamicgraph::sot::ParameterServer::setRightFootForceSensorXYZ
void setRightFootForceSensorXYZ(const dynamicgraph::Vector &)
Definition: parameter-server.cpp:329
dynamicgraph::sot::createRobotUtil
RobotUtilShrPtr createRobotUtil(std::string &robotName)
Definition: robot-utils.cpp:536
dynamicgraph
makeCommandReturnType1
CommandReturnType1< E, ReturnType, T > * makeCommandReturnType1(E &entity, boost::function< ReturnType(const T &)> function, const std::string &docString)
dynamicgraph::sot::ParameterServer::init_simple
void init_simple(const double &dt)
Definition: parameter-server.cpp:207
dynamicgraph::sot::ParameterServer::setJoints
void setJoints(const dynamicgraph::Vector &)
Definition: parameter-server.cpp:311
dynamicgraph::command
dynamicgraph::sot::ParameterServer::convertJointNameToJointId
bool convertJointNameToJointId(const std::string &name, std::size_t &id)
Definition: parameter-server.cpp:383
dynamicgraph::Entity
dynamicgraph::sot::Index
Eigen::VectorXd::Index Index
Definition: robot-utils.hh:39
dynamicgraph::sot::ParameterServer::setHandFrameName
void setHandFrameName(const std::string &, const std::string &)
Definition: parameter-server.cpp:354
dynamicgraph::toString
std::string toString(const Eigen::MatrixBase< T > &v, const int precision=3, const int width=-1, const std::string separator=", ")
dynamicgraph::sot::ExceptionTools
Definition: exception-tools.hh:29
docCommandVoid0
std::string docCommandVoid0(const std::string &doc)
dynamicgraph::Entity::name
std::string name
parameter-server.hh
dynamicgraph::sot::JointLimits::upper
double upper
Definition: robot-utils.hh:31
dynamicgraph::sot::ParameterServer::display
virtual void display(std::ostream &os) const
Definition: parameter-server.cpp:424
dynamicgraph::sot::EntityClassName
FilterDifferentiator EntityClassName
Definition: filter-differentiator.cpp:49
dynamicgraph::sot::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(FeaturePosture, "FeaturePosture")
dynamicgraph::MSG_TYPE_INFO
MSG_TYPE_INFO
dynamicgraph::sot::getListOfRobots
std::shared_ptr< std::vector< std::string > > getListOfRobots()
Definition: robot-utils.cpp:508
dynamicgraph::MSG_TYPE_ERROR
MSG_TYPE_ERROR
dynamicgraph::Entity::getName
const std::string & getName() const
makeCommandVoid0
CommandVoid0< E > * makeCommandVoid0(E &entity, boost::function< void(E *)> function, const std::string &docString)
debug.hh
makeDirectGetter
DirectGetter< E, T > * makeDirectGetter(E &entity, T *ptr, const std::string &docString)
dynamicgraph::sot::ParameterServer::m_dt
double m_dt
true if the entity has been successfully initialized
Definition: parameter-server.hh:140
docCommandVoid1
std::string docCommandVoid1(const std::string &doc, const std::string &type)
localName
std::string localName("robot_test")
SEND_WARNING_STREAM_MSG
#define SEND_WARNING_STREAM_MSG(msg)
dynamicgraph::sot::ParameterServer::setForceLimitsFromId
void setForceLimitsFromId(const double &jointId, const dynamicgraph::Vector &lq, const dynamicgraph::Vector &uq)
Command related to ForceUtil.
Definition: parameter-server.cpp:286
dynamicgraph::sot::RefVoidRobotUtil
RobotUtilShrPtr RefVoidRobotUtil()
Definition: robot-utils.cpp:44
docCommandVoid3
std::string docCommandVoid3(const std::string &doc, const std::string &type1, const std::string &type2, const std::string &type3)
dynamicgraph::sot::ParameterServer::setImuJointName
void setImuJointName(const std::string &)
Definition: parameter-server.cpp:370
dynamicgraph::sot::JointLimits
Definition: robot-utils.hh:30
dynamicgraph::sot::ParameterServer::setFootFrameName
void setFootFrameName(const std::string &, const std::string &)
Definition: parameter-server.cpp:340
docDirectSetter
std::string docDirectSetter(const std::string &name, const std::string &type)
q
q
dynamicgraph::Vector
Eigen::VectorXd Vector
dynamicgraph::sot::ParameterServer::setForceNameToForceId
void setForceNameToForceId(const std::string &forceName, const double &forceId)
Definition: parameter-server.cpp:298
makeCommandVoid2
CommandVoid2< E, T1, T2 > * makeCommandVoid2(E &entity, boost::function< void(const T1 &, const T2 &)> function, const std::string &docString)
docCommandVoid2
std::string docCommandVoid2(const std::string &doc, const std::string &type1, const std::string &type2)
dynamicgraph::sot::ParameterServer::m_initSucceeded
bool m_initSucceeded
Definition: parameter-server.hh:139
dynamicgraph::sot::getRobotUtil
RobotUtilShrPtr getRobotUtil(std::string &robotName)
Definition: robot-utils.cpp:522
dynamicgraph::sot::ParameterServer::m_emergency_stop_triggered
bool m_emergency_stop_triggered
control loop time period
Definition: parameter-server.hh:141
dynamicgraph::sot::JointLimits::lower
double lower
Definition: robot-utils.hh:32
dynamicgraph::sot::ParameterServer::setNameToId
void setNameToId(const std::string &jointName, const double &jointId)
Commands related to joint name and joint id.
Definition: parameter-server.cpp:265
exception-tools.hh
test-parameter-server.dt
float dt
Definition: test-parameter-server.py:14
dynamicgraph::Entity::addCommand
void addCommand(const std::string &name, command::Command *command)
makeCommandVoid3
CommandVoid3< E, T1, T2, T3 > * makeCommandVoid3(E &entity, boost::function< void(E *, const T1 &, const T2 &, const T3 &)> function, const std::string &docString)
all-commands.h
dynamicgraph::sot::ParameterServer::init
void init(const double &dt, const std::string &urdfFile, const std::string &robotRef)
Definition: parameter-server.cpp:242
dynamicgraph::sot::ParameterServer::isJointInRange
bool isJointInRange(std::size_t id, double q)
Definition: parameter-server.cpp:400
dynamicgraph::sot::ParameterServer::displayRobotUtil
void displayRobotUtil()
Definition: parameter-server.cpp:378
makeCommandVoid1
CommandVoid1< E, T > * makeCommandVoid1(E &entity, boost::function< void(const T &)> function, const std::string &docString)
compile.name
name
Definition: compile.py:23
dynamicgraph::sot::isNameInRobotUtil
bool isNameInRobotUtil(std::string &robotName)
Definition: robot-utils.cpp:529
dynamicgraph::sot::ParameterServer::ParameterServer
ParameterServer(const std::string &name)
Definition: parameter-server.cpp:55


sot-core
Author(s): Olivier Stasse, ostasse@laas.fr
autogenerated on Tue Oct 24 2023 02:26:31