novaphy.solvers.SolverFeatherstone¶
Articulated-body solver implementing the Featherstone composite-rigid-body algorithm (CRBA + ABA) in reduced coordinates. The recommended backend for robots, kinematic chains, pendulums, and any tree-structured multibody system.
Pipeline¶
graph LR
A[Forward<br/>kinematics] --> B[RNEA<br/>bias forces]
B --> C[CRBA<br/>mass matrix]
C --> D[Cholesky<br/>solve]
D --> E[Integrate]
Algorithms:
- Forward Kinematics (FK) computes link transforms from
joint_q. - Recursive Newton-Euler (RNEA) computes bias forces (Coriolis + gravity
- applied wrenches).
- CRBA assembles the joint-space mass matrix
H(q). - Cholesky solve produces
qddfromH qdd = tau - bias. - Semi-implicit integration on
q/qdwith quaternion renormalization forFree/Balljoints.
Joint contacts and limits are enforced through the same Sequential Impulse PGS pipeline used by SolverSemiImplicit.
Constructor¶
novaphy.solvers.SolverFeatherstone(
model, *,
angular_damping: float = 0.05,
update_mass_matrix_interval: int = 1,
friction_smoothing: float = 1.0,
use_tile_gemm: bool = False,
fuse_cholesky: bool = True,
)
| Parameter | Description |
|---|---|
model |
Required. Model containing at least one articulation. |
angular_damping |
Multiplicative angular velocity damping per step. |
update_mass_matrix_interval |
Recompute H(q) every N steps (default 1 = every step). Higher values amortize CRBA cost when q changes slowly. |
friction_smoothing |
Smooths friction direction transitions. |
use_tile_gemm |
Use tiled GEMM for Cholesky factorization (experimental). |
fuse_cholesky |
Fuse the Cholesky factorize + solve into a single pass. |
All kwargs are mirrored into solver.settings so the C++ kernels see them.
Post-Construction Tuning¶
Additional NovaPhy-specific knobs (PGS contact knobs, error reduction):
solver.settings.<field> |
Type | Description |
|---|---|---|
num_iterations |
int |
Inner constraint solver iterations. |
linear_slop |
float |
Linear penetration slop tolerance. |
erp |
float |
Error reduction parameter for soft constraints. |
cfm |
float |
Constraint force mixing. |
warmstarting_factor |
float |
Warm-start impulse scaling. |
restitution_threshold |
float |
Velocity below this skips restitution. |
use_warmstarting |
bool |
Enable warm-starting. |
angular_damping |
float |
Angular damping coefficient. |
update_mass_matrix_interval |
int |
Mass-matrix rebuild cadence. |
friction_smoothing |
float |
Smooths friction direction transitions. |
use_tile_gemm |
bool |
Use tiled GEMM where available. |
fuse_cholesky |
bool |
Fuse Cholesky-related work where supported. |
solver = novaphy.solvers.SolverFeatherstone(model)
solver.settings.num_iterations = 50
solver.settings.linear_slop = 0.001
Joint Support¶
SolverFeatherstone supports reduced-coordinate joints:
| Joint | DOF | Notes |
|---|---|---|
Revolute |
1 | Rotation around an axis. |
Slide (alias Prismatic) |
1 | Translation along an axis. |
Ball |
3 | Spherical joint (3 rotational DOFs, quaternion state). |
Fixed |
0 | Rigid attachment. |
Free |
6 | Floating base (3 translation + quaternion). |
Distance, D6, and Cable are maximal-coordinate constraint types; use
solver.joint_support() to check whether a backend enforces them.
Query solver.joint_support() for the runtime
JointSupportMatrix.
Example¶
import numpy as np
import novaphy
builder = novaphy.ModelBuilder()
builder.add_ground_plane(y=0.0)
# Add a single-link revolute pendulum.
body_idx = builder.add_body(
novaphy.RigidBody.from_box(1.0, np.array([0.1, 0.5, 0.1], dtype=np.float32)),
)
dof = novaphy.JointDofConfig()
dof.axis = np.array([0, 0, 1], dtype=np.float32)
joint_idx = builder.add_joint_revolute(parent=-1, child=body_idx, axis=dof)
builder.add_articulation([joint_idx])
model = builder.finalize()
solver = novaphy.solvers.SolverFeatherstone(
model,
angular_damping=0.05,
update_mass_matrix_interval=1,
)
state = model.state()
control = model.control()
pipeline = novaphy.CollisionPipeline(model)
contacts = pipeline.contacts()
for _ in range(1000):
pipeline.collide(state, contacts)
solver.step(state, state, control, contacts, 1.0 / 120.0)
When To Use¶
| Scenario | Recommendation |
|---|---|
| Robots, manipulators, legged systems | Default articulated backend. |
| Long kinematic chains (ropes, wrecking balls) | Reduced coordinates handle long chains stably. |
| Free bodies only, no joints | Use SolverSemiImplicit. |
| Position-level joint constraints with compliance | Use SolverXPBD. |
Demos¶
| Demo | What it shows |
|---|---|
python/demos/multibody_demo/demo_newtons_cradle_pendulum.py |
Newton's cradle with hinge suspension. |
python/demos/multibody_demo/demo_rope.py |
15-link chain released from horizontal. |
python/demos/multibody_demo/demo_wrecking_ball.py |
Chain pendulum smashing a box tower. |
python/demos/multibody_demo/demo_seesaw.py |
Box dropped onto revolute seesaw. |
python/demos/multibody_demo/demo_motor_arm.py |
Motor-driven arm sweeping boxes (torque-level PD). |
See Also¶
- SolverBase
- SolverFeatherstoneSettings
- Articulated Bodies guide
- Featherstone helper functions: forward_kinematics, forward_dynamics, inverse_dynamics, mass_matrix_crba