diff --git a/scripts/convergence_benchmark.py b/scripts/convergence_benchmark.py new file mode 100644 index 00000000..58244280 --- /dev/null +++ b/scripts/convergence_benchmark.py @@ -0,0 +1,354 @@ +#!/usr/bin/env python3 +"""Convergence benchmark comparing asymptotically optimal planners on sphere cage. + +Runs each planner at increasing iteration budgets and plots cost vs wall-clock time. +Generates two figures: + 1. Deterministic (Halton) sampling — single run per budget. + 2. Multi-seed sampling — Halton with different skip offsets, mean +/- std over seeds. +""" + +import numpy as np +import matplotlib.pyplot as plt +from fire import Fire +import vamp + +# Sphere cage problem (from sphere_cage_example.py) +START = [0., -0.785, 0., -2.356, 0., 1.571, 0.785] +GOAL = [2.35, 1., 0., -0.8, 0, 2.5, 0.785] +SPHERES = [ + [0.55, 0, 0.25], + [0.35, 0.35, 0.25], + [0, 0.55, 0.25], + [-0.55, 0, 0.25], + [-0.35, -0.35, 0.25], + [0, -0.55, 0.25], + [0.35, -0.35, 0.25], + [0.35, 0.35, 0.8], + [0, 0.55, 0.8], + [-0.35, 0.35, 0.8], + [-0.55, 0, 0.8], + [-0.35, -0.35, 0.8], + [0, -0.55, 0.8], + [0.35, -0.35, 0.8], + ] + + +def make_environment(radius = 0.2): + e = vamp.Environment() + for sphere in SPHERES: + e.add_sphere(vamp.Sphere(sphere, radius)) + return e + + +def run_planner(planner_name, budget, env, start, goal, skip = 0): + """Run a planner with a given iteration budget. + + Args: + skip: Number of Halton samples to skip before planning (acts as seed). + + Returns (plan_time_ms, raw_cost, simp_cost, total_time_ms). + """ + robot_module, planner_func, plan_settings, simp_settings = \ + vamp.configure_robot_and_planner_with_kwargs("panda", planner_name) + + plan_settings.max_iterations = budget + plan_settings.max_samples = budget + + if hasattr(plan_settings, 'optimize'): + plan_settings.optimize = True + + rng = vamp.panda.halton() + if skip > 0: + rng.skip(skip) + result = planner_func(start, goal, env, plan_settings, rng) + + plan_time_ms = result.nanoseconds / 1e6 + raw_cost = result.path.cost() if result.solved else float('inf') + + if result.solved: + simp_rng = vamp.panda.halton() + simp_result = robot_module.simplify(result.path, env, simp_settings, simp_rng) + simp_cost = simp_result.path.cost() + total_time_ms = plan_time_ms + simp_result.nanoseconds / 1e6 + else: + simp_cost = float('inf') + total_time_ms = plan_time_ms + + return plan_time_ms, raw_cost, simp_cost, total_time_ms + + +def plot_deterministic(planner_list, budgets, env, start, goal, max_time_s, output): + """Single deterministic Halton run per budget.""" + results = {} + + for planner_name in planner_list: + print(f"\n=== {planner_name} (deterministic) ===") + results[planner_name] = {} + + for budget in budgets: + plan_t, raw_c, simp_c, total_t = run_planner(planner_name, budget, env, start, goal) + + results[planner_name][budget] = (plan_t, raw_c, simp_c, total_t) + + raw_s = f"{raw_c:.4f}" if raw_c < float('inf') else "FAIL" + simp_s = f"{simp_c:.4f}" if simp_c < float('inf') else "FAIL" + print(f" budget={budget:>7d} {plan_t:>7.0f}ms raw={raw_s} simp={simp_s}") + + if plan_t / 1000 > max_time_s: + print(f" -> {plan_t/1000:.1f}s > {max_time_s}s limit, stopping") + break + + fig, axes = plt.subplots(1, 2, figsize = (14, 6)) + colors = plt.cm.tab10.colors + + for idx, planner_name in enumerate(planner_list): + color = colors[idx % len(colors)] + data = results[planner_name] + + raw_times = [] + raw_costs = [] + for b in sorted(data.keys()): + pt, rc, _, _ = data[b] + if rc < float('inf'): + raw_times.append(pt) + raw_costs.append(rc) + if raw_times: + axes[0].plot( + raw_times, + raw_costs, + '-o', + color = color, + label = planner_name, + linewidth = 2, + markersize = 4 + ) + + simp_times = [] + simp_costs = [] + for b in sorted(data.keys()): + _, _, sc, tt = data[b] + if sc < float('inf'): + simp_times.append(tt) + simp_costs.append(sc) + if simp_times: + axes[1].plot( + simp_times, + simp_costs, + '-o', + color = color, + label = planner_name, + linewidth = 2, + markersize = 4 + ) + + for ax, title in zip(axes, ["Raw Planner Cost", "After Simplification"]): + ax.set_xlabel("Time (ms)", fontsize = 12) + ax.set_ylabel("Path Cost (L2)", fontsize = 12) + ax.set_title(title, fontsize = 14) + ax.set_xscale("log") + ax.legend(fontsize = 11) + ax.grid(True, alpha = 0.3) + + fig.suptitle("Convergence: Sphere Cage — Deterministic (Halton)", fontsize = 15, y = 1.01) + plt.tight_layout() + plt.savefig(output, dpi = 150, bbox_inches = "tight") + print(f"\nDeterministic plot saved to {output}") + plt.close(fig) + + +def plot_multi_seed(planner_list, budgets, env, start, goal, max_time_s, n_seeds, output): + """Multi-seed runs using Halton with different skip offsets.""" + # Use well-separated skip offsets so Halton subsequences don't overlap + skip_offsets = [i * 100000 for i in range(n_seeds)] + + # results[planner][budget] = list of (plan_t, raw_c, simp_c, total_t) per seed + results = {} + + for planner_name in planner_list: + print(f"\n=== {planner_name} (multi-seed, {n_seeds} seeds) ===") + results[planner_name] = {} + stopped_at_budget = None + + for budget in budgets: + if stopped_at_budget is not None: + break + + seed_results = [] + for seed_idx, skip in enumerate(skip_offsets): + plan_t, raw_c, simp_c, total_t = run_planner( + planner_name, budget, env, start, goal, skip=skip) + seed_results.append((plan_t, raw_c, simp_c, total_t)) + + results[planner_name][budget] = seed_results + + raw_costs = [r[1] for r in seed_results if r[1] < float('inf')] + plan_times = [r[0] for r in seed_results] + n_solved = len(raw_costs) + + if raw_costs: + print( + f" budget={budget:>7d} {np.mean(plan_times):>7.0f}ms " + f"raw={np.mean(raw_costs):.4f}±{np.std(raw_costs):.4f} " + f"solved={n_solved}/{n_seeds}" + ) + else: + print( + f" budget={budget:>7d} {np.mean(plan_times):>7.0f}ms " + f"raw=FAIL solved=0/{n_seeds}" + ) + + if np.mean(plan_times) / 1000 > max_time_s: + print(f" -> {np.mean(plan_times)/1000:.1f}s > {max_time_s}s limit, stopping") + stopped_at_budget = budget + + fig, axes = plt.subplots(1, 2, figsize = (14, 6)) + colors = plt.cm.tab10.colors + + for idx, planner_name in enumerate(planner_list): + color = colors[idx % len(colors)] + data = results[planner_name] + + # Collect per-budget statistics for raw cost + raw_mean_times = [] + raw_mean_costs = [] + raw_std_costs = [] + for b in sorted(data.keys()): + costs = [r[1] for r in data[b] if r[1] < float('inf')] + times = [r[0] for r in data[b] if r[1] < float('inf')] + if costs: + raw_mean_times.append(np.mean(times)) + raw_mean_costs.append(np.mean(costs)) + raw_std_costs.append(np.std(costs)) + + if raw_mean_times: + raw_mean_costs = np.array(raw_mean_costs) + raw_std_costs = np.array(raw_std_costs) + raw_mean_times = np.array(raw_mean_times) + axes[0].plot( + raw_mean_times, + raw_mean_costs, + '-o', + color = color, + label = planner_name, + linewidth = 2, + markersize = 4 + ) + axes[0].fill_between( + raw_mean_times, + raw_mean_costs - raw_std_costs, + raw_mean_costs + raw_std_costs, + color = color, + alpha = 0.15 + ) + + # Collect per-budget statistics for simplified cost + simp_mean_times = [] + simp_mean_costs = [] + simp_std_costs = [] + for b in sorted(data.keys()): + costs = [r[2] for r in data[b] if r[2] < float('inf')] + times = [r[3] for r in data[b] if r[2] < float('inf')] + if costs: + simp_mean_times.append(np.mean(times)) + simp_mean_costs.append(np.mean(costs)) + simp_std_costs.append(np.std(costs)) + + if simp_mean_times: + simp_mean_costs = np.array(simp_mean_costs) + simp_std_costs = np.array(simp_std_costs) + simp_mean_times = np.array(simp_mean_times) + axes[1].plot( + simp_mean_times, + simp_mean_costs, + '-o', + color = color, + label = planner_name, + linewidth = 2, + markersize = 4 + ) + axes[1].fill_between( + simp_mean_times, + simp_mean_costs - simp_std_costs, + simp_mean_costs + simp_std_costs, + color = color, + alpha = 0.15 + ) + + for ax, title in zip(axes, ["Raw Planner Cost", "After Simplification"]): + ax.set_xlabel("Time (ms)", fontsize = 12) + ax.set_ylabel("Path Cost (L2)", fontsize = 12) + ax.set_title(title, fontsize = 14) + ax.set_xscale("log") + ax.legend(fontsize = 11) + ax.grid(True, alpha = 0.3) + + fig.suptitle(f"Convergence: Sphere Cage — {n_seeds} Seeds (Halton skip offsets)", fontsize = 15, y = 1.01) + plt.tight_layout() + plt.savefig(output, dpi = 150, bbox_inches = "tight") + print(f"\nMulti-seed plot saved to {output}") + plt.close(fig) + + +def main( + output: str = "convergence", + planners: str = "grrtstar,aorrtc,fcit", + radius: float = 0.2, + max_time_s: float = 10., + n_seeds: int = 5, + ): + """Run convergence benchmark. + + Generates two figures: + {output}_deterministic.png — single Halton run per budget. + {output}_multi_seed.png — mean±std over n_seeds Halton skip offsets. + + Args: + output: Output filename prefix (without extension). + planners: Comma-separated planner names. + radius: Sphere obstacle radius. + max_time_s: Approximate max wall-clock time per planner point (seconds). + n_seeds: Number of seeds for multi-seed benchmark. + """ + if isinstance(planners, (list, tuple)): + planner_list = list(planners) + else: + planner_list = [p.strip() for p in planners.split(",")] + + budgets = [ + 500, + 1000, + 2000, + 3000, + 5000, + 7500, + 10000, + 15000, + 20000, + 30000, + 50000, + 75000, + 100000, + 150000, + 200000, + 300000, + 500000, + ] + + env = make_environment(radius) + start = np.array(START) + goal = np.array(GOAL) + + assert vamp.panda.validate(start, env), "Start config in collision!" + assert vamp.panda.validate(goal, env), "Goal config in collision!" + + # Strip extension if user provided one + if output.endswith('.png'): + output = output[:-4] + + plot_deterministic(planner_list, budgets, env, start, goal, max_time_s, f"{output}_deterministic.png") + + plot_multi_seed(planner_list, budgets, env, start, goal, max_time_s, n_seeds, f"{output}_multi_seed.png") + + +if __name__ == "__main__": + Fire(main) diff --git a/src/impl/vamp/bindings/robot_helper.hh b/src/impl/vamp/bindings/robot_helper.hh index d6c4d303..b4d1cef4 100644 --- a/src/impl/vamp/bindings/robot_helper.hh +++ b/src/impl/vamp/bindings/robot_helper.hh @@ -22,6 +22,7 @@ #include #include #include +#include #include #include @@ -231,6 +232,10 @@ namespace vamp::binding vamp::planning::AORRTC, vamp::planning::AORRTCSettings>; + using GRRTStar = PlannerHelper< + vamp::planning::GRRTStar, + vamp::planning::GRRTStarSettings>; + inline static auto fk(const Type &c_in) -> std::vector> { typename Robot::template Spheres<1> out; @@ -628,6 +633,7 @@ namespace vamp::binding PLANNER("prm", PRM, "PRM"); PLANNER("fcit", FCIT, "FCIT"); PLANNER("aorrtc", AORRTC, "AORRTC"); + PLANNER("grrtstar", GRRTStar, "GRRTStar"); if constexpr (has_set_lows_v) { diff --git a/src/impl/vamp/bindings/settings.cc b/src/impl/vamp/bindings/settings.cc index c76a0251..a76e4af4 100644 --- a/src/impl/vamp/bindings/settings.cc +++ b/src/impl/vamp/bindings/settings.cc @@ -3,6 +3,7 @@ #include #include #include +#include #include #include @@ -39,6 +40,26 @@ void vamp::binding::init_settings(nanobind::module_ &pymodule) .def_rw("max_cost_bound_resamples", &vp::AORRTCSettings::max_cost_bound_resamples) .def_rw("max_samples", &vp::AORRTCSettings::max_samples); + nb::class_(pymodule, "GRRTStarSettings") + .def(nb::init<>()) + .def_rw("range", &vp::GRRTStarSettings::range) + .def_rw("rewire_factor", &vp::GRRTStarSettings::rewire_factor) + .def_rw("greedy_biasing_ratio", &vp::GRRTStarSettings::greedy_biasing_ratio) + .def_rw("use_k_nearest", &vp::GRRTStarSettings::use_k_nearest) + .def_rw("delay_cc", &vp::GRRTStarSettings::delay_cc) + .def_rw("balanced", &vp::GRRTStarSettings::balanced) + .def_rw("tree_ratio", &vp::GRRTStarSettings::tree_ratio) + .def_rw("use_phs", &vp::GRRTStarSettings::use_phs) + .def_rw("delay_rewiring", &vp::GRRTStarSettings::delay_rewiring) + .def_rw("dynamic_domain", &vp::GRRTStarSettings::dynamic_domain) + .def_rw("dd_radius", &vp::GRRTStarSettings::dd_radius) + .def_rw("dd_alpha", &vp::GRRTStarSettings::dd_alpha) + .def_rw("dd_min_radius", &vp::GRRTStarSettings::dd_min_radius) + .def_rw("tree_pruning", &vp::GRRTStarSettings::tree_pruning) + .def_rw("prune_threshold", &vp::GRRTStarSettings::prune_threshold) + .def_rw("max_iterations", &vp::GRRTStarSettings::max_iterations) + .def_rw("max_samples", &vp::GRRTStarSettings::max_samples); + // TODO: Redesign a neater form of RoadmapSettings/NeighborParams // TODO: Expose the other NeighborParams types nb::class_(pymodule, "PRMNeighborParams") diff --git a/src/impl/vamp/planning/grrtstar.hh b/src/impl/vamp/planning/grrtstar.hh new file mode 100644 index 00000000..c6ab77fe --- /dev/null +++ b/src/impl/vamp/planning/grrtstar.hh @@ -0,0 +1,690 @@ +#pragma once + +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace vamp::planning +{ + template + struct GRRTStar + { + using Configuration = typename Robot::Configuration; + static constexpr auto dimension = Robot::dimension; + using RNG = typename vamp::rng::RNG; + using NNNodeType = NNNode; + using NNTree = NN; + + inline static auto solve( + const Configuration &start, + const Configuration &goal, + const collision::Environment> &environment, + const GRRTStarSettings &settings, + typename RNG::Ptr rng) noexcept -> PlanningResult + { + return solve(start, std::vector{goal}, environment, settings, rng); + } + + inline static auto solve( + const Configuration &start, + const std::vector &goals, + const collision::Environment> &environment, + const GRRTStarSettings &settings, + typename RNG::Ptr rng) noexcept -> PlanningResult + { + PlanningResult result; + + // Check straight-line solution + for (const auto &goal : goals) + { + if (validate_motion(start, goal, environment)) + { + result.path.emplace_back(start); + result.path.emplace_back(goal); + result.cost = start.distance(goal); + result.nanoseconds = 0; + result.iterations = 0; + result.size.emplace_back(1); + result.size.emplace_back(1); + return result; + } + } + + auto start_time = std::chrono::steady_clock::now(); + + NNTree start_tree; + NNTree goal_tree; + + constexpr const std::size_t start_index = 0; + + auto buffer = std::unique_ptr( + vamp::utils::vector_alloc( + settings.max_samples * Configuration::num_scalars_rounded), + &free); + + const auto buffer_index = [&buffer](std::size_t index) -> float * + { return buffer.get() + index * Configuration::num_scalars_rounded; }; + + std::vector parents(settings.max_samples); + std::vector costs(settings.max_samples, std::numeric_limits::max()); + std::vector radii(settings.max_samples); + std::vector> children(settings.max_samples); + std::vector in_start_tree(settings.max_samples, 0); + std::vector pruned(settings.max_samples, 0); + + // Best solution tracking + float best_cost = std::numeric_limits::max(); + float greedy_best_cost = std::numeric_limits::max(); + Path best_path; + + // Heuristic cost lower bound for a node + const auto solution_heuristic = [&](std::size_t idx) -> float + { + Configuration cfg(buffer_index(idx)); + float g_hat = cfg.distance(start); + float h_hat = std::numeric_limits::max(); + for (const auto &goal : goals) + { + h_hat = std::min(h_hat, cfg.distance(goal)); + } + return g_hat + h_hat; + }; + + // Check if a node and ALL its descendants can be pruned + const auto can_prune_branch = [&](const auto &self, std::size_t idx, float threshold) -> bool + { + if (solution_heuristic(idx) < threshold) + { + return false; + } + for (const auto child_idx : children[idx]) + { + if (not pruned[child_idx] and not self(self, child_idx, threshold)) + { + return false; + } + } + return true; + }; + + // Mark a node and all its descendants as pruned + const auto mark_pruned = [&](const auto &self, std::size_t idx) -> void + { + pruned[idx] = 1; + for (const auto child_idx : children[idx]) + { + self(self, child_idx); + } + }; + + // Initialize start node + start.to_array(buffer_index(start_index)); + start_tree.insert(NNNodeType{start_index, {buffer_index(start_index)}}); + parents[start_index] = start_index; + costs[start_index] = 0.F; + radii[start_index] = std::numeric_limits::max(); + in_start_tree[start_index] = 1; + + std::size_t free_index = start_index + 1; + + // Initialize goal nodes + std::vector goal_indices; + goal_indices.reserve(goals.size()); + for (const auto &goal : goals) + { + goal.to_array(buffer_index(free_index)); + goal_tree.insert(NNNodeType{free_index, {buffer_index(free_index)}}); + parents[free_index] = free_index; + costs[free_index] = 0.F; + radii[free_index] = std::numeric_limits::max(); + in_start_tree[free_index] = 0; + goal_indices.push_back(free_index); + free_index++; + } + + // Rebuild a tree from scratch, keeping only unpruned nodes. + const auto rebuild_tree = [&](NNTree &tree, bool is_start) + { + tree.clear(); + for (std::size_t i = 0; i < free_index; ++i) + { + if (not pruned[i] and static_cast(in_start_tree[i]) == is_start) + { + tree.insert(NNNodeType{i, {buffer_index(i)}}); + } + } + }; + + // Prune both trees and rebuild + const auto prune_trees = [&](float threshold) + { + // Mark prunable branches from start tree root + for (const auto child_idx : children[start_index]) + { + if (not pruned[child_idx] and can_prune_branch(can_prune_branch, child_idx, threshold)) + { + mark_pruned(mark_pruned, child_idx); + } + } + + // Mark prunable branches from each goal tree root + for (const auto goal_idx : goal_indices) + { + for (const auto child_idx : children[goal_idx]) + { + if (not pruned[child_idx] and + can_prune_branch(can_prune_branch, child_idx, threshold)) + { + mark_pruned(mark_pruned, child_idx); + } + } + } + + // Rebuild both trees without pruned nodes + rebuild_tree(start_tree, true); + rebuild_tree(goal_tree, false); + }; + + // PHS for informed sampling (single goal only) + bool has_solution = false; + std::unique_ptr> phs_ptr; + std::shared_ptr> phs_rng_ptr; + if (settings.use_phs and goals.size() == 1) + { + phs_ptr = std::make_unique>(start, goals[0]); + phs_rng_ptr = std::make_shared>(*phs_ptr, rng); + } + + // Rewiring constants + // k_rrt > 2^(d+1) * e * (1 + 1/d) + const double dim_d = static_cast(dimension); + const double k_rrt_star = settings.rewire_factor * std::pow(2.0, dim_d + 1.0) * + vamp::utils::constants::e * (1.0 + 1.0 / dim_d); + + // r_rrt > (2*(1+1/d))^(1/d) * (measure/ballvolume)^(1/d) + const double space_measure = Robot::space_measure(); + const double inverse_dim = 1.0 / dim_d; + const double r_rrt_star = + settings.rewire_factor * + std::pow( + 2.0 * (1.0 + 1.0 / dim_d) * (space_measure / utils::unit_ball_measure(dimension)), + inverse_dim); + + // Update descendant costs recursively after rewiring + const auto update_child_costs = + [&](const auto &self, std::size_t node_idx, float cost_delta) -> void + { + for (const auto child_idx : children[node_idx]) + { + costs[child_idx] -= cost_delta; + self(self, child_idx, cost_delta); + } + }; + + // Extract path through a start-side and goal-side connection point + const auto extract_path = [&](std::size_t start_side_node, + std::size_t goal_side_node) -> Path + { + Path path; + + std::vector start_chain; + auto current = start_side_node; + while (parents[current] != current) + { + start_chain.push_back(current); + current = parents[current]; + } + start_chain.push_back(current); + + for (auto it = start_chain.rbegin(); it != start_chain.rend(); ++it) + { + path.emplace_back(buffer_index(*it)); + } + + current = goal_side_node; + while (parents[current] != current) + { + auto parent = parents[current]; + path.emplace_back(buffer_index(parent)); + current = parent; + } + + return path; + }; + + // Sample a configuration (uniform or PHS-informed) + const auto sample = [&]() -> Configuration + { + if (has_solution and settings.use_phs and phs_rng_ptr and goals.size() == 1) + { + float u = rng->dist.uniform_01(); + if (u < settings.greedy_biasing_ratio and greedy_best_cost < best_cost) + { + phs_rng_ptr->phs.set_transverse_diameter(greedy_best_cost); + } + else + { + phs_rng_ptr->phs.set_transverse_diameter(best_cost); + } + + return phs_rng_ptr->next(); + } + + return rng->next(); + }; + + // Trees for balanced bidirectional growth + bool tree_a_is_start = not true; + auto *tree_a = &goal_tree; + auto *tree_b = &start_tree; + + std::size_t iter = 0; + std::vector> neighbors; + neighbors.reserve(settings.max_samples); + + while (iter++ < settings.max_iterations and free_index < settings.max_samples) + { + // Balanced bidirectional tree swapping + float asize = static_cast(tree_a->size()); + float bsize = static_cast(tree_b->size()); + float ratio = std::abs(asize - bsize) / std::max(asize, 1.F); + + if ((not settings.balanced) or ratio < settings.tree_ratio) + { + std::swap(tree_a, tree_b); + tree_a_is_start = not tree_a_is_start; + } + + // Sample + auto temp = sample(); + + // Cost gating + if (has_solution) + { + float g_hat = temp.distance(start); + float h_hat = std::numeric_limits::max(); + for (const auto &goal : goals) + { + h_hat = std::min(h_hat, temp.distance(goal)); + } + float f_hat = g_hat + h_hat; + if (f_hat >= best_cost) + { + continue; + } + } + + // Find nearest in active tree + if (tree_a->size() == 0) + { + continue; + } + + typename Robot::ConfigurationBuffer temp_array; + temp.to_array(temp_array.data()); + + auto nearest_result = tree_a->nearest(NNFloatArray{temp_array.data()}); + if (not nearest_result) + { + continue; + } + + const auto &[nearest_node, nearest_distance] = *nearest_result; + + // Dynamic domain check + if (settings.dynamic_domain and radii[nearest_node.index] < nearest_distance) + { + continue; + } + + const auto nearest_configuration = nearest_node.as_vector(); + auto nearest_vector = temp - nearest_configuration; + + bool reach = nearest_distance < settings.range; + auto extension_vector = + (reach) ? nearest_vector : nearest_vector * (settings.range / nearest_distance); + float extension_distance = reach ? nearest_distance : settings.range; + + // Validate extension edge + if (not validate_vector( + nearest_configuration, extension_vector, extension_distance, environment)) + { + if (settings.dynamic_domain) + { + if (radii[nearest_node.index] == std::numeric_limits::max()) + { + radii[nearest_node.index] = settings.dd_radius; + } + else + { + radii[nearest_node.index] = std::max( + radii[nearest_node.index] * (1.F - settings.dd_alpha), + settings.dd_min_radius); + } + } + continue; + } + + auto new_configuration = nearest_configuration + extension_vector; + float new_cost = costs[nearest_node.index] + extension_distance; + std::size_t best_parent = nearest_node.index; + + // Write config to buffer once (before both parent selection and node addition) + float *new_config_ptr = buffer_index(free_index); + new_configuration.to_array(new_config_ptr); + + // RRT* parent selection and rewiring (skip until first solution if delay_rewiring) + bool do_rewire = not settings.delay_rewiring or has_solution; + + if (do_rewire) + { + // Combined tree cardinality + // cardDbl = tStart_->size() + tGoal_->size() + 1 + const auto card = static_cast(start_tree.size() + goal_tree.size() + 1); + + NNFloatArray new_key{new_config_ptr}; + + // Query neighbors using nigh KD-tree (returns sorted by distance) + neighbors.clear(); + if (settings.use_k_nearest) + { + std::size_t k = static_cast(std::ceil(k_rrt_star * std::log(card))); + tree_a->nearest(neighbors, new_key, k); + } + else + { + float r = static_cast(std::min( + static_cast(settings.range), + r_rrt_star * std::pow(std::log(card) / card, inverse_dim))); + tree_a->nearest(neighbors, new_key, std::numeric_limits::max(), r); + } + + if (settings.delay_cc) + { + pdqsort( + neighbors.begin(), + neighbors.end(), + [&](const auto &a, const auto &b) + { return costs[a.first.index] + a.second < costs[b.first.index] + b.second; }); + + for (const auto &[nbr_node, nbr_dist] : neighbors) + { + float candidate_cost = costs[nbr_node.index] + nbr_dist; + if (candidate_cost >= new_cost) + { + break; + } + + if (settings.use_k_nearest or nbr_dist < settings.range) + { + const auto nbr_config = nbr_node.as_vector(); + if (validate_motion( + nbr_config, new_configuration, environment)) + { + new_cost = candidate_cost; + best_parent = nbr_node.index; + break; + } + } + } + } + else + { + for (const auto &[nbr_node, nbr_dist] : neighbors) + { + float candidate_cost = costs[nbr_node.index] + nbr_dist; + if (candidate_cost < new_cost) + { + const auto nbr_config = nbr_node.as_vector(); + if (validate_motion( + nbr_config, new_configuration, environment)) + { + new_cost = candidate_cost; + best_parent = nbr_node.index; + } + } + } + } + } + + // Tight cost gating: use actual tree cost (after parent selection) + heuristic. + // Placed after parent selection so new_cost reflects the best parent, not just nearest. + if (has_solution) + { + float h_hat; + if (tree_a_is_start) + { + h_hat = std::numeric_limits::max(); + for (const auto &g : goals) + { + h_hat = std::min(h_hat, new_configuration.distance(g)); + } + } + else + { + h_hat = new_configuration.distance(start); + } + + float tight_f = new_cost + h_hat; + if (tight_f >= best_cost) + { + continue; + } + } + + // Add new node (config already written to buffer) + tree_a->insert(NNNodeType{free_index, {new_config_ptr}}); + + parents[free_index] = best_parent; + costs[free_index] = new_cost; + radii[free_index] = std::numeric_limits::max(); + in_start_tree[free_index] = tree_a_is_start ? 1 : 0; + children[best_parent].push_back(free_index); + + const std::size_t new_node_index = free_index; + free_index++; + + // Dynamic domain grow + if (settings.dynamic_domain and + radii[nearest_node.index] != std::numeric_limits::max()) + { + radii[nearest_node.index] *= (1 + settings.dd_alpha); + } + + // Rewiring + if (do_rewire) + { + for (const auto &[nbr_node, nbr_dist] : neighbors) + { + if (nbr_node.index == best_parent) + { + continue; + } + + float nbr_new_cost = new_cost + nbr_dist; + if (nbr_new_cost < costs[nbr_node.index]) + { + bool motion_valid; + if (settings.use_k_nearest or nbr_dist < settings.range) + { + motion_valid = validate_motion( + new_configuration, nbr_node.as_vector(), environment); + } + else + { + motion_valid = false; + } + + if (motion_valid) + { + float cost_delta = costs[nbr_node.index] - nbr_new_cost; + + auto &old_parent_children = children[parents[nbr_node.index]]; + auto it = std::find( + old_parent_children.begin(), old_parent_children.end(), nbr_node.index); + if (it != old_parent_children.end()) + { + *it = old_parent_children.back(); + old_parent_children.pop_back(); + } + + parents[nbr_node.index] = new_node_index; + costs[nbr_node.index] = nbr_new_cost; + children[new_node_index].push_back(nbr_node.index); + + update_child_costs(update_child_costs, nbr_node.index, cost_delta); + } + } + } + } + + // Connect to other tree + if (tree_b->size() == 0) + { + continue; + } + + auto other_result = tree_b->nearest(NNFloatArray{new_config_ptr}); + if (not other_result) + { + continue; + } + + const auto &[other_nearest_node, other_nearest_distance] = *other_result; + + // Check if connection would improve best solution + float connection_cost = new_cost + other_nearest_distance + costs[other_nearest_node.index]; + if (has_solution and connection_cost >= best_cost) + { + continue; + } + + const auto other_nearest_configuration = other_nearest_node.as_vector(); + auto other_nearest_vector = other_nearest_configuration - new_configuration; + + // Extend incrementally toward other tree + const std::size_t n_extensions = std::max( + static_cast(std::ceil(other_nearest_distance / settings.range)), + static_cast(1)); + const float increment_length = other_nearest_distance / static_cast(n_extensions); + auto increment = other_nearest_vector * (1.0F / static_cast(n_extensions)); + + std::size_t i_extension = 0; + auto prior = new_configuration; + for (; i_extension < n_extensions and + validate_vector( + prior, increment, increment_length, environment) and + free_index < settings.max_samples; + ++i_extension) + { + auto next = prior + increment; + float *next_ptr = buffer_index(free_index); + next.to_array(next_ptr); + tree_a->insert(NNNodeType{free_index, {next_ptr}}); + parents[free_index] = free_index - 1; + costs[free_index] = costs[free_index - 1] + increment_length; + radii[free_index] = std::numeric_limits::max(); + in_start_tree[free_index] = tree_a_is_start ? 1 : 0; + children[free_index - 1].push_back(free_index); + + free_index++; + prior = next; + } + + if (i_extension == n_extensions) // connected + { + std::size_t connect_a_node = free_index - 1; + std::size_t connect_b_node = other_nearest_node.index; + + float total_cost = costs[connect_a_node] + costs[connect_b_node]; + + if (total_cost < best_cost) + { + std::size_t start_side_node, goal_side_node; + if (tree_a_is_start) + { + start_side_node = connect_a_node; + goal_side_node = connect_b_node; + } + else + { + start_side_node = connect_b_node; + goal_side_node = connect_a_node; + } + + auto candidate_path = extract_path(start_side_node, goal_side_node); + + if (not candidate_path.empty()) + { + float path_cost = candidate_path.cost(); + if (path_cost < best_cost) + { + bool should_prune = false; + + if (settings.tree_pruning and has_solution) + { + float improvement = (best_cost - path_cost) / best_cost; + if (improvement > settings.prune_threshold) + { + should_prune = true; + } + } + + best_cost = path_cost; + best_path = std::move(candidate_path); + has_solution = true; + + // Compute greedy best cost (max f^ along solution path) + if (settings.use_phs and phs_ptr and goals.size() == 1) + { + greedy_best_cost = 0.F; + for (std::size_t i = 0; i < best_path.size(); ++i) + { + float g_hat = best_path[i].distance(start); + float h_hat = best_path[i].distance(goals[0]); + float f_hat = g_hat + h_hat; + greedy_best_cost = std::max(greedy_best_cost, f_hat); + } + } + + if (should_prune) + { + float prune_cost_threshold = + (settings.greedy_biasing_ratio > 0.5F) ? greedy_best_cost : best_cost; + prune_trees(prune_cost_threshold); + } + } + } + } + } + } + + if (not best_path.empty()) + { + result.path = std::move(best_path); + result.cost = best_cost; + } + + result.nanoseconds = vamp::utils::get_elapsed_nanoseconds(start_time); + result.iterations = iter; + result.size.emplace_back(start_tree.size()); + result.size.emplace_back(goal_tree.size()); + return result; + } + }; +} // namespace vamp::planning diff --git a/src/impl/vamp/planning/grrtstar_settings.hh b/src/impl/vamp/planning/grrtstar_settings.hh new file mode 100644 index 00000000..62b6b9c3 --- /dev/null +++ b/src/impl/vamp/planning/grrtstar_settings.hh @@ -0,0 +1,25 @@ +#pragma once + +namespace vamp::planning +{ + struct GRRTStarSettings + { + float range = 2.; + float rewire_factor = 1.1; + float greedy_biasing_ratio = 0.9; + bool use_k_nearest = true; + bool delay_cc = true; + bool balanced = true; + float tree_ratio = 1.; + bool use_phs = true; + bool delay_rewiring = true; + bool dynamic_domain = true; + float dd_radius = 4.; + float dd_alpha = 0.0001; + float dd_min_radius = 1.; + bool tree_pruning = true; + float prune_threshold = 0.05; + std::size_t max_iterations = 100000; + std::size_t max_samples = 100000; + }; +} // namespace vamp::planning diff --git a/src/vamp/__init__.py b/src/vamp/__init__.py index 2bb88671..032ea17f 100644 --- a/src/vamp/__init__.py +++ b/src/vamp/__init__.py @@ -15,6 +15,7 @@ "FCITSettings", "FCITNeighborParams", "AORRTCSettings", + "GRRTStarSettings", "SimplifySettings", "SimplifyRoutine", "filter_pointcloud", @@ -40,6 +41,7 @@ from ._core import FCITNeighborParams as FCITNeighborParams from ._core import FCITSettings as FCITSettings from ._core import AORRTCSettings as AORRTCSettings +from ._core import GRRTStarSettings as GRRTStarSettings from ._core import SimplifyRoutine as SimplifyRoutine from ._core import SimplifySettings as SimplifySettings from ._core import filter_pointcloud as filter_pointcloud @@ -91,6 +93,11 @@ def configure_robot_and_planner_with_kwargs(robot_name: str, planner_name: str, if robot_name in ROBOT_RRT_RANGES: plan_settings.rrtc.range = ROBOT_RRT_RANGES[robot_name] + elif planner_name == "grrtstar": + plan_settings = GRRTStarSettings() + if robot_name in ROBOT_RRT_RANGES: + plan_settings.range = ROBOT_RRT_RANGES[robot_name] + else: raise NotImplementedError(f"Automatic setup for planner {planner_name} is not implemented yet!")