angle-estimator.h
Go to the documentation of this file.
1 /*
2  * Copyright 2010,
3  * François Bleibel,
4  * Olivier Stasse,
5  *
6  * CNRS/AIST
7  *
8  */
9 
10 #ifndef __SOT_ANGLE_ESTIMATOR_H__
11 #define __SOT_ANGLE_ESTIMATOR_H__
12 /* --------------------------------------------------------------------- */
13 /* --- API ------------------------------------------------------------- */
14 /* --------------------------------------------------------------------- */
15 
16 #if defined(WIN32)
17 #if defined(angle_estimator_EXPORTS)
18 #define SOTANGLEESTIMATOR_EXPORT __declspec(dllexport)
19 #else
20 #define SOTANGLEESTIMATOR_EXPORT __declspec(dllimport)
21 #endif
22 #else
23 #define SOTANGLEESTIMATOR_EXPORT
24 #endif
25 
26 /* --------------------------------------------------------------------- */
27 /* --- INCLUDE --------------------------------------------------------- */
28 /* --------------------------------------------------------------------- */
29 
30 /* Matrix */
32 
33 /* SOT */
34 #include <dynamic-graph/entity.h>
37 
39 
40 /* STD */
41 #include <string>
42 
43 namespace dynamicgraph {
44 namespace sot {
45 namespace dg = dynamicgraph;
46 
47 /* --------------------------------------------------------------------- */
48 /* --- CLASS ----------------------------------------------------------- */
49 /* --------------------------------------------------------------------- */
50 
52  public:
53  static const std::string CLASS_NAME;
54  virtual const std::string& getClassName(void) const { return CLASS_NAME; }
55 
56  public: /* --- CONSTRUCTION --- */
57  AngleEstimator(const std::string& name);
58  virtual ~AngleEstimator(void);
59 
60  public: /* --- SIGNAL --- */
62  sensorWorldRotationSIN; // estimate(worldRc)
64  sensorEmbeddedPositionSIN; // waistRchest
66  contactWorldPositionSIN; // estimate(worldRf)
70  anglesSOUT; // [ flex1 flex2 yaw_drift ]
72  flexibilitySOUT; // footRleg
74  driftSOUT; // Ryaw = worldRc est(wRc)^-1
78  waistWorldRotationSOUT; // worldRwaist
80  waistWorldPositionSOUT; // worldMwaist
82  waistWorldPoseRPYSOUT; // worldMwaist
83 
88 
89  public: /* --- FUNCTIONS --- */
90  dynamicgraph::Vector& computeAngles(dynamicgraph::Vector& res,
91  const sigtime_t& time);
92  MatrixRotation& computeFlexibilityFromAngles(MatrixRotation& res,
93  const sigtime_t& time);
94  MatrixRotation& computeDriftFromAngles(MatrixRotation& res,
95  const sigtime_t& time);
96  MatrixRotation& computeSensorWorldRotation(MatrixRotation& res,
97  const sigtime_t& time);
98  MatrixRotation& computeWaistWorldRotation(MatrixRotation& res,
99  const sigtime_t& time);
100  MatrixHomogeneous& computeWaistWorldPosition(MatrixHomogeneous& res,
101  const sigtime_t& time);
102  dynamicgraph::Vector& computeWaistWorldPoseRPY(dynamicgraph::Vector& res,
103  const sigtime_t& time);
104  dynamicgraph::Vector& compute_xff_dotSOUT(dynamicgraph::Vector& res,
105  const sigtime_t& time);
106  dynamicgraph::Vector& compute_qdotSOUT(dynamicgraph::Vector& res,
107  const sigtime_t& time);
108 
109  public: /* --- PARAMS --- */
110  void fromSensor(const bool& fs) { fromSensor_ = fs; }
111  bool fromSensor() const { return fromSensor_; }
112 
113  private:
115 };
116 
117 } /* namespace sot */
118 } /* namespace dynamicgraph */
119 
120 #endif // #ifndef __SOT_ANGLE_ESTIMATOR_H__
signal-ptr.h
dynamicgraph::sot::AngleEstimator::sensorWorldRotationSIN
dg::SignalPtr< MatrixRotation, sigtime_t > sensorWorldRotationSIN
Definition: angle-estimator.h:62
signal-time-dependent.h
dynamicgraph::sot::AngleEstimator::CLASS_NAME
static const std::string CLASS_NAME
Definition: angle-estimator.h:53
dynamicgraph::sot::AngleEstimator::contactEmbeddedPositionSIN
dg::SignalPtr< MatrixHomogeneous, sigtime_t > contactEmbeddedPositionSIN
Definition: angle-estimator.h:68
dynamicgraph::sot::AngleEstimator::qdotSOUT
dg::SignalTimeDependent< dynamicgraph::Vector, sigtime_t > qdotSOUT
Definition: angle-estimator.h:87
dynamicgraph::sot::AngleEstimator::fromSensor
void fromSensor(const bool &fs)
Definition: angle-estimator.h:110
dynamicgraph::sot::MatrixHomogeneous
Eigen::Transform< double, 3, Eigen::Affine > SOT_CORE_EXPORT MatrixHomogeneous
dynamicgraph::sot::AngleEstimator::flexibilitySOUT
dg::SignalTimeDependent< MatrixRotation, sigtime_t > flexibilitySOUT
Definition: angle-estimator.h:72
dynamicgraph::SignalPtr< MatrixRotation, sigtime_t >
dynamicgraph
matrix-geometry.hh
dynamicgraph::Entity
dynamicgraph::sot::AngleEstimator::fromSensor_
bool fromSensor_
Definition: angle-estimator.h:114
dynamicgraph::sot::AngleEstimator::sensorEmbeddedPositionSIN
dg::SignalPtr< MatrixHomogeneous, sigtime_t > sensorEmbeddedPositionSIN
Definition: angle-estimator.h:64
dynamicgraph::sot::AngleEstimator::waistWorldPositionSOUT
dg::SignalTimeDependent< MatrixHomogeneous, sigtime_t > waistWorldPositionSOUT
Definition: angle-estimator.h:80
dynamicgraph::sot::AngleEstimator::qdotSIN
dg::SignalPtr< dynamicgraph::Vector, sigtime_t > qdotSIN
Definition: angle-estimator.h:85
SOTANGLEESTIMATOR_EXPORT
#define SOTANGLEESTIMATOR_EXPORT
Definition: angle-estimator.h:23
dynamicgraph::sot::AngleEstimator::driftSOUT
dg::SignalTimeDependent< MatrixRotation, sigtime_t > driftSOUT
Definition: angle-estimator.h:74
dynamicgraph::sot::AngleEstimator::waistWorldRotationSOUT
dg::SignalTimeDependent< MatrixRotation, sigtime_t > waistWorldRotationSOUT
Definition: angle-estimator.h:78
dynamicgraph::Vector
Eigen::VectorXd Vector
dynamicgraph::sot::AngleEstimator
Definition: angle-estimator.h:51
dynamicgraph::sot::AngleEstimator::waistWorldPoseRPYSOUT
dg::SignalTimeDependent< dynamicgraph::Vector, sigtime_t > waistWorldPoseRPYSOUT
Definition: angle-estimator.h:82
dynamicgraph::sot::AngleEstimator::fromSensor
bool fromSensor() const
Definition: angle-estimator.h:111
linear-algebra.h
dynamicgraph::SignalTimeDependent< dynamicgraph::Vector, sigtime_t >
dynamicgraph::sot::AngleEstimator::xff_dotSOUT
dg::SignalTimeDependent< dynamicgraph::Vector, sigtime_t > xff_dotSOUT
Definition: angle-estimator.h:86
dynamicgraph::sot::AngleEstimator::jacobianSIN
dg::SignalPtr< dynamicgraph::Matrix, sigtime_t > jacobianSIN
Definition: angle-estimator.h:84
dynamicgraph::sot::AngleEstimator::getClassName
virtual const std::string & getClassName(void) const
Definition: angle-estimator.h:54
dynamicgraph::sot::MatrixRotation
Eigen::Matrix< double, 3, 3 > SOT_CORE_EXPORT MatrixRotation
dynamicgraph::sot::AngleEstimator::anglesSOUT
dg::SignalTimeDependent< dynamicgraph::Vector, sigtime_t > anglesSOUT
Definition: angle-estimator.h:70
dynamicgraph::sot::AngleEstimator::sensorWorldRotationSOUT
dg::SignalTimeDependent< MatrixRotation, sigtime_t > sensorWorldRotationSOUT
Definition: angle-estimator.h:76
dynamicgraph::sot::AngleEstimator::contactWorldPositionSIN
dg::SignalPtr< MatrixHomogeneous, sigtime_t > contactWorldPositionSIN
Definition: angle-estimator.h:66
sot
Definition: zmp-from-forces.cpp:11
compile.name
name
Definition: compile.py:22


sot-dynamic-pinocchio
Author(s): Olivier Stasse
autogenerated on Fri Jul 28 2023 02:10:01