#include <contact-6d.hpp>

Public Types | |
| typedef math::ConstraintEquality | ConstraintEquality |
| typedef math::ConstraintInequality | ConstraintInequality |
| typedef math::ConstRefVector | ConstRefVector |
| typedef math::Matrix3x | Matrix3x |
| typedef pinocchio::SE3 | SE3 |
| typedef tasks::TaskSE3Equality | TaskSE3Equality |
| typedef math::Vector | Vector |
| typedef math::Vector3 | Vector3 |
| typedef math::Vector6 | Vector6 |
Public Types inherited from tsid::contacts::ContactBase | |
| 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::TaskMotion | TaskMotion |
| typedef tasks::TaskSE3Equality | TaskSE3Equality |
Public Member Functions | |
| const ConstraintEquality & | computeForceRegularizationTask (double t, ConstRefVector q, ConstRefVector v, const Data &data) override |
| const ConstraintInequality & | computeForceTask (double t, ConstRefVector q, ConstRefVector v, const Data &data) override |
| const ConstraintBase & | computeMotionTask (double t, ConstRefVector q, ConstRefVector v, Data &data) override |
| Contact6d (const std::string &name, RobotWrapper &robot, const std::string &frameName, ConstRefMatrix contactPoints, ConstRefVector contactNormal, const double frictionCoefficient, const double minNormalForce, const double maxNormalForce) | |
| TSID_DEPRECATED | Contact6d (const std::string &name, RobotWrapper &robot, const std::string &frameName, ConstRefMatrix contactPoints, ConstRefVector contactNormal, const double frictionCoefficient, const double minNormalForce, const double maxNormalForce, const double forceRegWeight) |
| const Matrix3x & | getContactPoints () const override |
| const ConstraintInequality & | getForceConstraint () const override |
| const Matrix & | getForceGeneratorMatrix () override |
| const ConstraintEquality & | getForceRegularizationTask () const override |
| double | getMaxNormalForce () const override |
| double | getMinNormalForce () const override |
| const ConstraintBase & | getMotionConstraint () const override |
| const TaskSE3Equality & | getMotionTask () const override |
| double | getNormalForce (ConstRefVector f) const override |
| const Vector & | Kd () const |
| void | Kd (ConstRefVector Kp) |
| const Vector & | Kp () const |
| void | Kp (ConstRefVector Kp) |
| unsigned int | n_force () const override |
| Return the number of force variables. More... | |
| unsigned int | n_motion () const override |
| Return the number of motion constraints. More... | |
| bool | setContactNormal (ConstRefVector contactNormal) |
| bool | setContactPoints (ConstRefMatrix contactPoints) |
| void | setForceReference (ConstRefVector &f_ref) |
| bool | setFrictionCoefficient (double frictionCoefficient) |
| bool | setMaxNormalForce (double maxNormalForce) override |
| bool | setMinNormalForce (double minNormalForce) override |
| void | setReference (const SE3 &ref) |
| void | setRegularizationTaskWeightVector (ConstRefVector &w) |
Public Member Functions inherited from tsid::contacts::ContactBase | |
| ContactBase (const std::string &name, RobotWrapper &robot) | |
| const std::string & | name () const |
| void | name (const std::string &name) |
| virtual | ~ContactBase ()=default |
Public Attributes | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::ConstRefMatrix | ConstRefMatrix |
Public Attributes inherited from tsid::contacts::ContactBase | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::ConstraintBase | ConstraintBase |
Protected Member Functions | |
| void | updateForceGeneratorMatrix () |
| void | updateForceInequalityConstraints () |
| void | updateForceRegularizationTask () |
Protected Attributes | |
| Vector3 | m_contactNormal |
| Matrix3x | m_contactPoints |
| double | m_fMax |
| double | m_fMin |
| Matrix | m_forceGenMat |
| ConstraintInequality | m_forceInequality |
| ConstraintEquality | m_forceRegTask |
| Vector6 | m_fRef |
| TaskSE3Equality | m_motionTask |
| double | m_mu |
| Vector6 | m_weightForceRegTask |
Protected Attributes inherited from tsid::contacts::ContactBase | |
| std::string | m_name |
| RobotWrapper & | m_robot |
| Reference on the robot model. More... | |
Private Member Functions | |
| void | init () |
Definition at line 29 of file contacts/contact-6d.hpp.
Definition at line 41 of file contacts/contact-6d.hpp.
Definition at line 40 of file contacts/contact-6d.hpp.
| typedef math::ConstRefVector tsid::contacts::Contact6d::ConstRefVector |
Definition at line 34 of file contacts/contact-6d.hpp.
Definition at line 35 of file contacts/contact-6d.hpp.
Definition at line 42 of file contacts/contact-6d.hpp.
Definition at line 39 of file contacts/contact-6d.hpp.
Definition at line 38 of file contacts/contact-6d.hpp.
Definition at line 37 of file contacts/contact-6d.hpp.
Definition at line 36 of file contacts/contact-6d.hpp.
| Contact6d::Contact6d | ( | const std::string & | name, |
| RobotWrapper & | robot, | ||
| const std::string & | frameName, | ||
| ConstRefMatrix | contactPoints, | ||
| ConstRefVector | contactNormal, | ||
| const double | frictionCoefficient, | ||
| const double | minNormalForce, | ||
| const double | maxNormalForce | ||
| ) |
Definition at line 29 of file src/contacts/contact-6d.cpp.
| Contact6d::Contact6d | ( | const std::string & | name, |
| RobotWrapper & | robot, | ||
| const std::string & | frameName, | ||
| ConstRefMatrix | contactPoints, | ||
| ConstRefVector | contactNormal, | ||
| const double | frictionCoefficient, | ||
| const double | minNormalForce, | ||
| const double | maxNormalForce, | ||
| const double | forceRegWeight | ||
| ) |
Definition at line 46 of file src/contacts/contact-6d.cpp.
|
overridevirtual |
Implements tsid::contacts::ContactBase.
Definition at line 229 of file src/contacts/contact-6d.cpp.
|
overridevirtual |
Implements tsid::contacts::ContactBase.
Definition at line 220 of file src/contacts/contact-6d.cpp.
|
overridevirtual |
Implements tsid::contacts::ContactBase.
Definition at line 213 of file src/contacts/contact-6d.cpp.
|
overridevirtual |
Implements tsid::contacts::ContactBase.
Definition at line 161 of file src/contacts/contact-6d.cpp.
|
overridevirtual |
Implements tsid::contacts::ContactBase.
Definition at line 243 of file src/contacts/contact-6d.cpp.
|
overridevirtual |
Implements tsid::contacts::ContactBase.
Definition at line 227 of file src/contacts/contact-6d.cpp.
|
overridevirtual |
Implements tsid::contacts::ContactBase.
Definition at line 247 of file src/contacts/contact-6d.cpp.
|
overridevirtual |
Implements tsid::contacts::ContactBase.
Definition at line 235 of file src/contacts/contact-6d.cpp.
|
overridevirtual |
Implements tsid::contacts::ContactBase.
Definition at line 234 of file src/contacts/contact-6d.cpp.
|
overridevirtual |
Implements tsid::contacts::ContactBase.
Definition at line 239 of file src/contacts/contact-6d.cpp.
|
overridevirtual |
Implements tsid::contacts::ContactBase.
Definition at line 237 of file src/contacts/contact-6d.cpp.
|
overridevirtual |
Implements tsid::contacts::ContactBase.
Definition at line 110 of file src/contacts/contact-6d.cpp.
|
private |
Definition at line 67 of file src/contacts/contact-6d.cpp.
| const Vector & Contact6d::Kd | ( | ) | const |
Definition at line 146 of file src/contacts/contact-6d.cpp.
| void Contact6d::Kd | ( | ConstRefVector | Kp | ) |
Definition at line 148 of file src/contacts/contact-6d.cpp.
| const Vector & Contact6d::Kp | ( | ) | const |
Definition at line 145 of file src/contacts/contact-6d.cpp.
| void Contact6d::Kp | ( | ConstRefVector | Kp | ) |
Definition at line 147 of file src/contacts/contact-6d.cpp.
|
overridevirtual |
Return the number of force variables.
Implements tsid::contacts::ContactBase.
Definition at line 143 of file src/contacts/contact-6d.cpp.
|
overridevirtual |
Return the number of motion constraints.
Implements tsid::contacts::ContactBase.
Definition at line 142 of file src/contacts/contact-6d.cpp.
| bool Contact6d::setContactNormal | ( | ConstRefVector | contactNormal | ) |
Definition at line 163 of file src/contacts/contact-6d.cpp.
| bool Contact6d::setContactPoints | ( | ConstRefMatrix | contactPoints | ) |
Definition at line 150 of file src/contacts/contact-6d.cpp.
| void Contact6d::setForceReference | ( | ConstRefVector & | f_ref | ) |
Definition at line 206 of file src/contacts/contact-6d.cpp.
| bool Contact6d::setFrictionCoefficient | ( | double | frictionCoefficient | ) |
Definition at line 173 of file src/contacts/contact-6d.cpp.
|
overridevirtual |
Implements tsid::contacts::ContactBase.
Definition at line 195 of file src/contacts/contact-6d.cpp.
|
overridevirtual |
Implements tsid::contacts::ContactBase.
Definition at line 183 of file src/contacts/contact-6d.cpp.
| void Contact6d::setReference | ( | const SE3 & | ref | ) |
Definition at line 211 of file src/contacts/contact-6d.cpp.
| void Contact6d::setRegularizationTaskWeightVector | ( | ConstRefVector & | w | ) |
Definition at line 119 of file src/contacts/contact-6d.cpp.
|
protected |
Definition at line 132 of file src/contacts/contact-6d.cpp.
|
protected |
Definition at line 76 of file src/contacts/contact-6d.cpp.
|
protected |
Definition at line 124 of file src/contacts/contact-6d.cpp.
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::ConstRefMatrix tsid::contacts::Contact6d::ConstRefMatrix |
Definition at line 33 of file contacts/contact-6d.hpp.
|
protected |
Definition at line 114 of file contacts/contact-6d.hpp.
|
protected |
Definition at line 113 of file contacts/contact-6d.hpp.
|
protected |
Definition at line 119 of file contacts/contact-6d.hpp.
|
protected |
Definition at line 118 of file contacts/contact-6d.hpp.
|
protected |
Definition at line 120 of file contacts/contact-6d.hpp.
|
protected |
Definition at line 111 of file contacts/contact-6d.hpp.
|
protected |
Definition at line 112 of file contacts/contact-6d.hpp.
|
protected |
Definition at line 115 of file contacts/contact-6d.hpp.
|
protected |
Definition at line 110 of file contacts/contact-6d.hpp.
|
protected |
Definition at line 117 of file contacts/contact-6d.hpp.
|
protected |
Definition at line 116 of file contacts/contact-6d.hpp.