8 #ifndef __sot_talos_balance_ft_calibration_H__
9 #define __sot_talos_balance_ft_calibration_H__
16 #if defined(__sot_talos_balance_ft_calibration_H__)
17 #define SOTFTCALIBRATION_EXPORT __declspec(dllexport)
19 #define SOTFTCALIBRATION_EXPORT __declspec(dllimport)
22 #define SOTFTCALIBRATION_EXPORT
29 #include <pinocchio/fwd.hpp>
33 #include <dynamic-graph/real-time-logger.h>
34 #include <dynamic-graph/signal-helper.h>
37 #include <sot/core/matrix-geometry.hh>
38 #include <sot/core/robot-utils.hh>
41 #include "boost/assign.hpp"
45 namespace talos_balance {
53 DYNAMIC_GRAPH_ENTITY_DECL();
59 void init(
const std::string &robotRef);
70 void setRightFootWeight(
const double &rightW);
71 void setLeftFootWeight(
const double &leftW);
75 void calibrateFeetSensor();
80 virtual void display(std::ostream &os)
const;
87 int m_right_calibration_iter =
90 int m_left_calibration_iter =
Eigen::Matrix< double, 6, 1 > Vector6d
DECLARE_SIGNAL_IN(left_foot_force_in, dynamicgraph::Vector)
Vector6d m_left_foot_weight
DECLARE_SIGNAL_OUT(left_foot_force_out, dynamicgraph::Vector)
RobotUtilShrPtr m_robot_util
Vector6d m_left_FT_offset_calibration_sum
DECLARE_SIGNAL_IN(right_foot_force_in, dynamicgraph::Vector)
Vector6d m_right_FT_offset_calibration_sum
Offset or bias to be removed from Left FT sensor.
Vector6d m_right_FT_offset
DECLARE_SIGNAL_OUT(right_foot_force_out, dynamicgraph::Vector)
Vector6d m_left_FT_offset
Offset or bias to be removed from Right FT sensor.
Vector6d m_right_foot_weight
true if the entity has been successfully initialized
#define SOTFTCALIBRATION_EXPORT
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector