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

#include <task-joint-posVelAcc-bounds.hpp>

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

Public Types

typedef math::ConstraintBound ConstraintBound
 
typedef math::ConstraintInequality ConstraintInequality
 
typedef pinocchio::Data Data
 
typedef math::VectorXi VectorXi
 
- 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 (double t, ConstRefVector q, ConstRefVector v, Data &data) override
 
void computeAccLimits (ConstRefVector q, ConstRefVector dq, bool verbose=true)
 
void computeAccLimitsFromPosLimits (ConstRefVector q, ConstRefVector dq, bool verbose=true)
 
void computeAccLimitsFromViability (ConstRefVector q, ConstRefVector dq, bool verbose=true)
 
int dim () const override
 Return the dimension of the task. \info should be overloaded in the child class. More...
 
const VectorgetAccelerationBounds () const
 
const ConstraintBasegetConstraint () const override
 
const VectorgetPositionLowerBounds () const
 
const VectorgetPositionUpperBounds () const
 
const VectorgetVelocityBounds () const
 
void isStateViable (ConstRefVector q, ConstRefVector dq, bool verbose=true)
 
const TSID_DEPRECATED Vectormask () const
 
TSID_DEPRECATED void mask (const Vector &mask)
 
void setAccelerationBounds (ConstRefVector upper)
 
void setImposeBounds (bool impose_position_bounds, bool impose_velocity_bounds, bool impose_viability_bounds, bool impose_acceleration_bounds)
 
virtual void setMask (math::ConstRefVector mask) override
 
void setPositionBounds (ConstRefVector lower, ConstRefVector upper)
 
void setTimeStep (double dt)
 
void setVelocityBounds (ConstRefVector upper)
 
void setVerbose (bool verbose)
 
 TaskJointPosVelAccBounds (const std::string &name, RobotWrapper &robot, double dt, bool verbose=true)
 
- 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

VectorXi m_activeAxes
 
Vector m_b_1
 
Vector m_b_2
 
Vector m_c_1
 
Vector m_c_2
 
ConstraintInequality m_constraint
 
Vector m_ddq_1
 
Vector m_ddq_2
 
Vector m_ddqLB
 
Vector m_ddqLBAcc
 
Vector m_ddqLBPos
 
Vector m_ddqLBVel
 
Vector m_ddqLBVia
 
Vector m_ddqMax
 
Vector m_ddqMax_q2
 
Vector m_ddqMax_q3
 
Vector m_ddqMin_q2
 
Vector m_ddqMin_q3
 
Vector m_ddqUB
 
Vector m_ddqUBAcc
 
Vector m_ddqUBPos
 
Vector m_ddqUBVel
 
Vector m_ddqUBVia
 
Vector m_delta_1
 
Vector m_delta_2
 
Vector m_dq_square
 
Vector m_dqa
 
Vector m_dqMax
 
Vector m_dqMaxViab
 
Vector m_dqMinViab
 
double m_dt
 
Vector m_dt_ddqMax_dt
 
Vector m_dt_dq
 
double m_dt_square
 
Vector m_dt_two_dq
 
double m_eps
 
bool m_impose_acceleration_bounds
 
bool m_impose_position_bounds
 
bool m_impose_velocity_bounds
 
bool m_impose_viability_bounds
 
Vector m_lb
 
Vector m_mask
 
Vector m_minus_dq_over_dt
 
int m_na
 
int m_nv
 
Vector m_q_plus_dt_dq
 
Vector m_qa
 
Vector m_qMax
 
Vector m_qMin
 
double m_two_a
 
Vector m_two_ddqMax
 
double m_two_dt_sq
 
Vector m_ub
 
bool m_verbose
 
Vector m_viabViol
 
- 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 36 of file tasks/task-joint-posVelAcc-bounds.hpp.

Member Typedef Documentation

◆ ConstraintBound

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

◆ ConstraintInequality

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

◆ Data

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

◆ VectorXi

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

Constructor & Destructor Documentation

◆ TaskJointPosVelAccBounds()

tsid::tasks::TaskJointPosVelAccBounds::TaskJointPosVelAccBounds ( const std::string &  name,
RobotWrapper robot,
double  dt,
bool  verbose = true 
)

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

Member Function Documentation

◆ compute()

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

Implements tsid::tasks::TaskBase.

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

◆ computeAccLimits()

void tsid::tasks::TaskJointPosVelAccBounds::computeAccLimits ( ConstRefVector  q,
ConstRefVector  dq,
bool  verbose = true 
)

Given the current position and velocity, the bounds of position, velocity and acceleration and the control time step, compute the bounds of the acceleration such that all the bounds are respected at the next time step and can be respected in the future. ddqMax is the absolute maximum acceleration.

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

◆ computeAccLimitsFromPosLimits()

void tsid::tasks::TaskJointPosVelAccBounds::computeAccLimitsFromPosLimits ( ConstRefVector  q,
ConstRefVector  dq,
bool  verbose = true 
)

Compute acceleration limits imposed by position bounds. Fills in m_ddqLBPos and m_ddqUBPos

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

◆ computeAccLimitsFromViability()

void tsid::tasks::TaskJointPosVelAccBounds::computeAccLimitsFromViability ( ConstRefVector  q,
ConstRefVector  dq,
bool  verbose = true 
)

Compute acceleration limits imposed by viability. ddqMax is the maximum acceleration that will be necessary to stop the joint before hitting the position limits.

-sqrt( 2*ddqMax*(q-qMin) ) < dq[t+1] < sqrt( 2*ddqMax*(qMax-q) ) ddqMin[2] = (-sqrt(max(0.0, 2*MAX_ACC*(q[i]+DT*dq[i]-qMin))) - dq[i])/DT; ddqMax[2] = (sqrt(max(0.0, 2*MAX_ACC*(qMax-q[i]-DT*dq[i]))) - dq[i])/DT;

Fills in m_ddqLBVia and m_ddqUBVia

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

◆ dim()

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

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

Implements tsid::tasks::TaskBase.

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

◆ getAccelerationBounds()

const Vector & tsid::tasks::TaskJointPosVelAccBounds::getAccelerationBounds ( ) const

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

◆ getConstraint()

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

Implements tsid::tasks::TaskBase.

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

◆ getPositionLowerBounds()

const Vector & tsid::tasks::TaskJointPosVelAccBounds::getPositionLowerBounds ( ) const

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

◆ getPositionUpperBounds()

const Vector & tsid::tasks::TaskJointPosVelAccBounds::getPositionUpperBounds ( ) const

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

◆ getVelocityBounds()

const Vector & tsid::tasks::TaskJointPosVelAccBounds::getVelocityBounds ( ) const

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

◆ isStateViable()

void tsid::tasks::TaskJointPosVelAccBounds::isStateViable ( ConstRefVector  q,
ConstRefVector  dq,
bool  verbose = true 
)

Check if the state is viable, otherwise it returns a measure of the violation of the violated inequality. Fills in m_viabViol , if the state of joint i is viable m_viabViol[i] = 0

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

◆ mask() [1/2]

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

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

◆ mask() [2/2]

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

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

◆ setAccelerationBounds()

void tsid::tasks::TaskJointPosVelAccBounds::setAccelerationBounds ( ConstRefVector  upper)

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

◆ setImposeBounds()

void tsid::tasks::TaskJointPosVelAccBounds::setImposeBounds ( bool  impose_position_bounds,
bool  impose_velocity_bounds,
bool  impose_viability_bounds,
bool  impose_acceleration_bounds 
)

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

◆ setMask()

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

Reimplemented from tsid::tasks::TaskMotion.

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

◆ setPositionBounds()

void tsid::tasks::TaskJointPosVelAccBounds::setPositionBounds ( ConstRefVector  lower,
ConstRefVector  upper 
)

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

◆ setTimeStep()

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

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

◆ setVelocityBounds()

void tsid::tasks::TaskJointPosVelAccBounds::setVelocityBounds ( ConstRefVector  upper)

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

◆ setVerbose()

void tsid::tasks::TaskJointPosVelAccBounds::setVerbose ( bool  verbose)

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

Member Data Documentation

◆ m_activeAxes

VectorXi tsid::tasks::TaskJointPosVelAccBounds::m_activeAxes
protected

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

◆ m_b_1

Vector tsid::tasks::TaskJointPosVelAccBounds::m_b_1
protected

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

◆ m_b_2

Vector tsid::tasks::TaskJointPosVelAccBounds::m_b_2
protected

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

◆ m_c_1

Vector tsid::tasks::TaskJointPosVelAccBounds::m_c_1
protected

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

◆ m_c_2

Vector tsid::tasks::TaskJointPosVelAccBounds::m_c_2
protected

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

◆ m_constraint

ConstraintInequality tsid::tasks::TaskJointPosVelAccBounds::m_constraint
protected

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

◆ m_ddq_1

Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddq_1
protected

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

◆ m_ddq_2

Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddq_2
protected

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

◆ m_ddqLB

Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqLB
protected

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

◆ m_ddqLBAcc

Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqLBAcc
protected

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

◆ m_ddqLBPos

Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqLBPos
protected

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

◆ m_ddqLBVel

Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqLBVel
protected

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

◆ m_ddqLBVia

Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqLBVia
protected

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

◆ m_ddqMax

Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqMax
protected

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

◆ m_ddqMax_q2

Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqMax_q2
protected

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

◆ m_ddqMax_q3

Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqMax_q3
protected

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

◆ m_ddqMin_q2

Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqMin_q2
protected

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

◆ m_ddqMin_q3

Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqMin_q3
protected

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

◆ m_ddqUB

Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqUB
protected

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

◆ m_ddqUBAcc

Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqUBAcc
protected

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

◆ m_ddqUBPos

Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqUBPos
protected

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

◆ m_ddqUBVel

Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqUBVel
protected

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

◆ m_ddqUBVia

Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqUBVia
protected

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

◆ m_delta_1

Vector tsid::tasks::TaskJointPosVelAccBounds::m_delta_1
protected

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

◆ m_delta_2

Vector tsid::tasks::TaskJointPosVelAccBounds::m_delta_2
protected

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

◆ m_dq_square

Vector tsid::tasks::TaskJointPosVelAccBounds::m_dq_square
protected

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

◆ m_dqa

Vector tsid::tasks::TaskJointPosVelAccBounds::m_dqa
protected

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

◆ m_dqMax

Vector tsid::tasks::TaskJointPosVelAccBounds::m_dqMax
protected

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

◆ m_dqMaxViab

Vector tsid::tasks::TaskJointPosVelAccBounds::m_dqMaxViab
protected

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

◆ m_dqMinViab

Vector tsid::tasks::TaskJointPosVelAccBounds::m_dqMinViab
protected

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

◆ m_dt

double tsid::tasks::TaskJointPosVelAccBounds::m_dt
protected

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

◆ m_dt_ddqMax_dt

Vector tsid::tasks::TaskJointPosVelAccBounds::m_dt_ddqMax_dt
protected

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

◆ m_dt_dq

Vector tsid::tasks::TaskJointPosVelAccBounds::m_dt_dq
protected

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

◆ m_dt_square

double tsid::tasks::TaskJointPosVelAccBounds::m_dt_square
protected

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

◆ m_dt_two_dq

Vector tsid::tasks::TaskJointPosVelAccBounds::m_dt_two_dq
protected

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

◆ m_eps

double tsid::tasks::TaskJointPosVelAccBounds::m_eps
protected

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

◆ m_impose_acceleration_bounds

bool tsid::tasks::TaskJointPosVelAccBounds::m_impose_acceleration_bounds
protected

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

◆ m_impose_position_bounds

bool tsid::tasks::TaskJointPosVelAccBounds::m_impose_position_bounds
protected

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

◆ m_impose_velocity_bounds

bool tsid::tasks::TaskJointPosVelAccBounds::m_impose_velocity_bounds
protected

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

◆ m_impose_viability_bounds

bool tsid::tasks::TaskJointPosVelAccBounds::m_impose_viability_bounds
protected

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

◆ m_lb

Vector tsid::tasks::TaskJointPosVelAccBounds::m_lb
protected

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

◆ m_mask

Vector tsid::tasks::TaskJointPosVelAccBounds::m_mask
protected

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

◆ m_minus_dq_over_dt

Vector tsid::tasks::TaskJointPosVelAccBounds::m_minus_dq_over_dt
protected

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

◆ m_na

int tsid::tasks::TaskJointPosVelAccBounds::m_na
protected

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

◆ m_nv

int tsid::tasks::TaskJointPosVelAccBounds::m_nv
protected

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

◆ m_q_plus_dt_dq

Vector tsid::tasks::TaskJointPosVelAccBounds::m_q_plus_dt_dq
protected

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

◆ m_qa

Vector tsid::tasks::TaskJointPosVelAccBounds::m_qa
protected

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

◆ m_qMax

Vector tsid::tasks::TaskJointPosVelAccBounds::m_qMax
protected

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

◆ m_qMin

Vector tsid::tasks::TaskJointPosVelAccBounds::m_qMin
protected

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

◆ m_two_a

double tsid::tasks::TaskJointPosVelAccBounds::m_two_a
protected

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

◆ m_two_ddqMax

Vector tsid::tasks::TaskJointPosVelAccBounds::m_two_ddqMax
protected

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

◆ m_two_dt_sq

double tsid::tasks::TaskJointPosVelAccBounds::m_two_dt_sq
protected

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

◆ m_ub

Vector tsid::tasks::TaskJointPosVelAccBounds::m_ub
protected

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

◆ m_verbose

bool tsid::tasks::TaskJointPosVelAccBounds::m_verbose
protected

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

◆ m_viabViol

Vector tsid::tasks::TaskJointPosVelAccBounds::m_viabViol
protected

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

◆ Vector

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Vector tsid::tasks::TaskJointPosVelAccBounds::Vector

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