| sot-talos-balance
    2.0.5
    Collection of dynamic-graph entities aimed at implementing balance control on talos. |  | 
 
 
 
Go to the documentation of this file.
    9 #ifndef __sot_talos_balance_ft_wrist_calibration_H__ 
   10 #define __sot_talos_balance_ft_wrist_calibration_H__ 
   17 #if defined(__sot_talos_balance_ft_wrist_calibration_H__) 
   18 #define SOTFTWRISTCALIBRATION_EXPORT __declspec(dllexport) 
   20 #define SOTFTWRISTCALIBRATION_EXPORT __declspec(dllimport) 
   23 #define SOTFTWRISTCALIBRATION_EXPORT 
   30 #include <pinocchio/fwd.hpp> 
   32 #include <dynamic-graph/real-time-logger.h> 
   33 #include <dynamic-graph/signal-helper.h> 
   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> 
   47 #include "boost/assign.hpp" 
   51 namespace talos_balance {
 
   58     : 
public ::dynamicgraph::Entity {
 
   60   DYNAMIC_GRAPH_ENTITY_DECL();
 
   66   void init(
const std::string &robotRef);
 
   85   void calibrateWristSensor();
 
   92   void setRemoveWeight(
const bool &removeWeight);
 
   94   void displayRobotUtil();
 
   97   virtual void display(std::ostream &os) 
const;
 
  116   int m_rightCalibrationIter = -2;
 
  119   int m_leftCalibrationIter = -2;
 
  151 #endif  // #ifndef __sot_talos_balance_ft_wrist_calibration_H__ 
  
 
Vector6d m_right_FT_offset
Offset or bias to be removed from Right FT sensor.
bool m_initSucceeded
true if the entity has been successfully initialized
Vector6d m_right_weight_calibration_sum
Variable used during average computation of the weight.
bool m_removeWeight
If true, the weight of the end effector is removed from the force.
Vector6d m_right_FT_offset_calibration_sum
Variable used during average computation of the offset.
Eigen::Matrix< double, 3, 1 > Vector3d
Vector3d m_rightLeverArm
right hand lever arm
Vector6d m_left_FT_offset
Offset or bias to be removed from Left FT sensor.
RobotUtilShrPtr m_robot_util
Robot Util instance to get the sensor frame.
Vector6d m_left_weight_calibration_sum
Variable used during average computation of the weight.
#define SOTFTWRISTCALIBRATION_EXPORT
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
pinocchio::FrameIndex m_rightSensorId
Id of the force sensor frame.
Vector6d m_leftHandWeight
weight of the left hand
Vector6d m_rightHandWeight
weight of the right hand
Eigen::Matrix< double, 6, 1 > Vector6d
Vector3d m_leftLeverArm
left hand lever arm
pinocchio::FrameIndex m_leftSensorId
Id of the joint of the end-effector.
pinocchio::Model m_model
Pinocchio robot model.
pinocchio::Data * m_data
Pinocchio robot data.
Vector6d m_left_FT_offset_calibration_sum
Variable used during average computation of the offset.