Base template of a Contact. More...
#include <contact-base.hpp>

Public Types | |
| typedef math::ConstraintEquality | ConstraintEquality |
| typedef math::ConstraintInequality | ConstraintInequality |
| typedef math::ConstRefVector | ConstRefVector |
| typedef pinocchio::Data | Data |
| typedef math::Matrix | Matrix |
| typedef math::Matrix3x | Matrix3x |
| typedef robots::RobotWrapper | RobotWrapper |
| typedef tasks::TaskSE3Equality | TaskSE3Equality |
Public Member Functions | |
| virtual const ConstraintEquality & | computeForceRegularizationTask (const double t, ConstRefVector q, ConstRefVector v, const Data &data)=0 |
| virtual const ConstraintInequality & | computeForceTask (const double t, ConstRefVector q, ConstRefVector v, const Data &data)=0 |
| virtual const ConstraintBase & | computeMotionTask (const double t, ConstRefVector q, ConstRefVector v, Data &data)=0 |
| ContactBase (const std::string &name, RobotWrapper &robot) | |
| virtual const Matrix3x & | getContactPoints () const =0 |
| virtual const ConstraintInequality & | getForceConstraint () const =0 |
| virtual const Matrix & | getForceGeneratorMatrix ()=0 |
| virtual const ConstraintEquality & | getForceRegularizationTask () const =0 |
| virtual double | getMaxNormalForce () const =0 |
| virtual double | getMinNormalForce () const =0 |
| virtual const ConstraintBase & | getMotionConstraint () const =0 |
| virtual const TaskSE3Equality & | getMotionTask () const =0 |
| virtual double | getNormalForce (ConstRefVector f) const =0 |
| virtual unsigned int | n_force () const =0 |
| Return the number of force variables. More... | |
| virtual unsigned int | n_motion () const =0 |
| Return the number of motion constraints. More... | |
| const std::string & | name () const |
| void | name (const std::string &name) |
| virtual bool | setMaxNormalForce (const double maxNormalForce)=0 |
| virtual bool | setMinNormalForce (const double minNormalForce)=0 |
| virtual | ~ContactBase () |
Public Attributes | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::ConstraintBase | ConstraintBase |
Protected Attributes | |
| std::string | m_name |
| RobotWrapper & | m_robot |
| Reference on the robot model. More... | |
Base template of a Contact.
Definition at line 31 of file contact-base.hpp.
Definition at line 37 of file contact-base.hpp.
Definition at line 36 of file contact-base.hpp.
Definition at line 38 of file contact-base.hpp.
Definition at line 42 of file contact-base.hpp.
Definition at line 39 of file contact-base.hpp.
Definition at line 40 of file contact-base.hpp.
Definition at line 43 of file contact-base.hpp.
Definition at line 41 of file contact-base.hpp.
| tsid::contacts::ContactBase::ContactBase | ( | const std::string & | name, |
| RobotWrapper & | robot | ||
| ) |
Definition at line 22 of file contact-base.cpp.
|
inlinevirtual |
Definition at line 47 of file contact-base.hpp.
|
pure virtual |
Implemented in tsid::contacts::Contact6d, and tsid::contacts::ContactPoint.
|
pure virtual |
Implemented in tsid::contacts::Contact6d, and tsid::contacts::ContactPoint.
|
pure virtual |
Implemented in tsid::contacts::Contact6d, and tsid::contacts::ContactPoint.
|
pure virtual |
Implemented in tsid::contacts::Contact6d, and tsid::contacts::ContactPoint.
|
pure virtual |
Implemented in tsid::contacts::Contact6d, and tsid::contacts::ContactPoint.
|
pure virtual |
Implemented in tsid::contacts::Contact6d, and tsid::contacts::ContactPoint.
|
pure virtual |
Implemented in tsid::contacts::Contact6d, and tsid::contacts::ContactPoint.
|
pure virtual |
Implemented in tsid::contacts::Contact6d, and tsid::contacts::ContactPoint.
|
pure virtual |
Implemented in tsid::contacts::Contact6d, and tsid::contacts::ContactPoint.
|
pure virtual |
Implemented in tsid::contacts::Contact6d, and tsid::contacts::ContactPoint.
|
pure virtual |
Implemented in tsid::contacts::Contact6d, and tsid::contacts::ContactPoint.
|
pure virtual |
Implemented in tsid::contacts::Contact6d, and tsid::contacts::ContactPoint.
|
pure virtual |
Return the number of force variables.
Implemented in tsid::contacts::Contact6d, and tsid::contacts::ContactPoint.
|
pure virtual |
Return the number of motion constraints.
Implemented in tsid::contacts::Contact6d, and tsid::contacts::ContactPoint.
| const std::string & tsid::contacts::ContactBase::name | ( | ) | const |
Definition at line 25 of file contact-base.cpp.
| void tsid::contacts::ContactBase::name | ( | const std::string & | name | ) |
Definition at line 27 of file contact-base.cpp.
|
pure virtual |
Implemented in tsid::contacts::Contact6d, and tsid::contacts::ContactPoint.
|
pure virtual |
Implemented in tsid::contacts::Contact6d, and tsid::contacts::ContactPoint.
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::ConstraintBase tsid::contacts::ContactBase::ConstraintBase |
Definition at line 35 of file contact-base.hpp.
|
protected |
Definition at line 87 of file contact-base.hpp.
|
protected |
Reference on the robot model.
Definition at line 89 of file contact-base.hpp.