-
Notifications
You must be signed in to change notification settings - Fork 87
Home
Welcome to the invdyn wiki!
This document tries to justify the design choice behind this library. The goal of this library is to create inverse-dynamics controllers for legged robots. We suppose that an inverse-dynamics control algorithm always boils down to solving a Hierarchical Least-Squares Program (HLSP), that can be seen as a cascade of standard Least-Squares Programs (LSP). A LSP is a special case of Quadratic Program (QP), in which the cost function is the 2-norm of a linear function, and the equality/inequality constraints are linear (in this document the term linear is used loosely to mean also affine). The key concepts of this library are:
- Constraint: a linear equality or inequality; a HLSP is defined as a collection of constraints with difference priority levels and weights.
- Task: a control objective for the robot, which is used at each control cycle to generate a constraint. Note that constraints are purely mathematical objects that are independent of the concept of robot, while Tasks are instead robot-related objects.
- Rigid Contact: a description of a rigid contact between a body of the robot and another object; the main difference between a task and a rigid contact is that a rigid contact is associated to reaction forces, while a task is not.
- Trajectory: a multi-dimensional function of time describing the motion of an object and its time derivatives
- QpSolver: an algorithm capable of solving a hierarchical QP
The main class of the library is InverseDynamicsFormulation, which offers the following interface:
bool addMotionTask(MotionTask task, double weight, int priorityLevel, double transition_duration=0.0);
bool addForceTask(ForceTask task, double weight, int priorityLevel, double transition_duration=0.0);
bool addTorqueTask(TorqueTask task, double weight, int priorityLevel, double transition_duration=0.0);
bool addRigidContact(AbstractRigidContact contact);
bool removeTask(string task_name, double transition_duration=0.0);
bool removeRigidContact(string contact_name, double transition_duration=0.0);
virtual QpData computeProblemData(double time, Vector q, Vector v) = 0;