Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
dynamicgraph::sot::Task Class Reference

Class that defines the basic elements of a task. More...

#include "Definition"

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

Public Types

typedef std::list< FeatureAbstract * > FeatureList_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

void addControlSelection (const Flags &act)
 
void addFeature (FeatureAbstract &s)
 
void addFeatureFromName (const std::string &name)
 
void clearControlSelection (void)
 
void clearFeatureList (void)
 
dynamicgraph::VectorcomputeError (dynamicgraph::Vector &error, int time)
 
dynamicgraph::VectorcomputeErrorTimeDerivative (dynamicgraph::Vector &res, int time)
 
dynamicgraph::MatrixcomputeJacobian (dynamicgraph::Matrix &J, int time)
 
VectorMultiBoundcomputeTaskExponentialDecrease (VectorMultiBound &errorRef, int time)
 
void display (std::ostream &os) const
 
FeatureList_tgetFeatureList (void)
 
bool getWithDerivative (void)
 
void initCommands (void)
 
void setControlSelection (const Flags &act)
 
void setWithDerivative (const bool &s)
 
 Task (const std::string &n)
 
virtual std::ostream & writeGraph (std::ostream &os) const
 
- Public Member Functions inherited from dynamicgraph::sot::TaskAbstract
 TaskAbstract (const std::string &n)
 
- Public Member Functions inherited from dynamicgraph::Entity
std::ostream & displaySignalList (std::ostream &os) const
 
 Entity (const std::string &name)
 
virtual const std::string & getClassName () const
 
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

dynamicgraph::SignalPtr< double, int > controlGainSIN
 
dynamicgraph::SignalPtr< Flags, int > controlSelectionSIN
 
dynamicgraph::SignalPtr< double, int > dampingGainSINOUT
 
dynamicgraph::SignalTimeDependent< dynamicgraph::Vector, int > errorSOUT
 
dynamicgraph::SignalTimeDependent< dynamicgraph::Vector, int > errorTimeDerivativeSOUT
 
- Public Attributes inherited from dynamicgraph::sot::TaskAbstract
dynamicgraph::SignalTimeDependent< dynamicgraph::Matrix, int > jacobianSOUT
 
MemoryTaskAbstractmemoryInternal
 
dynamicgraph::SignalTimeDependent< VectorMultiBound, int > taskSOUT
 

Protected Member Functions

 DYNAMIC_GRAPH_ENTITY_DECL ()
 
- Protected Member Functions inherited from dynamicgraph::sot::TaskAbstract
void taskRegistration (void)
 
- 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

FeatureList_t featureList
 
bool withDerivative
 
- Protected Attributes inherited from dynamicgraph::Entity
CommandMap_t commandMap
 
Logger logger_
 
std::string name
 
SignalMap signalMap
 

Detailed Description

Class that defines the basic elements of a task.

A task is defined as $ {\bf s} ={\bf e}({\bf q}) $ where ${\bf s} $ is a set of features and ${\bf q}$ the actuated joints of the robot.
It is assumes that $ \dot{\bf e} = - \lambda {\bf e} $. Moreover as it assumed that this task can provide: $ {\bf J} = \frac{\delta f}{\delta {\bf q}} $ It then possible to compute $ \dot{\bf q} = -\lambda {\bf J}^{\#} \dot{\bf e}$ with $ \dot{\bf e} = {\bf s}^{des} - {\bf s}^* $, and $ {\bf s}^{des}$ the desired feature and $ {\bf s}^* $ the one currently measured.

It is possible to add features or clear the list of features. This class makes also possible to select some of the listed of features to compute the control law through setControlSelection, addControlSelection, clearControlSelection.

Definition at line 72 of file task.hh.

Member Typedef Documentation

◆ FeatureList_t

Definition at line 74 of file task.hh.

Constructor & Destructor Documentation

◆ Task()

Task::Task ( const std::string &  n)

Definition at line 34 of file task.cpp.

Member Function Documentation

◆ addControlSelection()

void Task::addControlSelection ( const Flags act)

Definition at line 134 of file task.cpp.

◆ addFeature()

void Task::addFeature ( FeatureAbstract s)

Definition at line 108 of file task.cpp.

◆ addFeatureFromName()

void Task::addFeatureFromName ( const std::string &  name)

Definition at line 115 of file task.cpp.

◆ clearControlSelection()

void Task::clearControlSelection ( void  )

Definition at line 139 of file task.cpp.

◆ clearFeatureList()

void Task::clearFeatureList ( void  )

Definition at line 121 of file task.cpp.

◆ computeError()

dynamicgraph::Vector & Task::computeError ( dynamicgraph::Vector error,
int  time 
)

Definition at line 148 of file task.cpp.

◆ computeErrorTimeDerivative()

dynamicgraph::Vector & Task::computeErrorTimeDerivative ( dynamicgraph::Vector res,
int  time 
)

Definition at line 214 of file task.cpp.

◆ computeJacobian()

dynamicgraph::Matrix & Task::computeJacobian ( dynamicgraph::Matrix J,
int  time 
)

Definition at line 252 of file task.cpp.

◆ computeTaskExponentialDecrease()

VectorMultiBound & Task::computeTaskExponentialDecrease ( VectorMultiBound errorRef,
int  time 
)

Definition at line 232 of file task.cpp.

◆ display()

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

Reimplemented from dynamicgraph::Entity.

Definition at line 319 of file task.cpp.

◆ DYNAMIC_GRAPH_ENTITY_DECL()

dynamicgraph::sot::Task::DYNAMIC_GRAPH_ENTITY_DECL ( )
protected

◆ getFeatureList()

FeatureList_t& dynamicgraph::sot::Task::getFeatureList ( void  )
inline

Definition at line 89 of file task.hh.

◆ getWithDerivative()

bool Task::getWithDerivative ( void  )

Definition at line 142 of file task.cpp.

◆ initCommands()

void Task::initCommands ( void  )

Definition at line 68 of file task.cpp.

◆ setControlSelection()

void Task::setControlSelection ( const Flags act)

Definition at line 133 of file task.cpp.

◆ setWithDerivative()

void Task::setWithDerivative ( const bool &  s)

Definition at line 141 of file task.cpp.

◆ writeGraph()

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

Reimplemented from dynamicgraph::Entity.

Definition at line 329 of file task.cpp.

Member Data Documentation

◆ controlGainSIN

dynamicgraph::SignalPtr<double, int> dynamicgraph::sot::Task::controlGainSIN

Definition at line 108 of file task.hh.

◆ controlSelectionSIN

dynamicgraph::SignalPtr<Flags, int> dynamicgraph::sot::Task::controlSelectionSIN

Definition at line 110 of file task.hh.

◆ dampingGainSINOUT

dynamicgraph::SignalPtr<double, int> dynamicgraph::sot::Task::dampingGainSINOUT

Definition at line 109 of file task.hh.

◆ errorSOUT

dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> dynamicgraph::sot::Task::errorSOUT

Definition at line 111 of file task.hh.

◆ errorTimeDerivativeSOUT

dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> dynamicgraph::sot::Task::errorTimeDerivativeSOUT

Definition at line 113 of file task.hh.

◆ featureList

FeatureList_t dynamicgraph::sot::Task::featureList
protected

Definition at line 77 of file task.hh.

◆ withDerivative

bool dynamicgraph::sot::Task::withDerivative
protected

Definition at line 78 of file task.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