Introduction
oxmpl is a sampling-based motion planning library written in Rust, inspired by the structure and concepts of the Open Motion Planning Library (OMPL).
It is NOT OMPL with Rust bindings.
It provides a flexible and type-safe Rust API for core planning algorithms and offers high-level Python and JavaScript/WASM bindings for rapid prototyping and integration into diverse robotics projects.
Key Features
- Safe & Fast: Built in Rust for memory safety and performance.
- Extensible Architecture: Core concepts like
StateSpace,StateValidityChecker, andPlannerare defined as traits, making the library highly extensible. - Pythonic Bindings: A simple, easy-to-use Python API powered by PyO3 that allows users to define problem-specific logic (like collision checkers) in pure Python.
- JavaScript/WASM Bindings: Run your motion planning logic in the browser or Node.js with high performance.
- Inspired by OMPL: Follows the modular design of OMPL, making it familiar to those in the robotics community.
Rationale
OMPL is great, but it isn’t written in Rust. While that’s not a valid reason to rewrite it, the truth is C++ doesn’t particularly spark joy for many modern developers.
The creator of OxMPL started this project while teaching themselves Rust. After a few small projects, they found that Rust sparked joy. To really dive deep into the language, they decided to rewrite something that already exists: OMPL.
Goals
The goal isn’t necessarily to create a full “drop-in” replacement for OMPL. Rust’s traits and implementations can handle OMPL’s modular nature more elegantly than C++’s inheritance models in some cases.
However, the project aims to:
- Provide a memory-safe and high-performance core in Rust.
- Offer Python and JavaScript bindings so the library can be used by researchers and web developers not keen on diving into Rust.
- Mimic the high-level structure of OMPL to make it familiar and easy to adopt.
Installation
You can use oxmpl in Rust, Python, or JavaScript projects.
Rust
The core library is available on crates.io and can be added to your project’s Cargo.toml:
[dependencies]
oxmpl = "0.4.0" # Replace with the latest version
Python
The library is available on PyPI and can be installed with pip:
pip install oxmpl-py
JavaScript / WASM
JavaScript/WASM bindings are available:
npm install oxmpl-js
Building from Source
If you want to use the latest features or contribute to the project, you can build the libraries from source.
Rust
To build the core Rust library:
# Clone the repository
git clone https://github.com/juniorsundar/oxmpl.git
cd oxmpl
# Build
cargo build --release
Python
To build the Python bindings (oxmpl-py):
Prerequisites
- Python 3.8+
maturin(install viapip install maturin)
Commands
# Build and install in the current environment
maturin develop -m oxmpl-py/Cargo.toml
JavaScript / WASM
If you need to build the JavaScript bindings from source:
Prerequisites
- Node.js (v22 or later recommended)
- Rust toolchain with
wasm32-unknown-unknowntarget wasm-pack(installed automatically vianpm install)
Commands
cd oxmpl-js
# Install dependencies and build WASM module
npm install
# Build only
npm run build
# Create a packaged version
npm run pack
Concepts
OxMPL follows the modular design principles of OMPL. Understanding these core concepts is key to using the library effectively.
State Space (StateSpace)
The StateSpace defines the configuration space of the robot. Common spaces include:
RealVectorStateSpace: For $R^n$ spaces (e.g., 2D or 3D positions).SE2StateSpace/SE3StateSpace: For rigid bodies in 2D or 3D.SO2StateSpace/SO3StateSpace: For rotations.
State (State)
A State represents a single point in the StateSpace. In Rust, these are often specific types like RealVectorState.
State Validity Checker (StateValidityChecker)
This is a user-defined component that determines if a given State is “valid” (e.g., collision-free, within joint limits).
Goal (Goal)
A Goal defines the termination criteria for the planner. It can be a simple state, a region, or a complex condition.
Problem Definition (ProblemDefinition)
This brings together the StateSpace, the start state(s), and the Goal. It defines what problem the planner is trying to solve.
Planner (Planner)
The algorithm used to find a path from the start to the goal. Examples include RRT, RRT*, PRM, and RRTConnect.
Simple 2D Planning: Rust
This is a basic example of solving a 2D planning problem with a custom collision checker and goal region.
use std::{f64::consts::PI, sync::Arc, time::Duration};
use oxmpl::base::{
error::StateSamplingError,
goal::{Goal, GoalRegion, GoalSampleableRegion},
planner::{Planner, PlannerConfig},
problem_definition::ProblemDefinition,
space::{RealVectorStateSpace, StateSpace},
state::RealVectorState,
validity::StateValidityChecker,
};
use oxmpl::geometric::RRT;
use rand::Rng;
/// A StateValidityChecker that defines a simple vertical wall obstacle.
struct WallObstacleChecker {
wall_x_pos: f64,
wall_y_min: f64,
wall_y_max: f64,
wall_thickness: f64,
}
impl StateValidityChecker<RealVectorState> for WallObstacleChecker {
fn is_valid(&self, state: &RealVectorState) -> bool {
let x = state.values[0];
let y = state.values[1];
let is_in_wall = x >= self.wall_x_pos - self.wall_thickness / 2.0
&& x <= self.wall_x_pos + self.wall_thickness / 2.0
&& y >= self.wall_y_min
&& y <= self.wall_y_max;
!is_in_wall
}
}
/// A Goal definition where success is being within a certain radius of a target state.
struct CircularGoalRegion {
target: RealVectorState,
radius: f64,
space: Arc<RealVectorStateSpace>,
}
impl Goal<RealVectorState> for CircularGoalRegion {
fn is_satisfied(&self, state: &RealVectorState) -> bool {
self.space.distance(state, &self.target) <= self.radius
}
}
impl GoalRegion<RealVectorState> for CircularGoalRegion {
fn distance_goal(&self, state: &RealVectorState) -> f64 {
let dist_to_center = self.space.distance(state, &self.target);
(dist_to_center - self.radius).max(0.0)
}
}
impl GoalSampleableRegion<RealVectorState> for CircularGoalRegion {
fn sample_goal(&self, rng: &mut impl Rng) -> Result<RealVectorState, StateSamplingError> {
let angle = rng.random_range(0.0..2.0 * PI);
let radius = self.radius * rng.random::<f64>().sqrt();
let x = self.target.values[0] + radius * angle.cos();
let y = self.target.values[1] + radius * angle.sin();
Ok(RealVectorState { values: vec![x, y] })
}
}
fn main() {
let new_rvss_result = RealVectorStateSpace::new(2, Some(vec![(0.0, 10.0), (0.0, 10.0)]));
let space = Arc::new(new_rvss_result.expect("Error creating new RealVectorState!"));
let start_state = RealVectorState {
values: vec![1.0, 5.0],
};
let goal_definition = Arc::new(CircularGoalRegion {
target: RealVectorState {
values: vec![9.0, 5.0],
},
radius: 0.5,
space: space.clone(),
});
let problem_definition = Arc::new(ProblemDefinition {
space: space.clone(),
start_states: vec![start_state.clone()],
goal: goal_definition.clone(),
});
let validity_checker = Arc::new(WallObstacleChecker {
wall_x_pos: 5.0,
wall_y_min: 2.0,
wall_y_max: 8.0,
wall_thickness: 0.5,
});
let mut planner = RRT::new(0.5, 0.0, &PlannerConfig { seed: Some(123) });
planner.setup(problem_definition, validity_checker.clone());
let timeout = Duration::from_secs(5);
let result = planner.solve(timeout);
let path = result.expect("Planner failed to find a solution");
println!("Found path with {} states.", path.0.len());
}
Simple 2D Planning: Python
This is a basic example of solving a 2D planning problem with a custom collision checker written in Python.
import math
from oxmpl_py.base import RealVectorState, RealVectorStateSpace, ProblemDefinition, PlannerConfig
from oxmpl_py.geometric import RRT
def is_state_valid(state: RealVectorState) -> bool:
"""A state is invalid if it's inside a circular obstacle at the origin."""
x, y = state.values
return math.sqrt(x**2 + y**2) > 2.0
class MyCircularGoal:
def __init__(self, space, x, y, radius):
self.space = space
self.target = RealVectorState([x, y])
self.radius = radius
def is_satisfied(self, state: RealVectorState) -> bool:
return self.space.distance(self.target, state) <= self.radius
def sample_goal(self) -> RealVectorState:
return self.target
space = RealVectorStateSpace(dimension=2, bounds=[(-10.0, 10.0), (-10.0, 10.0)])
start_state = RealVectorState([-5.0, -5.0])
goal_region = MyCircularGoal(space, x=5.0, y=5.0, radius=0.5)
problem_def = ProblemDefinition.from_real_vector(space, start_state, goal_region)
planner_config = PlannerConfig(seed=123)
planner = RRT(max_distance=0.5,
goal_bias=0.05,
problem_definition=problem_def,
planner_config=planner_config)
planner.setup(is_state_valid)
try:
path = planner.solve(timeout_secs=5.0)
print(f"Solution found with {len(path.states)} states!")
except Exception as e:
print(f"Planning failed: {e}")
Simple 2D Planning: JavaScript
This is a basic example of solving a 2D planning problem with a custom collision checker written in JavaScript.
import oxmpl from 'oxmpl-js';
// A state is invalid if it's inside a circular obstacle at the origin
function isStateValid(state) {
const [x, y] = state.values;
return Math.sqrt(x * x + y * y) > 2.0;
}
// Create a 2D state space with bounds
const space = new oxmpl.base.RealVectorStateSpace(2, [-10.0, 10.0, -10.0, 10.0]);
// Define start state
const start = new oxmpl.base.RealVectorState([-5.0, -5.0]);
// Define circular goal region
const target = [5.0, 5.0];
const radius = 0.5;
const goal = new oxmpl.base.Goal({
isSatisfied: (state) => {
const [x, y] = state.values;
const dist = Math.sqrt((x - target[0]) ** 2 + (y - target[1]) ** 2);
return dist <= radius;
},
distanceGoal: (state) => {
const [x, y] = state.values;
const dist = Math.sqrt((x - target[0]) ** 2 + (y - target[1]) ** 2);
return Math.max(0, dist - radius);
},
sampleGoal: () => new oxmpl.base.RealVectorState(target),
});
// Create problem and run planner
const problem = oxmpl.base.ProblemDefinition.fromRealVectorState(space, start, goal);
const validityChecker = new oxmpl.base.StateValidityChecker(isStateValid);
const plannerConfig = new oxmpl.base.PlannerConfig(123);
const planner = new oxmpl.geometric.RRT(0.5, 0.05, problem, plannerConfig);
planner.setup(validityChecker);
try {
const path = planner.solve(5.0);
if (path && path.getLength() > 0) {
console.log(`Solution found with ${path.getLength()} states!`);
} else {
console.log('No solution found');
}
} catch (e) {
console.log(`Planning failed: ${e}`);
}
Compound State Planning: Rust
This example demonstrates how to use CompoundStateSpace to combine multiple state spaces (in this case, RealVectorStateSpace for position and SO2StateSpace for orientation) into a single planning problem.
use std::{f64::consts::PI, sync::Arc, time::Duration};
use oxmpl::base::{
error::StateSamplingError,
goal::{Goal, GoalRegion, GoalSampleableRegion},
planner::{Planner, PlannerConfig},
problem_definition::ProblemDefinition,
space::{CompoundStateSpace, RealVectorStateSpace, SO2StateSpace, StateSpace},
state::{CompoundState, RealVectorState, SO2State},
validity::StateValidityChecker,
};
use oxmpl::geometric::RRT;
use rand::Rng;
/// A StateValidityChecker that checks for collision with a box obstacle.
/// The robot is considered a point with orientation, but we check if the point
/// is inside the box.
struct BoxObstacleChecker {
x_min: f64,
x_max: f64,
y_min: f64,
y_max: f64,
}
impl StateValidityChecker<CompoundState> for BoxObstacleChecker {
fn is_valid(&self, state: &CompoundState) -> bool {
// Extract the RealVector component (index 0)
if let Some(rv_state) = state.components[0]
.as_any()
.downcast_ref::<RealVectorState>()
{
let x = rv_state.values[0];
let y = rv_state.values[1];
// Check if inside the box
let inside_box =
x >= self.x_min && x <= self.x_max && y >= self.y_min && y <= self.y_max;
!inside_box
} else {
// Should not happen if constructed correctly
false
}
}
}
/// A Goal definition for a CompoundState (Position + Orientation).
/// Success is being within a radius of the target position.
struct CompoundGoalRegion {
target: CompoundState,
radius: f64,
space: Arc<CompoundStateSpace>,
}
impl Goal<CompoundState> for CompoundGoalRegion {
fn is_satisfied(&self, state: &CompoundState) -> bool {
self.space.distance(state, &self.target) <= self.radius
}
}
impl GoalRegion<CompoundState> for CompoundGoalRegion {
fn distance_goal(&self, state: &CompoundState) -> f64 {
let dist = self.space.distance(state, &self.target);
(dist - self.radius).max(0.0)
}
}
impl GoalSampleableRegion<CompoundState> for CompoundGoalRegion {
fn sample_goal(&self, rng: &mut impl Rng) -> Result<CompoundState, StateSamplingError> {
// Get target components
let target_rv = self.target.components[0]
.as_any()
.downcast_ref::<RealVectorState>()
.unwrap();
// Sample a position around the target within radius
let angle = rng.random_range(0.0..2.0 * PI);
let radius = self.radius * rng.random::<f64>().sqrt();
let x = target_rv.values[0] + radius * angle.cos();
let y = target_rv.values[1] + radius * angle.sin();
// Sample a random orientation for the goal (or keep it fixed if desired)
// Here we sample a random orientation effectively ignoring orientation for the goal region
let theta = rng.random_range(0.0..2.0 * PI);
Ok(CompoundState {
components: vec![
Box::new(RealVectorState { values: vec![x, y] }),
Box::new(SO2State::new(theta)),
],
})
}
}
#[allow(clippy::arc_with_non_send_sync)]
fn main() {
// 1. Define the state space: R^2 x SO(2)
// R^2 for position (x, y)
let r2 = RealVectorStateSpace::new(2, Some(vec![(-5.0, 5.0), (-5.0, 5.0)]))
.expect("Failed to create R2 space");
// SO(2) for orientation (theta)
let so2 = SO2StateSpace::new(None).expect("Failed to create SO2 space");
// Combine them into a CompoundStateSpace
// Weights: 1.0 for position, 0.5 for orientation (orientation matters less for distance)
let space = Arc::new(CompoundStateSpace::new(
vec![Box::new(r2), Box::new(so2)],
vec![1.0, 0.5],
));
// 2. Define Start and Goal states
let start_state = CompoundState {
components: vec![
Box::new(RealVectorState::new(vec![-2.0, 0.0])),
Box::new(SO2State::new(0.0)),
],
};
let target_state = CompoundState {
components: vec![
Box::new(RealVectorState::new(vec![2.0, 0.0])),
Box::new(SO2State::new(PI)),
],
};
// 3. Define Goal Region
let goal_definition = Arc::new(CompoundGoalRegion {
target: target_state.clone(),
radius: 0.5,
space: space.clone(),
});
// 4. Define Problem
let problem_definition = Arc::new(ProblemDefinition {
space: space.clone(),
start_states: vec![start_state.clone()],
goal: goal_definition.clone(),
});
// 5. Define Validity Checker (Box Obstacle)
let validity_checker = Arc::new(BoxObstacleChecker {
x_min: -0.5,
x_max: 0.5,
y_min: -2.0,
y_max: 2.0,
});
// 6. Setup Planner (RRT)
let mut planner = RRT::new(0.5, 0.1, &PlannerConfig { seed: Some(123) });
planner.setup(problem_definition, validity_checker.clone());
// 7. Solve
println!("Solving Compound State planning problem...");
let timeout = Duration::from_secs(5);
match planner.solve(timeout) {
Ok(path) => {
println!("Solution found with {} states.", path.0.len());
// Print first and last state to verify
if let Some(first) = path.0.first() {
let rv = first.components[0]
.as_any()
.downcast_ref::<RealVectorState>()
.unwrap();
let so2 = first.components[1]
.as_any()
.downcast_ref::<SO2State>()
.unwrap();
println!(
"Start: ({:.2}, {:.2}, {:.2})",
rv.values[0], rv.values[1], so2.value
);
}
if let Some(last) = path.0.last() {
let rv = last.components[0]
.as_any()
.downcast_ref::<RealVectorState>()
.unwrap();
let so2 = last.components[1]
.as_any()
.downcast_ref::<SO2State>()
.unwrap();
println!(
"End: ({:.2}, {:.2}, {:.2})",
rv.values[0], rv.values[1], so2.value
);
}
}
Err(e) => println!("Planner failed: {:?}", e),
}
}
Compound State Planning: Python
This example demonstrates how to use CompoundStateSpace in Python to plan for a system with both position and orientation.
import math
import random
from oxmpl_py.base import (
CompoundState,
CompoundStateSpace,
RealVectorStateSpace,
SO2StateSpace,
ProblemDefinition,
RealVectorState,
SO2State,
PlannerConfig,
)
from oxmpl_py.geometric import RRT
class CompoundCircularGoal:
def __init__(self, space: CompoundStateSpace, x: float, y: float, radius: float):
self.space = space
# Target: Position (x,y) and Orientation 0.0 (though orientation is ignored for goal satisfaction here)
self.target = CompoundState([RealVectorState([x, y]), SO2State(0.0)])
self.radius = radius
self.rng = random.Random(123)
def is_satisfied(self, state: CompoundState) -> bool:
return self.space.distance(self.target, state) <= self.radius
def sample_goal(self) -> CompoundState:
angle = self.rng.uniform(0, 2 * math.pi)
radius = self.radius * math.sqrt(self.rng.uniform(0, 1))
x = self.target.components[0].values[0] + radius * math.cos(angle)
y = self.target.components[0].values[1] + radius * math.sin(angle)
# Random orientation for the goal sample
so2_value = self.rng.uniform(0, 2 * math.pi)
return CompoundState([RealVectorState([x, y]), SO2State(so2_value)])
def is_state_valid(state: CompoundState) -> bool:
"""
Checks if the state is valid.
Invalid if the position is inside a box obstacle centered at (0, 0)
with width 1.0 and height 4.0.
"""
rv_state = state.components[0]
x, y = rv_state.values
# Obstacle definition
x_min, x_max = -0.5, 0.5
y_min, y_max = -2.0, 2.0
is_in_wall = (
x >= x_min and x <= x_max and
y >= y_min and y <= y_max
)
return not is_in_wall
def main():
# 1. Define State Space: R^2 x SO(2)
rv_space = RealVectorStateSpace(dimension=2, bounds=[(-5.0, 5.0), (-5.0, 5.0)])
so2_space = SO2StateSpace()
# Combined space with weights
space = CompoundStateSpace([rv_space, so2_space], weights=[1.0, 0.5])
# 2. Define Start and Goal
start_state = CompoundState([RealVectorState([-2.0, 0.0]), SO2State(0.0)])
# Goal region around (2.0, 0.0) with radius 0.5
goal_region = CompoundCircularGoal(space, x=2.0, y=0.0, radius=0.5)
# 3. Create Problem Definition
problem_def = ProblemDefinition.from_compound(space, start_state, goal_region)
planner_config = PlannerConfig(seed=123)
# 4. Setup Planner (RRT)
planner = RRT(
max_distance=0.5,
goal_bias=0.1,
problem_definition=problem_def,
planner_config=planner_config,
)
planner.setup(is_state_valid)
# 5. Solve
print("Solving Compound State planning problem (Python)...")
try:
path = planner.solve(timeout_secs=5.0)
print(f"Solution found with {len(path.states)} states.")
if len(path.states) > 0:
start = path.states[0]
end = path.states[-1]
s_rv = start.components[0].values
s_so2 = start.components[1].value
e_rv = end.components[0].values
e_so2 = end.components[1].value
print(f"Start: ({s_rv[0]:.2f}, {s_rv[1]:.2f}, {s_so2:.2f})")
print(f"End: ({e_rv[0]:.2f}, {e_rv[1]:.2f}, {e_so2:.2f})")
except Exception as e:
print(f"Planning failed: {e}")
if __name__ == "__main__":
main()
Compound State Planning: JavaScript
This example demonstrates how to use CompoundStateSpace and CompoundStateBuilder in JavaScript/WASM to solve a planning problem in a composite state space.
import oxmpl from 'oxmpl-js';
// Define the validity checker
// State is invalid if the position (x, y) is inside a box obstacle
function isStateValid(state) {
try {
const rvPart = state.getComponent(0);
const [x, y] = rvPart.values;
// Box obstacle
const x_min = -0.5,
x_max = 0.5;
const y_min = -2.0,
y_max = 2.0;
const insideBox = x >= x_min && x <= x_max && y >= y_min && y <= y_max;
return !insideBox;
} catch (e) {
console.error('Validity check error:', e);
return false;
}
}
// 1. Create State Space
const r2 = new oxmpl.base.RealVectorStateSpace(2, [-5.0, 5.0, -5.0, 5.0]);
const so2 = new oxmpl.base.SO2StateSpace();
const spaceBuilder = new oxmpl.base.CompoundStateSpaceBuilder();
spaceBuilder.addRealVectorStateSpace(r2, 1.0);
spaceBuilder.addSO2StateSpace(so2, 0.5);
const space = spaceBuilder.build();
// 2. Define Start State
const startBuilder = new oxmpl.base.CompoundStateBuilder();
startBuilder.addRealVectorState(new oxmpl.base.RealVectorState([-2.0, 0.0]));
startBuilder.addSO2State(new oxmpl.base.SO2State(0.0));
const startState = startBuilder.build();
// 3. Define Goal Region
const targetBuilder = new oxmpl.base.CompoundStateBuilder();
targetBuilder.addRealVectorState(new oxmpl.base.RealVectorState([2.0, 0.0]));
targetBuilder.addSO2State(new oxmpl.base.SO2State(Math.PI));
const targetState = targetBuilder.build();
const radius = 0.5;
const goal = new oxmpl.base.Goal({
isSatisfied: (state) => {
return space.distance(state, targetState) <= radius;
},
distanceGoal: (state) => {
const dist = space.distance(state, targetState);
return Math.max(0, dist - radius);
},
sampleGoal: () => {
// Sample a random point within radius of the target position
// For simplicity in this example, we sample a random angle and distance
// But we need to construct a proper CompoundState
const tRV = targetState.getComponent(0);
const [tx, ty] = tRV.values;
const angle = Math.random() * 2 * Math.PI;
const r = radius * Math.sqrt(Math.random());
const x = tx + r * Math.cos(angle);
const y = ty + r * Math.sin(angle);
// Random orientation for goal
const theta = Math.random() * 2 * Math.PI;
const builder = new oxmpl.base.CompoundStateBuilder();
builder.addRealVectorState(new oxmpl.base.RealVectorState([x, y]));
builder.addSO2State(new oxmpl.base.SO2State(theta));
return builder.build();
},
});
// 4. Create Problem
const problem = oxmpl.base.ProblemDefinition.fromCompoundState(space, startState, goal);
const validityChecker = new oxmpl.base.StateValidityChecker(isStateValid);
const plannerConfig = new oxmpl.base.PlannerConfig(123);
// 5. Setup Planner
const planner = new oxmpl.geometric.RRT(0.5, 0.1, problem, plannerConfig);
planner.setup(validityChecker);
// 6. Solve
console.log('Solving Compound State planning problem (JS)...');
try {
const path = planner.solve(5.0);
if (path && path.getLength() > 0) {
const states = path.getStates();
console.log(`Solution found with ${states.length} states!`);
if (states.length > 0) {
const start = states[0];
const end = states[states.length - 1];
const sRV = start.getComponent(0);
const sSO2 = start.getComponent(1);
const eRV = end.getComponent(0);
const eSO2 = end.getComponent(1);
console.log(
`Start: (${sRV.values[0].toFixed(2)}, ${sRV.values[1].toFixed(2)}, ${sSO2.value.toFixed(2)})`
);
console.log(
`End: (${eRV.values[0].toFixed(2)}, ${eRV.values[1].toFixed(2)}, ${eSO2.value.toFixed(2)})`
);
}
} else {
console.log('No solution found');
}
} catch (e) {
console.log(`Planning failed: ${e}`);
}
State Validity Checkers
The StateValidityChecker is a crucial component in any motion planning problem. It defines all the valide configurations the robot is allowed to be. Its primary job is to take a state and return true if it is valid (collision-free, within constraints) or false otherwise.
The Interface
A validity checker is essentially a function or closure with the signature:
fn(state) -> bool
Since planners call this function thousands of times, it must be efficient.
Implementations
Rust
In Rust, you implement the StateValidityChecker trait for your specific state type.
#![allow(unused)]
fn main() {
use oxmpl::base::{validity::StateValidityChecker, state::RealVectorState};
struct MyObstacleChecker {
// Store efficient data structures here
obstacles: Vec<(f64, f64, f64)>, // x, y, radius
}
impl StateValidityChecker<RealVectorState> for MyObstacleChecker {
fn is_valid(&self, state: &RealVectorState) -> bool {
let x = state.values[0];
let y = state.values[1];
for (ox, oy, r) in &self.obstacles {
let dist_sq = (x - ox).powi(2) + (y - oy).powi(2);
if dist_sq < r.powi(2) {
return false; // Collision!
}
}
true
}
}
}
Python
In Python, you simply provide a callable (function or lambda) that accepts a state and returns a boolean.
from oxmpl_py.base import RealVectorState
def is_state_valid(state: RealVectorState) -> bool:
x, y = state.values
# Check bounds (optional if StateSpace already handles it, but good practice)
if not (-10 < x < 10 and -10 < y < 10):
return False
# Check circular obstacle at (0,0) with radius 2
if x*x + y*y < 4.0:
return False
return True
# Pass this function to the planner setup
planner.setup(is_state_valid)
JavaScript
In JavaScript, you pass a callback function to the StateValidityChecker constructor.
const validityChecker = new oxmpl.base.StateValidityChecker((state) => {
// Assuming RealVectorState
const [x, y] = state.values;
// Check circular obstacle
if (x*x + y*y < 4.0) {
return false;
}
return true;
});
planner.setup(validityChecker);
Best Practices
- Fail Fast: Check the most likely collisions first. If you have a bounding box for your robot, check that against the environment bounds before doing complex mesh collision detection.
- Broad-Phase vs. Narrow-Phase: Use simple geometric shapes (spheres, boxes) to approximate obstacles for a quick check. Only perform expensive checks (detailed mesh intersection) if the broad-phase check passes.
- Thread Safety: The
StateValidityCheckertrait enforcesSend + Sync. This is in anticipation of a future where multithreading will be implemented.
Goal Definitions
The Goal component defines the termination condition for the planner. It tells the planner when it has successfully found a valid configuration.
Core Concepts
A Goal generally consists of three parts (though some are optional depending on the planner):
is_satisfied(state) -> bool: Returnstrueif the state is in the goal region.distance_goal(state) -> float: Heuristic distance to the goal. Used by some planners to bias sampling towards the goal.sample_goal() -> State: Returns a random state within the goal region. Required by bi-directional planners (likeRRTConnect) to grow trees from the goal.
Implementations
Rust
OxMPL provides traits for different levels of goal capability: Goal, GoalRegion, and GoalSampleableRegion.
#![allow(unused)]
fn main() {
use oxmpl::base::{
goal::{Goal, GoalRegion, GoalSampleableRegion},
state::RealVectorState,
space::RealVectorStateSpace,
error::StateSamplingError
};
use std::sync::Arc;
use rand::Rng;
struct MyGoal {
target: RealVectorState,
threshold: f64,
space: Arc<RealVectorStateSpace>,
}
// Basic Goal: Just checks satisfaction
impl Goal<RealVectorState> for MyGoal {
fn is_satisfied(&self, state: &RealVectorState) -> bool {
self.space.distance(state, &self.target) <= self.threshold
}
}
// GoalRegion: Provides distance heuristic
impl GoalRegion<RealVectorState> for MyGoal {
fn distance_goal(&self, state: &RealVectorState) -> f64 {
let dist = self.space.distance(state, &self.target);
(dist - self.threshold).max(0.0)
}
}
// GoalSampleableRegion: Allows sampling (Required for RRTConnect)
impl GoalSampleableRegion<RealVectorState> for MyGoal {
fn sample_goal(&self, _rng: &mut impl Rng) -> Result<RealVectorState, StateSamplingError> {
// Simple implementation: just return the target
// A better implementation would sample around the target
Ok(self.target.clone())
}
}
}
Python
In Python, you define a class that implements the required methods.
import random
from oxmpl_py.base import RealVectorStateSpace, RealVectorState
class MyGoal:
def __init__(self, space, target_x, target_y, radius):
self.space = space
self.target = RealVectorState([target_x, target_y])
self.radius = radius
def is_satisfied(self, state: RealVectorState) -> bool:
return self.space.distance(state, self.target) <= self.radius
def distance_goal(self, state: RealVectorState) -> float:
dist = self.space.distance(state, self.target)
return max(0.0, dist - self.radius)
def sample_goal(self) -> RealVectorState:
# Sample a random point within the goal circle
angle = random.uniform(0, 6.28)
r = self.radius * random.uniform(0, 1)**0.5
x = self.target.values[0] + r * math.cos(angle)
y = self.target.values[1] + r * math.sin(angle)
return RealVectorState([x, y])
# Usage
goal = MyGoal(space, 5.0, 5.0, 0.5)
problem = ProblemDefinition.from_real_vector(space, start, goal)
JavaScript
In JavaScript, you pass an object (or class instance) with the required function properties.
const goal = new oxmpl.base.Goal({
isSatisfied: (state) => {
return space.distance(state, targetState) <= radius;
},
distanceGoal: (state) => {
const dist = space.distance(state, targetState);
return Math.max(0, dist - radius);
},
sampleGoal: () => {
// Return a new State object inside the goal region
return new oxmpl.base.RealVectorState([5.0, 5.0]);
}
});
Types of Goals
- Fixed State Goal: The goal is a single specific configuration.
- Goal Region: The goal is a set of states.
- Threshold Goal: The goal is defined by a condition.
Python API Reference
The oxmpl-py package provides Python bindings for the core OxMPL functionality.
oxmpl_py.base
This module contains the fundamental components for defining a motion planning problem.
States
These classes represent a single point or configuration in a state space.
RealVectorState
A state in an N-dimensional Euclidean space ($R^n$).
__init__(values: List[float])values: List[float](read-only)
SO2State
A state representing a 2D rotation ($[-\pi, \pi)$).
__init__(value: float)value: float(read-only)
SO3State
A state representing a 3D rotation (Quaternion).
__init__(x: float, y: float, z: float, w: float)identity() -> SO3State(static)x: float,y: float,z: float,w: float(read-only)
SE2State
A state representing a 2D rigid body transformation ($x, y, yaw$). It is a composition of RealVectorState (for translation) and SO2State (for rotation).
__init__(x: float, y: float, yaw: float)x: float,y: float,yaw: float(read-only)translation: RealVectorState(read-only)rotation: SO2State(read-only)
SE3State
A state representing a 3D rigid body transformation ($x, y, z, rotation$). It is a composition of RealVectorState and SO3State.
__init__(x: float, y: float, z: float, rotation: SO3State)x: float,y: float,z: float(read-only)translation: RealVectorState(read-only)rotation: SO3State(read-only)
CompoundState
A state composed of one or more other state objects.
__init__(components: List[State])components: List[State](read-only)__len__() -> int: Returns the number of component states.
State Spaces
These classes define the planning space, including its dimensions, boundaries, and distance metrics.
RealVectorStateSpace
Defines an N-dimensional space for RealVectorState instances.
__init__(dimension: int, bounds: Optional[List[Tuple[float, float]]] = None)distance(s1: RealVectorState, s2: RealVectorState) -> floatget_maximum_extent() -> floatset_longest_valid_segment_fraction(fraction: float)
SO2StateSpace
Defines a space for SO2State instances.
__init__(bounds: Optional[Tuple[float, float]] = None)distance(s1: SO2State, s2: SO2State) -> floatget_maximum_extent() -> floatset_longest_valid_segment_fraction(fraction: float)
SO3StateSpace
Defines a space for SO3State instances.
__init__(bounds: Optional[Tuple[SO3State, float]] = None)bounds: A tuple containing a center rotation and the max angle from that center.
distance(s1: SO3State, s2: SO3State) -> floatget_maximum_extent() -> floatset_longest_valid_segment_fraction(fraction: float)
SE2StateSpace
Defines the state space for 2D rigid body motion (SE(2)).
__init__(weight: float, bounds: Optional[List[Tuple[float, float]]] = None)bounds: min/max for x and y.
distance(state1: SE2State, state2: SE2State) -> float
SE3StateSpace
Defines the state space for 3D rigid body motion (SE(3)).
__init__(weight: float, bounds: Optional[List[Tuple[float, float]]] = None)bounds: min/max for x, y, and z.
distance(state1: SE3State, state2: SE3State) -> float
CompoundStateSpace
Defines a space composed of multiple, weighted subspaces.
__init__(subspaces: List[StateSpace], weights: List[float])distance(state1: CompoundState, state2: CompoundState) -> float
Planning Components
Goal
A user-defined Python class that specifies the goal condition for the planner. It must implement the following methods:
is_satisfied(state: State) -> bool: Returns true if the state satisfies the goal.distance_goal(state: State) -> float: The distance from a state to the goal region.sample_goal() -> State: Returns a state sampled from the goal region.
ProblemDefinition
Encapsulates all components of a motion planning problem.
from_real_vector(space: RealVectorStateSpace, start: RealVectorState, goal: Goal) -> ProblemDefinition(classmethod)from_so2(space: SO2StateSpace, start: SO2State, goal: Goal) -> ProblemDefinition(classmethod)from_so3(space: SO3StateSpace, start: SO3State, goal: Goal) -> ProblemDefinition(classmethod)from_se2(space: SE2StateSpace, start: SE2State, goal: Goal) -> ProblemDefinition(classmethod)from_se3(space: SE3StateSpace, start: SE3State, goal: Goal) -> ProblemDefinition(classmethod)from_compound(space: CompoundStateSpace, start: CompoundState, goal: Goal) -> ProblemDefinition(classmethod)
PlannerConfig
General configuration for planners.
__init__(seed: Optional[int] = None)seed: Optional[int](read-only)
Path
A sequence of states representing a solution path.
from_..._states(...): Static methods to create a Path from a list of specific state types.states: List[State](read-only): Returns the list of states in the path.__len__() -> int
oxmpl_py.geometric
This module contains the geometric planner implementations.
RRT
Rapidly-exploring Random Tree.
__init__(max_distance: float, goal_bias: float, problem_definition: ProblemDefinition, planner_config: PlannerConfig)setup(validity_checker: Callable[[State], bool])solve(timeout_secs: float) -> Path
RRTConnect
Bi-directional RRT algorithm.
__init__(max_distance: float, goal_bias: float, problem_definition: ProblemDefinition, planner_config: PlannerConfig)setup(validity_checker: Callable[[State], bool])solve(timeout_secs: float) -> Path
RRTStar
RRT* (Optimal RRT) algorithm.
__init__(max_distance: float, goal_bias: float, search_radius: float, problem_definition: ProblemDefinition, planner_config: PlannerConfig)setup(validity_checker: Callable[[State], bool])solve(timeout_secs: float) -> Path
PRM
Probabilistic RoadMap.
__init__(timeout: float, connection_radius: float, problem_definition: ProblemDefinition, planner_config: PlannerConfig)timeout: Time in seconds to spend building the roadmap.
setup(validity_checker: Callable[[State], bool])construct_roadmap()solve(timeout_secs: float) -> Path
JavaScript API Reference
The oxmpl-js package provides WASM-based bindings for JavaScript environments.
oxmpl.base
This module contains the fundamental components for defining a motion planning problem.
States
These classes represent a single point or configuration in a state space.
RealVectorState
A state in an N-dimensional Euclidean space ($R^n$).
constructor(values: number[])values: number[](read-only)
SO2State
A state representing a 2D rotation ($[-\pi, \pi)$).
constructor(value: number)value: number(read-only)normalise(): SO2State
SO3State
A state representing a 3D rotation (Quaternion).
constructor(x: number, y: number, z: number, w: number)identity(): SO3State(static)x: number,y: number,z: number,w: number(read-only)normalise(): SO3State
SE2State
A state representing a 2D rigid body transformation ($x, y, yaw$).
constructor(x: number, y: number, yaw: number)x: number,y: number,yaw: number(read-only)translation: RealVectorState(read-only)rotation: SO2State(read-only)
SE3State
A state representing a 3D rigid body transformation ($x, y, z, rotation$).
constructor(x: number, y: number, z: number, rotation: SO3State)x: number,y: number,z: number(read-only)translation: RealVectorState(read-only)rotation: SO3State(read-only)
CompoundState
A state composed of one or more other state objects.
componentCount: number(read-only)getComponent(index: number): State
CompoundStateBuilder
A helper class to construct CompoundState instances.
constructor()addRealVectorState(state: RealVectorState)addSO2State(state: SO2State)addSO3State(state: SO3State)addSE2State(state: SE2State)addSE3State(state: SE3State)addCompoundState(state: CompoundState)build(): CompoundState
State Spaces
These classes define the planning space, including its dimensions, boundaries, and distance metrics.
RealVectorStateSpace
Defines an N-dimensional space for RealVectorState instances.
constructor(dimension: number, bounds: number[] | undefined)bounds: A flat array[min1, max1, min2, max2, ...].
sample(): RealVectorStatedistance(state1: RealVectorState, state2: RealVectorState): numbersatisfiesBounds(state: RealVectorState): booleanenforceBounds(state: RealVectorState): RealVectorStateinterpolate(from: RealVectorState, to: RealVectorState, t: number): RealVectorStategetDimension(): numbergetMaximumExtent(): numbergetLongestValidSegmentLength(): numbersetLongestValidLineSegmentFraction(fraction: number)
SO2StateSpace
Defines a space for SO2State instances.
constructor(bounds: number[] | undefined)bounds:[min, max].
sample(): SO2Statedistance(state1: SO2State, state2: SO2State): numbersatisfiesBounds(state: SO2State): booleanenforceBounds(state: SO2State): SO2Stateinterpolate(from: SO2State, to: SO2State, t: number): SO2StategetMaximumExtent(): numbergetLongestValidSegmentLength(): numbersetLongestValidLineSegmentFraction(fraction: number)
SO3StateSpace
Defines a space for SO3State instances.
constructor(center: SO3State | undefined, maxAngle: number | undefined)sample(): SO3Statedistance(state1: SO3State, state2: SO3State): numbersatisfiesBounds(state: SO3State): booleanenforceBounds(state: SO3State): SO3Stateinterpolate(from: SO3State, to: SO3State, t: number): SO3StategetMaximumExtent(): numbergetLongestValidSegmentLength(): numbersetLongestValidLineSegmentFraction(fraction: number)
SE2StateSpace
Defines the state space for 2D rigid body motion (SE(2)).
constructor(weight: number, bounds: number[] | undefined)bounds:[x_min, x_max, y_min, y_max, yaw_min, yaw_max].
sample(): SE2Statedistance(state1: SE2State, state2: SE2State): numbersatisfiesBounds(state: SE2State): booleanenforceBounds(state: SE2State): SE2Stateinterpolate(from: SE2State, to: SE2State, t: number): SE2StategetLongestValidSegmentLength(): number
SE3StateSpace
Defines the state space for 3D rigid body motion (SE(3)).
constructor(weight: number, bounds: number[] | undefined)bounds:[x_min, x_max, y_min, y_max, z_min, z_max].
sample(): SE3Statedistance(state1: SE3State, state2: SE3State): numbersatisfiesBounds(state: SE3State): booleanenforceBounds(state: SE3State): SE3Stateinterpolate(from: SE3State, to: SE3State, t: number): SE3StategetLongestValidSegmentLength(): number
CompoundStateSpace
Defines a space composed of multiple, weighted subspaces.
sample(): CompoundStatedistance(state1: CompoundState, state2: CompoundState): numbersatisfiesBounds(state: CompoundState): booleanenforceBounds(state: CompoundState): CompoundStateinterpolate(from: CompoundState, to: CompoundState, t: number): CompoundStategetLongestValidSegmentLength(): number
CompoundStateSpaceBuilder
A helper class to construct CompoundStateSpace instances.
constructor()addRealVectorStateSpace(space: RealVectorStateSpace, weight: number)addSO2StateSpace(space: SO2StateSpace, weight: number)addSO3StateSpace(space: SO3StateSpace, weight: number)addSE2StateSpace(space: SE2StateSpace, weight: number)addSE3StateSpace(space: SE3StateSpace, weight: number)addCompoundStateSpace(space: CompoundStateSpace, weight: number)build(): CompoundStateSpace
Planning Components
Goal
An interface that user-provided objects must satisfy to define the goal.
constructor(config: { isSatisfied: Function, distanceGoal: Function, sampleGoal: Function })isSatisfied(state: State): booleandistanceGoal(state: State): numbersampleGoal(): State
ProblemDefinition
Encapsulates all components of a motion planning problem.
fromRealVectorState(space: RealVectorStateSpace, start: RealVectorState, goal: Goal): ProblemDefinition(static)fromSO2State(space: SO2StateSpace, start: SO2State, goal: Goal): ProblemDefinition(static)fromSO3State(space: SO3StateSpace, start: SO3State, goal: Goal): ProblemDefinition(static)fromSE2State(space: SE2StateSpace, start: SE2State, goal: Goal): ProblemDefinition(static)fromSE3State(space: SE3StateSpace, start: SE3State, goal: Goal): ProblemDefinition(static)fromCompoundState(space: CompoundStateSpace, start: CompoundState, goal: Goal): ProblemDefinition(static)
StateValidityChecker
Wrapper for a user-defined function that checks if a state is valid (collision-free).
constructor(callback: (state: State) => boolean)
PlannerConfig
General configuration for planners.
constructor(seed: number | undefined)
Path
A sequence of states representing a solution path.
getStates(): State[]getLength(): number
oxmpl.geometric
RRT
Rapidly-exploring Random Tree.
constructor(maxDistance: number, goalBias: number, problem: ProblemDefinition, config: PlannerConfig)setup(validityChecker: StateValidityChecker)solve(timeout: number): Path
RRTConnect
Bi-directional RRT algorithm.
constructor(maxDistance: number, goalBias: number, problem: ProblemDefinition, config: PlannerConfig)setup(validityChecker: StateValidityChecker)solve(timeout: number): Path
RRTStar
RRT* (Optimal RRT) algorithm.
constructor(maxDistance: number, goalBias: number, searchRadius: number, problem: ProblemDefinition, config: PlannerConfig)setup(validityChecker: StateValidityChecker)solve(timeout: number): Path
PRM
Probabilistic RoadMap.
constructor(timeout: number, connectionRadius: number, problem: ProblemDefinition, config: PlannerConfig)timeout: Time in seconds to spend building the roadmap.
setup(validityChecker: StateValidityChecker)constructRoadmap()solve(timeout: number): Path
Contributing
Thank you for your interest in contributing to OxMPL!
This section provides guides on how to extend the library with new functionality, specifically focusing on adding new planners and state spaces, and ensuring they are available in the Python and JavaScript bindings.
Implementing New Planners
This guide outlines the steps to add a new planning algorithm to OxMPL and expose it to the Python and JavaScript bindings.
Rust Implementation (oxmpl)
- Create the Planner Struct: Define your planner struct in
oxmpl/src/geometric/planners/<your_planner>.rs. - Implement
PlannerTrait: Implement theoxmpl::base::planner::Plannertrait for your struct.setup: Initialize the planner with the problem definition.solve: The core logic to find a path.get_planner_data: Return internal data (like the graph) for visualization/debugging.
- Export: Add your planner to
oxmpl/src/geometric/planners/mod.rsand re-export it inoxmpl/src/geometric/mod.rs.
// oxmpl/src/geometric/planners/my_planner.rs
use crate::base::planner::Planner;
pub struct MyPlanner<State, Space, Goal> {
// ... fields
}
impl<State, Space, Goal> Planner<State, Space, Goal> for MyPlanner<State, Space, Goal>
where
// ... constraints
{
// ... implementation
}
Python Bindings (oxmpl-py)
To make your planner available in Python, you need to wrap the Rust struct using PyO3.
- Create Wrapper File: Create
oxmpl-py/src/geometric/<my_planner>.rs. - Define Type Aliases: Since PyO3 classes cannot be generic, define type aliases for your planner specialized for each supported state space (e.g.,
MyPlannerForRealVector,MyPlannerForSO2, etc.). - Define the PyO3 Class: Create a struct (e.g.,
PyMyPlanner) decorated with#[pyclass].- It should hold an enum
PlannerVariantthat wraps the specialized Rust planner instances (usually insideRc<RefCell<...>>).
- It should hold an enum
- Implement
__init__: In#[new], inspect thePyProblemDefinitionto determine which variant to instantiate. - Implement Methods: Implement
solve,setup, etc., delegating the call to the inner Rust planner. - Export: Register the class in
oxmpl-py/src/geometric/mod.rs.
Template:
// oxmpl-py/src/geometric/my_planner.rs
use pyo3::prelude::*;
use crate::base::{ProblemDefinitionVariant, PyGoal, PyPath, PyPlannerConfig, PyProblemDefinition};
use oxmpl::geometric::MyPlanner;
// ... imports
// 1. Define aliases for concrete types
type MyPlannerForRealVector = MyPlanner<RealVectorState, RealVectorStateSpace, PyGoal<RealVectorState>>;
// ... repeat for SO2, SO3, SE2, SE3, Compound
// 2. Define enum wrapper
enum PlannerVariant {
RealVector(Rc<RefCell<MyPlannerForRealVector>>),
// ...
}
// 3. Define Python class
#[pyclass(name = "MyPlanner", unsendable)]
pub struct PyMyPlanner {
planner: PlannerVariant,
pd: ProblemDefinitionVariant,
}
#[pymethods]
impl PyMyPlanner {
#[new]
fn new(
problem_definition: &PyProblemDefinition,
planner_config: &PyPlannerConfig,
) -> PyResult<Self> {
// Switch on problem_definition type to create correct PlannerVariant
}
fn solve(&mut self, timeout_secs: f32) -> PyResult<PyPath> {
// Delegate to self.planner
}
}
JavaScript Bindings (oxmpl-js)
To make your planner available in JavaScript/WASM, wrap it using wasm-bindgen.
- Create Wrapper File: Create
oxmpl-js/src/geometric/<my_planner>.rs. - Define Enum Wrapper: Similar to Python, define an enum
MyPlannerVariantholding the specialized Rust planners. - Define JS Class: Create a struct
JsMyPlannerdecorated with#[wasm_bindgen]. - Implement Constructor: Match the
JsProblemDefinitionvariant to instantiate the correct planner type. - Implement Methods: Implement
solveetc., delegating to the inner planner and returningJsPath. - Export: Add to
oxmpl-js/src/geometric/mod.rs.
Template:
// oxmpl-js/src/geometric/my_planner.rs
use wasm_bindgen::prelude::*;
use crate::base::{JsPath, JsProblemDefinition, ProblemDefinitionVariant, JsPlannerConfig};
use oxmpl::geometric::MyPlanner;
enum MyPlannerVariant {
RealVector(MyPlanner<RealVectorState, RealVectorStateSpace, JsGoal>),
// ...
}
#[wasm_bindgen(js_name = MyPlanner)]
pub struct JsMyPlanner {
planner: MyPlannerVariant,
pd: ProblemDefinitionVariant,
}
#[wasm_bindgen(js_class = MyPlanner)]
impl JsMyPlanner {
#[wasm_bindgen(constructor)]
pub fn new(problem_def: &JsProblemDefinition, config: &JsPlannerConfig) -> Self {
// Switch on problem_def.inner to create correct MyPlannerVariant
}
pub fn solve(&mut self, timeout_secs: f32) -> Result<JsPath, String> {
// Delegate and convert result
}
}
Integration Testing
Strict testing is required for any new planner to ensure correctness and stability across all bindings. You must implement integration tests for each layer of the stack.
Rust (oxmpl/tests/)
Create a new integration test file oxmpl/tests/<planner_name>_tests.rs.
- Verify the planner solves basic problems (e.g., finding a path in a free space).
- Test with all supported state spaces (RealVector, SO2, SO3, SE2, SE3, Compound).
- Ensure the planner respects time limits and goal conditions.
Python (oxmpl-py/tests/)
Add tests in oxmpl-py/tests/ using pytest.
- Create a file
test_<planner_name>.py. - Implement tests that mirror the Rust integration tests.
- Ensure the Python bindings correctly expose the planner and return valid paths.
- Run tests with:
pytest oxmpl-py/tests/
JavaScript (oxmpl-js/tests/)
Add tests in oxmpl-js/tests/ using vitest.
- Create a file
test_<planner_name>.test.js. - Verify the planner works in a simulated JS environment.
- Check that the API handles JavaScript objects correctly (e.g., passing options, callbacks).
- Run tests with:
npm testinside theoxmpl-jsdirectory.
Implementing New State Spaces
This guide explains how to add a new State and StateSpace to OxMPL and expose them to the bindings.
Do You Need a New State Type?
Before implementing a custom State and StateSpace, consider if your requirements can be met using CompoundState and CompoundStateSpace.
Using CompoundStateSpace
Most robotic systems can be represented as a collection of simpler state spaces. A CompoundStateSpace allows you to combine existing spaces (like RealVectorStateSpace, SO2StateSpace, SO3StateSpace) via a Cartesian product.
When to use CompoundStateSpace:
- Your system is composed of multiple independent parts (e.g., a mobile base ($SE(2)$) + a robotic arm ($R^n$)).
- You need to assign different weights to different components during distance calculation.
When to implement a New State:
- Unique Topology: You are working with a manifold that is not easily represented by existing spaces (e.g., a specific non-Euclidean surface).
- Custom Metric: You require a specialized distance function that cannot be decomposed into component-wise distances (e.g., Dubins path distance for non-holonomic vehicles).
- Custom Interpolation: The path between two states follows specific rules (e.g., geodesic on a sphere).
Rust Implementation (oxmpl)
- Define State: Create a struct implementing
oxmpl::base::state::State(andClone,Debug,serde::Serialize,serde::Deserialize). - Define State Space: Create a struct implementing
oxmpl::base::space::StateSpace.sample_uniform: Generate a random state.distance: Compute distance between two states.interpolate: Interpolate between two states.satisfies_bounds/enforce_bounds: Check/enforce constraints.
- Export: Add them to
oxmpl/src/base/states/andoxmpl/src/base/spaces/.
Python Bindings (oxmpl-py)
- Wrap the State:
- Create
oxmpl-py/src/base/<my_state>.rs. - Define
PyMyState(pub Arc<OxmplMyState>)with#[pyclass]. - Implement
__init__, getters, and__repr__. - Implement
oxmpl_py::base::py_state_convert::PyStateConvertforOxmplMyStateto handle conversion between Rust and Python wrappers.
- Create
- Wrap the State Space:
- Create
oxmpl-py/src/base/<my_state_space>.rs. - Define
PyMyStateSpace(pub Arc<Mutex<OxmplMyStateSpace>>)with#[pyclass]. - Implement
distance,sample, etc.
- Create
- Register: Add the classes to
oxmpl-py/src/base/mod.rsincreate_module. - Update Planners: You may need to update the
PlannerVariantenums inoxmpl-py/src/geometric/*.rsto include a variant for your new state type if it’s not covered by existing generic logic.
JavaScript Bindings (oxmpl-js)
- Wrap the State:
- Create
oxmpl-js/src/base/<my_state>.rs. - Define
JsMyStatestruct wrappingArc<OxmplMyState>with#[wasm_bindgen]. - Implement constructor and getters.
- Implement
oxmpl_js::base::js_state_convert::JsStateConvertforOxmplMyState.
- Create
- Wrap the State Space:
- Create
oxmpl-js/src/base/<my_state_space>.rs. - Define
JsMyStateSpacestruct wrappingArc<Mutex<OxmplMyStateSpace>>. - Implement
sample,distance, etc.
- Create
- Register: Export them in
oxmpl-js/src/base/mod.rs. - Update Planners: Similar to Python, update
oxmpl-js/src/geometric/*.rsto include the new state variant in the planner enums.
Note on JsStateConvert:
When implementing from_js_value for your state, you often need to inspect the JS object properties to ensure it matches your state type (e.g., check for x, y for a 2D point).
Integration Testing
Ensure your new state space is robust by adding tests across the stack.
Rust
- Unit Tests: Add
#[test]functions in your implementation file (or a separate test module) to verify:- Distance calculation properties (symmetry, non-negativity).
- Interpolation accuracy.
- Bounds enforcement.
- Serialization/Deserialization (if applicable).
- Integration Tests: Add a test file in
oxmpl/tests/to check interaction with planners.
Python (oxmpl-py/tests/)
Add tests in oxmpl-py/tests/ to ensure the bindings are correct.
- Verify that
__init__works with valid arguments and raises errors for invalid ones. - Check that methods like
distance()andsample()return expected types and values. - Ensure that states can be passed to and retrieved from planners correctly.
JavaScript (oxmpl-js/tests/)
Add tests in oxmpl-js/tests/ to ensure the WASM bindings work as expected.
- Verify object creation and property access.
- Test that the
JsStateConverttrait correctly handles conversion between JS objects and Rust structs. - Ensure usage within a
ProblemDefinitionworks without panic.
Contributors
We would like to thank the following individuals for their contributions to the OxMPL project:
- Junior Sundar: First Commit
- Ross Gardiner: First Commit
If you have contributed and your name is missing, please open a pull request to add yourself!