sot-torque-control  1.6.5
Collection of dynamic-graph entities aimed at implementing torque control on different robots.
base-estimator.hh
Go to the documentation of this file.
1 /*
2  * Copyright 2017, Thomas Flayols, LAAS-CNRS
3  *
4  */
5 
6 #ifndef __sot_torque_control_base_estimator_H__
7 #define __sot_torque_control_base_estimator_H__
8 
9 /* --------------------------------------------------------------------- */
10 /* --- API ------------------------------------------------------------- */
11 /* --------------------------------------------------------------------- */
12 
13 #if defined(WIN32)
14 #if defined(base_estimator_EXPORTS)
15 #define SOTBASEESTIMATOR_EXPORT __declspec(dllexport)
16 #else
17 #define SOTBASEESTIMATOR_EXPORT __declspec(dllimport)
18 #endif
19 #else
20 #define SOTBASEESTIMATOR_EXPORT
21 #endif
22 
23 /* --------------------------------------------------------------------- */
24 /* --- INCLUDE --------------------------------------------------------- */
25 /* --------------------------------------------------------------------- */
26 
27 #include <pinocchio/fwd.hpp>
28 
29 // include pinocchio first
30 
31 #include <map>
32 
33 #include "boost/assign.hpp"
34 // #include <boost/random/normal_distribution.hpp>
35 #include <boost/math/distributions/normal.hpp> // for normal_distribution
36 
37 /* Pinocchio */
38 #include <pinocchio/algorithm/kinematics.hpp>
39 #include <pinocchio/multibody/model.hpp>
40 #include <pinocchio/parsers/urdf.hpp>
41 
42 /* HELPER */
43 #include <dynamic-graph/signal-helper.h>
44 
45 #include <sot/core/matrix-geometry.hh>
46 #include <sot/core/robot-utils.hh>
48 
49 namespace dynamicgraph {
50 namespace sot {
51 namespace torque_control {
52 
53 /* --------------------------------------------------------------------- */
54 /* --- CLASS ----------------------------------------------------------- */
55 /* --------------------------------------------------------------------- */
56 
58 void se3Interp(const pinocchio::SE3& s1, const pinocchio::SE3& s2,
59  const double alpha, pinocchio::SE3& s12);
60 
62 void rpyToMatrix(double r, double p, double y, Eigen::Matrix3d& R);
63 
65 void rpyToMatrix(const Eigen::Vector3d& rpy, Eigen::Matrix3d& R);
66 
68 void matrixToRpy(const Eigen::Matrix3d& M, Eigen::Vector3d& rpy);
69 
71 void quanternionMult(const Eigen::Vector4d& q1, const Eigen::Vector4d& q2,
72  Eigen::Vector4d& q12);
73 
75 void pointRotationByQuaternion(const Eigen::Vector3d& point,
76  const Eigen::Vector4d& quat,
77  Eigen::Vector3d& rotatedPoint);
78 
79 class SOTBASEESTIMATOR_EXPORT BaseEstimator : public ::dynamicgraph::Entity {
81  typedef pinocchio::SE3 SE3;
82  typedef Eigen::Vector2d Vector2;
83  typedef Eigen::Vector3d Vector3;
84  typedef Eigen::Vector4d Vector4;
85  typedef dynamicgraph::sot::Vector6d Vector6;
86  typedef dynamicgraph::sot::Vector7d Vector7;
87  typedef Eigen::Matrix3d Matrix3;
88  typedef boost::math::normal normal;
89 
90  DYNAMIC_GRAPH_ENTITY_DECL();
91 
92  public:
93  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
94 
95  /* --- CONSTRUCTOR ---- */
96  BaseEstimator(const std::string& name);
97 
98  void init(const double& dt, const std::string& urdfFile);
99 
100  void set_fz_stable_windows_size(const int& ws);
101  void set_alpha_w_filter(const double& a);
102  void set_alpha_DC_acc(const double& a);
103  void set_alpha_DC_vel(const double& a);
104  void reset_foot_positions();
105  void set_imu_weight(const double& w);
106  void set_zmp_std_dev_right_foot(const double& std_dev);
107  void set_zmp_std_dev_left_foot(const double& std_dev);
108  void set_normal_force_std_dev_right_foot(const double& std_dev);
109  void set_normal_force_std_dev_left_foot(const double& std_dev);
110  void set_stiffness_right_foot(const dynamicgraph::Vector& k);
111  void set_stiffness_left_foot(const dynamicgraph::Vector& k);
112  void set_right_foot_sizes(const dynamicgraph::Vector& s);
113  void set_left_foot_sizes(const dynamicgraph::Vector& s);
114  void set_zmp_margin_right_foot(const double& margin);
115  void set_zmp_margin_left_foot(const double& margin);
116  void set_normal_force_margin_right_foot(const double& margin);
117  void set_normal_force_margin_left_foot(const double& margin);
118 
119  void reset_foot_positions_impl(const Vector6& ftlf, const Vector6& ftrf);
120  void compute_zmp(const Vector6& w, Vector2& zmp);
121  double compute_zmp_weight(const Vector2& zmp, const Vector4& foot_sizes,
122  double std_dev, double margin);
123  double compute_force_weight(double fz, double std_dev, double margin);
124  void kinematics_estimation(const Vector6& ft, const Vector6& K,
125  const SE3& oMfs, const int foot_id, SE3& oMff,
126  SE3& oMfa, SE3& fsMff);
127 
128  /* --- SIGNALS --- */
129  DECLARE_SIGNAL_IN(joint_positions, dynamicgraph::Vector);
130  DECLARE_SIGNAL_IN(joint_velocities, dynamicgraph::Vector);
131  DECLARE_SIGNAL_IN(imu_quaternion, dynamicgraph::Vector);
132  DECLARE_SIGNAL_IN(forceLLEG, dynamicgraph::Vector);
133  DECLARE_SIGNAL_IN(forceRLEG, dynamicgraph::Vector);
134  DECLARE_SIGNAL_IN(
135  dforceLLEG,
136  dynamicgraph::Vector);
137  DECLARE_SIGNAL_IN(
138  dforceRLEG,
139  dynamicgraph::Vector);
140  DECLARE_SIGNAL_IN(
141  w_lf_in, double);
142  DECLARE_SIGNAL_IN(
143  w_rf_in, double);
144  DECLARE_SIGNAL_IN(
145  K_fb_feet_poses,
146  double);
147  DECLARE_SIGNAL_IN(lf_ref_xyzquat, dynamicgraph::Vector);
149  DECLARE_SIGNAL_IN(rf_ref_xyzquat, dynamicgraph::Vector);
150  DECLARE_SIGNAL_IN(accelerometer, dynamicgraph::Vector);
151  DECLARE_SIGNAL_IN(gyroscope, dynamicgraph::Vector);
152 
153  DECLARE_SIGNAL_INNER(kinematics_computations, dynamicgraph::Vector);
154 
155  DECLARE_SIGNAL_OUT(
156  q, dynamicgraph::Vector);
157  DECLARE_SIGNAL_OUT(v, dynamicgraph::Vector);
158  DECLARE_SIGNAL_OUT(
159  v_kin, dynamicgraph::Vector);
160  DECLARE_SIGNAL_OUT(
162  v_flex,
163  dynamicgraph::Vector);
164  DECLARE_SIGNAL_OUT(
166  v_imu,
167  dynamicgraph::Vector);
168  DECLARE_SIGNAL_OUT(
170  v_gyr, dynamicgraph::Vector);
171  DECLARE_SIGNAL_OUT(lf_xyzquat, dynamicgraph::Vector);
174  DECLARE_SIGNAL_OUT(rf_xyzquat, dynamicgraph::Vector);
175  DECLARE_SIGNAL_OUT(a_ac,
176  dynamicgraph::Vector);
177  DECLARE_SIGNAL_OUT(v_ac,
179  dynamicgraph::Vector);
180 
182  DECLARE_SIGNAL_OUT(
183  q_lf,
184  dynamicgraph::Vector);
185  DECLARE_SIGNAL_OUT(
186  q_rf,
187  dynamicgraph::Vector);
188  DECLARE_SIGNAL_OUT(
189  q_imu,
190  dynamicgraph::Vector);
191  DECLARE_SIGNAL_OUT(
192  w_lf, double);
193  DECLARE_SIGNAL_OUT(
194  w_rf, double);
195  DECLARE_SIGNAL_OUT(
196  w_lf_filtered,
197  double);
198  DECLARE_SIGNAL_OUT(
199  w_rf_filtered,
200  double);
201 
202  /* --- COMMANDS --- */
203  /* --- ENTITY INHERITANCE --- */
204  virtual void display(std::ostream& os) const;
205 
206  void sendMsg(const std::string& msg, MsgType t = MSG_TYPE_INFO,
207  const char* = "", int = 0) {
208  logger_.stream(t) << ("[" + name + "] " + msg) << '\n';
209  }
210 
211  protected:
212  bool
214  bool
216  double m_dt;
217  RobotUtilShrPtr m_robot_util;
218 
220  bool m_right_foot_is_stable;
222  int m_fz_stable_windows_size;
224  int m_lf_fz_stable_cpt;
226  int m_rf_fz_stable_cpt;
228 
230  /* Estimator parameters */
231  double m_w_imu;
233  double m_zmp_std_dev_lf;
235  double m_fz_std_dev_rf;
237  double m_fz_std_dev_lf;
239  Vector4 m_left_foot_sizes;
241  Vector4 m_right_foot_sizes;
243  double m_zmp_margin_lf;
246  double m_fz_margin_lf;
247  double m_fz_margin_rf;
248  Vector6 m_K_rf;
249  Vector6 m_K_lf;
250 
251  Eigen::VectorXd m_v_kin;
252  Eigen::VectorXd m_v_flex;
254  Eigen::VectorXd m_v_imu;
256  Eigen::VectorXd m_v_gyr;
258 
260  Vector3
262  Vector3 m_a_ac;
263 
265  double m_alpha_DC_acc;
266  double m_alpha_DC_vel;
268 
271 
274  double m_w_rf_filtered;
276 
278  pinocchio::Model m_model;
279  pinocchio::Data* m_data;
280  pinocchio::SE3
282  pinocchio::SE3
284  SE3 m_oMlfs;
285  SE3 m_oMrfs;
289  SE3 m_oMrfs_default_ref;
291  normal m_normal;
293 
295 
298 
299  pinocchio::FrameIndex m_right_foot_id;
300  pinocchio::FrameIndex m_left_foot_id;
301  pinocchio::FrameIndex m_IMU_body_id;
302 
303  Eigen::VectorXd
305  Eigen::VectorXd m_q_sot;
306  Eigen::VectorXd
308  Eigen::VectorXd m_v_sot;
309  Matrix3 m_oRchest;
310  Matrix3 m_oRff;
311 
312  /* Filter buffers*/
313  Vector3 m_last_vel;
314  Vector3 m_last_DCvel;
315  Vector3 m_last_DCacc;
316 
317 }; // class BaseEstimator
318 
319 } // namespace torque_control
320 } // namespace sot
321 } // namespace dynamicgraph
322 
323 #endif // #ifndef __sot_torque_control_free_flyer_locator_H__
dynamicgraph::sot::torque_control::BaseEstimator::m_fz_margin_rf
double m_fz_margin_rf
margin used for computing normal force weight
Definition: base-estimator.hh:247
dynamicgraph::sot::torque_control::Vector3
Eigen::Matrix< double, 3, 1 > Vector3
Definition: admittance-controller.cpp:53
dynamicgraph::sot::torque_control::BaseEstimator::m_oRchest
Matrix3 m_oRchest
robot velocities according to SoT convention
Definition: base-estimator.hh:309
dynamicgraph::sot::torque_control::pointRotationByQuaternion
void pointRotationByQuaternion(const Eigen::Vector3d &point, const Eigen::Vector4d &quat, Eigen::Vector3d &rotatedPoint)
Definition: base-estimator.cpp:67
dynamicgraph::sot::torque_control::BaseEstimator::m_K_lf
Vector6 m_K_lf
6d stiffness of right foot spring
Definition: base-estimator.hh:249
dynamicgraph::sot::torque_control::BaseEstimator::m_data
pinocchio::Data * m_data
Pinocchio robot model.
Definition: base-estimator.hh:279
dynamicgraph::sot::torque_control::BaseEstimator::m_robot_util
RobotUtilShrPtr m_robot_util
sampling time step
Definition: base-estimator.hh:217
dynamicgraph::sot::torque_control::BaseEstimator::m_initSucceeded
bool m_initSucceeded
Definition: base-estimator.hh:213
dynamicgraph::sot::torque_control::BaseEstimator::m_v_ac
Vector3 m_v_ac
Definition: base-estimator.hh:261
dynamicgraph::sot::torque_control::BaseEstimator::m_dt
double m_dt
true after the command resetFootPositions is called
Definition: base-estimator.hh:216
dynamicgraph
to read text file
Definition: treeview.dox:22
dynamicgraph::sot::torque_control::BaseEstimator::m_q_sot
Eigen::VectorXd m_q_sot
robot configuration according to pinocchio convention
Definition: base-estimator.hh:305
dynamicgraph::sot::torque_control::BaseEstimator::m_oMrfs
SE3 m_oMrfs
transformation from world to left foot sole
Definition: base-estimator.hh:285
vector-conversions.hh
dynamicgraph::sot::torque_control::BaseEstimator::m_oMrfs_xyzquat
Vector7 m_oMrfs_xyzquat
Definition: base-estimator.hh:287
dynamicgraph::sot::torque_control::BaseEstimator::m_w_imu
double m_w_imu
Definition: base-estimator.hh:231
dynamicgraph::sot::torque_control::rpyToMatrix
void rpyToMatrix(double r, double p, double y, Eigen::Matrix3d &R)
Definition: base-estimator.cpp:35
dynamicgraph::sot::torque_control::BaseEstimator::m_w_lf_filtered
double m_w_lf_filtered
Definition: base-estimator.hh:273
dynamicgraph::sot::torque_control::BaseEstimator::m_alpha_DC_acc
double m_alpha_DC_acc
Definition: base-estimator.hh:265
dynamicgraph::sot::torque_control::BaseEstimator::m_reset_foot_pos
bool m_reset_foot_pos
true if the entity has been successfully initialized
Definition: base-estimator.hh:215
dynamicgraph::sot::torque_control::BaseEstimator
Definition: base-estimator.hh:79
dynamicgraph::sot::torque_control::BaseEstimator::sendMsg
void sendMsg(const std::string &msg, MsgType t=MSG_TYPE_INFO, const char *="", int=0)
Definition: base-estimator.hh:206
dynamicgraph::sot::torque_control::BaseEstimator::m_oMlfs_xyzquat
Vector7 m_oMlfs_xyzquat
transformation from world to right foot sole
Definition: base-estimator.hh:286
dynamicgraph::sot::torque_control::BaseEstimator::m_zmp_std_dev_rf
double m_zmp_std_dev_rf
weight of IMU for sensor fusion
Definition: base-estimator.hh:232
dynamicgraph::sot::torque_control::BaseEstimator::m_v_kin
Eigen::VectorXd m_v_kin
6d stiffness of left foot spring
Definition: base-estimator.hh:251
dynamicgraph::sot::torque_control::BaseEstimator::m_v_pin
Eigen::VectorXd m_v_pin
robot configuration according to SoT convention
Definition: base-estimator.hh:307
SOTBASEESTIMATOR_EXPORT
#define SOTBASEESTIMATOR_EXPORT
Definition: base-estimator.hh:20
dynamicgraph::sot::torque_control::quanternionMult
void quanternionMult(const Eigen::Vector4d &q1, const Eigen::Vector4d &q2, Eigen::Vector4d &q12)
Definition: base-estimator.cpp:59
torque_control
Definition: __init__.py:1
dynamicgraph::sot::torque_control::BaseEstimator::m_last_vel
Vector3 m_last_vel
base orientation in the world
Definition: base-estimator.hh:313
dynamicgraph::sot::torque_control::BaseEstimator::m_left_foot_is_stable
bool m_left_foot_is_stable
Definition: base-estimator.hh:219
dynamicgraph::sot::torque_control::BaseEstimator::m_q_pin
Eigen::VectorXd m_q_pin
Definition: base-estimator.hh:304
dynamicgraph::sot::torque_control::se3Interp
void se3Interp(const pinocchio::SE3 &s1, const pinocchio::SE3 &s2, const double alpha, pinocchio::SE3 &s12)
Definition: base-estimator.cpp:25
dynamicgraph::sot::torque_control::Vector2
Eigen::Matrix< double, 2, 1 > Vector2
Definition: inverse-dynamics-balance-controller.cpp:133
dynamicgraph::sot::torque_control::BaseEstimator::m_oMlfs_default_ref
SE3 m_oMlfs_default_ref
Definition: base-estimator.hh:288
dynamicgraph::sot::torque_control::BaseEstimator::m_oMff_rf
pinocchio::SE3 m_oMff_rf
world-to-base transformation obtained through left foot
Definition: base-estimator.hh:283
dynamicgraph::sot::torque_control::BaseEstimator::m_model
pinocchio::Model m_model
Definition: base-estimator.hh:278
dynamicgraph::sot::torque_control::Vector6
Eigen::Matrix< double, 6, 1 > Vector6
Definition: admittance-controller.cpp:54
dynamicgraph::sot::torque_control::BaseEstimator::m_K_rf
Vector6 m_K_rf
margin used for computing normal force weight
Definition: base-estimator.hh:248
dynamicgraph::sot::torque_control::EntityClassName
AdmittanceController EntityClassName
Definition: admittance-controller.cpp:51
dynamicgraph::sot::torque_control::BaseEstimator::m_a_ac
Vector3 m_a_ac
velocity of the base in the world with DC component removed
Definition: base-estimator.hh:262
dynamicgraph::sot::torque_control::BaseEstimator::m_last_DCacc
Vector3 m_last_DCacc
Definition: base-estimator.hh:315
dynamicgraph::sot::torque_control::BaseEstimator::m_sole_M_ftSens
SE3 m_sole_M_ftSens
Definition: base-estimator.hh:297
dynamicgraph::sot::torque_control::BaseEstimator::m_v_sot
Eigen::VectorXd m_v_sot
robot velocities according to pinocchio convention
Definition: base-estimator.hh:308
dynamicgraph::sot::torque_control::matrixToRpy
void matrixToRpy(const Eigen::Matrix3d &M, Eigen::Vector3d &rpy)
Definition: base-estimator.cpp:47
dynamicgraph::sot::torque_control::BaseEstimator::m_oMff_lf
pinocchio::SE3 m_oMff_lf
Pinocchio robot data.
Definition: base-estimator.hh:281
dynamicgraph::sot::torque_control::BaseEstimator::m_isFirstIterFlag
bool m_isFirstIterFlag
Normal distribution.
Definition: base-estimator.hh:294
dynamicgraph::sot::torque_control::BaseEstimator::m_oRff
Matrix3 m_oRff
chest orientation in the world from angular fusion
Definition: base-estimator.hh:310
dynamicgraph::sot::torque_control::BaseEstimator::m_last_DCvel
Vector3 m_last_DCvel
Definition: base-estimator.hh:314
dynamicgraph::sot::torque_control::BaseEstimator::m_zmp_margin_rf
double m_zmp_margin_rf
margin used for computing zmp weight
Definition: base-estimator.hh:245
dynamicgraph::sot::torque_control::BaseEstimator::m_fz_margin_lf
double m_fz_margin_lf
margin used for computing zmp weight
Definition: base-estimator.hh:246
dynamicgraph::sot::torque_control::BaseEstimator::m_right_foot_id
pinocchio::FrameIndex m_right_foot_id
foot sole to F/T sensor transformation
Definition: base-estimator.hh:299
dynamicgraph::sot::torque_control::BaseEstimator::m_alpha_w_filter
double m_alpha_w_filter
Definition: base-estimator.hh:270
dynamicgraph::sot::torque_control::BaseEstimator::m_IMU_body_id
pinocchio::FrameIndex m_IMU_body_id
Definition: base-estimator.hh:301
dynamicgraph::sot::torque_control::BaseEstimator::m_left_foot_id
pinocchio::FrameIndex m_left_foot_id
Definition: base-estimator.hh:300
dynamicgraph::sot::torque_control::BaseEstimator::m_oMlfs
SE3 m_oMlfs
world-to-base transformation obtained through right foot
Definition: base-estimator.hh:284