Public Member Functions | Static Public Attributes | Protected Attributes | List of all members
dynamicgraph::sot::FeatureGeneric Class Reference

Class that defines a generic implementation of the abstract interface for features. More...

#include <feature-generic.hh>

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

Public Member Functions

virtual void display (std::ostream &os) const
 Display the information related to this generic implementation. More...
 
virtual const std::string & getClassName (void) const
 
Output signals
 FeatureGeneric (const std::string &name)
 Default constructor. More...
 
virtual ~FeatureGeneric (void)
 Default destructor. More...
 
virtual unsigned int & getDimension (unsigned int &dim, int time)
 Get the dimension of the feature. More...
 
Methods to trigger computation related to this feature.
virtual dynamicgraph::VectorcomputeError (dynamicgraph::Vector &res, int time)
 Compute the error between the desired value and the value itself. More...
 
virtual dynamicgraph::MatrixcomputeJacobian (dynamicgraph::Matrix &res, int time)
 Compute the Jacobian of the value according to the robot state.. More...
 
Dealing with the reference value to be reach with this feature.
 DECLARE_REFERENCE_FUNCTIONS (FeatureGeneric)
 
- Public Member Functions inherited from dynamicgraph::sot::FeatureAbstract
 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...
 
void initCommands (void)
 
virtual ~FeatureAbstract (void)
 Default destructor. More...
 
unsigned int getDimension (int time)
 Short method. More...
 
unsigned int getDimension (void) const
 Shortest method. More...
 
virtual dynamicgraph::VectorcomputeErrorDot (dynamicgraph::Vector &res, int time)
 
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
 
virtual std::ostream & writeGraph (std::ostream &os) const
 This method write a graph description on the file named FileName. More...
 
virtual SignalTimeDependent< dynamicgraph::Vector, int > & getErrorDot ()
 
- Public Member Functions inherited from dynamicgraph::Entity
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< int > & getSignal (const std::string &signalName)
 
const SignalBase< int > & 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 ()
 
Logger const & logger () const
 
Loggerlogger ()
 
Logger const & logger () 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< int > * test ()
 
virtual void test2 (SignalBase< int > *)
 
virtual std::ostream & writeCompletionList (std::ostream &os) const
 
virtual ~Entity ()
 

Public Attributes

Input signals
dynamicgraph::SignalPtr< dynamicgraph::Vector, int > errorSIN
 Input for the error. More...
 
dynamicgraph::SignalPtr< dynamicgraph::Matrix, int > jacobianSIN
 Input for the Jacobian. More...
 
- Public Attributes inherited from dynamicgraph::sot::FeatureAbstract
SignalPtr< Flags, int > 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] $. More...
 
SignalPtr< dynamicgraph::Vector, int > errordotSIN
 Derivative of the reference value. More...
 
SignalTimeDependent< dynamicgraph::Vector, int > errorSOUT
 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, int > errordotSOUT
 Derivative of the error with respect to time: $ \frac{\partial e}{\partial t} = - \frac{d{\bf s}^*}{dt} $. More...
 
SignalTimeDependent< dynamicgraph::Matrix, int > jacobianSOUT
 Jacobian of the error wrt the robot state: $ J = \frac{\partial {\bf s}}{\partial {\bf q}}$. More...
 
SignalTimeDependent< unsigned int, int > dimensionSOUT
 Returns the dimension of the feature as an output signal. More...
 

Static Public Attributes

static const std::string CLASS_NAME
 
- Static Public Attributes inherited from dynamicgraph::sot::FeatureAbstract
static const std::string CLASS_NAME = "FeatureAbstract"
 Store the name of the class. More...
 

Protected Attributes

dynamicgraph::Vector::Index dimensionDefault
 
- Protected Attributes inherited from dynamicgraph::Entity
CommandMap_t commandMap
 
Logger logger_
 
std::string name
 
SignalMap signalMap
 

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< int > *> 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< int > &signals)
 
- Private Member Functions inherited from dynamicgraph::sot::FeatureReferenceHelper< FeatureGeneric >
 FeatureReferenceHelper (void)
 
FeatureGenericgetReference (void)
 
const FeatureGenericgetReference (void) const
 
bool isReferenceSet (void) const
 
void setReference (FeatureAbstract *sdes)
 
void unsetReference (void)
 

Detailed Description

Class that defines a generic implementation of the abstract interface for features.

This class is very useful if the feature can be easily computed using the basic operator provided. For instance a free space controller on a end-effector is basically directly computed from the Jacobian provided by dyn and some appropriate addition and soustraction. Instead of building a specific feature for this, it is possible to use the signals and plug the computed error, Jacobian and activation to the input of this generic feature implementation.

Definition at line 56 of file feature-generic.hh.

Constructor & Destructor Documentation

◆ FeatureGeneric()

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

Default constructor.

Definition at line 29 of file feature-generic.cpp.

◆ ~FeatureGeneric()

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

Default destructor.

Definition at line 100 of file feature-generic.hh.

Member Function Documentation

◆ computeError()

Vector & FeatureGeneric::computeError ( dynamicgraph::Vector res,
int  time 
)
virtual

Compute the error between the desired value and the value itself.

Implements dynamicgraph::sot::FeatureAbstract.

Definition at line 78 of file feature-generic.cpp.

◆ computeJacobian()

Matrix & FeatureGeneric::computeJacobian ( dynamicgraph::Matrix res,
int  time 
)
virtual

Compute the Jacobian of the value according to the robot state..

Implements dynamicgraph::sot::FeatureAbstract.

Definition at line 118 of file feature-generic.cpp.

◆ DECLARE_REFERENCE_FUNCTIONS()

dynamicgraph::sot::FeatureGeneric::DECLARE_REFERENCE_FUNCTIONS ( FeatureGeneric  )

◆ display()

void FeatureGeneric::display ( std::ostream &  os) const
virtual

Display the information related to this generic implementation.

Reimplemented from dynamicgraph::Entity.

Reimplemented in dynamicgraph::sot::FeatureTask.

Definition at line 142 of file feature-generic.cpp.

◆ getClassName()

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

Returns the name of the class.

Reimplemented from dynamicgraph::sot::FeatureAbstract.

Reimplemented in dynamicgraph::sot::FeatureTask.

Definition at line 63 of file feature-generic.hh.

◆ getDimension()

unsigned int & FeatureGeneric::getDimension ( unsigned int &  dim,
int  time 
)
virtual

Get the dimension of the feature.

Implements dynamicgraph::sot::FeatureAbstract.

Definition at line 63 of file feature-generic.cpp.

Member Data Documentation

◆ CLASS_NAME

const std::string dynamicgraph::sot::FeatureGeneric::CLASS_NAME
static

Field storing the class name.

Definition at line 61 of file feature-generic.hh.

◆ dimensionDefault

dynamicgraph::Vector::Index dynamicgraph::sot::FeatureGeneric::dimensionDefault
protected

Definition at line 66 of file feature-generic.hh.

◆ errorSIN

dynamicgraph::SignalPtr<dynamicgraph::Vector, int> dynamicgraph::sot::FeatureGeneric::errorSIN

Input for the error.

Definition at line 77 of file feature-generic.hh.

◆ jacobianSIN

dynamicgraph::SignalPtr<dynamicgraph::Matrix, int> dynamicgraph::sot::FeatureGeneric::jacobianSIN

Input for the Jacobian.

Definition at line 80 of file feature-generic.hh.


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


sot-core
Author(s): Olivier Stasse, ostasse@laas.fr
autogenerated on Wed Jun 21 2023 02:51:27