Go to the documentation of this file.
18 #ifndef __invdyn_inverse_dynamics_formulation_base_hpp__
19 #define __invdyn_inverse_dynamics_formulation_base_hpp__
21 #include "tsid/deprecated.hh"
36 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
46 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
56 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
68 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
85 bool verbose =
false);
91 virtual unsigned int nVar()
const = 0;
92 virtual unsigned int nEq()
const = 0;
93 virtual unsigned int nIn()
const = 0;
96 unsigned int priorityLevel,
97 double transition_duration = 0.0) = 0;
100 unsigned int priorityLevel,
101 double transition_duration = 0.0) = 0;
104 unsigned int priorityLevel,
105 double transition_duration = 0.0) = 0;
122 double force_regularization_weight,
123 double motion_weight = 1.0,
124 unsigned int motion_priority_level = 0) = 0;
138 double force_regularization_weight,
139 double motion_weight = -1.0) = 0;
143 virtual bool removeTask(
const std::string& taskName,
144 double transition_duration = 0.0) = 0;
147 double transition_duration = 0.0) = 0;
168 #endif // ifndef __invdyn_inverse_dynamics_formulation_base_hpp__
EIGEN_MAKE_ALIGNED_OPERATOR_NEW tasks::TaskContactForce & task
Base template of a Task. Each class is defined according to a constant model of a robot.
std::shared_ptr< math::ConstraintBase > constraint
TaskLevel(tasks::TaskBase &task, unsigned int priority)
Eigen::Ref< Vector > RefVector
const typedef Eigen::Ref< const Vector > ConstRefVector
EIGEN_MAKE_ALIGNED_OPERATOR_NEW contacts::MeasuredForceBase & measuredForce
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
std::shared_ptr< math::ConstraintBase > constraint
TaskLevelForce(tasks::TaskContactForce &task, unsigned int priority)
Wrapper for a robot based on pinocchio.
MeasuredForceLevel(contacts::MeasuredForceBase &measuredForce)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW tasks::TaskBase & task
pinocchio::container::aligned_vector< ConstraintLevel > HQPData
tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Thu Apr 3 2025 02:47:15