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

#include <tsid/formulations/inverse-dynamics-formulation-acc-force.hpp>

Inheritance diagram for tsid::InverseDynamicsFormulationAccForce:
Collaboration diagram for tsid::InverseDynamicsFormulationAccForce:

Public Types

typedef math::Vector Vector
 
typedef math::Matrix Matrix
 
typedef math::ConstRefVector ConstRefVector
 
typedef tasks::TaskBase TaskBase
 
typedef tasks::TaskMotion TaskMotion
 
typedef tasks::TaskContactForce TaskContactForce
 
typedef tasks::TaskActuation TaskActuation
 
typedef contacts::MeasuredForceBase MeasuredForceBase
 
typedef solvers::HQPOutput HQPOutput
 
- Public Types inherited from tsid::InverseDynamicsFormulationBase
typedef math::Vector Vector
 
typedef math::RefVector RefVector
 
typedef math::ConstRefVector ConstRefVector
 
typedef tasks::TaskMotion TaskMotion
 
typedef tasks::TaskContactForce TaskContactForce
 
typedef tasks::TaskActuation TaskActuation
 
typedef tasks::TaskBase TaskBase
 
typedef contacts::MeasuredForceBase MeasuredForceBase
 
typedef contacts::ContactBase ContactBase
 
typedef solvers::HQPData HQPData
 
typedef solvers::HQPOutput HQPOutput
 
typedef robots::RobotWrapper RobotWrapper
 

Public Member Functions

 InverseDynamicsFormulationAccForce (const std::string &name, RobotWrapper &robot, bool verbose=false)
 
Datadata () override
 
unsigned int nVar () const override
 
unsigned int nEq () const override
 
unsigned int nIn () const override
 
bool addMotionTask (TaskMotion &task, double weight, unsigned int priorityLevel, double transition_duration=0.0) override
 
bool addForceTask (TaskContactForce &task, double weight, unsigned int priorityLevel, double transition_duration=0.0) override
 
bool addActuationTask (TaskActuation &task, double weight, unsigned int priorityLevel, double transition_duration=0.0) override
 
bool updateTaskWeight (const std::string &task_name, double weight) override
 
bool addRigidContact (ContactBase &contact, double force_regularization_weight, double motion_weight=1.0, unsigned int motion_priority_level=0) override
 Add a rigid contact constraint to the model, introducing the associated reaction forces as problem variables. More...
 
TSID_DEPRECATED bool addRigidContact (ContactBase &contact) override
 
bool updateRigidContactWeights (const std::string &contact_name, double force_regularization_weight, double motion_weight=-1.0) override
 Update the weights associated to the specified contact. More...
 
bool addMeasuredForce (MeasuredForceBase &measuredForce) override
 
bool removeTask (const std::string &taskName, double transition_duration=0.0) override
 
bool removeRigidContact (const std::string &contactName, double transition_duration=0.0) override
 
bool removeMeasuredForce (const std::string &measuredForceName) override
 
const HQPDatacomputeProblemData (double time, ConstRefVector q, ConstRefVector v) override
 
const VectorgetActuatorForces (const HQPOutput &sol) override
 
const VectorgetAccelerations (const HQPOutput &sol) override
 
const VectorgetContactForces (const HQPOutput &sol) override
 
Vector getContactForces (const std::string &name, const HQPOutput &sol)
 
bool getContactForces (const std::string &name, const HQPOutput &sol, RefVector f) override
 
template<class TaskLevelPointer >
void addTask (TaskLevelPointer task, double weight, unsigned int priorityLevel)
 
void resizeHqpData ()
 
bool removeFromHqpData (const std::string &name)
 
bool decodeSolution (const HQPOutput &sol)
 
- Public Member Functions inherited from tsid::InverseDynamicsFormulationBase
 InverseDynamicsFormulationBase (const std::string &name, RobotWrapper &robot, bool verbose=false)
 
virtual ~InverseDynamicsFormulationBase ()=default
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef pinocchio::Data Data
 
Data m_data
 
HQPData m_hqpData
 
std::vector< std::shared_ptr< TaskLevel > > m_taskMotions
 
std::vector< std::shared_ptr< TaskLevelForce > > m_taskContactForces
 
std::vector< std::shared_ptr< TaskLevel > > m_taskActuations
 
std::vector< std::shared_ptr< ContactLevel > > m_contacts
 
std::vector< std::shared_ptr< MeasuredForceLevel > > m_measuredForces
 
double m_t
 
unsigned int m_k
 time More...
 
unsigned int m_v
 number of contact-force variables More...
 
unsigned int m_u
 number of acceleration variables More...
 
unsigned int m_eq
 number of unactuated DoFs More...
 
unsigned int m_in
 number of equality constraints More...
 
Matrix m_Jc
 number of inequality constraints More...
 
std::shared_ptr< math::ConstraintEqualitym_baseDynamics
 contact force Jacobian More...
 
bool m_solutionDecoded
 
Vector m_dv
 
Vector m_f
 
Vector m_tau
 
Vector h_fext
 
std::vector< std::shared_ptr< ContactTransitionInfo > > m_contactTransitions
 sum of external measured forces More...
 
- Public Attributes inherited from tsid::InverseDynamicsFormulationBase
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef pinocchio::Data Data
 

Additional Inherited Members

- Protected Attributes inherited from tsid::InverseDynamicsFormulationBase
std::string m_name
 
RobotWrapper m_robot
 
bool m_verbose
 

Member Typedef Documentation

◆ ConstRefVector

◆ HQPOutput

◆ Matrix

◆ MeasuredForceBase

◆ TaskActuation

◆ TaskBase

◆ TaskContactForce

◆ TaskMotion

◆ Vector

Constructor & Destructor Documentation

◆ InverseDynamicsFormulationAccForce()

InverseDynamicsFormulationAccForce::InverseDynamicsFormulationAccForce ( const std::string &  name,
RobotWrapper robot,
bool  verbose = false 
)

Member Function Documentation

◆ addActuationTask()

bool InverseDynamicsFormulationAccForce::addActuationTask ( TaskActuation task,
double  weight,
unsigned int  priorityLevel,
double  transition_duration = 0.0 
)
overridevirtual

◆ addForceTask()

bool InverseDynamicsFormulationAccForce::addForceTask ( TaskContactForce task,
double  weight,
unsigned int  priorityLevel,
double  transition_duration = 0.0 
)
overridevirtual

◆ addMeasuredForce()

bool InverseDynamicsFormulationAccForce::addMeasuredForce ( MeasuredForceBase measuredForce)
overridevirtual

◆ addMotionTask()

bool InverseDynamicsFormulationAccForce::addMotionTask ( TaskMotion task,
double  weight,
unsigned int  priorityLevel,
double  transition_duration = 0.0 
)
overridevirtual

◆ addRigidContact() [1/2]

bool InverseDynamicsFormulationAccForce::addRigidContact ( ContactBase contact)
overridevirtual

◆ addRigidContact() [2/2]

bool InverseDynamicsFormulationAccForce::addRigidContact ( ContactBase contact,
double  force_regularization_weight,
double  motion_weight = 1.0,
unsigned int  motion_priority_level = 0 
)
overridevirtual

Add a rigid contact constraint to the model, introducing the associated reaction forces as problem variables.

Parameters
contactThe contact constraint to add
force_regularization_weightThe weight of the force regularization task
motion_weightThe weight of the motion task (e.g., zero acceleration of contact points)
motion_priority_levelPriority level of the motion task
Returns
True if everything went fine, false otherwise

Implements tsid::InverseDynamicsFormulationBase.

◆ addTask()

template<class TaskLevelPointer >
void InverseDynamicsFormulationAccForce::addTask ( TaskLevelPointer  task,
double  weight,
unsigned int  priorityLevel 
)

◆ computeProblemData()

const HQPData & InverseDynamicsFormulationAccForce::computeProblemData ( double  time,
ConstRefVector  q,
ConstRefVector  v 
)
overridevirtual

◆ data()

Data & InverseDynamicsFormulationAccForce::data ( )
overridevirtual

◆ decodeSolution()

bool InverseDynamicsFormulationAccForce::decodeSolution ( const HQPOutput sol)

◆ getAccelerations()

const Vector & InverseDynamicsFormulationAccForce::getAccelerations ( const HQPOutput sol)
overridevirtual

◆ getActuatorForces()

const Vector & InverseDynamicsFormulationAccForce::getActuatorForces ( const HQPOutput sol)
overridevirtual

◆ getContactForces() [1/3]

const Vector & InverseDynamicsFormulationAccForce::getContactForces ( const HQPOutput sol)
overridevirtual

◆ getContactForces() [2/3]

Vector InverseDynamicsFormulationAccForce::getContactForces ( const std::string &  name,
const HQPOutput sol 
)

◆ getContactForces() [3/3]

bool InverseDynamicsFormulationAccForce::getContactForces ( const std::string &  name,
const HQPOutput sol,
RefVector  f 
)
overridevirtual

◆ nEq()

unsigned int InverseDynamicsFormulationAccForce::nEq ( ) const
overridevirtual

◆ nIn()

unsigned int InverseDynamicsFormulationAccForce::nIn ( ) const
overridevirtual

◆ nVar()

unsigned int InverseDynamicsFormulationAccForce::nVar ( ) const
overridevirtual

◆ removeFromHqpData()

bool InverseDynamicsFormulationAccForce::removeFromHqpData ( const std::string &  name)

◆ removeMeasuredForce()

bool InverseDynamicsFormulationAccForce::removeMeasuredForce ( const std::string &  measuredForceName)
overridevirtual

◆ removeRigidContact()

bool InverseDynamicsFormulationAccForce::removeRigidContact ( const std::string &  contactName,
double  transition_duration = 0.0 
)
overridevirtual

◆ removeTask()

bool InverseDynamicsFormulationAccForce::removeTask ( const std::string &  taskName,
double  transition_duration = 0.0 
)
overridevirtual

◆ resizeHqpData()

void InverseDynamicsFormulationAccForce::resizeHqpData ( )

◆ updateRigidContactWeights()

bool InverseDynamicsFormulationAccForce::updateRigidContactWeights ( const std::string &  contact_name,
double  force_regularization_weight,
double  motion_weight = -1.0 
)
overridevirtual

Update the weights associated to the specified contact.

Parameters
contact_nameName of the contact to update
force_regularization_weightWeight of the force regularization task, if negative it is not updated
motion_weightWeight of the motion task, if negative it is not update
Returns
True if everything went fine, false otherwise

Implements tsid::InverseDynamicsFormulationBase.

◆ updateTaskWeight()

bool InverseDynamicsFormulationAccForce::updateTaskWeight ( const std::string &  task_name,
double  weight 
)
overridevirtual

Member Data Documentation

◆ Data

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef pinocchio::Data tsid::InverseDynamicsFormulationAccForce::Data

◆ h_fext

Vector tsid::InverseDynamicsFormulationAccForce::h_fext

◆ m_baseDynamics

std::shared_ptr<math::ConstraintEquality> tsid::InverseDynamicsFormulationAccForce::m_baseDynamics

contact force Jacobian

◆ m_contacts

std::vector<std::shared_ptr<ContactLevel> > tsid::InverseDynamicsFormulationAccForce::m_contacts

◆ m_contactTransitions

std::vector<std::shared_ptr<ContactTransitionInfo> > tsid::InverseDynamicsFormulationAccForce::m_contactTransitions

sum of external measured forces

◆ m_data

Data tsid::InverseDynamicsFormulationAccForce::m_data

◆ m_dv

Vector tsid::InverseDynamicsFormulationAccForce::m_dv

◆ m_eq

unsigned int tsid::InverseDynamicsFormulationAccForce::m_eq

number of unactuated DoFs

◆ m_f

Vector tsid::InverseDynamicsFormulationAccForce::m_f

◆ m_hqpData

HQPData tsid::InverseDynamicsFormulationAccForce::m_hqpData

◆ m_in

unsigned int tsid::InverseDynamicsFormulationAccForce::m_in

number of equality constraints

◆ m_Jc

Matrix tsid::InverseDynamicsFormulationAccForce::m_Jc

number of inequality constraints

◆ m_k

unsigned int tsid::InverseDynamicsFormulationAccForce::m_k

time

◆ m_measuredForces

std::vector<std::shared_ptr<MeasuredForceLevel> > tsid::InverseDynamicsFormulationAccForce::m_measuredForces

◆ m_solutionDecoded

bool tsid::InverseDynamicsFormulationAccForce::m_solutionDecoded

◆ m_t

double tsid::InverseDynamicsFormulationAccForce::m_t

◆ m_taskActuations

std::vector<std::shared_ptr<TaskLevel> > tsid::InverseDynamicsFormulationAccForce::m_taskActuations

◆ m_taskContactForces

std::vector<std::shared_ptr<TaskLevelForce> > tsid::InverseDynamicsFormulationAccForce::m_taskContactForces

◆ m_taskMotions

std::vector<std::shared_ptr<TaskLevel> > tsid::InverseDynamicsFormulationAccForce::m_taskMotions

◆ m_tau

Vector tsid::InverseDynamicsFormulationAccForce::m_tau

◆ m_u

unsigned int tsid::InverseDynamicsFormulationAccForce::m_u

number of acceleration variables

◆ m_v

unsigned int tsid::InverseDynamicsFormulationAccForce::m_v

number of contact-force variables


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