#include <task-joint-posture.hpp>

Public Types | |
| typedef math::ConstraintEquality | ConstraintEquality |
| typedef pinocchio::Data | Data |
| typedef trajectories::TrajectorySample | TrajectorySample |
| typedef math::Vector | Vector |
| 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 ConstraintBase & | compute (const double t, ConstRefVector q, ConstRefVector v, Data &data) |
| int | dim () const |
| Return the dimension of the task. should be overloaded in the child class. More... | |
| Vector | getAcceleration (ConstRefVector dv) const |
| const ConstraintBase & | getConstraint () const |
| const Vector & | getDesiredAcceleration () const |
| const TrajectorySample & | getReference () const |
| const Vector & | Kd () |
| void | Kd (ConstRefVector Kp) |
| const Vector & | Kp () |
| void | Kp (ConstRefVector Kp) |
| TSID_DEPRECATED const Vector & | mask () const |
| TSID_DEPRECATED void | mask (const Vector &mask) |
| const Vector & | position () const |
| const Vector & | position_error () const |
| const Vector & | position_ref () const |
| virtual void | setMask (math::ConstRefVector mask) |
| void | setReference (const TrajectorySample &ref) |
| TaskJointPosture (const std::string &name, RobotWrapper &robot) | |
| const Vector & | velocity () const |
| const Vector & | velocity_error () const |
| const Vector & | velocity_ref () const |
| virtual | ~TaskJointPosture () |
Public Member Functions inherited from tsid::tasks::TaskMotion | |
| virtual const Vector & | getMask () const |
| virtual bool | hasMask () |
| TaskMotion (const std::string &name, RobotWrapper &robot) | |
| virtual | ~TaskMotion () |
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 () |
Public Attributes | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Index | Index |
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_des |
| VectorXi | m_activeAxes |
| ConstraintEquality | m_constraint |
| Vector | m_Kd |
| Vector | m_Kp |
| Vector | m_p |
| Vector | m_p_error |
| TrajectorySample | m_ref |
| Vector | m_ref_q_augmented |
| Vector | m_v |
| Vector | m_v_error |
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 29 of file tasks/task-joint-posture.hpp.
Definition at line 37 of file tasks/task-joint-posture.hpp.
Definition at line 38 of file tasks/task-joint-posture.hpp.
Definition at line 34 of file tasks/task-joint-posture.hpp.
Definition at line 35 of file tasks/task-joint-posture.hpp.
Definition at line 36 of file tasks/task-joint-posture.hpp.
| tsid::tasks::TaskJointPosture::TaskJointPosture | ( | const std::string & | name, |
| RobotWrapper & | robot | ||
| ) |
Definition at line 28 of file src/tasks/task-joint-posture.cpp.
|
inlinevirtual |
Definition at line 42 of file tasks/task-joint-posture.hpp.
|
virtual |
Implements tsid::tasks::TaskBase.
Definition at line 136 of file src/tasks/task-joint-posture.cpp.
|
virtual |
Return the dimension of the task. should be overloaded in the child class.
Implements tsid::tasks::TaskBase.
Definition at line 69 of file src/tasks/task-joint-posture.cpp.
|
virtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 112 of file src/tasks/task-joint-posture.cpp.
|
virtual |
Implements tsid::tasks::TaskBase.
Definition at line 132 of file src/tasks/task-joint-posture.cpp.
|
virtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 108 of file src/tasks/task-joint-posture.cpp.
|
virtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 106 of file src/tasks/task-joint-posture.cpp.
| const Vector & tsid::tasks::TaskJointPosture::Kd | ( | ) |
Definition at line 73 of file src/tasks/task-joint-posture.cpp.
| void tsid::tasks::TaskJointPosture::Kd | ( | ConstRefVector | Kp | ) |
Definition at line 82 of file src/tasks/task-joint-posture.cpp.
| const Vector & tsid::tasks::TaskJointPosture::Kp | ( | ) |
Definition at line 71 of file src/tasks/task-joint-posture.cpp.
| void tsid::tasks::TaskJointPosture::Kp | ( | ConstRefVector | Kp | ) |
Definition at line 75 of file src/tasks/task-joint-posture.cpp.
| const Vector & tsid::tasks::TaskJointPosture::mask | ( | ) | const |
Definition at line 39 of file src/tasks/task-joint-posture.cpp.
| void tsid::tasks::TaskJointPosture::mask | ( | const Vector & | mask | ) |
Definition at line 41 of file src/tasks/task-joint-posture.cpp.
|
virtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 120 of file src/tasks/task-joint-posture.cpp.
|
virtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 116 of file src/tasks/task-joint-posture.cpp.
|
virtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 124 of file src/tasks/task-joint-posture.cpp.
|
virtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 47 of file src/tasks/task-joint-posture.cpp.
| void tsid::tasks::TaskJointPosture::setReference | ( | const TrajectorySample & | ref | ) |
Definition at line 89 of file src/tasks/task-joint-posture.cpp.
|
virtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 122 of file src/tasks/task-joint-posture.cpp.
|
virtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 118 of file src/tasks/task-joint-posture.cpp.
|
virtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 128 of file src/tasks/task-joint-posture.cpp.
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Index tsid::tasks::TaskJointPosture::Index |
Definition at line 33 of file tasks/task-joint-posture.hpp.
|
protected |
Definition at line 78 of file tasks/task-joint-posture.hpp.
|
protected |
Definition at line 79 of file tasks/task-joint-posture.hpp.
|
protected |
Definition at line 82 of file tasks/task-joint-posture.hpp.
|
protected |
Definition at line 75 of file tasks/task-joint-posture.hpp.
|
protected |
Definition at line 74 of file tasks/task-joint-posture.hpp.
|
protected |
Definition at line 77 of file tasks/task-joint-posture.hpp.
|
protected |
Definition at line 76 of file tasks/task-joint-posture.hpp.
|
protected |
Definition at line 80 of file tasks/task-joint-posture.hpp.
|
protected |
Definition at line 81 of file tasks/task-joint-posture.hpp.
|
protected |
Definition at line 77 of file tasks/task-joint-posture.hpp.
|
protected |
Definition at line 76 of file tasks/task-joint-posture.hpp.