Public Member Functions | Static Public Attributes | List of all members
dynamicgraph::sot::FeatureAbstract Class Referenceabstract

This class gives the abstract definition of a feature. More...

#include <feature-abstract.hh>

Inheritance diagram for dynamicgraph::sot::FeatureAbstract:
Inheritance graph
[legend]

Public Member Functions

 FeatureAbstract (const std::string &name)
 Default constructor: the name of the class should be given. More...
 
void featureRegistration (void)
 Register the feature in the stack of tasks. More...
 
virtual const std::string & getClassName (void) const
 Returns the name class. More...
 
void initCommands (void)
 
virtual ~FeatureAbstract (void)
 Default destructor. More...
 
Methods returning the dimension of the feature.
virtual size_typegetDimension (size_type &res, sigtime_t time)=0
 Verbose method. More...
 
size_type getDimension (sigtime_t time)
 Short method. More...
 
size_type getDimension (void) const
 Shortest method. More...
 
Methods to control internal computation.

The main idea is that some feature may have a lower frequency than the internal control loop. In this case, the methods for computation are called only when needed.

virtual dynamicgraph::VectorcomputeError (dynamicgraph::Vector &res, sigtime_t time)=0
 Compute the error between the desired feature and the current value of the feature measured or deduced from the robot state. More...
 
virtual dynamicgraph::MatrixcomputeJacobian (dynamicgraph::Matrix &res, sigtime_t time)=0
 Compute the Jacobian of the error according the robot state. More...
 
virtual dynamicgraph::VectorcomputeErrorDot (dynamicgraph::Vector &res, sigtime_t time)
 
Reference
virtual void setReference (FeatureAbstract *sdes)=0
 
virtual void unsetReference (void)
 
virtual const FeatureAbstractgetReferenceAbstract (void) const =0
 
virtual FeatureAbstractgetReferenceAbstract (void)=0
 
virtual bool isReferenceSet (void) const
 
virtual void addDependenciesFromReference (void)=0
 
virtual void removeDependenciesFromReference (void)=0
 
void setReferenceByName (const std::string &name)
 
std::string getReferenceByName (void) const
 
- Public Member Functions inherited from dynamicgraph::Entity
virtual void display (std::ostream &os) const
 
std::ostream & displaySignalList (std::ostream &os) const
 
 Entity (const std::string &name)
 
const std::string & getCommandList () const
 
virtual std::string getDocString () const
 
LoggerVerbosity getLoggerVerbosityLevel ()
 
LoggerVerbosity getLoggerVerbosityLevel ()
 
const std::string & getName () const
 
command::CommandgetNewStyleCommand (const std::string &cmdName)
 
CommandMap_t getNewStyleCommandMap ()
 
SignalBase< sigtime_t > & getSignal (const std::string &signalName)
 
const SignalBase< sigtime_t > & getSignal (const std::string &signalName) const
 
SignalMap getSignalMap () const
 
double getStreamPrintPeriod ()
 
double getStreamPrintPeriod ()
 
double getTimeSample ()
 
double getTimeSample ()
 
bool hasSignal (const std::string &signame) const
 
Loggerlogger ()
 
Loggerlogger ()
 
const Loggerlogger () const
 
const Loggerlogger () const
 
void sendMsg (const std::string &msg, MsgType t=MSG_TYPE_INFO, const std::string &lineId="")
 
void sendMsg (const std::string &msg, MsgType t=MSG_TYPE_INFO, const std::string &lineId="")
 
void setLoggerVerbosityLevel (LoggerVerbosity lv)
 
void setLoggerVerbosityLevel (LoggerVerbosity lv)
 
bool setStreamPrintPeriod (double t)
 
bool setStreamPrintPeriod (double t)
 
bool setTimeSample (double t)
 
bool setTimeSample (double t)
 
virtual SignalBase< sigtime_t > * test ()
 
virtual void test2 (SignalBase< sigtime_t > *)
 
virtual std::ostream & writeCompletionList (std::ostream &os) const
 
virtual ~Entity ()
 

Public Attributes

Input signals:
SignalPtr< Flags, sigtime_tselectionSIN
 This vector specifies which dimension are used to perform the computation. For instance let us assume that the feature is a 3D point. If only the Y-axis should be used for computing error, activation and Jacobian, then the vector to specify is $ [ 0 1 0] $. More...
 
SignalPtr< dynamicgraph::Vector, sigtime_terrordotSIN
 Derivative of the reference value. More...
 

Static Public Attributes

static const std::string CLASS_NAME = "FeatureAbstract"
 Store the name of the class. More...
 

Output signals:

SignalTimeDependent< dynamicgraph::Vector, sigtime_terrorSOUT
 This signal returns the error between the desired value and the current value : $ E(t) = {\bf s}(t) - {\bf s}^*(t)$. More...
 
SignalTimeDependent< dynamicgraph::Vector, sigtime_terrordotSOUT
 Derivative of the error with respect to time: $ \frac{\partial e}{\partial t} = - \frac{d{\bf s}^*}{dt} $. More...
 
SignalTimeDependent< dynamicgraph::Matrix, sigtime_tjacobianSOUT
 Jacobian of the error wrt the robot state: $ J = \frac{\partial {\bf s}}{\partial {\bf q}}$. More...
 
SignalTimeDependent< size_type, sigtime_tdimensionSOUT
 Returns the dimension of the feature as an output signal. More...
 
virtual std::ostream & writeGraph (std::ostream &os) const
 This method write a graph description on the file named FileName. More...
 
virtual SignalTimeDependent< dynamicgraph::Vector, sigtime_t > & getErrorDot ()
 

Additional Inherited Members

- Public Types inherited from dynamicgraph::Entity
typedef std::map< const std::string, command::Command * > CommandMap_t
 
typedef std::map< std::string, SignalBase< sigtime_t > * > SignalMap
 
- Protected Member Functions inherited from dynamicgraph::Entity
void addCommand (const std::string &name, command::Command *command)
 
void entityDeregistration ()
 
void entityRegistration ()
 
void signalDeregistration (const std::string &name)
 
void signalRegistration (const SignalArray< sigtime_t > &signals)
 
- Protected Attributes inherited from dynamicgraph::Entity
CommandMap_t commandMap
 
Logger logger_
 
std::string name
 
SignalMap signalMap
 

Detailed Description

This class gives the abstract definition of a feature.

par_features_definition Definition
In short, a feature is a data evolving according to time. It is defined by a vector ${\bf s}({\bf q}) \in \mathbb{R}^n $ where $ {\bf q} $ is a robot configuration, which depends on the time $ t $. By default a feature has a desired ${\bf s}^*(t) $. ${\bf s}^*$ is provided by another feature of the same type called reference. The feature is in charge of collecting its own current state. A feature is supposed to compute an error between its current state and the desired one: $ E(t) = e({\bf q}(t), t) = {\bf s}({\bf q}(t)) \ominus {\bf s}^*(t) $. Here, $ \ominus $ is the difference operator of Lie group in which $ {\bf s} $ and $ {\bf s}^* $ are. The documentation below assumes the Lie group is a vector space and $\ominus$ is the usual difference operator.

A feature computes:

The task is in general computed from the value of the feature at the current instant $E(t) = e({\bf q},t)$. The derivative of $ E $ is:

\[ \frac{dE}{dt} = J({\bf q}) \dot{q} + \frac{\partial e}{\partial t} \]

Feature diagram: Feature types derive from

FeatureAbstract. Each feature has a reference of the same type and compute an error by comparing errorSIN signals from itself and from the reference."

Definition at line 76 of file feature-abstract.hh.

Constructor & Destructor Documentation

◆ FeatureAbstract()

FeatureAbstract::FeatureAbstract ( const std::string &  name)

Default constructor: the name of the class should be given.

Definition at line 24 of file feature-abstract.cpp.

◆ ~FeatureAbstract()

virtual dynamicgraph::sot::FeatureAbstract::~FeatureAbstract ( void  )
inlinevirtual

Default destructor.

Definition at line 93 of file feature-abstract.hh.

Member Function Documentation

◆ addDependenciesFromReference()

virtual void dynamicgraph::sot::FeatureAbstract::addDependenciesFromReference ( void  )
pure virtual

◆ computeError()

virtual dynamicgraph::Vector& dynamicgraph::sot::FeatureAbstract::computeError ( dynamicgraph::Vector res,
sigtime_t  time 
)
pure virtual

Compute the error between the desired feature and the current value of the feature measured or deduced from the robot state.

[out] res: The error will be set into res.
[in] time: The time at which the error is computed.
Returns
The vector res with the appropriate value.

Implemented in dynamicgraph::sot::FeaturePosture, dynamicgraph::sot::FeaturePose< representation >, dynamicgraph::sot::FeatureGeneric, dynamicgraph::sot::Feature1D, dynamicgraph::sot::FeatureJointLimits, dynamicgraph::sot::FeatureLineDistance, dynamicgraph::sot::FeatureVisualPoint, and dynamicgraph::sot::FeatureVector3.

◆ computeErrorDot()

dynamicgraph::Vector & FeatureAbstract::computeErrorDot ( dynamicgraph::Vector res,
sigtime_t  time 
)
virtual

Callback for signal errordotSOUT

Copy components of the input signal errordotSIN defined by selection flag selectionSIN.

Reimplemented in dynamicgraph::sot::FeaturePose< representation >, and dynamicgraph::sot::FeaturePosture.

Definition at line 95 of file feature-abstract.cpp.

◆ computeJacobian()

virtual dynamicgraph::Matrix& dynamicgraph::sot::FeatureAbstract::computeJacobian ( dynamicgraph::Matrix res,
sigtime_t  time 
)
pure virtual

Compute the Jacobian of the error according the robot state.

[out] res: The matrix in which the error will be written.
Returns
The matrix res with the appropriate values.

Implemented in dynamicgraph::sot::FeaturePosture, dynamicgraph::sot::FeaturePose< representation >, dynamicgraph::sot::FeatureGeneric, dynamicgraph::sot::Feature1D, dynamicgraph::sot::FeatureJointLimits, dynamicgraph::sot::FeatureLineDistance, dynamicgraph::sot::FeatureVisualPoint, and dynamicgraph::sot::FeatureVector3.

◆ featureRegistration()

void FeatureAbstract::featureRegistration ( void  )

Register the feature in the stack of tasks.

Definition at line 66 of file feature-abstract.cpp.

◆ getClassName()

virtual const std::string& dynamicgraph::sot::FeatureAbstract::getClassName ( void  ) const
inlinevirtual

◆ getDimension() [1/3]

size_type dynamicgraph::sot::FeatureAbstract::getDimension ( sigtime_t  time)
inline

Short method.

time: The time at which the feature should be considered.
Returns
Dimension of the feature.
Note
Be careful with features changing their dimension according to time.

Definition at line 111 of file feature-abstract.hh.

◆ getDimension() [2/3]

virtual size_type& dynamicgraph::sot::FeatureAbstract::getDimension ( size_type res,
sigtime_t  time 
)
pure virtual

Verbose method.

res: The integer in which the dimension will be return.
time: The time at which the feature should be considered.
Returns
Dimension of the feature.
Note
Be careful with features changing their dimension according to time.

Implemented in dynamicgraph::sot::FeaturePosture, dynamicgraph::sot::FeaturePose< representation >, dynamicgraph::sot::FeatureGeneric, dynamicgraph::sot::Feature1D, dynamicgraph::sot::FeatureJointLimits, dynamicgraph::sot::FeatureLineDistance, dynamicgraph::sot::FeatureVisualPoint, and dynamicgraph::sot::FeatureVector3.

◆ getDimension() [3/3]

size_type dynamicgraph::sot::FeatureAbstract::getDimension ( void  ) const
inline

Shortest method.

Returns
Dimension of the feature.
Note
The feature is not changing its dimension according to time.

Definition at line 121 of file feature-abstract.hh.

◆ getErrorDot()

virtual SignalTimeDependent<dynamicgraph::Vector, sigtime_t>& dynamicgraph::sot::FeatureAbstract::getErrorDot ( )
inlinevirtual

Definition at line 202 of file feature-abstract.hh.

◆ getReferenceAbstract() [1/2]

virtual const FeatureAbstract* dynamicgraph::sot::FeatureAbstract::getReferenceAbstract ( void  ) const
pure virtual

◆ getReferenceAbstract() [2/2]

virtual FeatureAbstract* dynamicgraph::sot::FeatureAbstract::getReferenceAbstract ( void  )
pure virtual

◆ getReferenceByName()

std::string FeatureAbstract::getReferenceByName ( void  ) const

Definition at line 88 of file feature-abstract.cpp.

◆ initCommands()

void FeatureAbstract::initCommands ( void  )

Definition at line 52 of file feature-abstract.cpp.

◆ isReferenceSet()

virtual bool dynamicgraph::sot::FeatureAbstract::isReferenceSet ( void  ) const
inlinevirtual

Definition at line 217 of file feature-abstract.hh.

◆ removeDependenciesFromReference()

virtual void dynamicgraph::sot::FeatureAbstract::removeDependenciesFromReference ( void  )
pure virtual

◆ setReference()

virtual void dynamicgraph::sot::FeatureAbstract::setReference ( FeatureAbstract sdes)
pure virtual

◆ setReferenceByName()

void FeatureAbstract::setReferenceByName ( const std::string &  name)

Definition at line 83 of file feature-abstract.cpp.

◆ unsetReference()

virtual void dynamicgraph::sot::FeatureAbstract::unsetReference ( void  )
inlinevirtual

Definition at line 214 of file feature-abstract.hh.

◆ writeGraph()

std::ostream & FeatureAbstract::writeGraph ( std::ostream &  os) const
virtual

This method write a graph description on the file named FileName.

Reimplemented from dynamicgraph::Entity.

Definition at line 70 of file feature-abstract.cpp.

Member Data Documentation

◆ CLASS_NAME

const std::string FeatureAbstract::CLASS_NAME = "FeatureAbstract"
static

Store the name of the class.

Definition at line 79 of file feature-abstract.hh.

◆ dimensionSOUT

SignalTimeDependent<size_type, sigtime_t> dynamicgraph::sot::FeatureAbstract::dimensionSOUT

Returns the dimension of the feature as an output signal.

Definition at line 196 of file feature-abstract.hh.

◆ errordotSIN

SignalPtr<dynamicgraph::Vector, sigtime_t> dynamicgraph::sot::FeatureAbstract::errordotSIN

Derivative of the reference value.

Definition at line 176 of file feature-abstract.hh.

◆ errordotSOUT

SignalTimeDependent<dynamicgraph::Vector, sigtime_t> dynamicgraph::sot::FeatureAbstract::errordotSOUT

Derivative of the error with respect to time: $ \frac{\partial e}{\partial t} = - \frac{d{\bf s}^*}{dt} $.

Definition at line 189 of file feature-abstract.hh.

◆ errorSOUT

SignalTimeDependent<dynamicgraph::Vector, sigtime_t> dynamicgraph::sot::FeatureAbstract::errorSOUT

This signal returns the error between the desired value and the current value : $ E(t) = {\bf s}(t) - {\bf s}^*(t)$.

Definition at line 185 of file feature-abstract.hh.

◆ jacobianSOUT

SignalTimeDependent<dynamicgraph::Matrix, sigtime_t> dynamicgraph::sot::FeatureAbstract::jacobianSOUT

Jacobian of the error wrt the robot state: $ J = \frac{\partial {\bf s}}{\partial {\bf q}}$.

Definition at line 193 of file feature-abstract.hh.

◆ selectionSIN

SignalPtr<Flags, sigtime_t> dynamicgraph::sot::FeatureAbstract::selectionSIN

This vector specifies which dimension are used to perform the computation. For instance let us assume that the feature is a 3D point. If only the Y-axis should be used for computing error, activation and Jacobian, then the vector to specify is $ [ 0 1 0] $.

Definition at line 173 of file feature-abstract.hh.


The documentation for this class was generated from the following files:


sot-core
Author(s): Olivier Stasse, ostasse@laas.fr
autogenerated on Tue Oct 24 2023 02:26:32