sot-core  4.11.8
Hierarchical task solver plug-in for dynamic-graph.
feature-pose.hh
Go to the documentation of this file.
1 /*
2  * Copyright 2019,
3  * Joseph Mirabel
4  *
5  * LAAS-CNRS
6  *
7  */
8 
9 #ifndef __SOT_FEATURE_POSE_HH__
10 #define __SOT_FEATURE_POSE_HH__
11 
12 /* --------------------------------------------------------------------- */
13 /* --- INCLUDE --------------------------------------------------------- */
14 /* --------------------------------------------------------------------- */
15 
16 /* SOT */
17 #include <sot/core/config.hh>
20 
21 /* --------------------------------------------------------------------- */
22 /* --- CLASS ----------------------------------------------------------- */
23 /* --------------------------------------------------------------------- */
24 
25 namespace dynamicgraph {
26 namespace sot {
27 
30 
61 template <Representation_t representation = R3xSO3Representation>
63  public:
64  static const std::string CLASS_NAME;
65  virtual const std::string &getClassName(void) const { return CLASS_NAME; }
66 
67  public:
72  dynamicgraph::SignalPtr<MatrixHomogeneous, int> oMja;
74  dynamicgraph::SignalPtr<MatrixHomogeneous, int> jaMfa;
76  dynamicgraph::SignalPtr<MatrixHomogeneous, int> oMjb;
78  dynamicgraph::SignalPtr<MatrixHomogeneous, int> jbMfb;
80  dynamicgraph::SignalPtr<Matrix, int> jaJja;
82  dynamicgraph::SignalPtr<Matrix, int> jbJjb;
83 
85  dynamicgraph::SignalPtr<MatrixHomogeneous, int> faMfbDes;
88  dynamicgraph::SignalPtr<Vector, int> faNufafbDes;
95  SignalTimeDependent<MatrixHomogeneous, int> faMfb;
96 
99  SignalTimeDependent<Vector7, int> q_faMfb;
100 
103  SignalTimeDependent<Vector7, int> q_faMfbDes;
109 
115  public:
116  FeaturePose(const std::string &name);
117  virtual ~FeaturePose(void);
118 
119  virtual unsigned int &getDimension(unsigned int &dim, int time);
120 
122  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res,
123  int time);
130  virtual dynamicgraph::Vector &computeErrorDot(dynamicgraph::Vector &res,
131  int time);
138  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res,
139  int time);
140 
141  virtual void display(std::ostream &os) const;
142 
143  public:
144  void servoCurrentPosition(const int &time);
145 
146  private:
147  MatrixHomogeneous &computefaMfb(MatrixHomogeneous &res, int time);
148  Vector7 &computeQfaMfb(Vector7 &res, int time);
149  Vector7 &computeQfaMfbDes(Vector7 &res, int time);
150 
152 };
153 
154 template <typename T>
156  const MatrixHomogeneous &Mdes,
157  const Vector &faNufafbDes);
158 
159 template <>
161 template <>
163 
164 #if __cplusplus >= 201103L
165 extern template class FeaturePose<SE3Representation>;
166 extern template class FeaturePose<R3xSO3Representation>;
167 #endif
168 
171 
172 } /* namespace sot */
173 } /* namespace dynamicgraph */
174 
175 #endif // #ifndef __SOT_FEATURE_POSE_HH__
176 
177 /*
178  * Local variables:
179  * c-basic-offset: 2
180  * End:
181  */
This class gives the abstract definition of a feature.
Definition: feature-abstract.hh:76
SignalTimeDependent< dynamicgraph::Matrix, int > jacobianSOUT
Jacobian of the error wrt the robot state: .
Definition: feature-abstract.hh:193
SignalTimeDependent< dynamicgraph::Vector, int > errorSOUT
This signal returns the error between the desired value and the current value : .
Definition: feature-abstract.hh:185
SignalPtr< Flags, int > selectionSIN
This vector specifies which dimension are used to perform the computation. For instance let us assume...
Definition: feature-abstract.hh:173
Feature that controls the relative (or absolute) pose between two frames A (or world) and B.
Definition: feature-pose.hh:62
dynamicgraph::SignalPtr< Matrix, int > jbJjb
Jacobian of the input Joint B, expressed in Joint B
Definition: feature-pose.hh:82
dynamicgraph::SignalPtr< Vector, int > faNufafbDes
Definition: feature-pose.hh:88
dynamicgraph::SignalPtr< MatrixHomogeneous, int > faMfbDes
The desired pose of Frame B wrt to Frame A.
Definition: feature-pose.hh:85
SignalTimeDependent< Vector7, int > q_faMfbDes
Definition: feature-pose.hh:103
SignalTimeDependent< MatrixHomogeneous, int > faMfb
Pose of Frame B wrt to Frame A.
Definition: feature-pose.hh:95
dynamicgraph::SignalPtr< MatrixHomogeneous, int > oMjb
Input pose of Joint B wrt to world frame.
Definition: feature-pose.hh:76
virtual const std::string & getClassName(void) const
Returns the name class.
Definition: feature-pose.hh:65
dynamicgraph::SignalPtr< MatrixHomogeneous, int > jbMfb
Input pose of Frame B wrt to Joint B.
Definition: feature-pose.hh:78
static const std::string CLASS_NAME
Definition: feature-pose.hh:64
dynamicgraph::SignalPtr< MatrixHomogeneous, int > oMja
Input pose of Joint A wrt to world frame.
Definition: feature-pose.hh:72
dynamicgraph::SignalPtr< Matrix, int > jaJja
Jacobian of the input Joint A, expressed in Joint A
Definition: feature-pose.hh:80
SignalTimeDependent< Vector7, int > q_faMfb
Definition: feature-pose.hh:99
dynamicgraph::SignalPtr< MatrixHomogeneous, int > jaMfa
Input pose of Frame A wrt to Joint A.
Definition: feature-pose.hh:74
#define SOT_CORE_DLLAPI
Definition: config.hh:64
FeaturePose< SE3Representation > FeaturePoseSE3_t
Definition: feature-pose.hh:170
Representation_t
Enum used to specify what difference operation is used in FeaturePose.
Definition: feature-pose.hh:29
@ SE3Representation
Definition: feature-pose.hh:29
@ R3xSO3Representation
Definition: feature-pose.hh:29
Eigen::Transform< double, 3, Eigen::Affine > SOT_CORE_EXPORT MatrixHomogeneous
Definition: matrix-geometry.hh:75
Eigen::Matrix< double, 7, 1 > SOT_CORE_EXPORT Vector7
Definition: matrix-geometry.hh:84
Vector6d convertVelocity(const MatrixHomogeneous &M, const MatrixHomogeneous &Mdes, const Vector &faNufafbDes)
FeaturePose< R3xSO3Representation > FeaturePose_t
Definition: feature-pose.hh:169
Definition: abstract-sot-external-interface.hh:17