sot-talos-balance  2.0.5
Collection of dynamic-graph entities aimed at implementing balance control on talos.
FtCalibration Class Reference

#include <sot/talos_balance/ft-calibration.hh>

Inheritance diagram for FtCalibration:
Collaboration diagram for FtCalibration:

Public Types

typedef Eigen::Matrix< double, 6, 1 > Vector6d
 

Public Member Functions

 FtCalibration (const std::string &name)
 
void calibrateFeetSensor ()
 
 DECLARE_SIGNAL_IN (left_foot_force_in, dynamicgraph::Vector)
 
 DECLARE_SIGNAL_IN (right_foot_force_in, dynamicgraph::Vector)
 
 DECLARE_SIGNAL_OUT (left_foot_force_out, dynamicgraph::Vector)
 
 DECLARE_SIGNAL_OUT (right_foot_force_out, dynamicgraph::Vector)
 
virtual void display (std::ostream &os) const
 
void displayRobotUtil ()
 
void init (const std::string &robotRef)
 Initialize. More...
 
void setLeftFootWeight (const double &leftW)
 
void setRightFootWeight (const double &rightW)
 Commands for setting the feet weight. More...
 

Protected Attributes

bool m_initSucceeded
 
int m_left_calibration_iter
 
Vector6d m_left_foot_weight
 
Vector6d m_left_FT_offset
 Offset or bias to be removed from Right FT sensor. More...
 
Vector6d m_left_FT_offset_calibration_sum
 
int m_right_calibration_iter
 
Vector6d m_right_foot_weight
 true if the entity has been successfully initialized More...
 
Vector6d m_right_FT_offset
 
Vector6d m_right_FT_offset_calibration_sum
 Offset or bias to be removed from Left FT sensor. More...
 
RobotUtilShrPtr m_robot_util
 

Detailed Description

Definition at line 51 of file ft-calibration.hh.

Member Typedef Documentation

◆ Vector6d

typedef Eigen::Matrix<double, 6, 1> Vector6d

Definition at line 83 of file ft-calibration.hh.

Constructor & Destructor Documentation

◆ FtCalibration()

FtCalibration ( const std::string &  name)

Definition at line 41 of file ft-calibration.cpp.

Member Function Documentation

◆ calibrateFeetSensor()

void calibrateFeetSensor ( )

Command to calibrate the foot sensors when the robot is standing in the air with horizontal feet

Definition at line 167 of file ft-calibration.cpp.

◆ DECLARE_SIGNAL_IN() [1/2]

DECLARE_SIGNAL_IN ( left_foot_force_in  ,
dynamicgraph::Vector   
)

◆ DECLARE_SIGNAL_IN() [2/2]

DECLARE_SIGNAL_IN ( right_foot_force_in  ,
dynamicgraph::Vector   
)

◆ DECLARE_SIGNAL_OUT() [1/2]

DECLARE_SIGNAL_OUT ( left_foot_force_out  ,
dynamicgraph::Vector   
)

◆ DECLARE_SIGNAL_OUT() [2/2]

DECLARE_SIGNAL_OUT ( right_foot_force_out  ,
dynamicgraph::Vector   
)

◆ display()

void display ( std::ostream &  os) const
virtual

Definition at line 183 of file ft-calibration.cpp.

◆ displayRobotUtil()

void displayRobotUtil ( )

◆ init()

void init ( const std::string &  robotRef)

Initialize.

Definition at line 75 of file ft-calibration.cpp.

◆ setLeftFootWeight()

void setLeftFootWeight ( const double &  leftW)

Definition at line 158 of file ft-calibration.cpp.

◆ setRightFootWeight()

void setRightFootWeight ( const double &  rightW)

Commands for setting the feet weight.

Definition at line 149 of file ft-calibration.cpp.

Member Data Documentation

◆ m_initSucceeded

bool m_initSucceeded
protected

Variable used durring average computation of the offset

Definition at line 102 of file ft-calibration.hh.

◆ m_left_calibration_iter

int m_left_calibration_iter
protected
Initial value:
=
-1

Number of iteration left for calibration (-1= not cailbrated, 0=caibration done)

Definition at line 90 of file ft-calibration.hh.

◆ m_left_foot_weight

Vector6d m_left_foot_weight
protected

Definition at line 106 of file ft-calibration.hh.

◆ m_left_FT_offset

Vector6d m_left_FT_offset
protected

Offset or bias to be removed from Right FT sensor.

Definition at line 96 of file ft-calibration.hh.

◆ m_left_FT_offset_calibration_sum

Vector6d m_left_FT_offset_calibration_sum
protected

Variable used durring average computation of the offset

Definition at line 99 of file ft-calibration.hh.

◆ m_right_calibration_iter

int m_right_calibration_iter
protected
Initial value:
=
-1

Definition at line 87 of file ft-calibration.hh.

◆ m_right_foot_weight

Vector6d m_right_foot_weight
protected

true if the entity has been successfully initialized

Definition at line 104 of file ft-calibration.hh.

◆ m_right_FT_offset

Vector6d m_right_FT_offset
protected

Number of iteration left for calibration (-1= not cailbrated, 0=caibration done)

Definition at line 94 of file ft-calibration.hh.

◆ m_right_FT_offset_calibration_sum

Vector6d m_right_FT_offset_calibration_sum
protected

Offset or bias to be removed from Left FT sensor.

Definition at line 97 of file ft-calibration.hh.

◆ m_robot_util

RobotUtilShrPtr m_robot_util
protected

Definition at line 86 of file ft-calibration.hh.


The documentation for this class was generated from the following files: