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

#include <contact-two-frames.hpp>

Inheritance diagram for tsid::python::ContactTwoFramesPythonVisitor< ContactTwoFrames >:
Inheritance graph
[legend]

Public Member Functions

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

Static Public Member Functions

static math::ConstraintEquality computeForceRegularizationTask (ContactTwoFrames &self, const double t, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const pinocchio::Data &data)
 
static math::ConstraintInequality computeForceTask (ContactTwoFrames &self, const double t, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const pinocchio::Data &data)
 
static math::ConstraintEquality computeMotionTask (ContactTwoFrames &self, const double t, const Eigen::VectorXd &q, const Eigen::VectorXd &v, pinocchio::Data &data)
 
static void expose (const std::string &class_name)
 
static const Eigen::MatrixXd & getForceGeneratorMatrix (ContactTwoFrames &self)
 
static double getNormalForce (ContactTwoFrames &self, Eigen::VectorXd f)
 
static const Eigen::VectorXd & Kd (ContactTwoFrames &self)
 
static const Eigen::VectorXd & Kp (ContactTwoFrames &self)
 
static std::string name (ContactTwoFrames &self)
 
static bool setContactNormal (ContactTwoFrames &self, const ::Eigen::VectorXd contactNormal)
 
static bool setContactTwoFramess (ContactTwoFrames &self, const ::Eigen::MatrixXd ContactTwoFramess)
 
static void setForceReference (ContactTwoFrames &self, const ::Eigen::VectorXd f_ref)
 
static bool setFrictionCoefficient (ContactTwoFrames &self, const double frictionCoefficient)
 
static void setKd (ContactTwoFrames &self, const ::Eigen::VectorXd Kd)
 
static void setKp (ContactTwoFrames &self, const ::Eigen::VectorXd Kp)
 
static bool setMaxNormalForce (ContactTwoFrames &self, const double maxNormalForce)
 
static bool setMinNormalForce (ContactTwoFrames &self, const double minNormalForce)
 
static void setReference (ContactTwoFrames &self, const pinocchio::SE3 &ref)
 
static void setRegularizationTaskWeightVector (ContactTwoFrames &self, const ::Eigen::VectorXd w)
 
static void useLocalFrame (ContactTwoFrames &self, const bool local_frame)
 

Detailed Description

template<typename ContactTwoFrames>
struct tsid::python::ContactTwoFramesPythonVisitor< ContactTwoFrames >

Definition at line 34 of file contact-two-frames.hpp.

Member Function Documentation

◆ computeForceRegularizationTask()

template<typename ContactTwoFrames >
static math::ConstraintEquality tsid::python::ContactTwoFramesPythonVisitor< ContactTwoFrames >::computeForceRegularizationTask ( ContactTwoFrames &  self,
const double  t,
const Eigen::VectorXd &  q,
const Eigen::VectorXd &  v,
const pinocchio::Data data 
)
inlinestatic

Definition at line 133 of file contact-two-frames.hpp.

◆ computeForceTask()

template<typename ContactTwoFrames >
static math::ConstraintInequality tsid::python::ContactTwoFramesPythonVisitor< ContactTwoFrames >::computeForceTask ( ContactTwoFrames &  self,
const double  t,
const Eigen::VectorXd &  q,
const Eigen::VectorXd &  v,
const pinocchio::Data data 
)
inlinestatic

Definition at line 123 of file contact-two-frames.hpp.

◆ computeMotionTask()

template<typename ContactTwoFrames >
static math::ConstraintEquality tsid::python::ContactTwoFramesPythonVisitor< ContactTwoFrames >::computeMotionTask ( ContactTwoFrames &  self,
const double  t,
const Eigen::VectorXd &  q,
const Eigen::VectorXd &  v,
pinocchio::Data data 
)
inlinestatic

Definition at line 112 of file contact-two-frames.hpp.

◆ expose()

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

Definition at line 193 of file contact-two-frames.hpp.

◆ getForceGeneratorMatrix()

template<typename ContactTwoFrames >
static const Eigen::MatrixXd& tsid::python::ContactTwoFramesPythonVisitor< ContactTwoFrames >::getForceGeneratorMatrix ( ContactTwoFrames &  self)
inlinestatic

Definition at line 146 of file contact-two-frames.hpp.

◆ getNormalForce()

template<typename ContactTwoFrames >
static double tsid::python::ContactTwoFramesPythonVisitor< ContactTwoFrames >::getNormalForce ( ContactTwoFrames &  self,
Eigen::VectorXd  f 
)
inlinestatic

Definition at line 189 of file contact-two-frames.hpp.

◆ Kd()

template<typename ContactTwoFrames >
static const Eigen::VectorXd& tsid::python::ContactTwoFramesPythonVisitor< ContactTwoFrames >::Kd ( ContactTwoFrames &  self)
inlinestatic

Definition at line 151 of file contact-two-frames.hpp.

◆ Kp()

template<typename ContactTwoFrames >
static const Eigen::VectorXd& tsid::python::ContactTwoFramesPythonVisitor< ContactTwoFrames >::Kp ( ContactTwoFrames &  self)
inlinestatic

Definition at line 150 of file contact-two-frames.hpp.

◆ name()

template<typename ContactTwoFrames >
static std::string tsid::python::ContactTwoFramesPythonVisitor< ContactTwoFrames >::name ( ContactTwoFrames &  self)
inlinestatic

Definition at line 107 of file contact-two-frames.hpp.

◆ setContactNormal()

template<typename ContactTwoFrames >
static bool tsid::python::ContactTwoFramesPythonVisitor< ContactTwoFrames >::setContactNormal ( ContactTwoFrames &  self,
const ::Eigen::VectorXd  contactNormal 
)
inlinestatic

Definition at line 162 of file contact-two-frames.hpp.

◆ setContactTwoFramess()

template<typename ContactTwoFrames >
static bool tsid::python::ContactTwoFramesPythonVisitor< ContactTwoFrames >::setContactTwoFramess ( ContactTwoFrames &  self,
const ::Eigen::MatrixXd  ContactTwoFramess 
)
inlinestatic

Definition at line 158 of file contact-two-frames.hpp.

◆ setForceReference()

template<typename ContactTwoFrames >
static void tsid::python::ContactTwoFramesPythonVisitor< ContactTwoFrames >::setForceReference ( ContactTwoFrames &  self,
const ::Eigen::VectorXd  f_ref 
)
inlinestatic

Definition at line 181 of file contact-two-frames.hpp.

◆ setFrictionCoefficient()

template<typename ContactTwoFrames >
static bool tsid::python::ContactTwoFramesPythonVisitor< ContactTwoFrames >::setFrictionCoefficient ( ContactTwoFrames &  self,
const double  frictionCoefficient 
)
inlinestatic

Definition at line 166 of file contact-two-frames.hpp.

◆ setKd()

template<typename ContactTwoFrames >
static void tsid::python::ContactTwoFramesPythonVisitor< ContactTwoFrames >::setKd ( ContactTwoFrames &  self,
const ::Eigen::VectorXd  Kd 
)
inlinestatic

Definition at line 155 of file contact-two-frames.hpp.

◆ setKp()

template<typename ContactTwoFrames >
static void tsid::python::ContactTwoFramesPythonVisitor< ContactTwoFrames >::setKp ( ContactTwoFrames &  self,
const ::Eigen::VectorXd  Kp 
)
inlinestatic

Definition at line 152 of file contact-two-frames.hpp.

◆ setMaxNormalForce()

template<typename ContactTwoFrames >
static bool tsid::python::ContactTwoFramesPythonVisitor< ContactTwoFrames >::setMaxNormalForce ( ContactTwoFrames &  self,
const double  maxNormalForce 
)
inlinestatic

Definition at line 174 of file contact-two-frames.hpp.

◆ setMinNormalForce()

template<typename ContactTwoFrames >
static bool tsid::python::ContactTwoFramesPythonVisitor< ContactTwoFrames >::setMinNormalForce ( ContactTwoFrames &  self,
const double  minNormalForce 
)
inlinestatic

Definition at line 170 of file contact-two-frames.hpp.

◆ setReference()

template<typename ContactTwoFrames >
static void tsid::python::ContactTwoFramesPythonVisitor< ContactTwoFrames >::setReference ( ContactTwoFrames &  self,
const pinocchio::SE3 ref 
)
inlinestatic

Definition at line 178 of file contact-two-frames.hpp.

◆ setRegularizationTaskWeightVector()

template<typename ContactTwoFrames >
static void tsid::python::ContactTwoFramesPythonVisitor< ContactTwoFrames >::setRegularizationTaskWeightVector ( ContactTwoFrames &  self,
const ::Eigen::VectorXd  w 
)
inlinestatic

Definition at line 185 of file contact-two-frames.hpp.

◆ useLocalFrame()

template<typename ContactTwoFrames >
static void tsid::python::ContactTwoFramesPythonVisitor< ContactTwoFrames >::useLocalFrame ( ContactTwoFrames &  self,
const bool  local_frame 
)
inlinestatic

Definition at line 143 of file contact-two-frames.hpp.

◆ visit()

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

Definition at line 39 of file contact-two-frames.hpp.


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


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Thu Apr 3 2025 02:47:16