#include <task-cop-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::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... | |
const std::string & | getAssociatedContactName () override |
const ConstraintBase & | getConstraint () const override |
const Vector3 & | getContactNormal () const |
const Vector3 & | getReference () const |
void | setContactList (const std::vector< std::shared_ptr< ContactLevel > > *contacts) |
void | setContactNormal (const Vector3 &n) |
void | setReference (const Vector3 &ref) |
TaskCopEquality (const std::string &name, RobotWrapper &robot) | |
![]() | |
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 |
std::string | m_contact_name |
const std::vector< std::shared_ptr< ContactLevel > > * | m_contacts |
Vector3 | m_normal |
Vector3 | m_ref |
![]() | |
std::string | m_name |
RobotWrapper & | m_robot |
Reference on the robot model. More... | |
Definition at line 30 of file tasks/task-cop-equality.hpp.
Definition at line 38 of file tasks/task-cop-equality.hpp.
Definition at line 39 of file tasks/task-cop-equality.hpp.
Definition at line 35 of file tasks/task-cop-equality.hpp.
Definition at line 36 of file tasks/task-cop-equality.hpp.
Definition at line 37 of file tasks/task-cop-equality.hpp.
tsid::tasks::TaskCopEquality::TaskCopEquality | ( | const std::string & | name, |
RobotWrapper & | robot | ||
) |
Definition at line 26 of file src/tasks/task-cop-equality.cpp.
|
overridevirtual |
Implements tsid::tasks::TaskBase.
Definition at line 51 of file src/tasks/task-cop-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 45 of file src/tasks/task-cop-equality.cpp.
|
overridevirtual |
Return the dimension of the task. \info should be overloaded in the child class.
Implements tsid::tasks::TaskBase.
Definition at line 39 of file src/tasks/task-cop-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 41 of file src/tasks/task-cop-equality.cpp.
|
overridevirtual |
Implements tsid::tasks::TaskBase.
Definition at line 86 of file src/tasks/task-cop-equality.cpp.
const Vector3 & tsid::tasks::TaskCopEquality::getContactNormal | ( | ) | const |
Definition at line 100 of file src/tasks/task-cop-equality.cpp.
const Vector3 & tsid::tasks::TaskCopEquality::getReference | ( | ) | const |
Definition at line 96 of file src/tasks/task-cop-equality.cpp.
void tsid::tasks::TaskCopEquality::setContactList | ( | const std::vector< std::shared_ptr< ContactLevel > > * | contacts | ) |
Definition at line 34 of file src/tasks/task-cop-equality.cpp.
void tsid::tasks::TaskCopEquality::setContactNormal | ( | const Vector3 & | n | ) |
Definition at line 98 of file src/tasks/task-cop-equality.cpp.
void tsid::tasks::TaskCopEquality::setReference | ( | const Vector3 & | ref | ) |
Definition at line 90 of file src/tasks/task-cop-equality.cpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Index tsid::tasks::TaskCopEquality::Index |
Definition at line 34 of file tasks/task-cop-equality.hpp.
|
protected |
Definition at line 72 of file tasks/task-cop-equality.hpp.
|
protected |
Definition at line 69 of file tasks/task-cop-equality.hpp.
|
protected |
Definition at line 68 of file tasks/task-cop-equality.hpp.
|
protected |
Definition at line 70 of file tasks/task-cop-equality.hpp.
|
protected |
Definition at line 71 of file tasks/task-cop-equality.hpp.