18 #ifndef __invdyn_inverse_dynamics_formulation_base_hpp__ 19 #define __invdyn_inverse_dynamics_formulation_base_hpp__ 21 #include "tsid/deprecated.hh" 37 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
44 unsigned int priority);
49 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
56 unsigned int priority);
65 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
85 virtual Data & data() = 0;
87 virtual unsigned int nVar()
const = 0;
88 virtual unsigned int nEq()
const = 0;
89 virtual unsigned int nIn()
const = 0;
91 virtual bool addMotionTask(TaskMotion &
task,
93 unsigned int priorityLevel,
94 double transition_duration=0.0) = 0;
96 virtual bool addForceTask(TaskContactForce &
task,
98 unsigned int priorityLevel,
99 double transition_duration=0.0) = 0;
101 virtual bool addActuationTask(TaskActuation &
task,
103 unsigned int priorityLevel,
104 double transition_duration=0.0) = 0;
106 virtual bool updateTaskWeight(
const std::string & task_name,
118 virtual bool addRigidContact(ContactBase & contact,
double force_regularization_weight,
119 double motion_weight=1.0,
unsigned int motion_priority_level=0) = 0;
121 TSID_DEPRECATED
virtual bool addRigidContact(ContactBase & contact);
130 virtual bool updateRigidContactWeights(
const std::string & contact_name,
131 double force_regularization_weight,
132 double motion_weight=-1.0) = 0;
134 virtual bool removeTask(
const std::string & taskName,
135 double transition_duration=0.0) = 0;
137 virtual bool removeRigidContact(
const std::string & contactName,
138 double transition_duration=0.0) = 0;
140 virtual const HQPData & computeProblemData(
double time,
142 ConstRefVector v) = 0;
144 virtual const Vector & getActuatorForces(
const HQPOutput & sol) = 0;
145 virtual const Vector & getAccelerations(
const HQPOutput & sol) = 0;
146 virtual const Vector & getContactForces(
const HQPOutput & sol) = 0;
147 virtual bool getContactForces(
const std::string & name,
148 const HQPOutput & sol,
159 #endif // ifndef __invdyn_inverse_dynamics_formulation_base_hpp__ Eigen::Ref< Vector > RefVector
Definition: fwd.hpp:49
Definition: solver-HQP-output.hpp:32
Base template of a Task. Each class is defined according to a constant model of a robot...
Definition: task-base.hpp:36
EIGEN_MAKE_ALIGNED_OPERATOR_NEW tasks::TaskBase & task
Definition: inverse-dynamics-formulation-base.hpp:39
Definition: inverse-dynamics-formulation-base.hpp:35
EIGEN_MAKE_ALIGNED_OPERATOR_NEW tasks::TaskContactForce & task
Definition: inverse-dynamics-formulation-base.hpp:51
unsigned int priority
Definition: inverse-dynamics-formulation-base.hpp:41
Definition: task-motion.hpp:28
pinocchio::container::aligned_vector< ConstraintLevel > HQPData
Definition: fwd.hpp:91
Definition: task-actuation.hpp:27
TaskLevel(tasks::TaskBase &task, unsigned int priority)
Definition: inverse-dynamics-formulation-base.cpp:24
const Eigen::Ref< const Vector > ConstRefVector
Definition: fwd.hpp:50
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: fwd.hpp:37
std::shared_ptr< math::ConstraintBase > constraint
Definition: inverse-dynamics-formulation-base.hpp:40
Wrapper for a robot based on pinocchio.
Definition: robot-wrapper.hpp:40
std::shared_ptr< math::ConstraintBase > constraint
Definition: inverse-dynamics-formulation-base.hpp:52
unsigned int priority
Definition: inverse-dynamics-formulation-base.hpp:53
Definition: constraint-bound.hpp:26
Definition: inverse-dynamics-formulation-base.hpp:47