sot-talos-balance  2.0.5
Collection of dynamic-graph entities aimed at implementing balance control on talos.
ft-calibration.hh
Go to the documentation of this file.
1 /*
2  * Copyright 2019
3  * LAAS-CNRS
4  * F. Bailly
5  * T. Flayols
6  */
7 
8 #ifndef __sot_talos_balance_ft_calibration_H__
9 #define __sot_talos_balance_ft_calibration_H__
10 
11 /* --------------------------------------------------------------------- */
12 /* --- API ------------------------------------------------------------- */
13 /* --------------------------------------------------------------------- */
14 
15 #if defined(WIN32)
16 #if defined(__sot_talos_balance_ft_calibration_H__)
17 #define SOTFTCALIBRATION_EXPORT __declspec(dllexport)
18 #else
19 #define SOTFTCALIBRATION_EXPORT __declspec(dllimport)
20 #endif
21 #else
22 #define SOTFTCALIBRATION_EXPORT
23 #endif
24 
25 /* --------------------------------------------------------------------- */
26 /* --- INCLUDE --------------------------------------------------------- */
27 /* --------------------------------------------------------------------- */
28 
29 #include <pinocchio/fwd.hpp>
30 
31 // include pinocchio first
32 
33 #include <dynamic-graph/real-time-logger.h>
34 #include <dynamic-graph/signal-helper.h>
35 
36 #include <map>
37 #include <sot/core/matrix-geometry.hh>
38 #include <sot/core/robot-utils.hh>
40 
41 #include "boost/assign.hpp"
42 
43 namespace dynamicgraph {
44 namespace sot {
45 namespace talos_balance {
46 
47 /* --------------------------------------------------------------------- */
48 /* --- CLASS ----------------------------------------------------------- */
49 /* --------------------------------------------------------------------- */
50 
51 class SOTFTCALIBRATION_EXPORT FtCalibration : public ::dynamicgraph::Entity {
52  // typedef FtCalibration EntityClassName;
53  DYNAMIC_GRAPH_ENTITY_DECL();
54 
55  public:
56  /* --- CONSTRUCTOR ---- */
57  FtCalibration(const std::string &name);
59  void init(const std::string &robotRef);
60 
61  /* --- SIGNALS --- */
62  DECLARE_SIGNAL_IN(right_foot_force_in, dynamicgraph::Vector);
63  DECLARE_SIGNAL_IN(left_foot_force_in, dynamicgraph::Vector);
64  DECLARE_SIGNAL_OUT(right_foot_force_out, dynamicgraph::Vector);
65  DECLARE_SIGNAL_OUT(left_foot_force_out, dynamicgraph::Vector);
66 
67  /* --- COMMANDS --- */
68 
70  void setRightFootWeight(const double &rightW);
71  void setLeftFootWeight(const double &leftW);
72 
75  void calibrateFeetSensor();
76 
77  void displayRobotUtil();
78 
79  /* --- ENTITY INHERITANCE --- */
80  virtual void display(std::ostream &os) const;
81 
82  /* --- TYPEDEFS ---- */
83  typedef Eigen::Matrix<double, 6, 1> Vector6d;
84 
85  protected:
86  RobotUtilShrPtr m_robot_util;
87  int m_right_calibration_iter =
88  -1;
89  int m_left_calibration_iter =
91  -1;
92  Vector6d
95  Vector6d
98  Vector6d m_left_FT_offset_calibration_sum;
100  bool
103  Vector6d
104  m_right_foot_weight; // weight of the right feet underneath the ft sensor
105  Vector6d
106  m_left_foot_weight; // weight of the left feet underneath the ft sensor
107 
108 }; // class FtCalibration
109 
110 } // namespace talos_balance
111 } // namespace sot
112 } // namespace dynamicgraph
113 
114 #endif // #ifndef __sot_talos_balance_ft_calibration_H__
dynamicgraph::sot::talos_balance::FtCalibration::m_left_FT_offset
Vector6d m_left_FT_offset
Offset or bias to be removed from Right FT sensor.
Definition: ft-calibration.hh:96
dynamicgraph::sot::talos_balance::FtCalibration::m_right_FT_offset
Vector6d m_right_FT_offset
Definition: ft-calibration.hh:94
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::FtCalibration::Vector6d
Eigen::Matrix< double, 6, 1 > Vector6d
Definition: ft-calibration.hh:83
robot-wrapper.hh
dynamicgraph::sot::talos_balance::FtCalibration::m_right_FT_offset_calibration_sum
Vector6d m_right_FT_offset_calibration_sum
Offset or bias to be removed from Left FT sensor.
Definition: ft-calibration.hh:97
SOTFTCALIBRATION_EXPORT
#define SOTFTCALIBRATION_EXPORT
Definition: ft-calibration.hh:22
dynamicgraph::sot::talos_balance::math::Vector
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: fwd.hh:36
dynamicgraph::sot::talos_balance::FtCalibration::m_robot_util
RobotUtilShrPtr m_robot_util
Definition: ft-calibration.hh:86
dynamicgraph::sot::talos_balance::FtCalibration
Definition: ft-calibration.hh:51
dynamicgraph::sot::talos_balance::FtCalibration::m_initSucceeded
bool m_initSucceeded
Definition: ft-calibration.hh:102
dynamicgraph::sot::talos_balance::FtCalibration::m_left_foot_weight
Vector6d m_left_foot_weight
Definition: ft-calibration.hh:106
dynamicgraph::sot::talos_balance::FtCalibration::m_right_foot_weight
Vector6d m_right_foot_weight
true if the entity has been successfully initialized
Definition: ft-calibration.hh:104
sot_talos_balance.test.appli_dcm_zmp_control.name
name
Definition: appli_dcm_zmp_control.py:298