A Python library for symbolic derivation of equations of motion, variation based linearization on smooth manifolds,
This work builds on the methods and math described in
- Global Formulations of Lagrangian and Hamiltonian Dynamics on Manifolds
- Symbolic Computation of Dynamics on Smooth Manifolds and its Scala implementation.
Given a Lagrangian and virtual work, geomech automatically derives
globally valid, singularity-free equations of motion on smooth manifolds
(SO(3), S2) using Hamilton's principle and variational calculus --
no Euler angles or quaternions required.
The pipeline:
- Define symbolic scalars, vectors, and matrices
- Build kinetic/potential energy and virtual work expressions
- Call
compute_eom()-- the library takes variations, applies the product rule, expands, integrates by parts, simplifies, and extracts the equations
Expressions are symbolic trees. Python operators (*, +, etc.) build
the tree; transformations rewrite it using match/case pattern matching.
Node arity:
| Arity | Nodes | Example |
|---|---|---|
| N-ary | Add, VAdd, MAdd |
a + b + c → one node, three children |
| Binary | Mul, Dot, Cross, SVMul, MVMul, ... |
Dot(x, y) → two children |
| Unary | Hat, Vee, Transpose, TimeDerivative, Variation |
Hat(x) → one child |
Sample trees:
M * (x + y + Cross(m, n)) -- matrix-vector multiply with N-ary addition:
MVMul ← Binary (matrix × vector → vector)
╱ ╲
M VAdd ← N-ary (3 children)
╱ | ╲
x y Cross ← Binary (vector × vector)
╱ ╲
m n
KE = m * Dot(ẋ, ẋ) * 0.5 -- kinetic energy:
Mul ← Binary (scalar × scalar)
╱ ╲
Mul 0.5
╱ ╲
m Dot ← Binary (vector · vector → scalar)
╱ ╲
d/dt d/dt ← Unary (time derivative)
| |
x x ← Vector leaves
Pattern-matching transformations -- tree rewrites use Python match/case:
def _eliminate(expr):
"""Remove zeros and apply identities."""
match expr:
case Dot(): # binary
l, r = _eliminate(expr.left), _eliminate(expr.right)
if l.is_zero or r.is_zero:
return _ZERO()
return Dot(l, r)
case Hat(): # unary
inner = _eliminate(expr.expr)
if isinstance(inner, Vee):
return inner.expr # Hat(Vee(M)) = M
return Hat(inner)
case Add(nodes=nodes): # n-ary
return _simplify_add([_eliminate(n) for n in nodes])The full pipeline (compute_eom) applies variation → expand → integrate by parts →
simplify → extract coefficients, each as a recursive tree rewrite.
Requires Python >= 3.10.
pip install -e .Point mass -- derives m * ddot_x = f - m*g*e3:
from geomech import *
import numpy as np
m, g = getScalars('m g', attr=['Constant'])
e3 = Vector('e3', attr=['Constant'], value=np.array([0., 0., 1]))
x, f = getVectors(['x', 'f'])
v = x.t_diff()
KE = m * Dot(v, v) * 0.5
PE = m * x.dot(g * e3)
L = KE - PE
dW = Dot(x.delta(), f)
eqs = compute_eom(L, dW, SystemVariables(vectors=[x]))
print_eom(eqs)Spherical pendulum on S2:
m, g, l = getScalars('m g l', attr=['Constant'])
e3 = Vector('e3', attr=['Constant'], value=np.array([0., 0., 1]))
q = S2('q') # attitude on the 2-sphere
f = Vector('f')
x = l * q
v = x.t_diff()
KE = m * Dot(v, v) * 0.5
PE = m * x.dot(g * e3)
L = KE - PE
dW = Dot(q.delta(), f)
eqs = compute_eom(L, dW, SystemVariables(vectors=[q]))
print_eom(eqs)Rigid body on SO(3):
J = Matrix('J', attr=['Constant', 'SymmetricMatrix'])
rho = Vector('\\rho', attr=['Constant'])
m, g = getScalars('m g', attr=['Constant'])
e3 = Vector('e_3', attr=['Constant'], value=np.array([0., 0., 1]))
R = SO3('R') # rotation matrix on SO(3)
Om = R.get_tangent_vector()
eta = R.get_variation_vector()
M = Vector('M') # external torque
x = R * rho
v = x.t_diff()
KE = Dot(Om, J * Om) * 0.5 + Dot(v, v) * m * 0.5
PE = m * g * Dot(x, e3)
L = KE - PE
dW = Dot(eta, M)
eqs = compute_eom(L, dW, SystemVariables(matrices=[R]))
print_eom(eqs)More examples in examples/.
| Type | Description | Constructor |
|---|---|---|
Scalar |
Symbolic scalar | Scalar('m', attr=['Constant']) |
Vector |
Column vector (default 3x1) | Vector('x') |
Matrix |
Square matrix (default 3x3) | Matrix('J', attr=['Constant']) |
S2 |
Unit vector on the 2-sphere | S2('q') |
SO3 |
Rotation matrix on SO(3) | SO3('R') |
Batch constructors: getScalars('a b c'), getVectors(['x', 'y']), getMatrices('M N').
Arithmetic -- natural Python operators build expression trees:
a * b # scalar multiplication
a * x # scalar-vector multiplication
M * x # matrix-vector multiplication
x + y # vector addition
Dot(x, y) # dot product
Cross(x, y) # cross product
Hat(x) # hat map (R^3 -> so(3))
Vee(M) # vee map (so(3) -> R^3)
Transpose(x) # transposeCalculus:
x.t_diff() # time derivative
x.t_integrate() # time integral
x.delta() # variation (delta)Transformations:
expand(expr) # distribute products over sums
simplify(expr) # pull scalars, apply identities, eliminate zeros
full_simplify(expr) # expand + simplify until convergencegeomech/
core/
base/ # Expr types, flags, scalars/vectors/matrices, manifolds
operations/ # Add, Mul, Dot, Cross, Hat, Variation, TimeDerivative, ...
transformations/# expand, simplify, pull, vector_rules
math/ # extract_coeff, collect, integrate_by_parts
dynamics/ # compute_eom, SystemVariables
utils/ # print_eom, print_tree, render_eom
pip install -e ".[dev]"
pytestIf you use geomech in your research, please cite this package along with corresponding original work, Global Formulations of Lagrangian and Hamiltonian Dynamics on Manifolds and Symbolic Computation of Dynamics on Smooth Manifolds.
@software{kotaru2026geomech,
title={geomech: Symbolic toolbox for geometric mechanics on smooth manifolds},
author={Kotaru, Prasanth},
url={https://github.com/vkotaru/pygeomech},
year={2026}
}BSD 3-Clause. See LICENSE.