Skip to content

Commit 0d13c50

Browse files
feat: RNG is now a planner argument, expose XORShift generation (#29)
* 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]>
1 parent 53a7bd2 commit 0d13c50

33 files changed

+350
-254
lines changed

.github/workflows/format.yml

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -30,13 +30,13 @@ jobs:
3030
run: |
3131
wget https://apt.llvm.org/llvm.sh
3232
chmod +x llvm.sh
33-
yes | sudo ./llvm.sh 16 || true
34-
sudo apt-get install -y clang-format-16 python3-pip
33+
yes | sudo ./llvm.sh 18 || true
34+
sudo apt-get install -y clang-format-18 python3-pip
3535
pip install yapf
3636
3737
- name: Run clang-format style check.
3838
run: >
39-
find . -iname *.hh -o -iname *.cc | xargs -I{} clang-format-16 --dry-run -Werror {}
39+
find . -iname *.hh -o -iname *.cc | xargs -I{} clang-format-18 --dry-run -Werror {}
4040
4141
- name: Run yapf style check.
4242
run: >

README.md

Lines changed: 12 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -75,6 +75,13 @@ python scripts/sphere_cage_example.py --visualize
7575
Which will benchmark a simple scenario of the Franka Emika Panda in a cage of spheres and visualize one of the results.
7676
See the [README in the scripts directory](scripts/README.md) for more details.
7777

78+
#### Incremental Rebuilds
79+
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):
80+
```bash
81+
cd vamp
82+
pip install --no-build-isolation -Ceditable.rebuild=true -ve .
83+
```
84+
7885
### C++
7986
If you wish to extend `vamp` via C++, please build directly with CMake, e.g.:
8087
```
@@ -135,13 +142,17 @@ For the flying sphere in $\mathbb{R}^3$, additional operations are available to
135142
- `vamp.sphere.set_lows()` and `vamp.sphere.set_highs()` to set bounding box of space
136143
- `vamp.sphere.set_radius()` to set the sphere's radius
137144

145+
## Supported RNG
146+
We ship implementations of the following pseudorandom number generators (PRNGs):
147+
- `halton`: An implementation of a [multi-dimensional Halton sequence](https://en.wikipedia.org/wiki/Halton_sequence) [[12-13]](#12).
148+
- `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.
149+
138150
## Supported Planners
139151
We currently ship two planners:
140152
- `rrtc`, which is an implementation of a dynamic-domain [[6]](#6) balanced [[7]](#7) RRT-Connect [[1]](#1).
141153
- `prm`, which is an implementation of basic PRM [[2]](#2) (i.e., PRM without the bounce heuristic, etc.).
142154

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

146157
We also ship a number of heuristic simplification routines:
147158
- randomized and deterministic shortcutting [[8, 9]](#8) (`REDUCE` and `SHORTCUT`)

scripts/README.md

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,8 @@ These scripts support standard planner and simplifier configuration arguments (s
3939
In addition, they both support the following arguments:
4040
- `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.
4141
- `dataset`: which describes the specific dataset of problems that should be loaded and inspected. See [Datasets](../resources/README.md#supported-planners) for more information.
42+
- `sampler_name`: specify which PRNG sampler to use for generating random configurations (see [supported RNGs](../README.md#supported-rng)).
43+
- `skip_rng_iterations`: skip _n_ PRNG iterations. Can be used to "seed" trials differently.
4244
- `pointcloud`: construct a pointcloud approximation of the problem's scene geometry and plan against this representation using the CAPT datastructure.
4345
- `samples_per_object`: number of samples per each object for pointcloud generation.
4446
- `filter_radius`: pointcloud filtering radius. Will remove all redundant points that are within the specified radius.

scripts/attachments.py

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -70,8 +70,9 @@ def callback(configuration):
7070
sim.update_object_position(attachment_sphere, sphere.position)
7171

7272
# Plan and display
73-
result = planner_func(a, b, e, plan_settings)
74-
simple = vamp_module.simplify(result.path, e, simp_settings)
73+
sampler = vamp_module.halton()
74+
result = planner_func(a, b, e, plan_settings, sampler)
75+
simple = vamp_module.simplify(result.path, e, simp_settings, sampler)
7576
simple.path.interpolate(vamp.panda.resolution())
7677

7778
sim.animate(simple.path, callback)

scripts/cpp/ompl_integration.cc

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -130,8 +130,8 @@ struct VAMPMotionValidator : public ob::MotionValidator
130130
ompl_to_vamp(s1), ompl_to_vamp(s2), env_v);
131131
}
132132

133-
auto checkMotion(const ob::State *, const ob::State *, std::pair<ob::State *, double> &) const
134-
-> bool override
133+
auto
134+
checkMotion(const ob::State *, const ob::State *, std::pair<ob::State *, double> &) const -> bool override
135135
{
136136
throw ompl::Exception("Not implemented!");
137137
}

scripts/evaluate_mbm.py

Lines changed: 8 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,8 @@ def main(
1717
dataset: str = "problems.pkl", # Pickled dataset to use
1818
problem: Union[str, List[str]] = [], # Problem name or list of problems to evaluate
1919
trials: int = 1, # Number of trials to evaluate each instance
20+
sampler_name: str = "halton", # Sampler to use.
21+
skip_rng_iterations: int = 0, # Skip a number of RNG iterations
2022
print_failures: bool = False, # Print out failures and invalid problems
2123
pointcloud: bool = False, # Use pointcloud rather than primitive geometry
2224
samples_per_object: int = 10000, # If pointcloud, samples per object to use
@@ -48,6 +50,8 @@ def main(
4850
(vamp_module, planner_func, plan_settings,
4951
simp_settings) = vamp.configure_robot_and_planner_with_kwargs(robot, planner, **kwargs)
5052

53+
sampler = getattr(vamp_module, sampler_name)()
54+
5155
total_problems = 0
5256
valid_problems = 0
5357
failed_problems = 0
@@ -88,13 +92,15 @@ def main(
8892
else:
8993
env = vamp.problem_dict_to_vamp(data)
9094

95+
sampler.reset()
96+
sampler.skip(skip_rng_iterations)
9197
for _ in range(trials):
92-
result = planner_func(data['start'], data['goals'], env, plan_settings)
98+
result = planner_func(data['start'], data['goals'], env, plan_settings, sampler)
9399
if not result.solved:
94100
failures.append(i)
95101
break
96102

97-
simple = vamp_module.simplify(result.path, env, simp_settings)
103+
simple = vamp_module.simplify(result.path, env, simp_settings, sampler)
98104

99105
trial_result = vamp.results_to_dict(result, simple)
100106
if pointcloud:

scripts/flying_sphere.py

Lines changed: 9 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -8,12 +8,13 @@
88

99

1010
def main(
11-
visualize: bool = False,
12-
x: float = 20,
13-
y: float = 20,
14-
z: float = 1,
15-
radius: float = 0.1,
16-
iterations: int = 10000
11+
visualize: bool = False,
12+
x: float = 20,
13+
y: float = 20,
14+
z: float = 1,
15+
radius: float = 0.1,
16+
iterations: int = 10000,
17+
sampler_name: str = "halton",
1718
):
1819

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

36-
roadmap = vamp.sphere.roadmap(robot_initial_pos, goal_pos, env, settings)
37+
sampler = getattr(vamp.sphere, sampler_name)()
38+
roadmap = vamp.sphere.roadmap(robot_initial_pos, goal_pos, env, settings, sampler)
3739

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

scripts/sphere_cage_example.py

Lines changed: 9 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -38,12 +38,17 @@ def main(
3838
radius: float = 0.2,
3939
visualize: bool = False,
4040
planner: str = "rrtc",
41+
sampler_name: str = "halton", # Sampler to use.
42+
skip_rng_iterations: int = 0, # Skip a number of RNG iterations
4143
**kwargs,
4244
):
4345

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

49+
sampler = getattr(vamp_module, sampler_name)()
50+
sampler.skip(skip_rng_iterations)
51+
4752
if benchmark:
4853
random.seed(0)
4954
np.random.seed(0)
@@ -60,8 +65,8 @@ def main(
6065
e.add_sphere(vamp.Sphere(sphere, radius))
6166

6267
if vamp.panda.validate(a, e) and vamp.panda.validate(b, e):
63-
result = planner_func(a, b, e, plan_settings)
64-
simple = vamp_module.simplify(result.path, e, simp_settings)
68+
result = planner_func(a, b, e, plan_settings, sampler)
69+
simple = vamp_module.simplify(result.path, e, simp_settings, sampler)
6570
results.append(vamp.results_to_dict(result, simple))
6671

6772
df = pd.DataFrame.from_dict(results)
@@ -94,8 +99,8 @@ def main(
9499
e.add_sphere(vamp.Sphere(sphere, radius))
95100
sim.add_sphere(radius, sphere)
96101

97-
result = planner_func(a, b, e, plan_settings)
98-
simple = vamp_module.simplify(result.path, e, simp_settings)
102+
result = planner_func(a, b, e, plan_settings, sampler)
103+
simple = vamp_module.simplify(result.path, e, simp_settings, sampler)
99104

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

scripts/visualize_mbm.py

Lines changed: 8 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,8 @@ def main(
1515
dataset: str = "problems.pkl", # Pickled dataset to use
1616
problem: str = "", # Problem name
1717
index: int = 1, # Problem index
18+
sampler_name: str = "halton", # Sampler to use.
19+
skip_rng_iterations: int = 0, # Skip a number of RNG iterations
1820
display_object_names: bool = False, # Display object names over geometry
1921
pointcloud: bool = False, # Use pointcloud rather than primitive geometry
2022
samples_per_object: int = 10000, # If pointcloud, samples per object to use
@@ -77,16 +79,19 @@ def main(
7779
goals = problem_data['goals']
7880
valid = problem_data['valid']
7981

82+
sampler = getattr(vamp_module, sampler_name)()
83+
sampler.skip(skip_rng_iterations)
84+
8085
if valid:
81-
result = planner_func(start, goals, env, plan_settings)
86+
result = planner_func(start, goals, env, plan_settings, sampler)
8287
solved = result.solved
8388
else:
8489
print("Problem is invalid!")
8590
solved = False
8691

8792
if valid and solved:
8893
print("Solved problem!")
89-
simplify = vamp_module.simplify(result.path, env, simp_settings)
94+
simplify = vamp_module.simplify(result.path, env, simp_settings, sampler)
9095

9196
stats = vamp.results_to_dict(result, simplify)
9297
print(
@@ -152,4 +157,5 @@ def main(
152157

153158

154159
if __name__ == "__main__":
160+
155161
Fire(main)

0 commit comments

Comments
 (0)