Public Types | Public Member Functions | Public Attributes | Protected Attributes | List of all members
tsid::tasks::TaskActuationBounds Class Reference

#include <task-actuation-bounds.hpp>

Inheritance diagram for tsid::tasks::TaskActuationBounds:
Inheritance graph
[legend]

Public Types

typedef math::ConstraintInequality ConstraintInequality
 
typedef pinocchio::Data Data
 
typedef trajectories::TrajectorySample TrajectorySample
 
typedef math::Vector Vector
 
typedef math::VectorXi VectorXi
 
- Public Types inherited from tsid::tasks::TaskBase
typedef math::ConstRefVector ConstRefVector
 
typedef pinocchio::Data Data
 
typedef robots::RobotWrapper RobotWrapper
 

Public Member Functions

const ConstraintBasecompute (double t, ConstRefVector q, ConstRefVector v, Data &data) override
 
int dim () const override
 Return the dimension of the task. \info should be overloaded in the child class. More...
 
const ConstraintBasegetConstraint () const override
 
const VectorgetLowerBounds () const
 
const VectorgetUpperBounds () const
 
const Vectormask () const
 
void mask (const Vector &mask)
 
void setBounds (ConstRefVector lower, ConstRefVector upper)
 
 TaskActuationBounds (const std::string &name, RobotWrapper &robot)
 
- Public Member Functions inherited from tsid::tasks::TaskActuation
 TaskActuation (const std::string &name, RobotWrapper &robot)
 
- Public Member Functions inherited from tsid::tasks::TaskBase
const std::string & name () const
 
void name (const std::string &name)
 
 TaskBase (const std::string &name, RobotWrapper &robot)
 
virtual ~TaskBase ()=default
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Index Index
 
- Public Attributes inherited from tsid::tasks::TaskBase
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::ConstraintBase ConstraintBase
 

Protected Attributes

VectorXi m_activeAxes
 
ConstraintInequality m_constraint
 
Vector m_mask
 
- Protected Attributes inherited from tsid::tasks::TaskBase
std::string m_name
 
RobotWrapperm_robot
 Reference on the robot model. More...
 

Detailed Description

Definition at line 28 of file tasks/task-actuation-bounds.hpp.

Member Typedef Documentation

◆ ConstraintInequality

Definition at line 36 of file tasks/task-actuation-bounds.hpp.

◆ Data

Definition at line 37 of file tasks/task-actuation-bounds.hpp.

◆ TrajectorySample

Definition at line 33 of file tasks/task-actuation-bounds.hpp.

◆ Vector

Definition at line 34 of file tasks/task-actuation-bounds.hpp.

◆ VectorXi

Definition at line 35 of file tasks/task-actuation-bounds.hpp.

Constructor & Destructor Documentation

◆ TaskActuationBounds()

tsid::tasks::TaskActuationBounds::TaskActuationBounds ( const std::string &  name,
RobotWrapper robot 
)

Definition at line 27 of file src/tasks/task-actuation-bounds.cpp.

Member Function Documentation

◆ compute()

const ConstraintBase & tsid::tasks::TaskActuationBounds::compute ( double  t,
ConstRefVector  q,
ConstRefVector  v,
Data data 
)
overridevirtual

Implements tsid::tasks::TaskBase.

Definition at line 85 of file src/tasks/task-actuation-bounds.cpp.

◆ dim()

int tsid::tasks::TaskActuationBounds::dim ( ) const
overridevirtual

Return the dimension of the task. \info should be overloaded in the child class.

Implements tsid::tasks::TaskBase.

Definition at line 57 of file src/tasks/task-actuation-bounds.cpp.

◆ getConstraint()

const ConstraintBase & tsid::tasks::TaskActuationBounds::getConstraint ( ) const
overridevirtual

Implements tsid::tasks::TaskBase.

Definition at line 81 of file src/tasks/task-actuation-bounds.cpp.

◆ getLowerBounds()

const Vector & tsid::tasks::TaskActuationBounds::getLowerBounds ( ) const

Definition at line 59 of file src/tasks/task-actuation-bounds.cpp.

◆ getUpperBounds()

const Vector & tsid::tasks::TaskActuationBounds::getUpperBounds ( ) const

Definition at line 63 of file src/tasks/task-actuation-bounds.cpp.

◆ mask() [1/2]

const Vector & tsid::tasks::TaskActuationBounds::mask ( ) const

Definition at line 34 of file src/tasks/task-actuation-bounds.cpp.

◆ mask() [2/2]

void tsid::tasks::TaskActuationBounds::mask ( const Vector mask)

Definition at line 36 of file src/tasks/task-actuation-bounds.cpp.

◆ setBounds()

void tsid::tasks::TaskActuationBounds::setBounds ( ConstRefVector  lower,
ConstRefVector  upper 
)

Definition at line 67 of file src/tasks/task-actuation-bounds.cpp.

Member Data Documentation

◆ Index

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Index tsid::tasks::TaskActuationBounds::Index

Definition at line 32 of file tasks/task-actuation-bounds.hpp.

◆ m_activeAxes

VectorXi tsid::tasks::TaskActuationBounds::m_activeAxes
protected

Definition at line 57 of file tasks/task-actuation-bounds.hpp.

◆ m_constraint

ConstraintInequality tsid::tasks::TaskActuationBounds::m_constraint
protected

Definition at line 58 of file tasks/task-actuation-bounds.hpp.

◆ m_mask

Vector tsid::tasks::TaskActuationBounds::m_mask
protected

Definition at line 56 of file tasks/task-actuation-bounds.hpp.


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


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sat May 3 2025 02:48:17