Classes | Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | Friends | List of all members
dynamicgraph::sot::FeaturePosture Class Reference

#include <feature-posture.hh>

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

Classes

class  SelectDof
 

Public Types

typedef dynamicgraph::SignalPtr< dynamicgraph::Vector, int > signalIn_t
 
typedef dynamicgraph::SignalTimeDependent< dynamicgraph::Vector, int > signalOut_t
 
- Public Types inherited from dynamicgraph::Entity
typedef std::map< const std::string, command::Command *> CommandMap_t
 
typedef std::map< std::string, SignalBase< int > *> SignalMap
 

Public Member Functions

 FeaturePosture (const std::string &name)
 
virtual unsigned int & getDimension (unsigned int &res, int)
 Verbose method. More...
 
void selectDof (unsigned dofId, bool control)
 
virtual ~FeaturePosture ()
 
- 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...
 
virtual const std::string & getClassName (void) const
 Returns the name class. 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 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
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< 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

 DECLARE_NO_REFERENCE
 
- 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...
 

Protected Member Functions

virtual dynamicgraph::VectorcomputeError (dynamicgraph::Vector &res, int)
 Compute the error between the desired feature and the current value of the feature measured or deduced from the robot state. More...
 
virtual dynamicgraph::VectorcomputeErrorDot (dynamicgraph::Vector &res, int time)
 
virtual dynamicgraph::MatrixcomputeJacobian (dynamicgraph::Matrix &res, int)
 Compute the Jacobian of the error according the robot state. More...
 
- 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)
 

Protected Attributes

signalOut_t error_
 
signalIn_t posture_
 
signalIn_t postureDot_
 
signalIn_t state_
 
- Protected Attributes inherited from dynamicgraph::Entity
CommandMap_t commandMap
 
Logger logger_
 
std::string name
 
SignalMap signalMap
 

Private Member Functions

 DYNAMIC_GRAPH_ENTITY_DECL ()
 

Private Attributes

std::vector< bool > activeDofs_
 
std::size_t nbActiveDofs_
 

Friends

class SelectDof
 

Additional Inherited Members

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

Detailed Description

Feature that observes the posture of the robot, ie whose Jacobian is the identity, or slices of the identity. This feature can be exactly obtained with a generic posture, given the identity matrix as the input Jacobian, the identity matrix. It is even prefereable, as the reference value is then given by a signal, which can be reevalutated at each iteration, for example to track a reference trajectory in the configuration space. See for example the toFlag python function in the sot-dyninv module to nicely selec the posture DOF.

Definition at line 49 of file feature-posture.hh.

Member Typedef Documentation

◆ signalIn_t

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

◆ signalOut_t

Definition at line 58 of file feature-posture.hh.

Constructor & Destructor Documentation

◆ FeaturePosture()

dynamicgraph::sot::FeaturePosture::FeaturePosture ( const std::string &  name)
explicit

Definition at line 37 of file feature-posture.cpp.

◆ ~FeaturePosture()

dynamicgraph::sot::FeaturePosture::~FeaturePosture ( )
virtual

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

Member Function Documentation

◆ computeError()

dg::Vector & dynamicgraph::sot::FeaturePosture::computeError ( dynamicgraph::Vector res,
int  time 
)
protectedvirtual

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.

Implements dynamicgraph::sot::FeatureAbstract.

Definition at line 73 of file feature-posture.cpp.

◆ computeErrorDot()

dg::Vector & dynamicgraph::sot::FeaturePosture::computeErrorDot ( dynamicgraph::Vector res,
int  time 
)
protectedvirtual

Callback for signal errordotSOUT

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

Reimplemented from dynamicgraph::sot::FeatureAbstract.

Definition at line 94 of file feature-posture.cpp.

◆ computeJacobian()

dg::Matrix & dynamicgraph::sot::FeaturePosture::computeJacobian ( dynamicgraph::Matrix res,
int  time 
)
protectedvirtual

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.

Implements dynamicgraph::sot::FeatureAbstract.

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

◆ DYNAMIC_GRAPH_ENTITY_DECL()

dynamicgraph::sot::FeaturePosture::DYNAMIC_GRAPH_ENTITY_DECL ( )
private

◆ getDimension()

unsigned int & dynamicgraph::sot::FeaturePosture::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 68 of file feature-posture.cpp.

◆ selectDof()

void dynamicgraph::sot::FeaturePosture::selectDof ( unsigned  dofId,
bool  control 
)

Definition at line 105 of file feature-posture.cpp.

Friends And Related Function Documentation

◆ SelectDof

friend class SelectDof
friend

Definition at line 50 of file feature-posture.hh.

Member Data Documentation

◆ activeDofs_

std::vector<bool> dynamicgraph::sot::FeaturePosture::activeDofs_
private

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

◆ DECLARE_NO_REFERENCE

dynamicgraph::sot::FeaturePosture::DECLARE_NO_REFERENCE

Definition at line 60 of file feature-posture.hh.

◆ error_

signalOut_t dynamicgraph::sot::FeaturePosture::error_
protected

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

◆ nbActiveDofs_

std::size_t dynamicgraph::sot::FeaturePosture::nbActiveDofs_
private

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

◆ posture_

signalIn_t dynamicgraph::sot::FeaturePosture::posture_
protected

Definition at line 74 of file feature-posture.hh.

◆ postureDot_

signalIn_t dynamicgraph::sot::FeaturePosture::postureDot_
protected

Definition at line 75 of file feature-posture.hh.

◆ state_

signalIn_t dynamicgraph::sot::FeaturePosture::state_
protected

Definition at line 73 of file feature-posture.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