sot-talos-balance  2.0.5
Collection of dynamic-graph entities aimed at implementing balance control on talos.
ft-wrist-calibration.hh
Go to the documentation of this file.
1 /*
2  * Copyright 2019
3  * LAAS-CNRS
4  * F. Bailly
5  * T. Flayol
6  * F. Risbourg
7  */
8 
9 #ifndef __sot_talos_balance_ft_wrist_calibration_H__
10 #define __sot_talos_balance_ft_wrist_calibration_H__
11 
12 /* --------------------------------------------------------------------- */
13 /* --- API ------------------------------------------------------------- */
14 /* --------------------------------------------------------------------- */
15 
16 #if defined(WIN32)
17 #if defined(__sot_talos_balance_ft_wrist_calibration_H__)
18 #define SOTFTWRISTCALIBRATION_EXPORT __declspec(dllexport)
19 #else
20 #define SOTFTWRISTCALIBRATION_EXPORT __declspec(dllimport)
21 #endif
22 #else
23 #define SOTFTWRISTCALIBRATION_EXPORT
24 #endif
25 
26 /* --------------------------------------------------------------------- */
27 /* --- INCLUDE --------------------------------------------------------- */
28 /* --------------------------------------------------------------------- */
29 
30 #include <pinocchio/fwd.hpp>
31 // include pinocchio first
32 #include <dynamic-graph/real-time-logger.h>
33 #include <dynamic-graph/signal-helper.h>
34 
35 #include <map>
36 #include <pinocchio/algorithm/center-of-mass.hpp>
37 #include <pinocchio/algorithm/frames.hpp>
38 #include <pinocchio/algorithm/kinematics.hpp>
39 #include <pinocchio/multibody/model.hpp>
40 #include <pinocchio/parsers/urdf.hpp>
41 #include <pinocchio/spatial/motion.hpp>
42 #include <pinocchio/spatial/se3.hpp>
43 #include <sot/core/matrix-geometry.hh>
44 #include <sot/core/robot-utils.hh>
46 
47 #include "boost/assign.hpp"
48 
49 namespace dynamicgraph {
50 namespace sot {
51 namespace talos_balance {
52 
53 /* --------------------------------------------------------------------- */
54 /* --- CLASS ----------------------------------------------------------- */
55 /* --------------------------------------------------------------------- */
56 
58  : public ::dynamicgraph::Entity {
59  // typedef FtCalibration EntityClassName;
60  DYNAMIC_GRAPH_ENTITY_DECL();
61 
62  public:
63  /* --- CONSTRUCTOR ---- */
64  FtWristCalibration(const std::string &name);
66  void init(const std::string &robotRef);
67 
68  /* --- SIGNALS --- */
69  DECLARE_SIGNAL_IN(rightWristForceIn, dynamicgraph::Vector);
70  DECLARE_SIGNAL_IN(leftWristForceIn, dynamicgraph::Vector);
71  DECLARE_SIGNAL_IN(q, dynamicgraph::Vector);
72  DECLARE_SIGNAL_INNER(rightWeight, dynamicgraph::Vector);
73  DECLARE_SIGNAL_INNER(leftWeight, dynamicgraph::Vector);
74  DECLARE_SIGNAL_OUT(rightWristForceOut, dynamicgraph::Vector);
75  DECLARE_SIGNAL_OUT(leftWristForceOut, dynamicgraph::Vector);
76 
77  /* --- COMMANDS --- */
78 
80  void setRightHandConf(const double &rightW, const Vector &rightLeverArm);
81  void setLeftHandConf(const double &leftW, const Vector &leftLeverArm);
82 
85  void calibrateWristSensor();
86 
92  void setRemoveWeight(const bool &removeWeight);
93 
94  void displayRobotUtil();
95 
96  /* --- ENTITY INHERITANCE --- */
97  virtual void display(std::ostream &os) const;
98 
99  /* --- TYPEDEFS ---- */
100  typedef Eigen::Matrix<double, 6, 1> Vector6d;
101  typedef Eigen::Matrix<double, 3, 1> Vector3d;
102 
103  protected:
105  RobotUtilShrPtr m_robot_util;
107  pinocchio::Model m_model;
109  pinocchio::Data *m_data;
111  pinocchio::FrameIndex m_rightSensorId;
113  pinocchio::FrameIndex m_leftSensorId;
116  int m_rightCalibrationIter = -2;
119  int m_leftCalibrationIter = -2;
144 
145 }; // class FtWristCalibration
146 
147 } // namespace talos_balance
148 } // namespace sot
149 } // namespace dynamicgraph
150 
151 #endif // #ifndef __sot_talos_balance_ft_wrist_calibration_H__
sot_talos_balance.test.appli_admittance_end_effector.q
list q
Definition: appli_admittance_end_effector.py:30
dynamicgraph::sot::talos_balance::FtWristCalibration::m_right_FT_offset
Vector6d m_right_FT_offset
Offset or bias to be removed from Right FT sensor.
Definition: ft-wrist-calibration.hh:121
dynamicgraph::sot::talos_balance::FtWristCalibration::m_initSucceeded
bool m_initSucceeded
true if the entity has been successfully initialized
Definition: ft-wrist-calibration.hh:133
sot_talos_balance.test.appli_admittance_end_effector.sot
sot
Definition: appli_admittance_end_effector.py:117
dynamicgraph::sot::talos_balance::FtWristCalibration::m_right_weight_calibration_sum
Vector6d m_right_weight_calibration_sum
Variable used during average computation of the weight.
Definition: ft-wrist-calibration.hh:129
dynamicgraph
Definition: treeview.dox:24
dynamicgraph::sot::talos_balance::FtWristCalibration::m_removeWeight
bool m_removeWeight
If true, the weight of the end effector is removed from the force.
Definition: ft-wrist-calibration.hh:143
dynamicgraph::sot::talos_balance::FtWristCalibration::m_right_FT_offset_calibration_sum
Vector6d m_right_FT_offset_calibration_sum
Variable used during average computation of the offset.
Definition: ft-wrist-calibration.hh:125
dynamicgraph::sot::talos_balance::FtWristCalibration::Vector3d
Eigen::Matrix< double, 3, 1 > Vector3d
Definition: ft-wrist-calibration.hh:101
dynamicgraph::sot::talos_balance::FtWristCalibration::m_rightLeverArm
Vector3d m_rightLeverArm
right hand lever arm
Definition: ft-wrist-calibration.hh:139
dynamicgraph::sot::talos_balance::FtWristCalibration::m_left_FT_offset
Vector6d m_left_FT_offset
Offset or bias to be removed from Left FT sensor.
Definition: ft-wrist-calibration.hh:123
dynamicgraph::sot::talos_balance::FtWristCalibration
Definition: ft-wrist-calibration.hh:57
dynamicgraph::sot::talos_balance::FtWristCalibration::m_robot_util
RobotUtilShrPtr m_robot_util
Robot Util instance to get the sensor frame.
Definition: ft-wrist-calibration.hh:105
robot-wrapper.hh
dynamicgraph::sot::talos_balance::FtWristCalibration::m_left_weight_calibration_sum
Vector6d m_left_weight_calibration_sum
Variable used during average computation of the weight.
Definition: ft-wrist-calibration.hh:131
SOTFTWRISTCALIBRATION_EXPORT
#define SOTFTWRISTCALIBRATION_EXPORT
Definition: ft-wrist-calibration.hh:23
dynamicgraph::sot::talos_balance::math::Vector
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: fwd.hh:36
dynamicgraph::sot::talos_balance::FtWristCalibration::m_rightSensorId
pinocchio::FrameIndex m_rightSensorId
Id of the force sensor frame.
Definition: ft-wrist-calibration.hh:111
dynamicgraph::sot::talos_balance::FtWristCalibration::m_leftHandWeight
Vector6d m_leftHandWeight
weight of the left hand
Definition: ft-wrist-calibration.hh:137
dynamicgraph::sot::talos_balance::FtWristCalibration::m_rightHandWeight
Vector6d m_rightHandWeight
weight of the right hand
Definition: ft-wrist-calibration.hh:135
dynamicgraph::sot::talos_balance::FtWristCalibration::Vector6d
Eigen::Matrix< double, 6, 1 > Vector6d
Definition: ft-wrist-calibration.hh:100
dynamicgraph::sot::talos_balance::FtWristCalibration::m_leftLeverArm
Vector3d m_leftLeverArm
left hand lever arm
Definition: ft-wrist-calibration.hh:141
dynamicgraph::sot::talos_balance::FtWristCalibration::m_leftSensorId
pinocchio::FrameIndex m_leftSensorId
Id of the joint of the end-effector.
Definition: ft-wrist-calibration.hh:113
dynamicgraph::sot::talos_balance::FtWristCalibration::m_model
pinocchio::Model m_model
Pinocchio robot model.
Definition: ft-wrist-calibration.hh:107
sot_talos_balance.talos.ft_wrist_calibration_conf.rightLeverArm
list rightLeverArm
Definition: ft_wrist_calibration_conf.py:5
sot_talos_balance.test.appli_dcm_zmp_control.name
name
Definition: appli_dcm_zmp_control.py:298
sot_talos_balance.talos.ft_wrist_calibration_conf.leftLeverArm
list leftLeverArm
Definition: ft_wrist_calibration_conf.py:4
dynamicgraph::sot::talos_balance::FtWristCalibration::m_data
pinocchio::Data * m_data
Pinocchio robot data.
Definition: ft-wrist-calibration.hh:109
dynamicgraph::sot::talos_balance::FtWristCalibration::m_left_FT_offset_calibration_sum
Vector6d m_left_FT_offset_calibration_sum
Variable used during average computation of the offset.
Definition: ft-wrist-calibration.hh:127