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

Class that defines 2D visualPoint visual feature. More...

#include <feature-visual-point.hh>

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

Public Member Functions

virtual dynamicgraph::VectorcomputeError (dynamicgraph::Vector &res, int time)
 
virtual dynamicgraph::MatrixcomputeJacobian (dynamicgraph::Matrix &res, int time)
 
 DECLARE_REFERENCE_FUNCTIONS (FeatureVisualPoint)
 
virtual void display (std::ostream &os) const
 
 FeatureVisualPoint (const std::string &name)
 
virtual const std::string & getClassName (void) const
 Returns the name class. More...
 
virtual unsigned int & getDimension (unsigned int &dim, int time)
 Verbose method. More...
 
virtual ~FeatureVisualPoint (void)
 
- 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 Member Functions inherited from dynamicgraph::sot::FeatureReferenceHelper< FeatureVisualPoint >
 FeatureReferenceHelper (void)
 
FeatureVisualPointgetReference (void)
 
const FeatureVisualPointgetReference (void) const
 
bool isReferenceSet (void) const
 
void setReference (FeatureAbstract *sdes)
 
void unsetReference (void)
 

Static Public Member Functions

static Flags selectX (void)
 
static Flags selectY (void)
 

Public Attributes

dynamicgraph::SignalPtr< dynamicgraph::Matrix, int > articularJacobianSIN
 
dynamicgraph::SignalPtr< dynamicgraph::Vector, int > xySIN
 
dynamicgraph::SignalPtr< double, int > ZSIN
 
- 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::Matrix L
 
- 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)
 

Detailed Description

Class that defines 2D visualPoint visual feature.

Definition at line 46 of file feature-visual-point.hh.

Constructor & Destructor Documentation

◆ FeatureVisualPoint()

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

Definition at line 29 of file feature-visual-point.cpp.

◆ ~FeatureVisualPoint()

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

Definition at line 72 of file feature-visual-point.hh.

Member Function Documentation

◆ computeError()

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

Compute the error between two visual features from a subset a the possible features.

Implements dynamicgraph::sot::FeatureAbstract.

Definition at line 140 of file feature-visual-point.cpp.

◆ computeJacobian()

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

Compute the interaction matrix from a subset of the possible features.

Implements dynamicgraph::sot::FeatureAbstract.

Definition at line 78 of file feature-visual-point.cpp.

◆ DECLARE_REFERENCE_FUNCTIONS()

dynamicgraph::sot::FeatureVisualPoint::DECLARE_REFERENCE_FUNCTIONS ( FeatureVisualPoint  )

◆ display()

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

Reimplemented from dynamicgraph::Entity.

Definition at line 162 of file feature-visual-point.cpp.

◆ getClassName()

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

Returns the name class.

Reimplemented from dynamicgraph::sot::FeatureAbstract.

Definition at line 51 of file feature-visual-point.hh.

◆ getDimension()

unsigned int & FeatureVisualPoint::getDimension ( unsigned int &  res,
int  time 
)
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.

Implements dynamicgraph::sot::FeatureAbstract.

Definition at line 62 of file feature-visual-point.cpp.

◆ selectX()

static Flags dynamicgraph::sot::FeatureVisualPoint::selectX ( void  )
inlinestatic

Static Feature selection.

Definition at line 82 of file feature-visual-point.hh.

◆ selectY()

static Flags dynamicgraph::sot::FeatureVisualPoint::selectY ( void  )
inlinestatic

Definition at line 83 of file feature-visual-point.hh.

Member Data Documentation

◆ articularJacobianSIN

dynamicgraph::SignalPtr<dynamicgraph::Matrix, int> dynamicgraph::sot::FeatureVisualPoint::articularJacobianSIN

Definition at line 62 of file feature-visual-point.hh.

◆ CLASS_NAME

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

Definition at line 50 of file feature-visual-point.hh.

◆ L

dynamicgraph::Matrix dynamicgraph::sot::FeatureVisualPoint::L
protected

Definition at line 54 of file feature-visual-point.hh.

◆ xySIN

dynamicgraph::SignalPtr<dynamicgraph::Vector, int> dynamicgraph::sot::FeatureVisualPoint::xySIN

Definition at line 58 of file feature-visual-point.hh.

◆ ZSIN

dynamicgraph::SignalPtr<double, int> dynamicgraph::sot::FeatureVisualPoint::ZSIN

FeatureVisualPoint depth (required to compute the interaction matrix) default Z = 1m.

Definition at line 61 of file feature-visual-point.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