#include <measured-6d-wrench.hpp>

Public Types | |
| typedef pinocchio::Data | Data |
| typedef pinocchio::Data::Matrix6x | Matrix6x |
| typedef robots::RobotWrapper | RobotWrapper |
| typedef math::Vector6 | Vector6 |
Public Types inherited from tsid::contacts::MeasuredForceBase | |
| typedef pinocchio::Data | Data |
| typedef robots::RobotWrapper | RobotWrapper |
Public Member Functions | |
| const Vector & | computeJointTorques (Data &data) override |
| const Vector6 & | getMeasuredContactForce () const |
| Measured6Dwrench (const std::string &name, RobotWrapper &robot, const std::string &frameName) | |
| void | setMeasuredContactForce (const Vector6 &fext) |
| void | useLocalFrame (bool local_frame) |
| Specifies if the external force and jacobian is expressed in the local frame or the local world-oriented frame. More... | |
Public Member Functions inherited from tsid::contacts::MeasuredForceBase | |
| MeasuredForceBase (const std::string &name, RobotWrapper &robot) | |
| const std::string & | name () const |
| void | name (const std::string &name) |
| virtual | ~MeasuredForceBase ()=default |
Public Attributes | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Index | Index |
Public Attributes inherited from tsid::contacts::MeasuredForceBase | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Vector | Vector |
Protected Attributes | |
| Vector | m_computedTorques |
| Vector6 | m_fext |
| Index | m_frame_id |
| std::string | m_frame_name |
| Matrix6x | m_J |
| Matrix6x | m_J_rotated |
| bool | m_local_frame |
Protected Attributes inherited from tsid::contacts::MeasuredForceBase | |
| std::string | m_name |
| RobotWrapper & | m_robot |
| Reference on the robot model. More... | |
Definition at line 27 of file contacts/measured-6d-wrench.hpp.
Definition at line 34 of file contacts/measured-6d-wrench.hpp.
Definition at line 35 of file contacts/measured-6d-wrench.hpp.
Definition at line 33 of file contacts/measured-6d-wrench.hpp.
Definition at line 32 of file contacts/measured-6d-wrench.hpp.
| tsid::contacts::Measured6Dwrench::Measured6Dwrench | ( | const std::string & | name, |
| RobotWrapper & | robot, | ||
| const std::string & | frameName | ||
| ) |
Definition at line 29 of file src/contacts/measured-6d-wrench.cpp.
Compute the bias force (J^t F) associated to the external measured force.
Implements tsid::contacts::MeasuredForceBase.
Definition at line 43 of file src/contacts/measured-6d-wrench.cpp.
| const Vector6 & tsid::contacts::Measured6Dwrench::getMeasuredContactForce | ( | ) | const |
Definition at line 67 of file src/contacts/measured-6d-wrench.cpp.
| void tsid::contacts::Measured6Dwrench::setMeasuredContactForce | ( | const Vector6 & | fext | ) |
Set the value of the external wrench applied by the environment on the robot.
Definition at line 63 of file src/contacts/measured-6d-wrench.cpp.
| void tsid::contacts::Measured6Dwrench::useLocalFrame | ( | bool | local_frame | ) |
Specifies if the external force and jacobian is expressed in the local frame or the local world-oriented frame.
| local_frame | If true, represent external force and jacobian in the local frame. If false, represent them in the local world-oriented frame. |
Definition at line 71 of file src/contacts/measured-6d-wrench.cpp.
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Index tsid::contacts::Measured6Dwrench::Index |
Definition at line 31 of file contacts/measured-6d-wrench.hpp.
|
protected |
Definition at line 65 of file contacts/measured-6d-wrench.hpp.
|
protected |
Definition at line 62 of file contacts/measured-6d-wrench.hpp.
|
protected |
Definition at line 61 of file contacts/measured-6d-wrench.hpp.
|
protected |
Definition at line 60 of file contacts/measured-6d-wrench.hpp.
|
protected |
Definition at line 63 of file contacts/measured-6d-wrench.hpp.
|
protected |
Definition at line 64 of file contacts/measured-6d-wrench.hpp.
|
protected |
Definition at line 66 of file contacts/measured-6d-wrench.hpp.