Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
S
sot-core
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Container registry
Model registry
Operate
Environments
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Stack Of Tasks
sot-core
Commits
3a2714c3
Commit
3a2714c3
authored
4 years ago
by
Olivier Stasse
Browse files
Options
Downloads
Patches
Plain Diff
Remove definition of dg across various class.
Make it internal to the implementation.
parent
52e44937
No related branches found
No related tags found
No related merge requests found
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
include/sot/core/feature-abstract.hh
+8
-9
8 additions, 9 deletions
include/sot/core/feature-abstract.hh
include/sot/core/feature-generic.hh
+6
-7
6 additions, 7 deletions
include/sot/core/feature-generic.hh
include/sot/core/feature-posture.hh
+5
-5
5 additions, 5 deletions
include/sot/core/feature-posture.hh
with
19 additions
and
21 deletions
include/sot/core/feature-abstract.hh
+
8
−
9
View file @
3a2714c3
...
...
@@ -16,7 +16,6 @@
/* Matrix */
#include
<dynamic-graph/linear-algebra.h>
namespace
dg
=
dynamicgraph
;
/* SOT */
#include
"sot/core/api.hh"
...
...
@@ -137,20 +136,20 @@ public:
\par[in] time: The time at which the error is computed.
\return The vector res with the appropriate value.
*/
virtual
d
g
::
Vector
&
computeError
(
d
g
::
Vector
&
res
,
int
time
)
=
0
;
virtual
d
ynamicgraph
::
Vector
&
computeError
(
d
ynamicgraph
::
Vector
&
res
,
int
time
)
=
0
;
/*! \brief Compute the Jacobian of the error according the robot state.
\par[out] res: The matrix in which the error will be written.
\return The matrix res with the appropriate values.
*/
virtual
d
g
::
Matrix
&
computeJacobian
(
d
g
::
Matrix
&
res
,
int
time
)
=
0
;
virtual
d
ynamicgraph
::
Matrix
&
computeJacobian
(
d
ynamicgraph
::
Matrix
&
res
,
int
time
)
=
0
;
/// Callback for signal errordotSOUT
///
/// Copy components of the input signal errordotSIN defined by selection
/// flag selectionSIN.
virtual
d
g
::
Vector
&
computeErrorDot
(
d
g
::
Vector
&
res
,
int
time
);
virtual
d
ynamicgraph
::
Vector
&
computeErrorDot
(
d
ynamicgraph
::
Vector
&
res
,
int
time
);
/*! @} */
...
...
@@ -170,7 +169,7 @@ public:
SignalPtr
<
Flags
,
int
>
selectionSIN
;
/// Derivative of the reference value.
SignalPtr
<
d
g
::
Vector
,
int
>
errordotSIN
;
SignalPtr
<
d
ynamicgraph
::
Vector
,
int
>
errordotSIN
;
/*! @} */
...
...
@@ -179,15 +178,15 @@ public:
/*! \brief This signal returns the error between the desired value and
the current value : \f$ E(t) = {\bf s}(t) - {\bf s}^*(t)\f$ */
SignalTimeDependent
<
d
g
::
Vector
,
int
>
errorSOUT
;
SignalTimeDependent
<
d
ynamicgraph
::
Vector
,
int
>
errorSOUT
;
/*! \brief Derivative of the error with respect to time:
* \f$ \frac{\partial e}{\partial t} = - \frac{d{\bf s}^*}{dt} \f$ */
SignalTimeDependent
<
d
g
::
Vector
,
int
>
errordotSOUT
;
SignalTimeDependent
<
d
ynamicgraph
::
Vector
,
int
>
errordotSOUT
;
/*! \brief Jacobian of the error wrt the robot state:
* \f$ J = \frac{\partial {\bf s}}{\partial {\bf q}}\f$ */
SignalTimeDependent
<
d
g
::
Matrix
,
int
>
jacobianSOUT
;
SignalTimeDependent
<
d
ynamicgraph
::
Matrix
,
int
>
jacobianSOUT
;
/*! \brief Returns the dimension of the feature as an output signal. */
SignalTimeDependent
<
unsigned
int
,
int
>
dimensionSOUT
;
...
...
@@ -196,7 +195,7 @@ public:
FileName. */
virtual
std
::
ostream
&
writeGraph
(
std
::
ostream
&
os
)
const
;
virtual
SignalTimeDependent
<
d
g
::
Vector
,
int
>
&
getErrorDot
()
{
virtual
SignalTimeDependent
<
d
ynamicgraph
::
Vector
,
int
>
&
getErrorDot
()
{
return
errordotSOUT
;
}
...
...
This diff is collapsed.
Click to expand it.
include/sot/core/feature-generic.hh
+
6
−
7
View file @
3a2714c3
...
...
@@ -38,7 +38,6 @@
namespace
dynamicgraph
{
namespace
sot
{
namespace
dg
=
dynamicgraph
;
/*!
\class FeatureGeneric
...
...
@@ -65,21 +64,21 @@ public:
virtual
const
std
::
string
&
getClassName
(
void
)
const
{
return
CLASS_NAME
;
}
protected
:
d
g
::
Vector
::
Index
dimensionDefault
;
d
ynamicgraph
::
Vector
::
Index
dimensionDefault
;
/* --- SIGNALS ------------------------------------------------------------ */
public
:
/*! \name d
g
::Signals
/*! \name d
ynamicgraph
::Signals
@{
*/
/*! \name Input signals
@{
*/
/*! \brief Input for the error. */
d
g
::
SignalPtr
<
d
g
::
Vector
,
int
>
errorSIN
;
d
ynamicgraph
::
SignalPtr
<
d
ynamicgraph
::
Vector
,
int
>
errorSIN
;
/*! \brief Input for the Jacobian. */
d
g
::
SignalPtr
<
d
g
::
Matrix
,
int
>
jacobianSIN
;
d
ynamicgraph
::
SignalPtr
<
d
ynamicgraph
::
Matrix
,
int
>
jacobianSIN
;
/*! @} */
...
...
@@ -110,10 +109,10 @@ public:
/*! \brief Compute the error between the desired value and the value itself.
*/
virtual
d
g
::
Vector
&
computeError
(
d
g
::
Vector
&
res
,
int
time
);
virtual
d
ynamicgraph
::
Vector
&
computeError
(
d
ynamicgraph
::
Vector
&
res
,
int
time
);
/*! \brief Compute the Jacobian of the value according to the robot state.. */
virtual
d
g
::
Matrix
&
computeJacobian
(
d
g
::
Matrix
&
res
,
int
time
);
virtual
d
ynamicgraph
::
Matrix
&
computeJacobian
(
d
ynamicgraph
::
Matrix
&
res
,
int
time
);
/*! @} */
...
...
This diff is collapsed.
Click to expand it.
include/sot/core/feature-posture.hh
+
5
−
5
View file @
3a2714c3
...
...
@@ -52,8 +52,8 @@ class SOTFEATUREPOSTURE_EXPORT FeaturePosture : public FeatureAbstract {
DYNAMIC_GRAPH_ENTITY_DECL
();
public:
typedef
dynamicgraph
::
SignalPtr
<
d
g
::
Vector
,
int
>
signalIn_t
;
typedef
dynamicgraph
::
SignalTimeDependent
<
d
g
::
Vector
,
int
>
signalOut_t
;
typedef
dynamicgraph
::
SignalPtr
<
d
ynamicgraph
::
Vector
,
int
>
signalIn_t
;
typedef
dynamicgraph
::
SignalTimeDependent
<
d
ynamicgraph
::
Vector
,
int
>
signalOut_t
;
DECLARE_NO_REFERENCE
;
...
...
@@ -63,9 +63,9 @@ public:
void
selectDof
(
unsigned
dofId
,
bool
control
);
protected:
virtual
d
g
::
Vector
&
computeError
(
d
g
::
Vector
&
res
,
int
);
virtual
d
g
::
Matrix
&
computeJacobian
(
d
g
::
Matrix
&
res
,
int
);
virtual
d
g
::
Vector
&
computeErrorDot
(
d
g
::
Vector
&
res
,
int
time
);
virtual
d
ynamicgraph
::
Vector
&
computeError
(
d
ynamicgraph
::
Vector
&
res
,
int
);
virtual
d
ynamicgraph
::
Matrix
&
computeJacobian
(
d
ynamicgraph
::
Matrix
&
res
,
int
);
virtual
d
ynamicgraph
::
Vector
&
computeErrorDot
(
d
ynamicgraph
::
Vector
&
res
,
int
time
);
signalIn_t
state_
;
signalIn_t
posture_
;
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment