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

#include <task-joint-bounds.hpp>

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

Public Types

typedef math::ConstraintBound ConstraintBound
 
typedef pinocchio::Data Data
 
- Public Types inherited from tsid::tasks::TaskMotion
typedef trajectories::TrajectorySample TrajectorySample
 
- Public Types inherited from tsid::tasks::TaskBase
typedef math::ConstRefVector ConstRefVector
 
typedef pinocchio::Data Data
 
typedef robots::RobotWrapper RobotWrapper
 

Public Member Functions

const ConstraintBasecompute (const 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 VectorgetAccelerationLowerBounds () const
 
const VectorgetAccelerationUpperBounds () const
 
const ConstraintBasegetConstraint () const override
 
const VectorgetVelocityLowerBounds () const
 
const VectorgetVelocityUpperBounds () const
 
void setAccelerationBounds (ConstRefVector lower, ConstRefVector upper)
 
virtual void setMask (math::ConstRefVector mask) override
 
void setTimeStep (double dt)
 
void setVelocityBounds (ConstRefVector lower, ConstRefVector upper)
 
 TaskJointBounds (const std::string &name, RobotWrapper &robot, double dt)
 
- Public Member Functions inherited from tsid::tasks::TaskMotion
virtual Vector getAcceleration (ConstRefVector dv) const
 
virtual const VectorgetDesiredAcceleration () const
 
virtual const VectorgetMask () const
 
virtual const TrajectorySamplegetReference () const
 
virtual bool hasMask ()
 
virtual const Vectorposition () const
 
virtual const Vectorposition_error () const
 
virtual const Vectorposition_ref () const
 
 TaskMotion (const std::string &name, RobotWrapper &robot)
 
virtual const Vectorvelocity () const
 
virtual const Vectorvelocity_error () const
 
virtual const Vectorvelocity_ref () const
 
- 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::Vector Vector
 
- Public Attributes inherited from tsid::tasks::TaskMotion
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Vector Vector
 
- Public Attributes inherited from tsid::tasks::TaskBase
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::ConstraintBase ConstraintBase
 

Protected Attributes

Vector m_a_lb
 
Vector m_a_ub
 
ConstraintBound m_constraint
 
Vector m_ddq_max_due_to_vel
 
Vector m_ddq_min_due_to_vel
 
double m_dt
 
int m_na
 
int m_nv
 
Vector m_v_lb
 
Vector m_v_ub
 
- Protected Attributes inherited from tsid::tasks::TaskMotion
Vector m_dummy
 
Vector m_mask
 
trajectories::TrajectorySample TrajectorySample_dummy
 
- Protected Attributes inherited from tsid::tasks::TaskBase
std::string m_name
 
RobotWrapperm_robot
 Reference on the robot model. More...
 

Detailed Description

Definition at line 27 of file tasks/task-joint-bounds.hpp.

Member Typedef Documentation

◆ ConstraintBound

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

◆ Data

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

Constructor & Destructor Documentation

◆ TaskJointBounds()

tsid::tasks::TaskJointBounds::TaskJointBounds ( const std::string &  name,
RobotWrapper robot,
double  dt 
)

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

Member Function Documentation

◆ compute()

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

Implements tsid::tasks::TaskBase.

Definition at line 102 of file src/tasks/task-joint-bounds.cpp.

◆ dim()

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

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

Implements tsid::tasks::TaskBase.

Definition at line 49 of file src/tasks/task-joint-bounds.cpp.

◆ getAccelerationLowerBounds()

const Vector & tsid::tasks::TaskJointBounds::getAccelerationLowerBounds ( ) const

Definition at line 51 of file src/tasks/task-joint-bounds.cpp.

◆ getAccelerationUpperBounds()

const Vector & tsid::tasks::TaskJointBounds::getAccelerationUpperBounds ( ) const

Definition at line 55 of file src/tasks/task-joint-bounds.cpp.

◆ getConstraint()

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

Implements tsid::tasks::TaskBase.

Definition at line 96 of file src/tasks/task-joint-bounds.cpp.

◆ getVelocityLowerBounds()

const Vector & tsid::tasks::TaskJointBounds::getVelocityLowerBounds ( ) const

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

◆ getVelocityUpperBounds()

const Vector & tsid::tasks::TaskJointBounds::getVelocityUpperBounds ( ) const

Definition at line 61 of file src/tasks/task-joint-bounds.cpp.

◆ setAccelerationBounds()

void tsid::tasks::TaskJointBounds::setAccelerationBounds ( ConstRefVector  lower,
ConstRefVector  upper 
)

Definition at line 82 of file src/tasks/task-joint-bounds.cpp.

◆ setMask()

void tsid::tasks::TaskJointBounds::setMask ( math::ConstRefVector  mask)
overridevirtual

Reimplemented from tsid::tasks::TaskMotion.

Definition at line 100 of file src/tasks/task-joint-bounds.cpp.

◆ setTimeStep()

void tsid::tasks::TaskJointBounds::setTimeStep ( double  dt)

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

◆ setVelocityBounds()

void tsid::tasks::TaskJointBounds::setVelocityBounds ( ConstRefVector  lower,
ConstRefVector  upper 
)

Definition at line 68 of file src/tasks/task-joint-bounds.cpp.

Member Data Documentation

◆ m_a_lb

Vector tsid::tasks::TaskJointBounds::m_a_lb
protected

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

◆ m_a_ub

Vector tsid::tasks::TaskJointBounds::m_a_ub
protected

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

◆ m_constraint

ConstraintBound tsid::tasks::TaskJointBounds::m_constraint
protected

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

◆ m_ddq_max_due_to_vel

Vector tsid::tasks::TaskJointBounds::m_ddq_max_due_to_vel
protected

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

◆ m_ddq_min_due_to_vel

Vector tsid::tasks::TaskJointBounds::m_ddq_min_due_to_vel
protected

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

◆ m_dt

double tsid::tasks::TaskJointBounds::m_dt
protected

Definition at line 59 of file tasks/task-joint-bounds.hpp.

◆ m_na

int tsid::tasks::TaskJointBounds::m_na
protected

Definition at line 60 of file tasks/task-joint-bounds.hpp.

◆ m_nv

int tsid::tasks::TaskJointBounds::m_nv
protected

Definition at line 60 of file tasks/task-joint-bounds.hpp.

◆ m_v_lb

Vector tsid::tasks::TaskJointBounds::m_v_lb
protected

Definition at line 55 of file tasks/task-joint-bounds.hpp.

◆ m_v_ub

Vector tsid::tasks::TaskJointBounds::m_v_ub
protected

Definition at line 55 of file tasks/task-joint-bounds.hpp.

◆ Vector

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Vector tsid::tasks::TaskJointBounds::Vector

Definition at line 31 of file tasks/task-joint-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