#include <task-com-equality.hpp>
Public Types | |
typedef math::ConstraintEquality | ConstraintEquality |
typedef trajectories::TrajectorySample | TrajectorySample |
typedef math::Vector | Vector |
typedef math::Vector3 | Vector3 |
![]() | |
typedef trajectories::TrajectorySample | TrajectorySample |
![]() | |
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... | |
Vector | getAcceleration (ConstRefVector dv) const override |
const ConstraintBase & | getConstraint () const override |
const Vector & | getDesiredAcceleration () const override |
const TrajectorySample & | getReference () const override |
const Vector3 & | Kd () |
void | Kd (ConstRefVector Kp) |
const Vector3 & | Kp () |
void | Kp (ConstRefVector Kp) |
const Vector & | position () const override |
const Vector & | position_error () const override |
const Vector & | position_ref () const override |
virtual void | setMask (math::ConstRefVector mask) override |
void | setReference (const TrajectorySample &ref) |
TaskComEquality (const std::string &name, RobotWrapper &robot) | |
const Vector & | velocity () const override |
const Vector & | velocity_error () const override |
const Vector & | velocity_ref () const override |
![]() | |
virtual const Vector & | getMask () const |
virtual bool | hasMask () |
TaskMotion (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::Vector | Vector |
![]() | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::ConstraintBase | ConstraintBase |
Protected Attributes | |
Vector3 | m_a_des |
Vector | m_a_des_masked |
Vector | m_a_des_vec |
ConstraintEquality | m_constraint |
Vector3 | m_drift |
Vector | m_drift_masked |
Vector3 | m_Kd |
Vector3 | m_Kp |
Vector | m_p_com |
Vector3 | m_p_error |
Vector | m_p_error_masked_vec |
Vector | m_p_error_vec |
TrajectorySample | m_ref |
Vector | m_v_com |
Vector3 | m_v_error |
Vector | m_v_error_masked_vec |
Vector | m_v_error_vec |
![]() | |
Vector | m_dummy |
Vector | m_mask |
trajectories::TrajectorySample | TrajectorySample_dummy |
![]() | |
std::string | m_name |
RobotWrapper & | m_robot |
Reference on the robot model. More... | |
Definition at line 29 of file tasks/task-com-equality.hpp.
Definition at line 37 of file tasks/task-com-equality.hpp.
Definition at line 34 of file tasks/task-com-equality.hpp.
Definition at line 35 of file tasks/task-com-equality.hpp.
Definition at line 36 of file tasks/task-com-equality.hpp.
tsid::tasks::TaskComEquality::TaskComEquality | ( | const std::string & | name, |
RobotWrapper & | robot | ||
) |
Definition at line 27 of file src/tasks/task-com-equality.cpp.
|
overridevirtual |
Implements tsid::tasks::TaskBase.
Definition at line 106 of file src/tasks/task-com-equality.cpp.
|
overridevirtual |
Return the dimension of the task. \info should be overloaded in the child class.
Implements tsid::tasks::TaskBase.
Definition at line 54 of file src/tasks/task-com-equality.cpp.
|
overridevirtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 80 of file src/tasks/task-com-equality.cpp.
|
overridevirtual |
Implements tsid::tasks::TaskBase.
Definition at line 102 of file src/tasks/task-com-equality.cpp.
|
overridevirtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 76 of file src/tasks/task-com-equality.cpp.
|
overridevirtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 74 of file src/tasks/task-com-equality.cpp.
const Vector3 & tsid::tasks::TaskComEquality::Kd | ( | ) |
Definition at line 58 of file src/tasks/task-com-equality.cpp.
void tsid::tasks::TaskComEquality::Kd | ( | ConstRefVector | Kp | ) |
Definition at line 66 of file src/tasks/task-com-equality.cpp.
const Vector3 & tsid::tasks::TaskComEquality::Kp | ( | ) |
Definition at line 56 of file src/tasks/task-com-equality.cpp.
void tsid::tasks::TaskComEquality::Kp | ( | ConstRefVector | Kp | ) |
Definition at line 60 of file src/tasks/task-com-equality.cpp.
|
overridevirtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 92 of file src/tasks/task-com-equality.cpp.
|
overridevirtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 84 of file src/tasks/task-com-equality.cpp.
|
overridevirtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 96 of file src/tasks/task-com-equality.cpp.
|
overridevirtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 42 of file src/tasks/task-com-equality.cpp.
void tsid::tasks::TaskComEquality::setReference | ( | const TrajectorySample & | ref | ) |
Definition at line 72 of file src/tasks/task-com-equality.cpp.
|
overridevirtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 94 of file src/tasks/task-com-equality.cpp.
|
overridevirtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 88 of file src/tasks/task-com-equality.cpp.
|
overridevirtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 98 of file src/tasks/task-com-equality.cpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Index tsid::tasks::TaskComEquality::Index |
Definition at line 33 of file tasks/task-com-equality.hpp.
|
protected |
Definition at line 72 of file tasks/task-com-equality.hpp.
|
protected |
Definition at line 73 of file tasks/task-com-equality.hpp.
|
protected |
Definition at line 73 of file tasks/task-com-equality.hpp.
|
protected |
Definition at line 79 of file tasks/task-com-equality.hpp.
|
protected |
Definition at line 74 of file tasks/task-com-equality.hpp.
|
protected |
Definition at line 75 of file tasks/task-com-equality.hpp.
|
protected |
Definition at line 69 of file tasks/task-com-equality.hpp.
|
protected |
Definition at line 68 of file tasks/task-com-equality.hpp.
|
protected |
Definition at line 76 of file tasks/task-com-equality.hpp.
|
protected |
Definition at line 70 of file tasks/task-com-equality.hpp.
|
protected |
Definition at line 71 of file tasks/task-com-equality.hpp.
|
protected |
Definition at line 77 of file tasks/task-com-equality.hpp.
|
protected |
Definition at line 78 of file tasks/task-com-equality.hpp.
|
protected |
Definition at line 76 of file tasks/task-com-equality.hpp.
|
protected |
Definition at line 70 of file tasks/task-com-equality.hpp.
|
protected |
Definition at line 71 of file tasks/task-com-equality.hpp.
|
protected |
Definition at line 77 of file tasks/task-com-equality.hpp.