Skip to content

Commit

Permalink
feat: RNG is now a planner argument, expose XORShift generation (#29)
Browse files Browse the repository at this point in the history
* doc: note about incremental rebuilds

* feat: initial implementation

* feat: Python RNG functions

* fix: Halton sequence blows up after around 1.5M iters - restart and rotate bases after 1M

* wip: refactor names, remove old RNG code

* feat: added xorshift

* fix/feat: xorshift mapping fixed + sampling feature on other scripts

* feat: final script fix + documentation

* format: applied clang-format

* Update LLVM version

* goof, update format version

* yapf format

* Update scripts/README.md

Co-authored-by: Wil Thomason <[email protected]>

* initial nits

* Initial nits

* documentation

* format

---------

Co-authored-by: Wil Thomason <[email protected]>
  • Loading branch information
zkingston and wbthomason authored Oct 18, 2024
1 parent 53a7bd2 commit 0d13c50
Show file tree
Hide file tree
Showing 33 changed files with 350 additions and 254 deletions.
6 changes: 3 additions & 3 deletions .github/workflows/format.yml
Original file line number Diff line number Diff line change
Expand Up @@ -30,13 +30,13 @@ jobs:
run: |
wget https://apt.llvm.org/llvm.sh
chmod +x llvm.sh
yes | sudo ./llvm.sh 16 || true
sudo apt-get install -y clang-format-16 python3-pip
yes | sudo ./llvm.sh 18 || true
sudo apt-get install -y clang-format-18 python3-pip
pip install yapf
- name: Run clang-format style check.
run: >
find . -iname *.hh -o -iname *.cc | xargs -I{} clang-format-16 --dry-run -Werror {}
find . -iname *.hh -o -iname *.cc | xargs -I{} clang-format-18 --dry-run -Werror {}
- name: Run yapf style check.
run: >
Expand Down
13 changes: 12 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,13 @@ python scripts/sphere_cage_example.py --visualize
Which will benchmark a simple scenario of the Franka Emika Panda in a cage of spheres and visualize one of the results.
See the [README in the scripts directory](scripts/README.md) for more details.

#### Incremental Rebuilds
Rather than building the entire library from scratch each time, `nanobind` supports [incremental rebuilds](https://nanobind.readthedocs.io/en/latest/packaging.html#step-5-incremental-rebuilds):
```bash
cd vamp
pip install --no-build-isolation -Ceditable.rebuild=true -ve .
```

### C++
If you wish to extend `vamp` via C++, please build directly with CMake, e.g.:
```
Expand Down Expand Up @@ -135,13 +142,17 @@ For the flying sphere in $\mathbb{R}^3$, additional operations are available to
- `vamp.sphere.set_lows()` and `vamp.sphere.set_highs()` to set bounding box of space
- `vamp.sphere.set_radius()` to set the sphere's radius

## Supported RNG
We ship implementations of the following pseudorandom number generators (PRNGs):
- `halton`: An implementation of a [multi-dimensional Halton sequence](https://en.wikipedia.org/wiki/Halton_sequence) [[12-13]](#12).
- `xorshift`: A SIMD-accelerated implementation of an [XOR shift](https://en.wikipedia.org/wiki/Xorshift) generator, only available on x86 machines. Uses the [`SIMDxorshift`](https://github.com/lemire/SIMDxorshift) library.

## Supported Planners
We currently ship two planners:
- `rrtc`, which is an implementation of a dynamic-domain [[6]](#6) balanced [[7]](#7) RRT-Connect [[1]](#1).
- `prm`, which is an implementation of basic PRM [[2]](#2) (i.e., PRM without the bounce heuristic, etc.).

Note that these planners support planning to a set of goals, not just a single goal.
Also, all planners use a multi-dimensional Halton sequence for deterministic planning [[12-13]](#12).

We also ship a number of heuristic simplification routines:
- randomized and deterministic shortcutting [[8, 9]](#8) (`REDUCE` and `SHORTCUT`)
Expand Down
2 changes: 2 additions & 0 deletions scripts/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,8 @@ These scripts support standard planner and simplifier configuration arguments (s
In addition, they both support the following arguments:
- `problem`: which takes in either a single problem name (e.g., `table_pick`) or a list (e.g., `table_pick,table_under_pick`) to evaluate against a specific set of problems.
- `dataset`: which describes the specific dataset of problems that should be loaded and inspected. See [Datasets](../resources/README.md#supported-planners) for more information.
- `sampler_name`: specify which PRNG sampler to use for generating random configurations (see [supported RNGs](../README.md#supported-rng)).
- `skip_rng_iterations`: skip _n_ PRNG iterations. Can be used to "seed" trials differently.
- `pointcloud`: construct a pointcloud approximation of the problem's scene geometry and plan against this representation using the CAPT datastructure.
- `samples_per_object`: number of samples per each object for pointcloud generation.
- `filter_radius`: pointcloud filtering radius. Will remove all redundant points that are within the specified radius.
Expand Down
5 changes: 3 additions & 2 deletions scripts/attachments.py
Original file line number Diff line number Diff line change
Expand Up @@ -70,8 +70,9 @@ def callback(configuration):
sim.update_object_position(attachment_sphere, sphere.position)

# Plan and display
result = planner_func(a, b, e, plan_settings)
simple = vamp_module.simplify(result.path, e, simp_settings)
sampler = vamp_module.halton()
result = planner_func(a, b, e, plan_settings, sampler)
simple = vamp_module.simplify(result.path, e, simp_settings, sampler)
simple.path.interpolate(vamp.panda.resolution())

sim.animate(simple.path, callback)
Expand Down
4 changes: 2 additions & 2 deletions scripts/cpp/ompl_integration.cc
Original file line number Diff line number Diff line change
Expand Up @@ -130,8 +130,8 @@ struct VAMPMotionValidator : public ob::MotionValidator
ompl_to_vamp(s1), ompl_to_vamp(s2), env_v);
}

auto checkMotion(const ob::State *, const ob::State *, std::pair<ob::State *, double> &) const
-> bool override
auto
checkMotion(const ob::State *, const ob::State *, std::pair<ob::State *, double> &) const -> bool override
{
throw ompl::Exception("Not implemented!");
}
Expand Down
10 changes: 8 additions & 2 deletions scripts/evaluate_mbm.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@ def main(
dataset: str = "problems.pkl", # Pickled dataset to use
problem: Union[str, List[str]] = [], # Problem name or list of problems to evaluate
trials: int = 1, # Number of trials to evaluate each instance
sampler_name: str = "halton", # Sampler to use.
skip_rng_iterations: int = 0, # Skip a number of RNG iterations
print_failures: bool = False, # Print out failures and invalid problems
pointcloud: bool = False, # Use pointcloud rather than primitive geometry
samples_per_object: int = 10000, # If pointcloud, samples per object to use
Expand Down Expand Up @@ -48,6 +50,8 @@ def main(
(vamp_module, planner_func, plan_settings,
simp_settings) = vamp.configure_robot_and_planner_with_kwargs(robot, planner, **kwargs)

sampler = getattr(vamp_module, sampler_name)()

total_problems = 0
valid_problems = 0
failed_problems = 0
Expand Down Expand Up @@ -88,13 +92,15 @@ def main(
else:
env = vamp.problem_dict_to_vamp(data)

sampler.reset()
sampler.skip(skip_rng_iterations)
for _ in range(trials):
result = planner_func(data['start'], data['goals'], env, plan_settings)
result = planner_func(data['start'], data['goals'], env, plan_settings, sampler)
if not result.solved:
failures.append(i)
break

simple = vamp_module.simplify(result.path, env, simp_settings)
simple = vamp_module.simplify(result.path, env, simp_settings, sampler)

trial_result = vamp.results_to_dict(result, simple)
if pointcloud:
Expand Down
16 changes: 9 additions & 7 deletions scripts/flying_sphere.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,12 +8,13 @@


def main(
visualize: bool = False,
x: float = 20,
y: float = 20,
z: float = 1,
radius: float = 0.1,
iterations: int = 10000
visualize: bool = False,
x: float = 20,
y: float = 20,
z: float = 1,
radius: float = 0.1,
iterations: int = 10000,
sampler_name: str = "halton",
):

env = vamp.Environment()
Expand All @@ -33,7 +34,8 @@ def main(
settings = vamp.PRMSettings(vamp.PRMNeighborParams(vamp.sphere.dimension(), vamp.sphere.space_measure()))
settings.max_iterations = iterations

roadmap = vamp.sphere.roadmap(robot_initial_pos, goal_pos, env, settings)
sampler = getattr(vamp.sphere, sampler_name)()
roadmap = vamp.sphere.roadmap(robot_initial_pos, goal_pos, env, settings, sampler)

print(f"Created roadmap with {len(roadmap)} nodes in {roadmap.nanoseconds / 1e9} seconds!")

Expand Down
13 changes: 9 additions & 4 deletions scripts/sphere_cage_example.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,12 +38,17 @@ def main(
radius: float = 0.2,
visualize: bool = False,
planner: str = "rrtc",
sampler_name: str = "halton", # Sampler to use.
skip_rng_iterations: int = 0, # Skip a number of RNG iterations
**kwargs,
):

(vamp_module, planner_func, plan_settings,
simp_settings) = vamp.configure_robot_and_planner_with_kwargs("panda", planner, **kwargs)

sampler = getattr(vamp_module, sampler_name)()
sampler.skip(skip_rng_iterations)

if benchmark:
random.seed(0)
np.random.seed(0)
Expand All @@ -60,8 +65,8 @@ def main(
e.add_sphere(vamp.Sphere(sphere, radius))

if vamp.panda.validate(a, e) and vamp.panda.validate(b, e):
result = planner_func(a, b, e, plan_settings)
simple = vamp_module.simplify(result.path, e, simp_settings)
result = planner_func(a, b, e, plan_settings, sampler)
simple = vamp_module.simplify(result.path, e, simp_settings, sampler)
results.append(vamp.results_to_dict(result, simple))

df = pd.DataFrame.from_dict(results)
Expand Down Expand Up @@ -94,8 +99,8 @@ def main(
e.add_sphere(vamp.Sphere(sphere, radius))
sim.add_sphere(radius, sphere)

result = planner_func(a, b, e, plan_settings)
simple = vamp_module.simplify(result.path, e, simp_settings)
result = planner_func(a, b, e, plan_settings, sampler)
simple = vamp_module.simplify(result.path, e, simp_settings, sampler)

simple.path.interpolate(vamp.panda.resolution())

Expand Down
10 changes: 8 additions & 2 deletions scripts/visualize_mbm.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@ def main(
dataset: str = "problems.pkl", # Pickled dataset to use
problem: str = "", # Problem name
index: int = 1, # Problem index
sampler_name: str = "halton", # Sampler to use.
skip_rng_iterations: int = 0, # Skip a number of RNG iterations
display_object_names: bool = False, # Display object names over geometry
pointcloud: bool = False, # Use pointcloud rather than primitive geometry
samples_per_object: int = 10000, # If pointcloud, samples per object to use
Expand Down Expand Up @@ -77,16 +79,19 @@ def main(
goals = problem_data['goals']
valid = problem_data['valid']

sampler = getattr(vamp_module, sampler_name)()
sampler.skip(skip_rng_iterations)

if valid:
result = planner_func(start, goals, env, plan_settings)
result = planner_func(start, goals, env, plan_settings, sampler)
solved = result.solved
else:
print("Problem is invalid!")
solved = False

if valid and solved:
print("Solved problem!")
simplify = vamp_module.simplify(result.path, env, simp_settings)
simplify = vamp_module.simplify(result.path, env, simp_settings, sampler)

stats = vamp.results_to_dict(result, simplify)
print(
Expand Down Expand Up @@ -152,4 +157,5 @@ def main(


if __name__ == "__main__":

Fire(main)
Loading

0 comments on commit 0d13c50

Please sign in to comment.