tsid  1.8.0
Efficient Task Space Inverse Dynamics for Multi-body Systems based on Pinocchio
tsid::contacts::Measured6Dwrench Class Reference

#include <tsid/contacts/measured-6d-wrench.hpp>

Inheritance diagram for tsid::contacts::Measured6Dwrench:
Collaboration diagram for tsid::contacts::Measured6Dwrench:

Public Types

typedef math::Vector6 Vector6
 
typedef robots::RobotWrapper RobotWrapper
 
typedef pinocchio::Data Data
 
typedef pinocchio::Data::Matrix6x Matrix6x
 
- Public Types inherited from tsid::contacts::MeasuredForceBase
typedef pinocchio::Data Data
 
typedef robots::RobotWrapper RobotWrapper
 

Public Member Functions

 Measured6Dwrench (const std::string &name, RobotWrapper &robot, const std::string &frameName)
 
const VectorcomputeJointTorques (Data &data) override
 
void setMeasuredContactForce (const Vector6 &fext)
 
const Vector6getMeasuredContactForce () const
 
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)
 
virtual ~MeasuredForceBase ()=default
 
const std::string & name () const
 
void name (const std::string &name)
 

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

std::string m_frame_name
 
Index m_frame_id
 
Vector6 m_fext
 
Matrix6x m_J
 
Matrix6x m_J_rotated
 
Vector m_computedTorques
 
bool m_local_frame
 
- Protected Attributes inherited from tsid::contacts::MeasuredForceBase
std::string m_name
 
RobotWrapperm_robot
 Reference on the robot model. More...
 

Member Typedef Documentation

◆ Data

typedef pinocchio::Data tsid::contacts::Measured6Dwrench::Data

◆ Matrix6x

typedef pinocchio::Data::Matrix6x tsid::contacts::Measured6Dwrench::Matrix6x

◆ RobotWrapper

◆ Vector6

Constructor & Destructor Documentation

◆ Measured6Dwrench()

tsid::contacts::Measured6Dwrench::Measured6Dwrench ( const std::string &  name,
RobotWrapper robot,
const std::string &  frameName 
)

Member Function Documentation

◆ computeJointTorques()

const Vector & tsid::contacts::Measured6Dwrench::computeJointTorques ( Data data)
overridevirtual

Compute the bias force (J^t F) associated to the external measured force.

Implements tsid::contacts::MeasuredForceBase.

◆ getMeasuredContactForce()

const Vector6 & tsid::contacts::Measured6Dwrench::getMeasuredContactForce ( ) const

◆ setMeasuredContactForce()

void tsid::contacts::Measured6Dwrench::setMeasuredContactForce ( const Vector6 fext)

Set the value of the external wrench applied by the environment on the robot.

◆ useLocalFrame()

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.

Parameters
local_frameIf true, represent external force and jacobian in the local frame. If false, represent them in the local world-oriented frame.

Member Data Documentation

◆ Index

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Index tsid::contacts::Measured6Dwrench::Index

◆ m_computedTorques

Vector tsid::contacts::Measured6Dwrench::m_computedTorques
protected

◆ m_fext

Vector6 tsid::contacts::Measured6Dwrench::m_fext
protected

◆ m_frame_id

Index tsid::contacts::Measured6Dwrench::m_frame_id
protected

◆ m_frame_name

std::string tsid::contacts::Measured6Dwrench::m_frame_name
protected

◆ m_J

Matrix6x tsid::contacts::Measured6Dwrench::m_J
protected

◆ m_J_rotated

Matrix6x tsid::contacts::Measured6Dwrench::m_J_rotated
protected

◆ m_local_frame

bool tsid::contacts::Measured6Dwrench::m_local_frame
protected

The documentation for this class was generated from the following files: