#include <task-angular-momentum-equality.hpp>
Public Types | |
typedef math::ConstraintEquality | ConstraintEquality |
typedef pinocchio::Data::Matrix6x | Matrix6x |
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... | |
const Vector & | dmomentum_ref () const |
const ConstraintBase & | getConstraint () const override |
const Vector3 & | getDesiredMomentumDerivative () const |
Vector3 | getdMomentum (ConstRefVector dv) const |
const TrajectorySample & | getReference () const override |
const Vector3 & | Kd () |
void | Kd (ConstRefVector Kp) |
const Vector3 & | Kp () |
void | Kp (ConstRefVector Kp) |
const Vector3 & | momentum () const |
const Vector3 & | momentum_error () const |
const Vector & | momentum_ref () const |
void | setReference (const TrajectorySample &ref) |
TaskAMEquality (const std::string &name, RobotWrapper &robot) | |
![]() | |
virtual Vector | getAcceleration (ConstRefVector dv) const |
virtual const Vector & | getDesiredAcceleration () const |
virtual const Vector & | getMask () const |
virtual bool | hasMask () |
virtual const Vector & | position () const |
virtual const Vector & | position_error () const |
virtual const Vector & | position_ref () const |
virtual void | setMask (math::ConstRefVector mask) |
TaskMotion (const std::string &name, RobotWrapper &robot) | |
virtual const Vector & | velocity () const |
virtual const Vector & | velocity_error () const |
virtual const Vector & | velocity_ref () const |
![]() | |
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 | |
ConstraintEquality | m_constraint |
Vector3 | m_dL |
Vector3 | m_dL_des |
Vector3 | m_dL_error |
Vector3 | m_drift |
Vector3 | m_Kd |
Vector3 | m_Kp |
Vector3 | m_L |
Vector3 | m_L_error |
TrajectorySample | m_ref |
![]() | |
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 32 of file task-angular-momentum-equality.hpp.
Definition at line 40 of file task-angular-momentum-equality.hpp.
Definition at line 41 of file task-angular-momentum-equality.hpp.
Definition at line 37 of file task-angular-momentum-equality.hpp.
Definition at line 38 of file task-angular-momentum-equality.hpp.
Definition at line 39 of file task-angular-momentum-equality.hpp.
tsid::tasks::TaskAMEquality::TaskAMEquality | ( | const std::string & | name, |
RobotWrapper & | robot | ||
) |
Definition at line 29 of file task-angular-momentum-equality.cpp.
|
overridevirtual |
Implements tsid::tasks::TaskBase.
Definition at line 87 of file task-angular-momentum-equality.cpp.
|
overridevirtual |
Return the dimension of the task. \info should be overloaded in the child class.
Implements tsid::tasks::TaskBase.
Definition at line 41 of file task-angular-momentum-equality.cpp.
const Vector & tsid::tasks::TaskAMEquality::dmomentum_ref | ( | ) | const |
Definition at line 79 of file task-angular-momentum-equality.cpp.
|
overridevirtual |
Implements tsid::tasks::TaskBase.
Definition at line 83 of file task-angular-momentum-equality.cpp.
const Vector3 & tsid::tasks::TaskAMEquality::getDesiredMomentumDerivative | ( | ) | const |
Definition at line 66 of file task-angular-momentum-equality.cpp.
Vector3 tsid::tasks::TaskAMEquality::getdMomentum | ( | ConstRefVector | dv | ) | const |
Definition at line 70 of file task-angular-momentum-equality.cpp.
|
overridevirtual |
Reimplemented from tsid::tasks::TaskMotion.
Definition at line 64 of file task-angular-momentum-equality.cpp.
const Vector3 & tsid::tasks::TaskAMEquality::Kd | ( | ) |
Definition at line 48 of file task-angular-momentum-equality.cpp.
void tsid::tasks::TaskAMEquality::Kd | ( | ConstRefVector | Kp | ) |
Definition at line 56 of file task-angular-momentum-equality.cpp.
const Vector3 & tsid::tasks::TaskAMEquality::Kp | ( | ) |
Definition at line 46 of file task-angular-momentum-equality.cpp.
void tsid::tasks::TaskAMEquality::Kp | ( | ConstRefVector | Kp | ) |
Definition at line 50 of file task-angular-momentum-equality.cpp.
const Vector3 & tsid::tasks::TaskAMEquality::momentum | ( | ) | const |
Definition at line 76 of file task-angular-momentum-equality.cpp.
const Vector3 & tsid::tasks::TaskAMEquality::momentum_error | ( | ) | const |
Definition at line 74 of file task-angular-momentum-equality.cpp.
const Vector & tsid::tasks::TaskAMEquality::momentum_ref | ( | ) | const |
Definition at line 77 of file task-angular-momentum-equality.cpp.
void tsid::tasks::TaskAMEquality::setReference | ( | const TrajectorySample & | ref | ) |
Definition at line 62 of file task-angular-momentum-equality.cpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Index tsid::tasks::TaskAMEquality::Index |
Definition at line 36 of file task-angular-momentum-equality.hpp.
|
protected |
Definition at line 77 of file task-angular-momentum-equality.hpp.
|
protected |
Definition at line 75 of file task-angular-momentum-equality.hpp.
|
protected |
Definition at line 72 of file task-angular-momentum-equality.hpp.
|
protected |
Definition at line 71 of file task-angular-momentum-equality.hpp.
|
protected |
Definition at line 74 of file task-angular-momentum-equality.hpp.
|
protected |
Definition at line 70 of file task-angular-momentum-equality.hpp.
|
protected |
Definition at line 69 of file task-angular-momentum-equality.hpp.
|
protected |
Definition at line 75 of file task-angular-momentum-equality.hpp.
|
protected |
Definition at line 71 of file task-angular-momentum-equality.hpp.
|
protected |
Definition at line 76 of file task-angular-momentum-equality.hpp.