#include <task-joint-bounds.hpp>

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 ConstraintBase & | compute (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 Vector & | getAccelerationLowerBounds () const |
| const Vector & | getAccelerationUpperBounds () const |
| const ConstraintBase & | getConstraint () const override |
| const Vector & | getVelocityLowerBounds () const |
| const Vector & | getVelocityUpperBounds () 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 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 |
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 |
| RobotWrapper & | m_robot |
| Reference on the robot model. More... | |
Definition at line 27 of file tasks/task-joint-bounds.hpp.
Definition at line 32 of file tasks/task-joint-bounds.hpp.
Definition at line 33 of file tasks/task-joint-bounds.hpp.
| tsid::tasks::TaskJointBounds::TaskJointBounds | ( | const std::string & | name, |
| RobotWrapper & | robot, | ||
| double | dt | ||
| ) |
Definition at line 27 of file src/tasks/task-joint-bounds.cpp.
|
overridevirtual |
Implements tsid::tasks::TaskBase.
Definition at line 102 of file src/tasks/task-joint-bounds.cpp.
|
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.
| const Vector & tsid::tasks::TaskJointBounds::getAccelerationLowerBounds | ( | ) | const |
Definition at line 51 of file src/tasks/task-joint-bounds.cpp.
| const Vector & tsid::tasks::TaskJointBounds::getAccelerationUpperBounds | ( | ) | const |
Definition at line 55 of file src/tasks/task-joint-bounds.cpp.
|
overridevirtual |
Implements tsid::tasks::TaskBase.
Definition at line 96 of file src/tasks/task-joint-bounds.cpp.
| const Vector & tsid::tasks::TaskJointBounds::getVelocityLowerBounds | ( | ) | const |
Definition at line 59 of file src/tasks/task-joint-bounds.cpp.
| const Vector & tsid::tasks::TaskJointBounds::getVelocityUpperBounds | ( | ) | const |
Definition at line 61 of file src/tasks/task-joint-bounds.cpp.
| void tsid::tasks::TaskJointBounds::setAccelerationBounds | ( | ConstRefVector | lower, |
| ConstRefVector | upper | ||
| ) |
Definition at line 82 of file src/tasks/task-joint-bounds.cpp.
|
overridevirtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 100 of file src/tasks/task-joint-bounds.cpp.
| void tsid::tasks::TaskJointBounds::setTimeStep | ( | double | dt | ) |
Definition at line 63 of file src/tasks/task-joint-bounds.cpp.
| void tsid::tasks::TaskJointBounds::setVelocityBounds | ( | ConstRefVector | lower, |
| ConstRefVector | upper | ||
| ) |
Definition at line 68 of file src/tasks/task-joint-bounds.cpp.
|
protected |
Definition at line 56 of file tasks/task-joint-bounds.hpp.
|
protected |
Definition at line 56 of file tasks/task-joint-bounds.hpp.
|
protected |
Definition at line 58 of file tasks/task-joint-bounds.hpp.
|
protected |
Definition at line 57 of file tasks/task-joint-bounds.hpp.
|
protected |
Definition at line 57 of file tasks/task-joint-bounds.hpp.
|
protected |
Definition at line 59 of file tasks/task-joint-bounds.hpp.
|
protected |
Definition at line 60 of file tasks/task-joint-bounds.hpp.
|
protected |
Definition at line 60 of file tasks/task-joint-bounds.hpp.
|
protected |
Definition at line 55 of file tasks/task-joint-bounds.hpp.
|
protected |
Definition at line 55 of file tasks/task-joint-bounds.hpp.
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Vector tsid::tasks::TaskJointBounds::Vector |
Definition at line 31 of file tasks/task-joint-bounds.hpp.