#include <task-actuation-bounds.hpp>
Public Types | |
typedef math::ConstraintInequality | ConstraintInequality |
typedef pinocchio::Data | Data |
typedef trajectories::TrajectorySample | TrajectorySample |
typedef math::Vector | Vector |
typedef math::VectorXi | VectorXi |
![]() | |
typedef math::ConstRefVector | ConstRefVector |
typedef pinocchio::Data | Data |
typedef robots::RobotWrapper | RobotWrapper |
Public Member Functions | |
const ConstraintBase & | compute (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 ConstraintBase & | getConstraint () const override |
const Vector & | getLowerBounds () const |
const Vector & | getUpperBounds () const |
const Vector & | mask () const |
void | mask (const Vector &mask) |
void | setBounds (ConstRefVector lower, ConstRefVector upper) |
TaskActuationBounds (const std::string &name, RobotWrapper &robot) | |
![]() | |
TaskActuation (const std::string &name, RobotWrapper &robot) | |
![]() | |
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 |
![]() | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::ConstraintBase | ConstraintBase |
Protected Attributes | |
VectorXi | m_activeAxes |
ConstraintInequality | m_constraint |
Vector | m_mask |
![]() | |
std::string | m_name |
RobotWrapper & | m_robot |
Reference on the robot model. More... | |
Definition at line 28 of file tasks/task-actuation-bounds.hpp.
Definition at line 36 of file tasks/task-actuation-bounds.hpp.
Definition at line 37 of file tasks/task-actuation-bounds.hpp.
Definition at line 33 of file tasks/task-actuation-bounds.hpp.
Definition at line 34 of file tasks/task-actuation-bounds.hpp.
Definition at line 35 of file tasks/task-actuation-bounds.hpp.
tsid::tasks::TaskActuationBounds::TaskActuationBounds | ( | const std::string & | name, |
RobotWrapper & | robot | ||
) |
Definition at line 27 of file src/tasks/task-actuation-bounds.cpp.
|
overridevirtual |
Implements tsid::tasks::TaskBase.
Definition at line 85 of file src/tasks/task-actuation-bounds.cpp.
|
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.
|
overridevirtual |
Implements tsid::tasks::TaskBase.
Definition at line 81 of file src/tasks/task-actuation-bounds.cpp.
const Vector & tsid::tasks::TaskActuationBounds::getLowerBounds | ( | ) | const |
Definition at line 59 of file src/tasks/task-actuation-bounds.cpp.
const Vector & tsid::tasks::TaskActuationBounds::getUpperBounds | ( | ) | const |
Definition at line 63 of file src/tasks/task-actuation-bounds.cpp.
const Vector & tsid::tasks::TaskActuationBounds::mask | ( | ) | const |
Definition at line 34 of file src/tasks/task-actuation-bounds.cpp.
void tsid::tasks::TaskActuationBounds::mask | ( | const Vector & | mask | ) |
Definition at line 36 of file src/tasks/task-actuation-bounds.cpp.
void tsid::tasks::TaskActuationBounds::setBounds | ( | ConstRefVector | lower, |
ConstRefVector | upper | ||
) |
Definition at line 67 of file src/tasks/task-actuation-bounds.cpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Index tsid::tasks::TaskActuationBounds::Index |
Definition at line 32 of file tasks/task-actuation-bounds.hpp.
|
protected |
Definition at line 57 of file tasks/task-actuation-bounds.hpp.
|
protected |
Definition at line 58 of file tasks/task-actuation-bounds.hpp.
|
protected |
Definition at line 56 of file tasks/task-actuation-bounds.hpp.