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

#include <task-joint-posVelAcc-bounds.hpp>

Inheritance diagram for tsid::python::TaskJointPosVelAccBoundsPythonVisitor< Task >:
Inheritance graph
[legend]

Public Member Functions

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

Static Public Member Functions

static math::ConstraintBound compute (Task &self, const double t, const Eigen::VectorXd &q, const Eigen::VectorXd &v, pinocchio::Data &data)
 
static void computeAccLimits (Task &self, ConstRefVector q, ConstRefVector dq, bool verbose=true)
 
static void computeAccLimitsFromPosLimits (Task &self, ConstRefVector q, ConstRefVector dq, bool verbose=true)
 
static void computeAccLimitsFromViability (Task &self, ConstRefVector q, ConstRefVector dq, bool verbose=true)
 
static void expose (const std::string &class_name)
 
static const Eigen::VectorXdgetAccelerationBounds (const Task &self)
 
static math::ConstraintBound getConstraint (const Task &self)
 
static const Eigen::VectorXdgetPositionLowerBounds (const Task &self)
 
static const Eigen::VectorXdgetPositionUpperBounds (const Task &self)
 
static const Eigen::VectorXdgetVelocityBounds (const Task &self)
 
static void isStateViable (Task &self, ConstRefVector q, ConstRefVector dq, bool verbose=true)
 
static std::string name (Task &self)
 
static void setAccelerationBounds (Task &self, const Eigen::VectorXd upper)
 
static void setImposeBounds (Task &self, bool impose_position_bounds, bool impose_velocity_bounds, bool impose_viability_bounds, bool impose_acceleration_bounds)
 
static void setMask (Task &self, math::ConstRefVector mask)
 
static void setPositionBounds (Task &self, const Eigen::VectorXd lower, const Eigen::VectorXd upper)
 
static void setTimeStep (Task &self, const double dt)
 
static void setVelocityBounds (Task &self, const Eigen::VectorXd upper)
 
static void setVerbose (Task &self, bool verbose)
 

Detailed Description

template<typename Task>
struct tsid::python::TaskJointPosVelAccBoundsPythonVisitor< Task >

Definition at line 34 of file bindings/python/tasks/task-joint-posVelAcc-bounds.hpp.

Member Function Documentation

◆ compute()

template<typename Task >
static math::ConstraintBound tsid::python::TaskJointPosVelAccBoundsPythonVisitor< Task >::compute ( Task &  self,
const double  t,
const Eigen::VectorXd q,
const Eigen::VectorXd v,
pinocchio::Data data 
)
inlinestatic

◆ computeAccLimits()

template<typename Task >
static void tsid::python::TaskJointPosVelAccBoundsPythonVisitor< Task >::computeAccLimits ( Task &  self,
ConstRefVector  q,
ConstRefVector  dq,
bool  verbose = true 
)
inlinestatic

◆ computeAccLimitsFromPosLimits()

template<typename Task >
static void tsid::python::TaskJointPosVelAccBoundsPythonVisitor< Task >::computeAccLimitsFromPosLimits ( Task &  self,
ConstRefVector  q,
ConstRefVector  dq,
bool  verbose = true 
)
inlinestatic

◆ computeAccLimitsFromViability()

template<typename Task >
static void tsid::python::TaskJointPosVelAccBoundsPythonVisitor< Task >::computeAccLimitsFromViability ( Task &  self,
ConstRefVector  q,
ConstRefVector  dq,
bool  verbose = true 
)
inlinestatic

◆ expose()

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

◆ getAccelerationBounds()

template<typename Task >
static const Eigen::VectorXd& tsid::python::TaskJointPosVelAccBoundsPythonVisitor< Task >::getAccelerationBounds ( const Task &  self)
inlinestatic

◆ getConstraint()

template<typename Task >
static math::ConstraintBound tsid::python::TaskJointPosVelAccBoundsPythonVisitor< Task >::getConstraint ( const Task &  self)
inlinestatic

◆ getPositionLowerBounds()

template<typename Task >
static const Eigen::VectorXd& tsid::python::TaskJointPosVelAccBoundsPythonVisitor< Task >::getPositionLowerBounds ( const Task &  self)
inlinestatic

◆ getPositionUpperBounds()

template<typename Task >
static const Eigen::VectorXd& tsid::python::TaskJointPosVelAccBoundsPythonVisitor< Task >::getPositionUpperBounds ( const Task &  self)
inlinestatic

◆ getVelocityBounds()

template<typename Task >
static const Eigen::VectorXd& tsid::python::TaskJointPosVelAccBoundsPythonVisitor< Task >::getVelocityBounds ( const Task &  self)
inlinestatic

◆ isStateViable()

template<typename Task >
static void tsid::python::TaskJointPosVelAccBoundsPythonVisitor< Task >::isStateViable ( Task &  self,
ConstRefVector  q,
ConstRefVector  dq,
bool  verbose = true 
)
inlinestatic

◆ name()

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

◆ setAccelerationBounds()

template<typename Task >
static void tsid::python::TaskJointPosVelAccBoundsPythonVisitor< Task >::setAccelerationBounds ( Task &  self,
const Eigen::VectorXd  upper 
)
inlinestatic

◆ setImposeBounds()

template<typename Task >
static void tsid::python::TaskJointPosVelAccBoundsPythonVisitor< Task >::setImposeBounds ( Task &  self,
bool  impose_position_bounds,
bool  impose_velocity_bounds,
bool  impose_viability_bounds,
bool  impose_acceleration_bounds 
)
inlinestatic

◆ setMask()

template<typename Task >
static void tsid::python::TaskJointPosVelAccBoundsPythonVisitor< Task >::setMask ( Task &  self,
math::ConstRefVector  mask 
)
inlinestatic

◆ setPositionBounds()

template<typename Task >
static void tsid::python::TaskJointPosVelAccBoundsPythonVisitor< Task >::setPositionBounds ( Task &  self,
const Eigen::VectorXd  lower,
const Eigen::VectorXd  upper 
)
inlinestatic

◆ setTimeStep()

template<typename Task >
static void tsid::python::TaskJointPosVelAccBoundsPythonVisitor< Task >::setTimeStep ( Task &  self,
const double  dt 
)
inlinestatic

◆ setVelocityBounds()

template<typename Task >
static void tsid::python::TaskJointPosVelAccBoundsPythonVisitor< Task >::setVelocityBounds ( Task &  self,
const Eigen::VectorXd  upper 
)
inlinestatic

◆ setVerbose()

template<typename Task >
static void tsid::python::TaskJointPosVelAccBoundsPythonVisitor< Task >::setVerbose ( Task &  self,
bool  verbose 
)
inlinestatic

◆ visit()

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

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