#include <task-joint-posVelAcc-bounds.hpp>
|
| const ConstraintBase & | compute (const double t, ConstRefVector q, ConstRefVector v, Data &data) |
| |
| 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 |
| | Return the dimension of the task. should be overloaded in the child class. More...
|
| |
| const Vector & | getAccelerationBounds () const |
| |
| const ConstraintBase & | getConstraint () const |
| |
| const Vector & | getPositionLowerBounds () const |
| |
| const Vector & | getPositionUpperBounds () const |
| |
| const Vector & | getVelocityBounds () const |
| |
| void | isStateViable (ConstRefVector q, ConstRefVector dq, bool verbose=true) |
| |
| TSID_DEPRECATED const Vector & | mask () 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) |
| |
| 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) |
| |
| virtual | ~TaskJointPosVelAccBounds () |
| |
| virtual Vector | getAcceleration (ConstRefVector dv) const |
| |
| virtual const Vector & | getDesiredAcceleration () const |
| |
| virtual const Vector & | getMask () const |
| |
| virtual const TrajectorySample & | getReference () const |
| |
| virtual bool | hasMask () |
| |
| virtual const Vector & | position () const |
| |
| virtual const Vector & | position_error () const |
| |
| virtual const Vector & | position_ref () const |
| |
| | TaskMotion (const std::string &name, RobotWrapper &robot) |
| |
| virtual const Vector & | velocity () const |
| |
| virtual const Vector & | velocity_error () const |
| |
| virtual const Vector & | velocity_ref () const |
| |
| virtual | ~TaskMotion () |
| |
| const std::string & | name () const |
| |
| void | name (const std::string &name) |
| |
| | TaskBase (const std::string &name, RobotWrapper &robot) |
| |
| virtual | ~TaskBase () |
| |
◆ ConstraintBound
◆ ConstraintInequality
◆ Data
◆ VectorXi
◆ TaskJointPosVelAccBounds()
| tsid::tasks::TaskJointPosVelAccBounds::TaskJointPosVelAccBounds |
( |
const std::string & |
name, |
|
|
RobotWrapper & |
robot, |
|
|
double |
dt, |
|
|
bool |
verbose = true |
|
) |
| |
◆ ~TaskJointPosVelAccBounds()
| virtual tsid::tasks::TaskJointPosVelAccBounds::~TaskJointPosVelAccBounds |
( |
| ) |
|
|
inlinevirtual |
◆ compute()
◆ computeAccLimits()
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()
◆ computeAccLimitsFromViability()
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 |
|
virtual |
◆ getAccelerationBounds()
| const Vector & tsid::tasks::TaskJointPosVelAccBounds::getAccelerationBounds |
( |
| ) |
const |
◆ getConstraint()
| const ConstraintBase & tsid::tasks::TaskJointPosVelAccBounds::getConstraint |
( |
| ) |
const |
|
virtual |
◆ getPositionLowerBounds()
| const Vector & tsid::tasks::TaskJointPosVelAccBounds::getPositionLowerBounds |
( |
| ) |
const |
◆ getPositionUpperBounds()
| const Vector & tsid::tasks::TaskJointPosVelAccBounds::getPositionUpperBounds |
( |
| ) |
const |
◆ getVelocityBounds()
| const Vector & tsid::tasks::TaskJointPosVelAccBounds::getVelocityBounds |
( |
| ) |
const |
◆ isStateViable()
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 |
◆ mask() [2/2]
| void tsid::tasks::TaskJointPosVelAccBounds::mask |
( |
const Vector & |
mask | ) |
|
◆ setAccelerationBounds()
| void tsid::tasks::TaskJointPosVelAccBounds::setAccelerationBounds |
( |
ConstRefVector |
upper | ) |
|
◆ setImposeBounds()
| void tsid::tasks::TaskJointPosVelAccBounds::setImposeBounds |
( |
bool |
impose_position_bounds, |
|
|
bool |
impose_velocity_bounds, |
|
|
bool |
impose_viability_bounds, |
|
|
bool |
impose_acceleration_bounds |
|
) |
| |
◆ setMask()
◆ setPositionBounds()
◆ setTimeStep()
| void tsid::tasks::TaskJointPosVelAccBounds::setTimeStep |
( |
double |
dt | ) |
|
◆ setVelocityBounds()
| void tsid::tasks::TaskJointPosVelAccBounds::setVelocityBounds |
( |
ConstRefVector |
upper | ) |
|
◆ setVerbose()
| void tsid::tasks::TaskJointPosVelAccBounds::setVerbose |
( |
bool |
verbose | ) |
|
◆ m_activeAxes
| VectorXi tsid::tasks::TaskJointPosVelAccBounds::m_activeAxes |
|
protected |
◆ m_b_1
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_b_1 |
|
protected |
◆ m_b_2
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_b_2 |
|
protected |
◆ m_c_1
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_c_1 |
|
protected |
◆ m_c_2
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_c_2 |
|
protected |
◆ m_constraint
◆ m_ddq_1
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddq_1 |
|
protected |
◆ m_ddq_2
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddq_2 |
|
protected |
◆ m_ddqLB
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqLB |
|
protected |
◆ m_ddqLBAcc
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqLBAcc |
|
protected |
◆ m_ddqLBPos
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqLBPos |
|
protected |
◆ m_ddqLBVel
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqLBVel |
|
protected |
◆ m_ddqLBVia
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqLBVia |
|
protected |
◆ m_ddqMax
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqMax |
|
protected |
◆ m_ddqMax_q2
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqMax_q2 |
|
protected |
◆ m_ddqMax_q3
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqMax_q3 |
|
protected |
◆ m_ddqMin_q2
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqMin_q2 |
|
protected |
◆ m_ddqMin_q3
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqMin_q3 |
|
protected |
◆ m_ddqUB
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqUB |
|
protected |
◆ m_ddqUBAcc
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqUBAcc |
|
protected |
◆ m_ddqUBPos
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqUBPos |
|
protected |
◆ m_ddqUBVel
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqUBVel |
|
protected |
◆ m_ddqUBVia
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_ddqUBVia |
|
protected |
◆ m_delta_1
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_delta_1 |
|
protected |
◆ m_delta_2
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_delta_2 |
|
protected |
◆ m_dq_square
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_dq_square |
|
protected |
◆ m_dqa
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_dqa |
|
protected |
◆ m_dqMax
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_dqMax |
|
protected |
◆ m_dqMaxViab
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_dqMaxViab |
|
protected |
◆ m_dqMinViab
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_dqMinViab |
|
protected |
◆ m_dt
| double tsid::tasks::TaskJointPosVelAccBounds::m_dt |
|
protected |
◆ m_dt_ddqMax_dt
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_dt_ddqMax_dt |
|
protected |
◆ m_dt_dq
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_dt_dq |
|
protected |
◆ m_dt_square
| double tsid::tasks::TaskJointPosVelAccBounds::m_dt_square |
|
protected |
◆ m_dt_two_dq
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_dt_two_dq |
|
protected |
◆ m_eps
| double tsid::tasks::TaskJointPosVelAccBounds::m_eps |
|
protected |
◆ m_impose_acceleration_bounds
| bool tsid::tasks::TaskJointPosVelAccBounds::m_impose_acceleration_bounds |
|
protected |
◆ m_impose_position_bounds
| bool tsid::tasks::TaskJointPosVelAccBounds::m_impose_position_bounds |
|
protected |
◆ m_impose_velocity_bounds
| bool tsid::tasks::TaskJointPosVelAccBounds::m_impose_velocity_bounds |
|
protected |
◆ m_impose_viability_bounds
| bool tsid::tasks::TaskJointPosVelAccBounds::m_impose_viability_bounds |
|
protected |
◆ m_lb
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_lb |
|
protected |
◆ m_mask
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_mask |
|
protected |
◆ m_minus_dq_over_dt
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_minus_dq_over_dt |
|
protected |
◆ m_na
| int tsid::tasks::TaskJointPosVelAccBounds::m_na |
|
protected |
◆ m_nv
| int tsid::tasks::TaskJointPosVelAccBounds::m_nv |
|
protected |
◆ m_q_plus_dt_dq
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_q_plus_dt_dq |
|
protected |
◆ m_qa
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_qa |
|
protected |
◆ m_qMax
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_qMax |
|
protected |
◆ m_qMin
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_qMin |
|
protected |
◆ m_two_a
| double tsid::tasks::TaskJointPosVelAccBounds::m_two_a |
|
protected |
◆ m_two_ddqMax
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_two_ddqMax |
|
protected |
◆ m_two_dt_sq
| double tsid::tasks::TaskJointPosVelAccBounds::m_two_dt_sq |
|
protected |
◆ m_ub
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_ub |
|
protected |
◆ m_verbose
| bool tsid::tasks::TaskJointPosVelAccBounds::m_verbose |
|
protected |
◆ m_viabViol
| Vector tsid::tasks::TaskJointPosVelAccBounds::m_viabViol |
|
protected |
◆ Vector
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Vector tsid::tasks::TaskJointPosVelAccBounds::Vector |
The documentation for this class was generated from the following files: