Skip to content

Latest commit

 

History

History
79 lines (56 loc) · 6.02 KB

Manual-Dynamics.md

File metadata and controls

79 lines (56 loc) · 6.02 KB

Klamp't Manual: Dynamics and contact mechanics

Robot Dynamic Parameters

Each body contains inertial properties, which are collectively set referred to as a Mass object.

  • mass (float)
  • center of mass (Vector3) given in local coordinates
  • inertia matrix (Matrix3) HL given in local coordinates

Robot (.rob) and Rigid Object (.obj) files can automatically infer inertial properties from link masses using the automass line.

Robot Dynamics

The fundamental Langrangian mechanics equation is

B(q)q''+C(q,q')+G(q)=τ+Σi Ji(q)T fi

Where:

  • q is configuration,
  • q' is velocity,
  • q'' is acceleration,
  • B(q) is the positive semidefinite mass matrix,
  • C(q,q') is the Coriolis force,
  • G(q) is the generalized gravity,
  • τ is the link torque,
  • fi are external forces, and
  • Ji(q) are the Jacobians of the points at which the points are applied.

A robot's motion under given torques and external forces can be computed by determining the acceleration q'' by multiplying both sides by B-1 and integrating the equation forward in time.

API summary

Klamp't has several methods for calculating and manipulating dynamics terms. The first set of methods is found in the Robot class, which use the "classic" Euler-Lagrange method that expands the terms mathematically in terms of Jacobians and Jacobian derivatives, and runs in O(n3).

  • CalcAcceleration: used to convert the RHS to accelerations (forward dynamics).
  • CalcTorques is used to convert from accelerations to the RHS (inverse dynamics).
  • KineticEnergy:
  • KineticEnergyInv:
  • GravityTorques:
  • CoriolisForce: Note that these are actually defined in RobotKinematics3D and RobotDynamics3D.

The second set of methods uses the Newton-Euler rigid body equations and the Featherstone algorithm (KrisLibrary/robotics/NewtonEuler.h). These equations are O(n) for sparsely branched chains and are typically faster than the classic methods for modestly sized robots (e.g., n>6). Although NewtonEuler is designed particularly for the CalcAccel and CalcTorques methods for forward and inverse dynamics, it is also possible to use it to calculate the C+G term in O(n) time, and it can calculate the B or B-1 matrices in O(n2) time.

Contact mechanics

Klamp't supports several operations for working with contacts. Currently these support legged locomotion more conveniently than object manipulation, because the manipulated object must be defined as part of the robot, and robot-object contact is considered self-contact.

API summary

These routines can be found in KrisLibrary/robotics, in particular Contact.h, Stability.h, and TorqueSolver.h.

  • A ContactPoint is either a frictionless or frictional point contact. Consist of a position, normal, and coefficient of friction.
  • A ContactFormation defines a set of contacts on multiple links of a robot. Consists of a list of links and a list of lists of contacts. For all indices i, contacts[i] is the set of contacts that affect links[i]. Optionally, self-contacts may be defined by providing the list of target links targets[i], with -1 denoting the world coordinate frame. Contact quantities may be given target space or in link-local coordinates is application-defined.
  • The TestCOMEquilibrium functions test whether the center of mass of a rigid body can be stably supported against gravity by valid contact forces at the given contact list.
  • The EquilibriumTester class provides richer functionality than TestCOMEquilibrium, such as force limiting and adding robustness factors. It may also save some memory allocations when testing multiple centers of mass with the same contact list.
  • The SupportPolygon class explicitly computes a support polygon for a given contact list, and provides even faster testing than EquilibriumTester for testing large numbers of centers of mass (typically around 10-20).
  • The TorqueSolver class solves for equilibrium of an articulated robot under gravity and torque constraints. It can handle both statically balanced and dynamically moving robots.

Holds, Stances, and Grasps

The contact state of a single link, or a related set of links, is modeled with three higher-level concepts.

  • Hold: a set of contacts of a link against the environment and are used for locomotion planning.
  • Stance: a set of Holds.
  • Grasp: like a Hold, but can also contain constraints on the values of related link DOFs (e.g., the fingers). Generally used for manipulation planning but could also be part of locomotion as well (grasping a rail for stability, for example).

A Hold is defined as a set of contacts (the contacts member) and the associated IK constraint (the ikConstraint member) that keeps a link on the robot placed at those contacts. These contacts are considered fixed in the world frame. Holds may be saved and loaded from disk. The C++ API defines them in Klampt/Cpp/Contact/Hold.h, which also defines convenience setup routines in the Setup* methods. The Python API defines them in klampt.model.contact.

A Stance (Klampt/Cpp/Contact/Stance.h) defines all contact constraints of a robot. It is defined simply as a map from links to Holds in C++, and is simply a list of Holds in Python.

A Grasp (Klampt/Cpp/Contact/Grasp.h) is more sophisticated than a Hold and are most appropriate for modeling hands that make contact with fingers. A Grasp defines an IK constraint of some link (e.g., a palm) relative to some movable object or the environment, as well as the values of related link DOFs (e.g., the fingers) and possibly the contact state. Note: support for planning with Grasps is limited in the current version.