Skip to content
Open
Show file tree
Hide file tree
Changes from 6 commits
Commits
Show all changes
27 commits
Select commit Hold shift + click to select a range
fc7f230
Lean up README.md
Giulero Dec 10, 2025
15feda5
Update README.md to clarify velocity representation and JAX usage
Giulero Dec 10, 2025
5a743b8
Fix gravity initialization to use torch.as_tensor for consistency
Giulero Dec 11, 2025
9030f4d
Remove unused KinDynComputationsBatch class and related imports
Giulero Dec 11, 2025
6c92585
Refactor import of KinDynComputationsBatch to use alias from computat…
Giulero Dec 11, 2025
fec8498
Enhance documentation for adam library
Giulero Dec 11, 2025
22fc0c5
Add first draft neural inverse-kinematics example with ADAM and MuJoC…
Giulero Dec 12, 2025
5fc6ad3
Clean up
Giulero Dec 12, 2025
dd85ccc
Clean up example
Giulero Dec 15, 2025
11ab1cb
Update readme
Giulero Dec 15, 2025
c53bb2f
Fix import statement for KinDynComputations in backend selection guide
Giulero Dec 15, 2025
16e2435
Clarify documentation on computing system acceleration with external …
Giulero Dec 15, 2025
33ab3e5
Clarify test suite description and update troubleshooting section for…
Giulero Dec 15, 2025
14af709
Cleanup PyTorch backend examples
Giulero Dec 15, 2025
35fcd82
Fix tensor creation
Giulero Dec 15, 2025
804f266
Remove unused Performance section from troubleshooting guide
Giulero Dec 15, 2025
2a221d4
Fix comment
Giulero Dec 15, 2025
8a9976f
Refactor: Replace KinDynComputationsBatch with KinDynComputations in …
Giulero Dec 17, 2025
c4dce9f
Make table visible
Giulero Dec 19, 2025
65772cc
Improve some concepts
Giulero Dec 19, 2025
0b092f5
Remove table
Giulero Dec 19, 2025
b15236b
Fix brace
Giulero Dec 19, 2025
7f6de3b
Fix
Giulero Dec 19, 2025
62d5045
Set joint origin to zero if none in the urdf
Giulero Dec 21, 2025
2938c9a
Update README to clarify usage of KinDynComputations for PyTorch
Giulero Dec 21, 2025
7533b1e
Fix formatting in README for KinDynComputationsBatch note
Giulero Dec 21, 2025
07505ca
Remove word
Giulero Dec 21, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
295 changes: 96 additions & 199 deletions README.md

Large diffs are not rendered by default.

158 changes: 158 additions & 0 deletions docs/guides/backend_selection.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,158 @@
Choosing a Backend
===================

adam supports multiple backends, each optimized for different use cases. This guide helps you choose the right one for your application.

.. Quick Comparison
.. ----------------
.. +-------------+--------+--------+--------+--------+
.. | Feature | NumPy | JAX | CasADi | PyTorch|
.. +=============+========+========+========+========+
.. | **Speed** | Good | Excellent | Good | Excellent |
.. | **Symbolic**| ❌ | ❌ | ✅ | ❌ |
.. | **Autodiff**| ❌ | ✅ | ✅ | ✅ |
.. | **GPU** | ❌ | ✅ | ❌ | ✅ |
.. | **Batch** | Manual | Native | Manual | Native |
.. | **Learning Curve** | Easy | Medium | Medium | Easy |
.. +-------------+--------+--------+--------+--------+
.. Detailed Breakdown
.. ------------------
NumPy
^^^^^

**Best for:** Quick prototyping, validation, simplicity

- Direct numerical computation
- No compilation or setup overhead
- Easiest to debug and understand
- Good for initial model verification

**When to use:**

- Validating robot models
- Quick experiments
- Educational purposes
Comment on lines +9 to +20
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do you think this is really required? 🤔

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yeah maybe this is just fancy. We could remove this piece and keep the doc more minimal.

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yeah maybe this is just fancy. We could remove this piece and keep the doc more minimal.


**Example:**

.. code-block:: python
from adam.numpy import KinDynComputations
kinDyn = KinDynComputations(model_path, joints_list)
M = kinDyn.mass_matrix(w_H_b, joints)
JAX
^^^

**Best for:** Research, optimization, vectorized computations

- JIT compilation for speed
- Automatic differentiation (grad, jacobian, hessian)
- Native batch support

**When to use:**

- Gradient-based optimization
- Computing derivatives and Jacobians
- Processing batches of configurations
- Control design with auto-differentiation

**Gotchas:**

- First call with jit is slow (compilation)
- Can't use Python branching on traced values

**Example:**

.. code-block:: python
from adam.jax import KinDynComputations
from jax import jit, grad
kinDyn = KinDynComputations(model_path, joints_list)
@jit
def compute_and_grad(w_H_b, joints):
M = kinDyn.mass_matrix(w_H_b, joints)
grad_fn = grad(lambda q: kinDyn.mass_matrix(w_H_b, q).sum())
return M, grad_fn(joints)
CasADi
^^^^^^

**Best for:** Optimal control, trajectory optimization, symbolic formulation

- Symbolic computation for optimization
- Function generation for code generation
- Both numeric and symbolic evaluation
- Constraint handling

**When to use:**

- Nonlinear model predictive control (NMPC)
- Trajectory optimization
- Building optimization problems
- When you need symbolic expressions
- Code generation for embedded systems

**Example:**

.. code-block:: python
import casadi as cs
from adam.casadi import KinDynComputations
kinDyn = KinDynComputations(model_path, joints_list)
# Numeric evaluation
M_fun = kinDyn.mass_matrix_fun()
M = M_fun(w_H_b, joints)
# Symbolic computation
w_H_b_sym = cs.SX.sym('H', 4, 4)
joints_sym = cs.SX.sym('q', n_dof)
M_sym = M_fun(w_H_b_sym, joints_sym)
PyTorch
^^^^^^^

**Best for:** Machine learning, GPU acceleration, batched computation

- GPU usage out of the box
- Native batch support
- Integration with neural networks
- Automatic differentiation

**When to use:**

- Learning-based control
- Large-scale batch processing
- GPU-accelerated robotics
- Integration with ML frameworks

**Gotchas:**

- GPU memory can be limiting
- Requires careful dtype/device handling

**Example:**

.. code-block:: python
import torch
from adam.pytorch import KinDynComputationsBatch
kinDyn = KinDynComputationsBatch(model_path, joints_list)
# Batched computation
batch_size = 1024
w_H_b_batch = torch.randn(batch_size, 4, 4)
joints_batch = torch.randn(batch_size, n_dof)
M_batch = kinDyn.mass_matrix(w_H_b_batch, joints_batch) # Shape: (batch, 6+n, 6+n)
221 changes: 221 additions & 0 deletions docs/guides/concepts.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,221 @@
Core Concepts
==============

This guide explains the fundamental concepts in adam.

Floating-Base Representation
-----------------------------

adam models robots as a **floating base** articulated system. The state consists of:

- **Base Transform** ``w_H_b``: The 4×4 homogeneous transformation matrix from world frame to base frame
- **Joint Positions** ``joints``: Scalar values for each actuated joint
- **Base Velocity** ``base_vel``: A 6D vector representing the linear and angular velocity of the base
- **Joint Velocities** ``joints_vel``: Scalar velocities for each actuated joint

Robot dynamics
----------------

The robot dynamics are described by the standard equations of motion for floating-base systems:

.. math::
M(q) \dot{\nu} + C(q, \nu) + g(q) = \tau + J^T(q) f_{ext}
where:

- :math:`M(q)` is the mass matrix
- :math:`C(q, \nu)` are Coriolis and centrifugal effects
- :math:`g(q)` is the gravity term
- :math:`\tau` are the generalized forces/torques
- :math:`J(q)` is the Jacobian matrix of the frame on which external wrenches act
- :math:`f_{ext}` are external wrenches (forces/torques)
- :math:`q` = [w_H_b, joints] is the configuration
- :math:`\nu` = [base_vel, joints_vel] is the configuration velocity
- :math:`\dot{\nu}` is the configuration acceleration


Velocity Representations
------------------------

There are three 6D velocity representations for the floating base (check also useful `iDynTree theory <https://github.com/robotology/idyntree/blob/master/doc/theory.md>`_).
Let :math:`A` denote the world (inertial) frame and :math:`B` denote the base frame. The 6D velocity is stacked as :math:`\begin{bmatrix} v \\ \omega \end{bmatrix}` with linear velocity first.

**Mixed (Default)**

Expressed as ``Representations.MIXED_REPRESENTATION`` (default in adam and iDynTree):

.. math::
{}^{A[B]}\mathrm{v}_{A,B} = \begin{bmatrix} {}^{A}v_{o_B} \\ {}^{A}\omega_{A,B} \end{bmatrix} = \begin{bmatrix} {}^{A}\dot{o}_{B} \\ (\dot{{}^{A}R_{B}} {}^{A}R_{B}^{-1})^{\vee} \end{bmatrix}
Linear velocity is the time derivative of the base origin position (expressed in world frame :math:`A`), and angular velocity is expressed in the **world frame**.
This hybrid representation is commonly used in humanoid robotics and is the default in adam.


**Left-Trivialized (Body-Fixed)**

Expressed as ``Representations.BODY_FIXED_REPRESENTATION``:

.. math::
{}^{B}\mathrm{v}_{A,B} = \begin{bmatrix} {}^{B}v_{B} \\ {}^{B}\omega_{A,B} \end{bmatrix}
Both linear and angular velocities are expressed in the **base frame** coordinates.
This is the "body-fixed" frame representation.

**Right-Trivialized (Inertial-Fixed)**

Expressed as ``Representations.INERTIAL_FIXED_REPRESENTATION``:

.. math::
{}^{A}\mathrm{v}_{A,B} = \begin{bmatrix} {}^{A}v_{B} \\ {}^{A}\omega_{A,B} \end{bmatrix}
Linear velocity is expressed in the **world frame**, angular velocity in the **world frame**.
This is the "inertial-fixed" frame representation.


**Setting the Representation**

Always set this early when creating a ``KinDynComputations`` object:

.. code-block:: python
kinDyn.set_frame_velocity_representation(adam.Representations.MIXED_REPRESENTATION)
# or
kinDyn.set_frame_velocity_representation(adam.Representations.BODY_FIXED_REPRESENTATION)
# or
kinDyn.set_frame_velocity_representation(adam.Representations.INERTIAL_FIXED_REPRESENTATION)
The representation affects:

- **Jacobian computations** – Jacobians transform between representations via adjoint matrices
- **Inertia matrix structure** – Mass matrix transforms according to representation
- **Centroidal momentum calculations** – Momentum definitions differ by representation
- **Any velocity-dependent quantities** – Coriolis forces, bias forces, etc.

See the `iDynTree theory documentation <https://github.com/robotology/idyntree/blob/master/doc/theory.md>`_ for mathematical details on 6D velocity representations.

State Format
^^^^^^^^^^^^

Velocities are always stacked as:

.. code-block:: python
[base_linear_vel, base_angular_vel, joint_velocities]
# Shape: (3,) + (3,) + (n_dof,) = (6 + n_dof,)
Key Matrices and Quantities
----------------------------

**Mass Matrix** ``M``

Shape: ``(6 + n_dof, 6 + n_dof)``

The inertia matrix relating generalized forces to generalized accelerations:

.. math::
M(q) \dot{\nu} = \tau - h(q, \nu) - g(q)
where:

- :math:`M` is symmetric and positive definite
- Describes how joint positions affect inertia
- Used in inverse dynamics, control design

**Centroidal Momentum Matrix** ``Ag``

Shape: ``(6, 6 + n_dof)``

Relates generalized velocities to centroidal momentum:

.. math::
\begin{bmatrix} L \\ h \end{bmatrix} = A_g(q) \nu
where:

- ``L``: Linear momentum
- ``h``: Angular momentum about CoM

**Jacobian** ``J``

Shape: ``(6, 6 + n_dof)``

Relates end-effector velocity to generalized velocities:

.. math::
v_{ee} = J(q) \nu
Available as:

- ``jacobian(frame_name, ...)`` – frame Jacobian
- ``CoM_jacobian(...)`` – CoM Jacobian
- ``jacobian_dot(...)`` – time derivative

**Forward Kinematics** ``w_H_frame``

Shape: ``(4, 4)``

The transformation from world to any frame:

.. code-block:: python
w_H_frame = kinDyn.forward_kinematics('frame_name', w_H_b, joints)
Dynamics Algorithms
-------------------

adam uses **Featherstone's Recursive Algorithms** under the hood, which compute all quantities efficiently in O(n) time where n is the number of joints.

**Articulated Body Algorithm (ABA)**

Computes accelerations given forces:

.. math::
\ddot{q} = \text{ABA}(q, \nu, \tau, f_{ext})
Used in forward dynamics simulation.


**Recursive Newton-Euler Algorithm (RNEA)**

Computes Coriolis, centrifugal, and gravity effects:

.. math::
h(q, \nu) = C(q,\nu) + g(q) = \text{RNEA}(q, \nu)
**Composite Rigid Body Algorithm (CRBA)**

Computes the mass matrix and centroidal momentum matrix:

.. math::
M(q), A_g(q) = \text{CRBA}(q)
External Wrenches
-----------------

When computing dynamics with external forces (e.g., contact forces), pass them as a dictionary:

.. code-block:: python
external_wrenches = {
'l_sole': np.array([fx, fy, fz, mx, my, mz]), # Contact force at left foot
'r_sole': np.array([fx, fy, fz, mx, my, mz]), # Contact force at right foot
}
tau = kinDyn.inverse_dynamics(
w_H_b, joints,
base_acc, joints_acc,
external_wrenches=external_wrenches
)
12 changes: 12 additions & 0 deletions docs/guides/index.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
Guides
======

Detailed guides for understanding and using adam effectively.

.. toctree::
:maxdepth: 2

concepts
backend_selection
mujoco
troubleshooting
Loading
Loading