Skip to content
This repository was archived by the owner on Nov 28, 2025. It is now read-only.

Commit 3c6363c

Browse files
committed
Format
1 parent 1fd2005 commit 3c6363c

31 files changed

+2306
-2877
lines changed

doc/additionalDoc/package.hh

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,8 @@ install these packages at https://github.com/jrl-umi3218.
2828
\section python_bindings Python bindings
2929
3030
As most packages based on the dynamic-graph framework (see https://github.com/jrl-umi3218/dynamic-graph),
31-
the functionnality is exposed through entities. Hence python sub-modules of dynamic_graph are generated. See <a href="../sphinx-html/index.html">sphinx documentation</a> for more details.
31+
the functionnality is exposed through entities. Hence python sub-modules of dynamic_graph are generated. See <a
32+
href="../sphinx-html/index.html">sphinx documentation</a> for more details.
3233
3334
The following entities are created by this package:\n
3435
(all entites are placed in the namespace sot::)

include/sot-dynamic-pinocchio/angle-estimator.h

Lines changed: 45 additions & 62 deletions
Original file line numberDiff line numberDiff line change
@@ -13,14 +13,14 @@
1313
/* --- API ------------------------------------------------------------- */
1414
/* --------------------------------------------------------------------- */
1515

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
16+
#if defined(WIN32)
17+
#if defined(angle_estimator_EXPORTS)
18+
#define SOTANGLEESTIMATOR_EXPORT __declspec(dllexport)
2219
#else
23-
# define SOTANGLEESTIMATOR_EXPORT
20+
#define SOTANGLEESTIMATOR_EXPORT __declspec(dllimport)
21+
#endif
22+
#else
23+
#define SOTANGLEESTIMATOR_EXPORT
2424
#endif
2525

2626
/* --------------------------------------------------------------------- */
@@ -30,87 +30,70 @@
3030
/* Matrix */
3131
#include <dynamic-graph/linear-algebra.h>
3232

33-
3433
/* SOT */
3534
#include <dynamic-graph/entity.h>
3635
#include <dynamic-graph/signal-ptr.h>
3736
#include <dynamic-graph/signal-time-dependent.h>
3837
#include <sot/core/matrix-geometry.hh>
3938

40-
4139
/* STD */
4240
#include <string>
4341

44-
45-
namespace dynamicgraph { namespace sot {
42+
namespace dynamicgraph {
43+
namespace sot {
4644
namespace dg = dynamicgraph;
4745

4846
/* --------------------------------------------------------------------- */
4947
/* --- CLASS ----------------------------------------------------------- */
5048
/* --------------------------------------------------------------------- */
5149

52-
class SOTANGLEESTIMATOR_EXPORT AngleEstimator
53-
:public dg::Entity
54-
{
50+
class SOTANGLEESTIMATOR_EXPORT AngleEstimator : public dg::Entity {
5551
public:
5652
static const std::string CLASS_NAME;
57-
virtual const std::string& getClassName( void ) const { return CLASS_NAME; }
53+
virtual const std::string& getClassName(void) const { return CLASS_NAME; }
5854

5955
public: /* --- CONSTRUCTION --- */
60-
61-
AngleEstimator( const std::string& name );
62-
virtual ~AngleEstimator( void );
63-
64-
public: /* --- SIGNAL --- */
65-
66-
dg::SignalPtr<MatrixRotation,int> sensorWorldRotationSIN; // estimate(worldRc)
67-
dg::SignalPtr<MatrixHomogeneous,int> sensorEmbeddedPositionSIN; // waistRchest
68-
dg::SignalPtr<MatrixHomogeneous,int> contactWorldPositionSIN; // estimate(worldRf)
69-
dg::SignalPtr<MatrixHomogeneous,int> contactEmbeddedPositionSIN; // waistRleg
70-
dg::SignalTimeDependent<dynamicgraph::Vector,int> anglesSOUT; // [ flex1 flex2 yaw_drift ]
71-
dg::SignalTimeDependent<MatrixRotation,int> flexibilitySOUT; // footRleg
72-
dg::SignalTimeDependent<MatrixRotation,int> driftSOUT; // Ryaw = worldRc est(wRc)^-1
73-
dg::SignalTimeDependent<MatrixRotation,int> sensorWorldRotationSOUT; // worldRc
74-
dg::SignalTimeDependent<MatrixRotation,int> waistWorldRotationSOUT; // worldRwaist
75-
dg::SignalTimeDependent<MatrixHomogeneous,int> waistWorldPositionSOUT; // worldMwaist
76-
dg::SignalTimeDependent<dynamicgraph::Vector,int> waistWorldPoseRPYSOUT; // worldMwaist
77-
78-
dg::SignalPtr<dynamicgraph::Matrix,int> jacobianSIN;
79-
dg::SignalPtr<dynamicgraph::Vector,int> qdotSIN;
80-
dg::SignalTimeDependent<dynamicgraph::Vector,int> xff_dotSOUT;
81-
dg::SignalTimeDependent<dynamicgraph::Vector,int> qdotSOUT;
56+
AngleEstimator(const std::string& name);
57+
virtual ~AngleEstimator(void);
58+
59+
public: /* --- SIGNAL --- */
60+
dg::SignalPtr<MatrixRotation, int> sensorWorldRotationSIN; // estimate(worldRc)
61+
dg::SignalPtr<MatrixHomogeneous, int> sensorEmbeddedPositionSIN; // waistRchest
62+
dg::SignalPtr<MatrixHomogeneous, int> contactWorldPositionSIN; // estimate(worldRf)
63+
dg::SignalPtr<MatrixHomogeneous, int> contactEmbeddedPositionSIN; // waistRleg
64+
dg::SignalTimeDependent<dynamicgraph::Vector, int> anglesSOUT; // [ flex1 flex2 yaw_drift ]
65+
dg::SignalTimeDependent<MatrixRotation, int> flexibilitySOUT; // footRleg
66+
dg::SignalTimeDependent<MatrixRotation, int> driftSOUT; // Ryaw = worldRc est(wRc)^-1
67+
dg::SignalTimeDependent<MatrixRotation, int> sensorWorldRotationSOUT; // worldRc
68+
dg::SignalTimeDependent<MatrixRotation, int> waistWorldRotationSOUT; // worldRwaist
69+
dg::SignalTimeDependent<MatrixHomogeneous, int> waistWorldPositionSOUT; // worldMwaist
70+
dg::SignalTimeDependent<dynamicgraph::Vector, int> waistWorldPoseRPYSOUT; // worldMwaist
71+
72+
dg::SignalPtr<dynamicgraph::Matrix, int> jacobianSIN;
73+
dg::SignalPtr<dynamicgraph::Vector, int> qdotSIN;
74+
dg::SignalTimeDependent<dynamicgraph::Vector, int> xff_dotSOUT;
75+
dg::SignalTimeDependent<dynamicgraph::Vector, int> qdotSOUT;
8276

8377
public: /* --- FUNCTIONS --- */
84-
dynamicgraph::Vector& computeAngles( dynamicgraph::Vector& res,
85-
const int& time );
86-
MatrixRotation& computeFlexibilityFromAngles( MatrixRotation& res,
87-
const int& time );
88-
MatrixRotation& computeDriftFromAngles( MatrixRotation& res,
89-
const int& time );
90-
MatrixRotation& computeSensorWorldRotation( MatrixRotation& res,
91-
const int& time );
92-
MatrixRotation& computeWaistWorldRotation( MatrixRotation& res,
93-
const int& time );
94-
MatrixHomogeneous& computeWaistWorldPosition( MatrixHomogeneous& res,
95-
const int& time );
96-
dynamicgraph::Vector& computeWaistWorldPoseRPY( dynamicgraph::Vector& res,
97-
const int& time );
98-
dynamicgraph::Vector& compute_xff_dotSOUT( dynamicgraph::Vector& res,
99-
const int& time );
100-
dynamicgraph::Vector& compute_qdotSOUT( dynamicgraph::Vector& res,
101-
const int& time );
78+
dynamicgraph::Vector& computeAngles(dynamicgraph::Vector& res, const int& time);
79+
MatrixRotation& computeFlexibilityFromAngles(MatrixRotation& res, const int& time);
80+
MatrixRotation& computeDriftFromAngles(MatrixRotation& res, const int& time);
81+
MatrixRotation& computeSensorWorldRotation(MatrixRotation& res, const int& time);
82+
MatrixRotation& computeWaistWorldRotation(MatrixRotation& res, const int& time);
83+
MatrixHomogeneous& computeWaistWorldPosition(MatrixHomogeneous& res, const int& time);
84+
dynamicgraph::Vector& computeWaistWorldPoseRPY(dynamicgraph::Vector& res, const int& time);
85+
dynamicgraph::Vector& compute_xff_dotSOUT(dynamicgraph::Vector& res, const int& time);
86+
dynamicgraph::Vector& compute_qdotSOUT(dynamicgraph::Vector& res, const int& time);
10287

10388
public: /* --- PARAMS --- */
10489
void fromSensor(const bool& fs) { fromSensor_ = fs; }
105-
bool fromSensor() const { return fromSensor_; }
90+
bool fromSensor() const { return fromSensor_; }
91+
10692
private:
10793
bool fromSensor_;
108-
10994
};
11095

96+
} /* namespace sot */
97+
} /* namespace dynamicgraph */
11198

112-
} /* namespace sot */} /* namespace dynamicgraph */
113-
114-
115-
116-
#endif // #ifndef __SOT_ANGLE_ESTIMATOR_H__
99+
#endif // #ifndef __SOT_ANGLE_ESTIMATOR_H__

0 commit comments

Comments
 (0)