|
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) |
|