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

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

Inheritance diagram for FtWristCalibration:
Collaboration diagram for FtWristCalibration:

Public Types

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

Public Member Functions

 FtWristCalibration (const std::string &name)
 
void calibrateWristSensor ()
 
 DECLARE_SIGNAL_IN (leftWristForceIn, dynamicgraph::Vector)
 
 DECLARE_SIGNAL_IN (q, dynamicgraph::Vector)
 
 DECLARE_SIGNAL_IN (rightWristForceIn, dynamicgraph::Vector)
 
 DECLARE_SIGNAL_INNER (leftWeight, dynamicgraph::Vector)
 
 DECLARE_SIGNAL_INNER (rightWeight, dynamicgraph::Vector)
 
 DECLARE_SIGNAL_OUT (leftWristForceOut, dynamicgraph::Vector)
 
 DECLARE_SIGNAL_OUT (rightWristForceOut, dynamicgraph::Vector)
 
virtual void display (std::ostream &os) const
 
void displayRobotUtil ()
 
void init (const std::string &robotRef)
 Initialize. More...
 
void setLeftHandConf (const double &leftW, const Vector &leftLeverArm)
 
void setRemoveWeight (const bool &removeWeight)
 Set to true if you want to remove the weight from the force. More...
 
void setRightHandConf (const double &rightW, const Vector &rightLeverArm)
 Commands for setting the hand weight. More...
 

Protected Attributes

pinocchio::Data * m_data
 Pinocchio robot data. More...
 
bool m_initSucceeded
 true if the entity has been successfully initialized More...
 
Vector6d m_left_FT_offset
 Offset or bias to be removed from Left FT sensor. More...
 
Vector6d m_left_FT_offset_calibration_sum
 Variable used during average computation of the offset. More...
 
Vector6d m_left_weight_calibration_sum
 Variable used during average computation of the weight. More...
 
int m_leftCalibrationIter = -2
 
Vector6d m_leftHandWeight
 weight of the left hand More...
 
Vector3d m_leftLeverArm
 left hand lever arm More...
 
pinocchio::FrameIndex m_leftSensorId
 Id of the joint of the end-effector. More...
 
pinocchio::Model m_model
 Pinocchio robot model. More...
 
bool m_removeWeight
 If true, the weight of the end effector is removed from the force. More...
 
Vector6d m_right_FT_offset
 Offset or bias to be removed from Right FT sensor. More...
 
Vector6d m_right_FT_offset_calibration_sum
 Variable used during average computation of the offset. More...
 
Vector6d m_right_weight_calibration_sum
 Variable used during average computation of the weight. More...
 
int m_rightCalibrationIter = -2
 
Vector6d m_rightHandWeight
 weight of the right hand More...
 
Vector3d m_rightLeverArm
 right hand lever arm More...
 
pinocchio::FrameIndex m_rightSensorId
 Id of the force sensor frame. More...
 
RobotUtilShrPtr m_robot_util
 Robot Util instance to get the sensor frame. More...
 

Detailed Description

Definition at line 57 of file ft-wrist-calibration.hh.

Member Typedef Documentation

◆ Vector3d

typedef Eigen::Matrix<double, 3, 1> Vector3d

Definition at line 101 of file ft-wrist-calibration.hh.

◆ Vector6d

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

Definition at line 100 of file ft-wrist-calibration.hh.

Constructor & Destructor Documentation

◆ FtWristCalibration()

FtWristCalibration ( const std::string &  name)

Definition at line 43 of file ft-wrist-calibration.cpp.

Member Function Documentation

◆ calibrateWristSensor()

void calibrateWristSensor ( )

Command to calibrate the wrist sensors when the robot is in half sitting with the hands aligned

Definition at line 272 of file ft-wrist-calibration.cpp.

◆ DECLARE_SIGNAL_IN() [1/3]

DECLARE_SIGNAL_IN ( leftWristForceIn  ,
dynamicgraph::Vector   
)

◆ DECLARE_SIGNAL_IN() [2/3]

DECLARE_SIGNAL_IN ( ,
dynamicgraph::Vector   
)

◆ DECLARE_SIGNAL_IN() [3/3]

DECLARE_SIGNAL_IN ( rightWristForceIn  ,
dynamicgraph::Vector   
)

◆ DECLARE_SIGNAL_INNER() [1/2]

DECLARE_SIGNAL_INNER ( leftWeight  ,
dynamicgraph::Vector   
)

◆ DECLARE_SIGNAL_INNER() [2/2]

DECLARE_SIGNAL_INNER ( rightWeight  ,
dynamicgraph::Vector   
)

◆ DECLARE_SIGNAL_OUT() [1/2]

DECLARE_SIGNAL_OUT ( leftWristForceOut  ,
dynamicgraph::Vector   
)

◆ DECLARE_SIGNAL_OUT() [2/2]

DECLARE_SIGNAL_OUT ( rightWristForceOut  ,
dynamicgraph::Vector   
)

◆ display()

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

Definition at line 292 of file ft-wrist-calibration.cpp.

◆ displayRobotUtil()

void displayRobotUtil ( )

◆ init()

void init ( const std::string &  robotRef)

Initialize.

Definition at line 90 of file ft-wrist-calibration.cpp.

◆ setLeftHandConf()

void setLeftHandConf ( const double &  leftW,
const Vector &  leftLeverArm 
)

Definition at line 261 of file ft-wrist-calibration.cpp.

◆ setRemoveWeight()

void setRemoveWeight ( const bool &  removeWeight)

Set to true if you want to remove the weight from the force.

Parameters
[in]removeWeightBoolean used to remove the weight

Definition at line 282 of file ft-wrist-calibration.cpp.

◆ setRightHandConf()

void setRightHandConf ( const double &  rightW,
const Vector &  rightLeverArm 
)

Commands for setting the hand weight.

Definition at line 250 of file ft-wrist-calibration.cpp.

Member Data Documentation

◆ m_data

pinocchio::Data* m_data
protected

Pinocchio robot data.

Definition at line 109 of file ft-wrist-calibration.hh.

◆ m_initSucceeded

bool m_initSucceeded
protected

true if the entity has been successfully initialized

Definition at line 133 of file ft-wrist-calibration.hh.

◆ m_left_FT_offset

Vector6d m_left_FT_offset
protected

Offset or bias to be removed from Left FT sensor.

Definition at line 123 of file ft-wrist-calibration.hh.

◆ m_left_FT_offset_calibration_sum

Vector6d m_left_FT_offset_calibration_sum
protected

Variable used during average computation of the offset.

Definition at line 127 of file ft-wrist-calibration.hh.

◆ m_left_weight_calibration_sum

Vector6d m_left_weight_calibration_sum
protected

Variable used during average computation of the weight.

Definition at line 131 of file ft-wrist-calibration.hh.

◆ m_leftCalibrationIter

int m_leftCalibrationIter = -2
protected

Number of iteration for right calibration (-2 = not calibrated, -1 = caibration done)

Definition at line 119 of file ft-wrist-calibration.hh.

◆ m_leftHandWeight

Vector6d m_leftHandWeight
protected

weight of the left hand

Definition at line 137 of file ft-wrist-calibration.hh.

◆ m_leftLeverArm

Vector3d m_leftLeverArm
protected

left hand lever arm

Definition at line 141 of file ft-wrist-calibration.hh.

◆ m_leftSensorId

pinocchio::FrameIndex m_leftSensorId
protected

Id of the joint of the end-effector.

Definition at line 113 of file ft-wrist-calibration.hh.

◆ m_model

pinocchio::Model m_model
protected

Pinocchio robot model.

Definition at line 107 of file ft-wrist-calibration.hh.

◆ m_removeWeight

bool m_removeWeight
protected

If true, the weight of the end effector is removed from the force.

Definition at line 143 of file ft-wrist-calibration.hh.

◆ m_right_FT_offset

Vector6d m_right_FT_offset
protected

Offset or bias to be removed from Right FT sensor.

Definition at line 121 of file ft-wrist-calibration.hh.

◆ m_right_FT_offset_calibration_sum

Vector6d m_right_FT_offset_calibration_sum
protected

Variable used during average computation of the offset.

Definition at line 125 of file ft-wrist-calibration.hh.

◆ m_right_weight_calibration_sum

Vector6d m_right_weight_calibration_sum
protected

Variable used during average computation of the weight.

Definition at line 129 of file ft-wrist-calibration.hh.

◆ m_rightCalibrationIter

int m_rightCalibrationIter = -2
protected

Number of iteration for right calibration (-2 = not calibrated, -1 = caibration done)

Definition at line 116 of file ft-wrist-calibration.hh.

◆ m_rightHandWeight

Vector6d m_rightHandWeight
protected

weight of the right hand

Definition at line 135 of file ft-wrist-calibration.hh.

◆ m_rightLeverArm

Vector3d m_rightLeverArm
protected

right hand lever arm

Definition at line 139 of file ft-wrist-calibration.hh.

◆ m_rightSensorId

pinocchio::FrameIndex m_rightSensorId
protected

Id of the force sensor frame.

Definition at line 111 of file ft-wrist-calibration.hh.

◆ m_robot_util

RobotUtilShrPtr m_robot_util
protected

Robot Util instance to get the sensor frame.

Definition at line 105 of file ft-wrist-calibration.hh.


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