#include <task-contact-force-equality.hpp>
Public Types | |
typedef math::ConstraintEquality | ConstraintEquality |
typedef pinocchio::SE3 | SE3 |
typedef trajectories::TrajectorySample | TrajectorySample |
typedef math::Vector | Vector |
typedef math::Vector3 | Vector3 |
typedef math::Vector6 | Vector6 |
![]() | |
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 |
const ConstraintBase & | compute (double t, ConstRefVector q, ConstRefVector v, Data &data, const std::vector< std::shared_ptr< ContactLevel > > *contacts) override |
int | dim () const override |
Return the dimension of the task. \info should be overloaded in the child class. More... | |
virtual const contacts::ContactBase & | getAssociatedContact () |
virtual const std::string & | getAssociatedContactName () override |
const ConstraintBase & | getConstraint () const override |
const TrajectorySample & | getExternalForce () const |
const double & | getLeakRate () const |
const TrajectorySample & | getReference () const |
const Vector & | Kd () const |
void | Kd (ConstRefVector Kp) |
const Vector & | Ki () const |
void | Ki (ConstRefVector Ki) |
const Vector & | Kp () const |
void | Kp (ConstRefVector Kp) |
void | setAssociatedContact (contacts::ContactBase &contact) |
void | setExternalForce (TrajectorySample &f_ext) |
void | setLeakRate (double leak) |
void | setReference (TrajectorySample &ref) |
TaskContactForceEquality (const std::string &name, RobotWrapper &robot, const double dt, contacts::ContactBase &contact) | |
![]() | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | TaskContactForce (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 | |
ConstraintEquality | m_constraint |
contacts::ContactBase * | m_contact |
std::string | m_contact_name |
double | m_dt |
TrajectorySample | m_fext |
Vector | m_forceIntegralError |
Vector | m_Kd |
Vector | m_Ki |
Vector | m_Kp |
double | m_leak_rate |
TrajectorySample | m_ref |
![]() | |
std::string | m_name |
RobotWrapper & | m_robot |
Reference on the robot model. More... | |
Definition at line 30 of file tasks/task-contact-force-equality.hpp.
Definition at line 39 of file tasks/task-contact-force-equality.hpp.
Definition at line 40 of file tasks/task-contact-force-equality.hpp.
Definition at line 35 of file tasks/task-contact-force-equality.hpp.
Definition at line 36 of file tasks/task-contact-force-equality.hpp.
Definition at line 38 of file tasks/task-contact-force-equality.hpp.
Definition at line 37 of file tasks/task-contact-force-equality.hpp.
tsid::tasks::TaskContactForceEquality::TaskContactForceEquality | ( | const std::string & | name, |
RobotWrapper & | robot, | ||
const double | dt, | ||
contacts::ContactBase & | contact | ||
) |
Definition at line 28 of file src/tasks/task-contact-force-equality.cpp.
|
overridevirtual |
Implements tsid::tasks::TaskBase.
Definition at line 129 of file src/tasks/task-contact-force-equality.cpp.
|
overridevirtual |
Contact force tasks have an additional compute method that takes as extra input argument the list of active contacts. This can be needed for force tasks that involve all contacts, such as the CoP task.
Implements tsid::tasks::TaskContactForce.
Definition at line 103 of file src/tasks/task-contact-force-equality.cpp.
|
overridevirtual |
Return the dimension of the task. \info should be overloaded in the child class.
Implements tsid::tasks::TaskBase.
Definition at line 42 of file src/tasks/task-contact-force-equality.cpp.
|
virtual |
Definition at line 75 of file src/tasks/task-contact-force-equality.cpp.
|
overridevirtual |
Return the name of the contact associated to this task if this task is associated to a specific contact. If this task is associated to multiple contact forces (all of them), returns an empty string.
Implements tsid::tasks::TaskContactForce.
Definition at line 71 of file src/tasks/task-contact-force-equality.cpp.
|
overridevirtual |
Implements tsid::tasks::TaskBase.
Definition at line 149 of file src/tasks/task-contact-force-equality.cpp.
const TaskContactForceEquality::TrajectorySample & tsid::tasks::TaskContactForceEquality::getExternalForce | ( | ) | const |
Definition at line 99 of file src/tasks/task-contact-force-equality.cpp.
const double & tsid::tasks::TaskContactForceEquality::getLeakRate | ( | ) | const |
Definition at line 47 of file src/tasks/task-contact-force-equality.cpp.
const TaskContactForceEquality::TrajectorySample & tsid::tasks::TaskContactForceEquality::getReference | ( | ) | const |
Definition at line 90 of file src/tasks/task-contact-force-equality.cpp.
const Vector & tsid::tasks::TaskContactForceEquality::Kd | ( | ) | const |
Definition at line 45 of file src/tasks/task-contact-force-equality.cpp.
void tsid::tasks::TaskContactForceEquality::Kd | ( | ConstRefVector | Kp | ) |
Definition at line 57 of file src/tasks/task-contact-force-equality.cpp.
const Vector & tsid::tasks::TaskContactForceEquality::Ki | ( | ) | const |
Definition at line 46 of file src/tasks/task-contact-force-equality.cpp.
void tsid::tasks::TaskContactForceEquality::Ki | ( | ConstRefVector | Ki | ) |
Definition at line 63 of file src/tasks/task-contact-force-equality.cpp.
const Vector & tsid::tasks::TaskContactForceEquality::Kp | ( | ) | const |
Definition at line 44 of file src/tasks/task-contact-force-equality.cpp.
void tsid::tasks::TaskContactForceEquality::Kp | ( | ConstRefVector | Kp | ) |
Definition at line 51 of file src/tasks/task-contact-force-equality.cpp.
void tsid::tasks::TaskContactForceEquality::setAssociatedContact | ( | contacts::ContactBase & | contact | ) |
Definition at line 79 of file src/tasks/task-contact-force-equality.cpp.
void tsid::tasks::TaskContactForceEquality::setExternalForce | ( | TrajectorySample & | f_ext | ) |
Definition at line 94 of file src/tasks/task-contact-force-equality.cpp.
void tsid::tasks::TaskContactForceEquality::setLeakRate | ( | double | leak | ) |
Definition at line 69 of file src/tasks/task-contact-force-equality.cpp.
void tsid::tasks::TaskContactForceEquality::setReference | ( | TrajectorySample & | ref | ) |
Definition at line 85 of file src/tasks/task-contact-force-equality.cpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Index tsid::tasks::TaskContactForceEquality::Index |
Definition at line 34 of file tasks/task-contact-force-equality.hpp.
|
protected |
Definition at line 80 of file tasks/task-contact-force-equality.hpp.
|
protected |
Definition at line 78 of file tasks/task-contact-force-equality.hpp.
|
protected |
Definition at line 79 of file tasks/task-contact-force-equality.hpp.
|
protected |
Definition at line 87 of file tasks/task-contact-force-equality.hpp.
|
protected |
Definition at line 82 of file tasks/task-contact-force-equality.hpp.
|
protected |
Definition at line 83 of file tasks/task-contact-force-equality.hpp.
|
protected |
Definition at line 85 of file tasks/task-contact-force-equality.hpp.
|
protected |
Definition at line 86 of file tasks/task-contact-force-equality.hpp.
|
protected |
Definition at line 84 of file tasks/task-contact-force-equality.hpp.
|
protected |
Definition at line 88 of file tasks/task-contact-force-equality.hpp.
|
protected |
Definition at line 81 of file tasks/task-contact-force-equality.hpp.