# Getting Started
## Installation
Add to your `Cargo.toml`:
```toml
[dependencies]
featherstone = "0.1"
nalgebra = "0.33"
```
## Your First Robot
Every robot in featherstone is an `ArticulatedBody` — a tree of rigid bodies connected by joints.
### Step 1: Create an empty body
```rust
use featherstone::prelude::*;
use nalgebra::{Matrix3, Vector3};
let mut robot = ArticulatedBody::new();
robot.set_gravity(Vector3::new(0.0, -9.81, 0.0));
```
### Step 2: Add links
Each link needs: a name, parent index (-1 for root), joint type, spatial inertia, and the fixed transform from parent to this joint.
```rust
// Link 1: 2 kg, COM at 0.15m from joint, revolute around Z
let inertia1 = SpatialInertia::from_mass_inertia(
2.0, // mass (kg)
Vector3::new(0.15, 0.0, 0.0), // COM offset from joint
Matrix3::from_diagonal(&Vector3::new(0.01, 0.01, 0.01)), // rotational inertia at COM
);
robot.add_body(
"shoulder", // name
-1, // parent (-1 = world/root)
GenJoint::Revolute { axis: Vector3::z() }, // joint type
inertia1, // spatial inertia
SpatialTransform::identity(), // transform from parent to joint
);
// Link 2: 1 kg, attached at end of link 1
let inertia2 = SpatialInertia::from_mass_inertia(
1.0,
Vector3::new(0.1, 0.0, 0.0),
Matrix3::from_diagonal(&Vector3::new(0.005, 0.005, 0.005)),
);
robot.add_body(
"elbow",
0, // parent = body 0 ("shoulder")
GenJoint::Revolute { axis: Vector3::z() },
inertia2,
SpatialTransform::from_translation(Vector3::new(0.3, 0.0, 0.0)), // 0.3m from shoulder
);
```
### Step 3: Set state and compute dynamics
```rust
// Set joint angles (radians)
robot.set_joint_q(0, &[0.5]); // shoulder at 0.5 rad
robot.set_joint_q(1, &[-0.3]); // elbow at -0.3 rad
// Compute forward dynamics: what accelerations does gravity produce?
aba_forward_dynamics(&mut robot);
println!("Joint accelerations: {}", robot.qdd);
// Compute inverse dynamics: what torques hold this pose?
let tau = gravity_compensation(&robot);
println!("Gravity compensation torques: {}", tau);
```
### Step 4: Simulate
```rust
let config = IntegratorConfig {
dt: 0.001, // 1 kHz
method: IntegrationMethod::SemiImplicitEuler,
..Default::default()
};
for _ in 0..10_000 { // 10 seconds
step(&mut robot, &config);
}
println!("Final position: {}", robot.q);
```
## Joint Types
| `Fixed` | 0 | 0 | Rigid connection |
| `Revolute { axis }` | 1 | 1 (angle) | Hinges, motors |
| `Prismatic { axis }` | 1 | 1 (displacement) | Linear actuators |
| `Spherical` | 3 | 4 (quaternion) | Ball joints |
| `Floating` | 6 | 7 (pos + quat) | Free-flying base |
| `Planar { normal }` | 3 | 3 (2 translation + 1 rotation) | Planar motion |
## What's Next
- [Algorithms Guide](algorithms.md) — ABA, RNEA, CRBA explained
- [Contact Dynamics](contacts.md) — ground contacts, LCP solver, smooth contacts
- [Integration Methods](integration.md) — choosing the right integrator
- [URDF Loading](urdf.md) — loading robots from URDF files
- [API Reference](https://docs.rs/featherstone) — full rustdoc