Public Member Functions | Static Public Member Functions | List of all members
tsid::python::InvDynPythonVisitor< T > Struct Template Reference

#include <formulation.hpp>

Inheritance diagram for tsid::python::InvDynPythonVisitor< T >:
Inheritance graph
[legend]

Public Member Functions

template<class PyClass >
void visit (PyClass &cl) const
 

Static Public Member Functions

static bool addActuationTask_Bounds (T &self, tasks::TaskActuationBounds &task, double weight, unsigned int priorityLevel, double transition_duration)
 
static bool addForceTask_COP (T &self, tasks::TaskCopEquality &task, double weight, unsigned int priorityLevel, double transition_duration)
 
static bool addMotionTask_AM (T &self, tasks::TaskAMEquality &task, double weight, unsigned int priorityLevel, double transition_duration)
 
static bool addMotionTask_COM (T &self, tasks::TaskComEquality &task, double weight, unsigned int priorityLevel, double transition_duration)
 
static bool addMotionTask_Joint (T &self, tasks::TaskJointPosture &task, double weight, unsigned int priorityLevel, double transition_duration)
 
static bool addMotionTask_JointBounds (T &self, tasks::TaskJointBounds &task, double weight, unsigned int priorityLevel, double transition_duration)
 
static bool addMotionTask_JointPosVelAccBounds (T &self, tasks::TaskJointPosVelAccBounds &task, double weight, unsigned int priorityLevel, double transition_duration)
 
static bool addMotionTask_SE3 (T &self, tasks::TaskSE3Equality &task, double weight, unsigned int priorityLevel, double transition_duration)
 
static bool addRigidContact6d (T &self, contacts::Contact6d &contact, double force_regularization_weight)
 
static bool addRigidContact6dDeprecated (T &self, contacts::Contact6d &contact)
 
static bool addRigidContact6dWithPriorityLevel (T &self, contacts::Contact6d &contact, double force_regularization_weight, double motion_weight, const bool priority_level)
 
static bool addRigidContactPoint (T &self, contacts::ContactPoint &contact, double force_regularization_weight)
 
static bool addRigidContactPointWithPriorityLevel (T &self, contacts::ContactPoint &contact, double force_regularization_weight, double motion_weight, const bool priority_level)
 
static bool checkContact (T &self, const std::string &name, const solvers::HQPOutput &sol)
 
static HQPDatas computeProblemData (T &self, double time, const Eigen::VectorXd &q, const Eigen::VectorXd &v)
 
static pinocchio::Data data (T &self)
 
static void expose (const std::string &class_name)
 
static Eigen::VectorXd getAccelerations (T &self, const solvers::HQPOutput &sol)
 
static Eigen::VectorXd getActuatorForces (T &self, const solvers::HQPOutput &sol)
 
static Eigen::VectorXd getContactForce (T &self, const std::string &name, const solvers::HQPOutput &sol)
 
static Eigen::VectorXd getContactForces (T &self, const solvers::HQPOutput &sol)
 
static bool removeFromHqpData (T &self, const std::string &constraintName)
 
static bool removeRigidContact (T &self, const std::string &contactName, double transition_duration)
 
static bool removeTask (T &self, const std::string &task_name, double transition_duration)
 
static bool updateRigidContactWeights (T &self, const std::string &contact_name, double force_regularization_weight)
 
static bool updateRigidContactWeightsWithMotionWeight (T &self, const std::string &contact_name, double force_regularization_weight, double motion_weight)
 
static bool updateTaskWeight (T &self, const std::string &task_name, double weight)
 

Detailed Description

template<typename T>
struct tsid::python::InvDynPythonVisitor< T >

Definition at line 43 of file formulation.hpp.

Member Function Documentation

◆ addActuationTask_Bounds()

template<typename T >
static bool tsid::python::InvDynPythonVisitor< T >::addActuationTask_Bounds ( T self,
tasks::TaskActuationBounds task,
double  weight,
unsigned int  priorityLevel,
double  transition_duration 
)
inlinestatic

Definition at line 159 of file formulation.hpp.

◆ addForceTask_COP()

template<typename T >
static bool tsid::python::InvDynPythonVisitor< T >::addForceTask_COP ( T self,
tasks::TaskCopEquality task,
double  weight,
unsigned int  priorityLevel,
double  transition_duration 
)
inlinestatic

Definition at line 154 of file formulation.hpp.

◆ addMotionTask_AM()

template<typename T >
static bool tsid::python::InvDynPythonVisitor< T >::addMotionTask_AM ( T self,
tasks::TaskAMEquality task,
double  weight,
unsigned int  priorityLevel,
double  transition_duration 
)
inlinestatic

Definition at line 149 of file formulation.hpp.

◆ addMotionTask_COM()

template<typename T >
static bool tsid::python::InvDynPythonVisitor< T >::addMotionTask_COM ( T self,
tasks::TaskComEquality task,
double  weight,
unsigned int  priorityLevel,
double  transition_duration 
)
inlinestatic

Definition at line 128 of file formulation.hpp.

◆ addMotionTask_Joint()

template<typename T >
static bool tsid::python::InvDynPythonVisitor< T >::addMotionTask_Joint ( T self,
tasks::TaskJointPosture task,
double  weight,
unsigned int  priorityLevel,
double  transition_duration 
)
inlinestatic

Definition at line 133 of file formulation.hpp.

◆ addMotionTask_JointBounds()

template<typename T >
static bool tsid::python::InvDynPythonVisitor< T >::addMotionTask_JointBounds ( T self,
tasks::TaskJointBounds task,
double  weight,
unsigned int  priorityLevel,
double  transition_duration 
)
inlinestatic

Definition at line 138 of file formulation.hpp.

◆ addMotionTask_JointPosVelAccBounds()

template<typename T >
static bool tsid::python::InvDynPythonVisitor< T >::addMotionTask_JointPosVelAccBounds ( T self,
tasks::TaskJointPosVelAccBounds task,
double  weight,
unsigned int  priorityLevel,
double  transition_duration 
)
inlinestatic

Definition at line 144 of file formulation.hpp.

◆ addMotionTask_SE3()

template<typename T >
static bool tsid::python::InvDynPythonVisitor< T >::addMotionTask_SE3 ( T self,
tasks::TaskSE3Equality task,
double  weight,
unsigned int  priorityLevel,
double  transition_duration 
)
inlinestatic

Definition at line 123 of file formulation.hpp.

◆ addRigidContact6d()

template<typename T >
static bool tsid::python::InvDynPythonVisitor< T >::addRigidContact6d ( T self,
contacts::Contact6d contact,
double  force_regularization_weight 
)
inlinestatic

Definition at line 185 of file formulation.hpp.

◆ addRigidContact6dDeprecated()

template<typename T >
static bool tsid::python::InvDynPythonVisitor< T >::addRigidContact6dDeprecated ( T self,
contacts::Contact6d contact 
)
inlinestatic

Definition at line 181 of file formulation.hpp.

◆ addRigidContact6dWithPriorityLevel()

template<typename T >
static bool tsid::python::InvDynPythonVisitor< T >::addRigidContact6dWithPriorityLevel ( T self,
contacts::Contact6d contact,
double  force_regularization_weight,
double  motion_weight,
const bool  priority_level 
)
inlinestatic

Definition at line 189 of file formulation.hpp.

◆ addRigidContactPoint()

template<typename T >
static bool tsid::python::InvDynPythonVisitor< T >::addRigidContactPoint ( T self,
contacts::ContactPoint contact,
double  force_regularization_weight 
)
inlinestatic

Definition at line 195 of file formulation.hpp.

◆ addRigidContactPointWithPriorityLevel()

template<typename T >
static bool tsid::python::InvDynPythonVisitor< T >::addRigidContactPointWithPriorityLevel ( T self,
contacts::ContactPoint contact,
double  force_regularization_weight,
double  motion_weight,
const bool  priority_level 
)
inlinestatic

Definition at line 199 of file formulation.hpp.

◆ checkContact()

template<typename T >
static bool tsid::python::InvDynPythonVisitor< T >::checkContact ( T self,
const std::string &  name,
const solvers::HQPOutput sol 
)
inlinestatic

Definition at line 236 of file formulation.hpp.

◆ computeProblemData()

template<typename T >
static HQPDatas tsid::python::InvDynPythonVisitor< T >::computeProblemData ( T self,
double  time,
const Eigen::VectorXd q,
const Eigen::VectorXd v 
)
inlinestatic

Definition at line 217 of file formulation.hpp.

◆ data()

template<typename T >
static pinocchio::Data tsid::python::InvDynPythonVisitor< T >::data ( T self)
inlinestatic

Definition at line 119 of file formulation.hpp.

◆ expose()

template<typename T >
static void tsid::python::InvDynPythonVisitor< T >::expose ( const std::string &  class_name)
inlinestatic

Definition at line 247 of file formulation.hpp.

◆ getAccelerations()

template<typename T >
static Eigen::VectorXd tsid::python::InvDynPythonVisitor< T >::getAccelerations ( T self,
const solvers::HQPOutput sol 
)
inlinestatic

Definition at line 228 of file formulation.hpp.

◆ getActuatorForces()

template<typename T >
static Eigen::VectorXd tsid::python::InvDynPythonVisitor< T >::getActuatorForces ( T self,
const solvers::HQPOutput sol 
)
inlinestatic

Definition at line 224 of file formulation.hpp.

◆ getContactForce()

template<typename T >
static Eigen::VectorXd tsid::python::InvDynPythonVisitor< T >::getContactForce ( T self,
const std::string &  name,
const solvers::HQPOutput sol 
)
inlinestatic

Definition at line 242 of file formulation.hpp.

◆ getContactForces()

template<typename T >
static Eigen::VectorXd tsid::python::InvDynPythonVisitor< T >::getContactForces ( T self,
const solvers::HQPOutput sol 
)
inlinestatic

Definition at line 232 of file formulation.hpp.

◆ removeFromHqpData()

template<typename T >
static bool tsid::python::InvDynPythonVisitor< T >::removeFromHqpData ( T self,
const std::string &  constraintName 
)
inlinestatic

Definition at line 214 of file formulation.hpp.

◆ removeRigidContact()

template<typename T >
static bool tsid::python::InvDynPythonVisitor< T >::removeRigidContact ( T self,
const std::string &  contactName,
double  transition_duration 
)
inlinestatic

Definition at line 210 of file formulation.hpp.

◆ removeTask()

template<typename T >
static bool tsid::python::InvDynPythonVisitor< T >::removeTask ( T self,
const std::string &  task_name,
double  transition_duration 
)
inlinestatic

Definition at line 206 of file formulation.hpp.

◆ updateRigidContactWeights()

template<typename T >
static bool tsid::python::InvDynPythonVisitor< T >::updateRigidContactWeights ( T self,
const std::string &  contact_name,
double  force_regularization_weight 
)
inlinestatic

Definition at line 169 of file formulation.hpp.

◆ updateRigidContactWeightsWithMotionWeight()

template<typename T >
static bool tsid::python::InvDynPythonVisitor< T >::updateRigidContactWeightsWithMotionWeight ( T self,
const std::string &  contact_name,
double  force_regularization_weight,
double  motion_weight 
)
inlinestatic

Definition at line 175 of file formulation.hpp.

◆ updateTaskWeight()

template<typename T >
static bool tsid::python::InvDynPythonVisitor< T >::updateTaskWeight ( T self,
const std::string &  task_name,
double  weight 
)
inlinestatic

Definition at line 165 of file formulation.hpp.

◆ visit()

template<typename T >
template<class PyClass >
void tsid::python::InvDynPythonVisitor< T >::visit ( PyClass &  cl) const
inline

Definition at line 47 of file formulation.hpp.


The documentation for this struct was generated from the following file:


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sun Jul 2 2023 02:21:52