From 96fbcf86c9f3a4a0fc16534c4d638fa4b49c5cf9 Mon Sep 17 00:00:00 2001 From: A-lamo <2727043@student.vu.nl> Date: Thu, 14 May 2026 14:59:03 +0200 Subject: [PATCH 01/27] First commit --- .claude/wiki/NEAT_Algorithm.md | 83 ++ ... Networks through Augmenting Topologies.md | 17 + .claude/wiki/competing_conventions.md | 37 + .claude/wiki/log.md | 5 + .claude/wiki/neat_speciation.md | 69 ++ examples/c_genotypes/5_body_evolution_cppn.py | 7 +- .../6_body_brain_evolution_cppn.py | 720 ++++++++++++++++++ examples/d_drones/1_hover_evolution.py | 184 +++++ examples/d_drones/2_drone_evolution.py | 201 +++++ examples/d_drones/3_neat_evolution.py | 168 ++++ examples/d_drones/4_simulate_lee_ctrl.py | 243 ++++++ examples/d_drones/5_tune_lee_controller.py | 409 ++++++++++ examples/d_drones/6_train_rl_figure8.py | 251 ++++++ examples/d_drones/7_visualize_genome.py | 233 ++++++ examples/d_drones/8_generate_stl.py | 184 +++++ examples/d_drones/9_repair_demo.py | 199 +++++ examples/d_drones/_ctrl_helpers.py | 89 +++ src/ariel/body_phenotypes/drone/__init__.py | 27 + src/ariel/body_phenotypes/drone/genome.py | 62 ++ src/ariel/body_phenotypes/drone/operations.py | 209 +++++ .../robogen_lite/cppn_neat/genome.py | 270 +++---- .../robogen_lite/decoders/cppn_best_first.py | 143 ++-- 22 files changed, 3564 insertions(+), 246 deletions(-) create mode 100644 .claude/wiki/NEAT_Algorithm.md create mode 100644 .claude/wiki/Source - Evolving Neural Networks through Augmenting Topologies.md create mode 100644 .claude/wiki/competing_conventions.md create mode 100644 .claude/wiki/neat_speciation.md create mode 100644 examples/c_genotypes/6_body_brain_evolution_cppn.py create mode 100644 examples/d_drones/1_hover_evolution.py create mode 100644 examples/d_drones/2_drone_evolution.py create mode 100644 examples/d_drones/3_neat_evolution.py create mode 100644 examples/d_drones/4_simulate_lee_ctrl.py create mode 100644 examples/d_drones/5_tune_lee_controller.py create mode 100644 examples/d_drones/6_train_rl_figure8.py create mode 100644 examples/d_drones/7_visualize_genome.py create mode 100644 examples/d_drones/8_generate_stl.py create mode 100644 examples/d_drones/9_repair_demo.py create mode 100644 examples/d_drones/_ctrl_helpers.py create mode 100644 src/ariel/body_phenotypes/drone/__init__.py create mode 100644 src/ariel/body_phenotypes/drone/genome.py create mode 100644 src/ariel/body_phenotypes/drone/operations.py diff --git a/.claude/wiki/NEAT_Algorithm.md b/.claude/wiki/NEAT_Algorithm.md new file mode 100644 index 000000000..501aea8c7 --- /dev/null +++ b/.claude/wiki/NEAT_Algorithm.md @@ -0,0 +1,83 @@ +--- +type: algorithm_reference +tags: [neat, neuroevolution, cppn, ga, algorithm] +source: https://gwern.net/doc/reinforcement-learning/exploration/2002-stanley.pdf +date_ingested: 2026-05-14 +--- + +# NEAT_Algorithm + +NEAT (NeuroEvolution of Augmenting Topologies) simultaneously evolves the weights *and* topology of neural networks using a genetic algorithm with historical gene markings, speciation, and incremental complexification. It is the algorithm underlying ARIEL's CPPN genome evolution (`src/ariel/body_phenotypes/robogen_lite/cppn_neat/`). + +## Formulation + +### Genome encoding + +Two gene lists per individual: + +``` +Node gene: node_id | type ∈ {input, hidden, output} + +Connection: in_node | out_node | weight | enabled | innovation_number +``` + +`enabled=False` silences a connection without removing it (used after add-node mutations). + +### Innovation numbers (historical markings) + +Every structural mutation receives a globally unique, permanent **innovation number** from a shared counter. If the same structural event occurs in two individuals within one generation, both receive the **same** number. + +Innovation numbers align heterogeneous topologies for crossover without needing explicit topology normalization. + +### Crossover (align by innovation number) + +``` +For each innovation ID in union(parent_A, parent_B): + matching gene → inherit randomly from A or B + disjoint gene → inherit from fitter parent + excess gene → inherit from fitter parent + (equal fitness → inherit from both, randomly) +``` + +### Structural mutations + +| Mutation | Action | New innovation IDs | +|---|---|---| +| Add connection | New enabled edge between two unconnected nodes | 1 | +| Add node | Disable existing edge; insert hidden node; add two new edges (weight=1 in, original weight out) | 2 | + +### Complexification from minimal topology + +All genomes start with direct input→output connections only (no hidden nodes). Hidden structure grows exclusively via add-node mutation. + +## Parameters + +| Name | Default | Role | +|---|---|---| +| `node_add_rate` | 0.2 (ARIEL) | Probability of add-node mutation per call | +| `conn_add_rate` | 0.3 (ARIEL) | Probability of add-connection mutation per call | +| `c1`, `c2`, `c3` | problem-dependent | Coefficients for [[neat_speciation]] compatibility distance | +| `δ_t` | problem-dependent | Speciation compatibility threshold | + +## Implementation Notes + +- **Feed-forward ordering**: use Kahn's topological sort (BFS with in-degree tracking). Raise on cycle detection. See `get_node_ordering()` in [[cppn_neat_genome]]. +- **Recurrent fallback**: if a cycle is detected, fall back to iterative relaxation for `len(nodes) + 1` steps. +- **Cache activation topology**: `incoming_map`, topological order, and input/output ID lists should be cached per genome and invalidated only on structural mutation or connection disable. +- **Innovation ID collisions in parallel runs**: the shared counter assumes single-threaded access; parallelism requires a lock or per-island counters. +- **Fitness in crossover**: the fitter-parent weighting requires that `genome.fitness` is synced from the EA individual's fitness before calling `crossover()`. + +## When to Use + +- When network topology is unknown and should be discovered by evolution rather than fixed by design. +- When starting from a small, fast-to-evaluate network and growing complexity incrementally is preferable to searching a large fixed topology space. +- When meaningful crossover between heterogeneous topologies is required — NEAT's innovation numbers solve the [[competing_conventions]] problem that defeats position-based crossover. + +Prefer fixed-topology neuroevolution (e.g., CMA-ES on weight vectors) when: topology is well-understood, population is large enough to make speciation overhead costly, or strict inference-time constraints make variable graph size problematic. + +## See Also + +- [[neat_speciation]] — speciation mechanics, compatibility distance formula, fitness sharing +- [[competing_conventions]] — the problem NEAT's historical markings solve +- [[cppn_neat_genome]] — ARIEL implementation of this algorithm +- [[CMA-ES_Algorithm]] — alternative optimizer for fixed-topology neuroevolution diff --git a/.claude/wiki/Source - Evolving Neural Networks through Augmenting Topologies.md b/.claude/wiki/Source - Evolving Neural Networks through Augmenting Topologies.md new file mode 100644 index 000000000..489cca4df --- /dev/null +++ b/.claude/wiki/Source - Evolving Neural Networks through Augmenting Topologies.md @@ -0,0 +1,17 @@ +--- +type: source_summary +tags: [source, neat, neuroevolution, cppn, algorithm] +source: https://gwern.net/doc/reinforcement-learning/exploration/2002-stanley.pdf +author: Stanley, K.O. & Miikkulainen, R. +date_ingested: 2026-05-14 +--- + +# Source - Evolving Neural Networks through Augmenting Topologies + +Foundational 2002 paper introducing NEAT — the algorithm used by ARIEL's CPPN genome evolution. Covers genome encoding with innovation numbers, speciation, fitness sharing, and incremental complexification from minimal topologies. + +## Entity Pages Created + +- [[NEAT_Algorithm]] — full algorithm reference: genome encoding, crossover by innovation number, structural mutations, complexification strategy, implementation notes for ARIEL +- [[neat_speciation]] — concept page: compatibility distance formula, fitness sharing, niche pressure, note that ARIEL's current CPPN loop does not implement speciation +- [[competing_conventions]] — concept page: why position-based crossover fails for variable-topology networks, and how innovation numbers resolve it diff --git a/.claude/wiki/competing_conventions.md b/.claude/wiki/competing_conventions.md new file mode 100644 index 000000000..2471b4aa4 --- /dev/null +++ b/.claude/wiki/competing_conventions.md @@ -0,0 +1,37 @@ +--- +type: concept_reference +tags: [neat, neuroevolution, ga, concept, algorithm] +source: https://gwern.net/doc/reinforcement-learning/exploration/2002-stanley.pdf +date_ingested: 2026-05-14 +--- + +# competing_conventions + +The competing conventions problem occurs when crossover is applied to two genomes that encode the same function via *different* network topologies or node orderings. Recombining them produces offspring with contradictory or disrupted weight assignments, making crossover harmful rather than beneficial. + +## Theory + +In a fixed-topology network, position-based crossover works because node i in parent A corresponds to node i in parent B. When topology evolves, two networks may use the same nodes in different roles — there is no consistent positional correspondence. Crossing them at the weight level mixes incompatible representations. + +Example: parent A uses node 3 as a hidden feature detector; parent B uses node 3 as a pass-through. Their offspring inherits node 3's weights from both parents, destroying both parents' solutions. + +This is structurally analogous to the permutation invariance problem in neural network weight space. + +## In Ariel + +[[NEAT_Algorithm]] resolves this via **innovation numbers**: each structural gene (connection or node) carries a globally unique ID assigned at creation time. Crossover aligns genes by innovation number rather than by position, so matching genes always correspond to the same historical structural event. + +Two genes with the same innovation number represent the same structural addition (same edge between the same two conceptual roles), regardless of what other mutations have occurred in each lineage. Genes with no matching partner (disjoint/excess) are inherited from the fitter parent, avoiding destructive mixing from non-corresponding genes. + +This is implemented in `Genome.crossover()` at `src/ariel/body_phenotypes/robogen_lite/cppn_neat/genome.py`. + +## Practical Notes + +- Competing conventions are only a problem when crossover is used *and* topology is variable. If you only mutate (no crossover), the problem does not arise. +- Even with innovation numbers, crossover between very dissimilar topologies (large δ) tends to produce unfit offspring. [[neat_speciation]] addresses this by restricting crossover to individuals within the same species. +- Alternative: abandon crossover entirely for topology-evolving systems and rely on mutation only. Faster per-generation but slower to combine building blocks across lineages. + +## See Also + +- [[NEAT_Algorithm]] — how innovation numbers resolve this problem +- [[neat_speciation]] — species restrict crossover to genetically similar individuals, reducing competing-convention disruption diff --git a/.claude/wiki/log.md b/.claude/wiki/log.md index 48312e1a2..7959f6755 100644 --- a/.claude/wiki/log.md +++ b/.claude/wiki/log.md @@ -1,3 +1,8 @@ +## [2026-05-14] Ingest | Evolving Neural Networks through Augmenting Topologies +- Files created: NEAT_Algorithm.md, neat_speciation.md, competing_conventions.md, Source - Evolving Neural Networks through Augmenting Topologies.md +- Files updated: (none) +- Model: Claude (subscription) + ## [2026-04-13] Ingest | MuJoCo Model Editing - Files created: mujoco_model_editing_c_api.md, mjsBody.md, mjsGeom.md, mjsJoint.md, mjsActuator.md, mjsSensor.md, mujoco_mjspec_enums.md, Source - MuJoCo Model Editing.md - Files updated: MjSpec.md diff --git a/.claude/wiki/neat_speciation.md b/.claude/wiki/neat_speciation.md new file mode 100644 index 000000000..43fe3be68 --- /dev/null +++ b/.claude/wiki/neat_speciation.md @@ -0,0 +1,69 @@ +--- +type: concept_reference +tags: [neat, neuroevolution, ga, algorithm, concept] +source: https://gwern.net/doc/reinforcement-learning/exploration/2002-stanley.pdf +date_ingested: 2026-05-14 +--- + +# neat_speciation + +Speciation in NEAT groups individuals into species by genetic similarity so that new structural mutations are protected from elimination before their weights can be optimized. Each species competes only internally; the global population is partitioned into niches. + +## Theory + +### Compatibility distance + +Two genomes `i` and `j` are assigned to the same species if their compatibility distance δ < δ_t: + +``` +δ = (c1 * E / N) + (c2 * D / N) + (c3 * W̄) + +E = number of excess genes (beyond the range of the shorter genome) +D = number of disjoint genes (gaps within the shared range) +N = number of genes in the larger genome (size normalization) +W̄ = mean weight difference of matching genes +c1, c2, c3 = importance coefficients (problem-dependent) +``` + +For small genomes (N < 20) the paper recommends N = 1 (no normalization). + +### Fitness sharing (niche pressure) + +Each individual's fitness is divided by the number of species-mates to prevent any one species from dominating offspring allocation: + +``` +f'_i = f_i / Σ_j sh(δ(i, j)) + +sh(δ) = 1 if δ < δ_t +sh(δ) = 0 otherwise +``` + +Species are allocated offspring in proportion to their **total adjusted fitness** (sum of `f'_i` within the species). + +### Representative-based assignment + +Each species keeps one **representative** genome (typically the previous generation's champion). New genomes are assigned to the first species whose representative is within δ_t; if none match, a new species is created. + +## In Ariel + +ARIEL's current CPPN evolution (`src/ariel/body_phenotypes/robogen_lite/cppn_neat/`, `examples/c_genotypes/5_body_evolution_cppn.py`) does **not** implement speciation. The `CPPNEvolution` class uses a flat tournament-style parent selection (top 50% by fitness) with no niche protection. + +This means new structural mutations in ARIEL are not shielded from selection pressure — a known limitation. Adding speciation would require: +1. A compatibility distance function over `Genome` objects. +2. A species registry with representatives. +3. Per-species offspring quotas in `reproduction()`. + +See [[NEAT_Algorithm]] for the crossover mechanics that speciation coordinates with. + +## Practical Notes + +- δ_t typically requires hand-tuning: too low → too many micro-species (slows convergence), too high → no protection for innovations. +- c1 = c2 = 1.0, c3 = 0.4 is a common starting point from the original paper; W̄ carries less signal than topology differences. +- Species with stagnating max fitness for N generations are typically culled (not part of the original paper formulation but standard in practice). +- Fitness sharing reduces effective selection pressure — compensate by raising raw population size or number of generations. + +## See Also + +- [[NEAT_Algorithm]] — full algorithm including crossover and mutation operators +- [[competing_conventions]] — the problem speciation + historical markings jointly solve +- [[cppn_neat_genome]] — ARIEL genome class where speciation would be added diff --git a/examples/c_genotypes/5_body_evolution_cppn.py b/examples/c_genotypes/5_body_evolution_cppn.py index 1aab58f10..eac66fc14 100644 --- a/examples/c_genotypes/5_body_evolution_cppn.py +++ b/examples/c_genotypes/5_body_evolution_cppn.py @@ -3,8 +3,6 @@ as the tree-based example. Decodes CPPNs into module graphs using the best-first decoder and evaluates with MorphologicalMeasures. """ -from __future__ import annotations - import argparse import copy import random @@ -26,7 +24,6 @@ from ariel.body_phenotypes.robogen_lite.decoders.cppn_best_first import ( MorphologyDecoderBestFirst, ) -from ariel.body_phenotypes.robogen_lite.decoders.score_cube import MorphologyDecoderCubePruning from ariel.body_phenotypes.robogen_lite.config import ( NUM_OF_ROTATIONS, NUM_OF_TYPES_OF_MODULES, @@ -178,13 +175,15 @@ def reproduction(self, population: Population) -> Population: parents = [ind for ind in population if ind.tags.get("ps", False)] if not parents: parents = population - new_offspring: List[Individual] = [] + new_offspring: list[Individual] = [] target_pool = self.config.target_population_size * 2 while len(population) + len(new_offspring) < target_pool: if len(parents) >= 2 and RNG.random() < 0.5: p1, p2 = random.sample(parents, 2) g1 = Genome.from_dict(p1.genotype["cppn"]) if isinstance(p1.genotype["cppn"], dict) else p1.genotype["cppn"] + g1.fitness = p1.fitness if p1.fitness is not None else 0.0 g2 = Genome.from_dict(p2.genotype["cppn"]) if isinstance(p2.genotype["cppn"], dict) else p2.genotype["cppn"] + g2.fitness = p2.fitness if p2.fitness is not None else 0.0 child = self.crossover(g1, g2) else: parent = random.choice(parents) diff --git a/examples/c_genotypes/6_body_brain_evolution_cppn.py b/examples/c_genotypes/6_body_brain_evolution_cppn.py new file mode 100644 index 000000000..cb6837125 --- /dev/null +++ b/examples/c_genotypes/6_body_brain_evolution_cppn.py @@ -0,0 +1,720 @@ +""" +Joint CPPN-morphology + brain-learning evolution (multiprocessing). + +Builds on 5_body_evolution_cppn.py (CPPN-NEAT body genetics) and +4_body_brain_joint_evolution_tree_nn_learning_multiprocessing.py (brain learning). + +Fitness = -(loco_weight * locomotion_score + morpho_weight * morpho_score) +Lower fitness is better. +""" + +import json +import multiprocessing as mp +import os +import random +import sys +import time +import warnings +import argparse +from concurrent.futures import ProcessPoolExecutor, as_completed +from pathlib import Path + +import mujoco +import mujoco.viewer +import nevergrad as ng +import numpy as np +import torch +from rich.console import Console +from rich.progress import track +from rich.traceback import install +from torch import nn + +from ariel.body_phenotypes.robogen_lite.config import NUM_OF_ROTATIONS, NUM_OF_TYPES_OF_MODULES +from ariel.body_phenotypes.robogen_lite.constructor import construct_mjspec_from_graph +from ariel.body_phenotypes.robogen_lite.cppn_neat.genome import Genome +from ariel.body_phenotypes.robogen_lite.cppn_neat.id_manager import IdManager +from ariel.body_phenotypes.robogen_lite.decoders.cppn_best_first import MorphologyDecoderBestFirst +from ariel.ec import EA, EAOperation, EASettings, Individual, Population +from ariel.simulation.controllers.controller import Controller, Tracker +from ariel.simulation.controllers.utils.data_get import get_state_from_data +from ariel.simulation.environments import SimpleFlatWorld +from ariel.simulation.environments._simple_flat_with_target import SimpleFlatWorldWithTarget +from ariel.utils.morphological_descriptor import MorphologicalMeasures +from ariel.utils.video_recorder import VideoRecorder + +install() +console = Console() + +warnings.filterwarnings( + "ignore", + message="TPA: apparent inconsistency", + category=UserWarning, + module="cma", +) + +parser = argparse.ArgumentParser(description="CPPN body + brain joint evolution (multiprocessing)") +parser.add_argument("--bud", type=int, default=10, help="Morphology generations") +parser.add_argument("--pop", type=int, default=10, help="Morphology population") +parser.add_argument("--dur", type=float, default=5.0, help="Active control duration (s)") +parser.add_argument( + "--eval-delay", + type=float, + default=2.0, + help="No-control warm-up seconds before scoring (minimum enforced: 2.0)", +) +parser.add_argument( + "--z-penalty-weight", + type=float, + default=2.0, + help="Penalty weight for vertical (z-axis) motion during active control", +) +parser.add_argument("--learn-bud", type=int, default=10, help="CMA iterations per morphology") +parser.add_argument("--learn-pop", type=int, default=10, help="CMA population per iteration") +parser.add_argument( + "--eval-workers", + type=int, + default=max(1, os.cpu_count() or 1), + help="Worker processes for parallel individual evaluation", +) +parser.add_argument("--max-modules", type=int, default=15, help="Max CPPN-decoded modules") +parser.add_argument( + "--loco-weight", + type=float, + default=0.7, + help="Weight for locomotion score in combined fitness", +) +parser.add_argument( + "--morpho-weight", + type=float, + default=0.3, + help="Weight for morphological score in combined fitness", +) +parser.add_argument( + "--visualize", + action=argparse.BooleanOptionalAction, + default=True, + help="Visualize the final best individual", +) +parser.add_argument( + "--save-video", + action=argparse.BooleanOptionalAction, + default=True, + help="Save a video of the final best individual", +) +parser.add_argument("--video-duration", type=float, default=10.0, help="Duration of saved video (s)") +args = parser.parse_args() + +POP_SIZE = args.pop +BUDGET = args.bud +DURATION = args.dur +EVAL_DELAY = max(2.0, args.eval_delay) +Z_PENALTY_WEIGHT = max(0.0, args.z_penalty_weight) +LEARN_BUDGET = args.learn_bud +LEARN_POP = args.learn_pop +EVAL_WORKERS = max(1, min(args.eval_workers, POP_SIZE)) +NUM_MODULES = args.max_modules +LOCO_WEIGHT = args.loco_weight +MORPHO_WEIGHT = args.morpho_weight + +SEED = 42 +RNG = np.random.default_rng(SEED) +torch.manual_seed(SEED) +random.seed(SEED) + +SCRIPT_NAME = Path(__file__).stem +DATA = Path.cwd() / "__data__" / SCRIPT_NAME +DATA.mkdir(exist_ok=True, parents=True) + +SPAWN_POSITION = (-0.8, 0.0, 0.1) +TARGET_POSITION = np.array([2.0, 0.0, 0.1], dtype=np.float32) + +T = NUM_OF_TYPES_OF_MODULES +R = NUM_OF_ROTATIONS +NUM_CPPN_INPUTS = 6 +NUM_CPPN_OUTPUTS = 1 + T + R + +id_manager = IdManager( + node_start=NUM_CPPN_INPUTS + NUM_CPPN_OUTPUTS - 1, + innov_start=(NUM_CPPN_INPUTS * NUM_CPPN_OUTPUTS) - 1, +) + + +# --------------------------------------------------------------------------- +# Brain network (identical to example 4) +# --------------------------------------------------------------------------- + +class Network(nn.Module): + def __init__(self, input_size: int, output_size: int, hidden_size: int = 16) -> None: + super().__init__() + self.fc1 = nn.Linear(input_size, hidden_size) + self.fc2 = nn.Linear(hidden_size, hidden_size) + self.fc_out = nn.Linear(hidden_size, output_size) + self.hidden_activation = nn.ELU() + self.output_activation = nn.Tanh() + for p in self.parameters(): + p.requires_grad = False + + @torch.inference_mode() + def forward(self, model, data): + robot_state = get_state_from_data(data) + phase_inputs = np.array( + [ + 2.0 * np.sin(data.time * 2.0 * np.pi), + 2.0 * np.cos(data.time * 2.0 * np.pi), + ], + dtype=np.float32, + ) + state = torch.tensor( + np.concatenate([robot_state, phase_inputs]).astype(np.float32), + dtype=torch.float32, + ) + x = self.hidden_activation(self.fc1(state)) + x = self.hidden_activation(self.fc2(x)) + x = self.output_activation(self.fc_out(x)) * (torch.pi / 2) + return x.detach().numpy() + + +@torch.no_grad() +def fill_parameters(net: nn.Module, vector: np.ndarray | list[float]) -> None: + address = 0 + for p in net.parameters(): + d = p.data.view(-1) + n = len(d) + d[:] = torch.as_tensor(vector[address: address + n], device=d.device) + address += n + + +# --------------------------------------------------------------------------- +# Morphological fitness (static, no simulation) +# --------------------------------------------------------------------------- + +def _morpho_score_from_graph(graph) -> float: + try: + m = MorphologicalMeasures(graph) + return ( + m.symmetry * 0.20 + + m.joints * 0.20 + + m.branching * 0.20 + + m.length_of_limbs * 0.20 + + m.module_diversity * 0.20 + ) + except Exception: + return 0.0 + + +# --------------------------------------------------------------------------- +# CPPN spawn helper (decode + collision-correction fallback) +# --------------------------------------------------------------------------- + +def _spawn_with_fallback( + genome_dict: dict, + position: tuple[float, float, float], +) -> tuple[SimpleFlatWorld, mujoco.MjModel, mujoco.MjData]: + def _build(correct_collision_with_floor: bool) -> tuple[SimpleFlatWorld, mujoco.MjModel, mujoco.MjData]: + genome = Genome.from_dict(genome_dict) + graph = MorphologyDecoderBestFirst(genome, NUM_MODULES).decode() + if graph.number_of_nodes() == 0: + raise ValueError("Empty CPPN decoded graph") + spec = construct_mjspec_from_graph(graph).spec + world = SimpleFlatWorld() + world.spawn(spec, position=position, correct_collision_with_floor=correct_collision_with_floor) + model = world.spec.compile() + data = mujoco.MjData(model) + return world, model, data + + try: + return _build(True) + except Exception: + return _build(False) + + +# --------------------------------------------------------------------------- +# Brain learning inner loop (runs inside worker process) +# --------------------------------------------------------------------------- + +def _learn_brain_for_genome( + genome_dict: dict, + duration: float, + eval_delay: float, + learn_budget: int, + learn_pop: int, + target_position: np.ndarray, + z_penalty_weight: float, +) -> tuple[float, float, list[float], list[float]]: + """Returns (loco_score, morpho_score, best_weight_vec, iteration_scores). + + loco_score and morpho_score are raw un-weighted values. + """ + # Static morpho score — decode once upfront + morpho_score = 0.0 + try: + _g = Genome.from_dict(genome_dict) + _graph = MorphologyDecoderBestFirst(_g, NUM_MODULES).decode() + if _graph.number_of_nodes() > 0: + morpho_score = _morpho_score_from_graph(_graph) + except Exception: + pass + + # Spawn simulation (decodes again inside, with fallback) + try: + world, model, data = _spawn_with_fallback(genome_dict, SPAWN_POSITION) + except Exception: + return -float("inf"), morpho_score, [], [] + + if model.nu == 0: + return -float("inf"), morpho_score, [], [] + + net = Network( + input_size=len(get_state_from_data(data)) + 2, + output_size=model.nu, + hidden_size=16, + ) + num_params = sum(p.numel() for p in net.parameters()) + + min_lambda = 4 + int(3 * np.log(max(num_params, 2))) + learn_pop = max(learn_pop, min_lambda) + if learn_pop % 2 != 0: + learn_pop += 1 + + param = ng.p.Array(shape=(num_params,)).set_mutation(sigma=0.5) + learner = ng.optimizers.registry["CMA"]( + parametrization=param, + budget=learn_budget * learn_pop, + num_workers=learn_pop, + ) + + tracker = Tracker(name_to_bind="core", observable_attributes=["xpos"], quiet=True) + tracker.setup(world.spec, data) + controller = Controller(controller_callback_function=net.forward, tracker=tracker) + + best_loco = -float("inf") + best_vec: list[float] = [] + iteration_scores: list[float] = [] + + for _ in range(learn_budget): + candidates = [learner.ask() for _ in range(learn_pop)] + iter_best = -float("inf") + for candidate in candidates: + vec = candidate.value + fill_parameters(net, vec) + + mujoco.mj_resetData(model, data) + if eval_delay > 0.0: + delay_steps = int(eval_delay / model.opt.timestep) + for _ in range(max(0, delay_steps)): + data.ctrl[:] = 0.0 + mujoco.mj_step(model, data) + + dist_start = float(np.linalg.norm(target_position - data.qpos[0:3])) + z_ref = float(data.qpos[2]) + z_dev_accum = 0.0 + active_steps = max(1, int(duration / model.opt.timestep)) + for _ in range(active_steps): + controller.set_control(model, data) + mujoco.mj_step(model, data) + z_dev_accum += abs(float(data.qpos[2]) - z_ref) + + dist_end = float(np.linalg.norm(target_position - data.qpos[0:3])) + progress = dist_start - dist_end + z_penalty = z_dev_accum / active_steps + score = progress - (z_penalty_weight * z_penalty) + + learner.tell(candidate, -score) + if score > best_loco: + best_loco = score + best_vec = vec.tolist() + if score > iter_best: + iter_best = score + + iteration_scores.append(iter_best) + + return best_loco, morpho_score, best_vec, iteration_scores + + +def _evaluate_individual_process( + task: tuple[dict, float, float, int, int, float, float, float], +) -> tuple[float, list[float], list[float]]: + genome_dict, duration, eval_delay, learn_budget, learn_pop, z_penalty_weight, loco_weight, morpho_weight = task + try: + loco_score, morpho_score, best_vec, iteration_scores = _learn_brain_for_genome( + genome_dict, + duration, + eval_delay, + learn_budget, + learn_pop, + TARGET_POSITION, + z_penalty_weight, + ) + + if not np.isfinite(loco_score): + return float("inf"), [], [] + + combined = loco_weight * loco_score + morpho_weight * morpho_score + fit = -combined if np.isfinite(combined) else float("inf") + + deltas: list[float] = [] + prev = 0.0 + for s in iteration_scores: + deltas.append(s - prev) + prev = s + + return fit, best_vec, deltas + except Exception: + return float("inf"), [], [] + + +# --------------------------------------------------------------------------- +# Evolution class +# --------------------------------------------------------------------------- + +class CPPNBrainEvolution: + def __init__(self) -> None: + self.config = EASettings( + is_maximisation=False, + num_steps=BUDGET, + target_population_size=POP_SIZE, + output_folder=DATA, + db_file_name=f"database_{int(time.time())}.db", + db_handling="delete", + ) + + # --- Genome helpers ----------------------------------------------------- + + def _create_random_genome(self) -> Genome: + g = Genome.random( + num_inputs=NUM_CPPN_INPUTS, + num_outputs=NUM_CPPN_OUTPUTS, + next_node_id=(NUM_CPPN_INPUTS + NUM_CPPN_OUTPUTS), + next_innov_id=0, + ) + for _ in range(3): + g.mutate(0.6, 0.6, id_manager.get_next_innov_id, id_manager.get_next_node_id) + return g + + def _mutate(self, genome: Genome) -> Genome: + g = genome.copy() + g.mutate(0.2, 0.3, id_manager.get_next_innov_id, id_manager.get_next_node_id) + return g + + def _crossover(self, a: Genome, b: Genome) -> Genome: + return a.crossover(b, is_maximisation=False) + + # --- EA operations ------------------------------------------------------ + + def create_individual(self) -> Individual: + ind = Individual() + ind.genotype = {"cppn": self._create_random_genome().to_dict()} + ind.tags = {"ps": False, "valid": True, "last_brain": [], "learning_deltas": []} + return ind + + def parent_selection(self, population: Population) -> Population: + population = population.sort(sort="min", attribute="fitness_") + cutoff = len(population) // 2 + for i, ind in enumerate(population): + ind.tags["ps"] = i < cutoff + return population + + def reproduction(self, population: Population) -> Population: + parents = [ind for ind in population if ind.tags.get("ps", False)] + if not parents: + parents = list(population) + + offspring: list[Individual] = [] + target_pool = self.config.target_population_size * 2 + + while len(population) + len(offspring) < target_pool: + if len(parents) >= 2 and RNG.random() < 0.5: + p1, p2 = random.sample(parents, 2) + g1 = Genome.from_dict(p1.genotype["cppn"]) + g1.fitness = p1.fitness if p1.fitness is not None else 0.0 + g2 = Genome.from_dict(p2.genotype["cppn"]) + g2.fitness = p2.fitness if p2.fitness is not None else 0.0 + child_genome = self._crossover(g1, g2) + else: + parent = random.choice(parents) + child_genome = Genome.from_dict(parent.genotype["cppn"]) + + child_genome = self._mutate(child_genome) + ind = Individual() + ind.genotype = {"cppn": child_genome.to_dict()} + ind.tags = {"ps": False, "valid": True, "last_brain": [], "learning_deltas": []} + ind.requires_eval = True + offspring.append(ind) + + population.extend(offspring) + return population + + def evaluate(self, population: Population) -> Population: + to_eval = [ + ind for ind in population + if ind.alive and ind.tags.get("valid") and ind.requires_eval + ] + if not to_eval: + return population + + tasks = [ + ( + ind.genotype["cppn"], + DURATION, + EVAL_DELAY, + LEARN_BUDGET, + LEARN_POP, + Z_PENALTY_WEIGHT, + LOCO_WEIGHT, + MORPHO_WEIGHT, + ) + for ind in to_eval + ] + + if EVAL_WORKERS == 1: + for ind, task in track( + zip(to_eval, tasks), total=len(to_eval), description="Learning + Evaluating..." + ): + fit, best_vec, deltas = _evaluate_individual_process(task) + ind.fitness = fit + ind.tags["last_brain"] = best_vec + ind.tags["learning_deltas"] = deltas + ind.requires_eval = False + return population + + ctx = mp.get_context("spawn") + with ProcessPoolExecutor(max_workers=EVAL_WORKERS, mp_context=ctx) as executor: + future_to_ind = { + executor.submit(_evaluate_individual_process, task): ind + for ind, task in zip(to_eval, tasks) + } + for fut in as_completed(future_to_ind): + ind = future_to_ind[fut] + try: + fit, best_vec, deltas = fut.result() + except Exception: + fit, best_vec, deltas = float("inf"), [], [] + ind.fitness = fit + ind.tags["last_brain"] = best_vec + ind.tags["learning_deltas"] = deltas + ind.requires_eval = False + + return population + + def survivor_selection(self, population: Population) -> Population: + population = population.sort(sort="min", attribute="fitness_") + survivors = population[: self.config.target_population_size] + for ind in population: + if ind not in survivors: + ind.alive = False + + finite = [ + ind.fitness_ + for ind in survivors + if ind.fitness_ is not None and np.isfinite(ind.fitness_) + ] + if finite: + console.log( + "[green]Survivors:[/green] " + f"avg={np.mean(finite):.3f}, min={np.min(finite):.3f}, max={np.max(finite):.3f}", + ) + return population + + # --- Post-evolution visualization / video -------------------------------- + + def _decode_best(self, best: Individual) -> tuple[mujoco.MjModel, mujoco.MjData, object, object]: + """Decode best individual for visualization. Uses SimpleFlatWorldWithTarget.""" + cppn = Genome.from_dict(best.genotype["cppn"]) + graph = MorphologyDecoderBestFirst(cppn, NUM_MODULES).decode() + if graph.number_of_nodes() == 0: + raise ValueError("Empty graph for best individual") + spec = construct_mjspec_from_graph(graph).spec + world = SimpleFlatWorldWithTarget() + world.spawn(spec, position=SPAWN_POSITION) + model = world.spec.compile() + data = mujoco.MjData(model) + return world, model, data + + def run_best(self, best: Individual, duration: float = 10.0) -> None: + mujoco.set_mjcb_control(None) + try: + try: + world, model, data = self._decode_best(best) + except Exception as exc: + console.log(f"[red]Could not decode best morphology: {exc}[/red]") + return + + if model.nu == 0: + console.log("[red]No actuators on best morphology.[/red]") + return + + net = Network( + input_size=len(get_state_from_data(data)) + 2, + output_size=model.nu, + hidden_size=16, + ) + brain_vec = best.tags.get("last_brain", []) + if brain_vec: + fill_parameters(net, brain_vec) + + tracker = Tracker(name_to_bind="core", observable_attributes=["xpos"], quiet=True) + tracker.setup(world.spec, data) + controller = Controller(controller_callback_function=net.forward, tracker=tracker) + + mujoco.mj_resetData(model, data) + total_duration = duration + EVAL_DELAY + + if sys.platform == "darwin" or not hasattr(mujoco.viewer, "launch_passive"): + console.log("[yellow]Using active MuJoCo viewer fallback.[/yellow]") + console.log("[yellow]Close the viewer window to continue.[/yellow]") + + def _delayed_control(model, data): + if data.time < EVAL_DELAY: + data.ctrl[:] = 0.0 + return + controller.set_control(model, data) + + mujoco.set_mjcb_control(_delayed_control) + mujoco.viewer.launch(model=model, data=data) + return + + with mujoco.viewer.launch_passive(model, data) as v: + sim_start = time.time() + while v.is_running() and (time.time() - sim_start) < total_duration: + step_start = time.time() + if data.time < EVAL_DELAY: + data.ctrl[:] = 0.0 + else: + controller.set_control(model, data) + mujoco.mj_step(model, data) + v.sync() + remaining = model.opt.timestep - (time.time() - step_start) + if remaining > 0: + time.sleep(remaining) + finally: + mujoco.set_mjcb_control(None) + + def save_best_video(self, best: Individual, duration: float = 10.0) -> None: + mujoco.set_mjcb_control(None) + try: + try: + world, model, data = self._decode_best(best) + except Exception as exc: + console.log(f"[red]Could not decode best morphology for video: {exc}[/red]") + return + + if model.nu == 0: + console.log("[red]No actuators on best morphology (video skipped).[/red]") + return + + net = Network( + input_size=len(get_state_from_data(data)) + 2, + output_size=model.nu, + hidden_size=16, + ) + brain_vec = best.tags.get("last_brain", []) + if brain_vec: + fill_parameters(net, brain_vec) + + tracker = Tracker(name_to_bind="core", observable_attributes=["xpos"], quiet=True) + tracker.setup(world.spec, data) + controller = Controller(controller_callback_function=net.forward, tracker=tracker) + + videos_dir = DATA / "videos" + videos_dir.mkdir(exist_ok=True, parents=True) + video_recorder = VideoRecorder(file_name="best_individual", output_folder=videos_dir) + + mujoco.mj_resetData(model, data) + total_duration = duration + EVAL_DELAY + steps_per_frame = max(1, int(round(1.0 / (model.opt.timestep * video_recorder.fps)))) + + with mujoco.Renderer( + model, + width=video_recorder.width, + height=video_recorder.height, + ) as renderer: + while data.time < total_duration: + for _ in range(steps_per_frame): + if data.time < EVAL_DELAY: + data.ctrl[:] = 0.0 + else: + controller.set_control(model, data) + mujoco.mj_step(model, data) + if data.time >= total_duration: + break + renderer.update_scene(data) + video_recorder.write(renderer.render()) + + video_recorder.release() + console.log(f"[green]Saved best-individual video to {videos_dir}[/green]") + finally: + mujoco.set_mjcb_control(None) + + # --- Main evolution loop ------------------------------------------------ + + def evolve(self) -> Individual | None: + console.log("Initializing CPPN population...") + population = Population([self.create_individual() for _ in range(POP_SIZE)]) + population = self.evaluate(population) + + ops = [ + EAOperation(self.parent_selection), + EAOperation(self.reproduction), + EAOperation(self.evaluate), + EAOperation(self.survivor_selection), + ] + + ea = EA( + population, + operations=ops, + num_steps=BUDGET, + db_file_path=self.config.db_file_path, + db_handling=self.config.db_handling, + quiet=self.config.quiet, + ) + ea.run() + return ea.get_solution("best", only_alive=False) + + +# --------------------------------------------------------------------------- +# Entry point +# --------------------------------------------------------------------------- + +def main() -> None: + console.rule("[bold magenta]CPPN Body + Brain Joint Evolution (Multiprocessing)[/bold magenta]") + console.log( + f"Pop={POP_SIZE}, Gens={BUDGET}, LearnBudget={LEARN_BUDGET}, LearnPop={LEARN_POP}, " + f"EvalWorkers={EVAL_WORKERS}, Dur={DURATION}s, Delay={EVAL_DELAY}s, " + f"ZPenalty={Z_PENALTY_WEIGHT}, LocoW={LOCO_WEIGHT}, MorphoW={MORPHO_WEIGHT}", + ) + + evo = CPPNBrainEvolution() + start = time.time() + best = evo.evolve() + elapsed = time.time() - start + + if best is None: + console.log("[red]No best individual found.[/red]") + return + + best_cppn = Genome.from_dict(best.genotype["cppn"]) + best_graph = MorphologyDecoderBestFirst(best_cppn, NUM_MODULES).decode() + best_brain = best.tags.get("last_brain", []) + timestamp = int(time.time()) + + genome_path = DATA / f"best_cppn_genome_{timestamp}.json" + brain_path = DATA / f"best_brain_{timestamp}.npy" + genome_path.write_text(json.dumps(best_cppn.to_dict(), indent=2), encoding="utf-8") + np.save(brain_path, np.asarray(best_brain, dtype=np.float32)) + + console.rule("[bold green]Final Best[/bold green]") + console.log(f"Best combined fitness: {best.fitness:.4f}") + console.log(f"Elapsed: {elapsed:.2f}s") + console.log(f"Modules decoded: {best_graph.number_of_nodes()}") + console.log(f"Saved CPPN genome to: {genome_path}") + console.log(f"Saved brain to: {brain_path}") + + if args.save_video: + evo.save_best_video(best, duration=args.video_duration) + + if args.visualize: + evo.run_best(best, duration=10.0) + + +if __name__ == "__main__": + main() diff --git a/examples/d_drones/1_hover_evolution.py b/examples/d_drones/1_hover_evolution.py new file mode 100644 index 000000000..be5a6cebe --- /dev/null +++ b/examples/d_drones/1_hover_evolution.py @@ -0,0 +1,184 @@ +"""Drone morphology evolution using ARIEL's EA engine and airevolve's drone simulator. + +Evolves drone arm configurations (number, position, orientation, spin direction) +to maximise hover quality (continuous_hover_fitness ∈ [0, 3]) using a mu+lambda +strategy with NEAT-style crossover. + +The simulation backend is airevolve's custom ODE dynamics — no MuJoCo involved. +Genomes are persisted in SQLite via ARIEL's EA engine. + +Run: + python examples/d_drones/1_hover_evolution.py + python examples/d_drones/1_hover_evolution.py --pop 30 --budget 50 --workers 8 + python examples/d_drones/1_hover_evolution.py --fitness gate --workers 4 +""" + +from __future__ import annotations + +import argparse +import os +from pathlib import Path + +import numpy as np +from rich.console import Console + +# BLAS thread caps must be set before numpy/torch are imported in sub-processes. +os.environ.setdefault("OMP_NUM_THREADS", "1") +os.environ.setdefault("OPENBLAS_NUM_THREADS", "1") +os.environ.setdefault("MKL_NUM_THREADS", "1") + +from airevolve.evolution_tools.genome_handlers.spherical_angular_genome_handler import ( + SphericalAngularDroneGenomeHandler, +) +from ariel.body_phenotypes.drone import ( + crossover_drones, + deserialize_genome, + evaluate_drones, + initialize_drones, + mutate_drones, + parent_tag, + truncation_select, +) +from ariel.ec import EA, EASettings, Individual, Population +from ariel.ec.archive import Archive + +console = Console() + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +parser = argparse.ArgumentParser(description="Drone hover-quality evolution") +parser.add_argument("--pop", type=int, default=50, help="Population size (mu)") +parser.add_argument("--budget", type=int, default=50, help="Number of EA generations") +parser.add_argument("--workers", type=int, default=1, help="Parallel evaluation workers") +parser.add_argument("--min-arms", type=int, default=3, help="Minimum number of rotor arms") +parser.add_argument("--max-arms", type=int, default=8, help="Maximum number of rotor arms") +parser.add_argument( + "--fitness", + choices=["pure_hover", "edit_distance", "zero"], + default="pure_hover", + help="Fitness function (pure_hover: analytical hover quality [0,3])", +) +parser.add_argument("--seed", type=int, default=42) +args = parser.parse_args() + +POP_SIZE: int = args.pop +BUDGET: int = args.budget +N_WORKERS: int = args.workers +FITNESS_MODE: str = args.fitness + +DATA = Path.cwd() / "__data__" / "drone_hover_evolution" +DATA.mkdir(parents=True, exist_ok=True) + +np.random.seed(args.seed) + +# --------------------------------------------------------------------------- +# Genome search space +# --------------------------------------------------------------------------- +# Columns: [magnitude, arm_azimuth, arm_elevation, motor_azimuth, motor_pitch, spin_dir] + +PARAMETER_LIMITS = np.array([ + [0.055, 0.17], # arm magnitude (metres from centre) + [-np.pi, np.pi], # arm azimuth (rad) + [-np.pi / 2, np.pi / 2], # arm elevation above horizontal (rad) + [-np.pi, np.pi], # motor disc azimuth (rad) + [-np.pi, np.pi], # motor disc pitch (rad) + [0, 1], # propeller spin direction (binary) +]) + +template_handler = SphericalAngularDroneGenomeHandler( + min_max_narms=(args.min_arms, args.max_arms), + parameter_limits=PARAMETER_LIMITS, + append_arm_chance=0.1, + bilateral_plane_for_symmetry=None, + repair=False, + rnd=np.random.default_rng(args.seed), +) + +# --------------------------------------------------------------------------- +# Pre-loop: build and evaluate the initial population outside the EA loop so +# that parent_tag and crossover_drones have valid fitnesses from generation 1. +# --------------------------------------------------------------------------- + +console.rule("[bold blue]Drone Hover Evolution") +console.log(f"pop={POP_SIZE} budget={BUDGET} workers={N_WORKERS} fitness={FITNESS_MODE}") +console.log(f"arms=[{args.min_arms}, {args.max_arms}] db={DATA / 'database.db'}") + +initial_pop = Population([Individual() for _ in range(POP_SIZE)]) + +init_op = initialize_drones(template_handler=template_handler) +eval_op = evaluate_drones(fitness_mode=FITNESS_MODE, n_workers=N_WORKERS) + +console.log("Initializing and evaluating initial population …") +initial_pop = init_op(initial_pop) +initial_pop = eval_op(initial_pop) + +best_init = initial_pop.best(sort="max", attribute="fitness_")[0] +console.log(f"Initial population best fitness: {best_init.fitness_:.4f}") + +# --------------------------------------------------------------------------- +# EA loop: mu+lambda strategy with NEAT crossover +# +# Each generation: +# 1. tag top-POP_SIZE alive individuals as parents +# 2. crossover: one child per parent pair (POP_SIZE // 2 offspring) +# 3. mutate: perturb all unevaluated offspring +# 4. evaluate: run drone physics for unevaluated individuals only +# 5. select: keep best POP_SIZE from parents + offspring (plus strategy) +# --------------------------------------------------------------------------- + +generation_ops = [ + parent_tag(n=POP_SIZE), + crossover_drones(template_handler=template_handler), + mutate_drones(template_handler=template_handler), + evaluate_drones(fitness_mode=FITNESS_MODE, n_workers=N_WORKERS), + truncation_select(n=POP_SIZE), +] + +ea = EA( + population=initial_pop, + operations=generation_ops, + num_steps=BUDGET, + db_file_path=DATA / "database.db", + db_handling="delete", +) + +console.rule("[bold green]Running EA") +ea.run() + +# --------------------------------------------------------------------------- +# Post-hoc analysis via Archive +# --------------------------------------------------------------------------- + +archive = Archive(DATA / "database.db") + +console.rule("[bold yellow]Results") +console.log(f"Archive size: {archive.size} evaluated individuals") +console.log(f"Generation range: {archive.generation_range}") + +stats = archive.fitness_stats() +console.log( + f"Fitness — min: {stats['min']:.4f} mean: {stats['mean']:.4f} " + f"max: {stats['max']:.4f} std: {stats['std']:.4f}" +) + +best = archive.best_individual(fitness_mode="max") +console.rule("[bold cyan]Best Individual") +console.log(f" id={best.id} fitness={best.fitness_:.4f} " + f"born={best.time_of_birth} died={best.time_of_death}") + +genome = deserialize_genome(best.genotype) +valid_mask = ~np.isnan(genome.arms[:, 0]) +valid_arms = genome.arms[valid_mask] +console.log(f" active arms: {int(valid_mask.sum())} / {genome.arms.shape[0]}") +console.log(" arm layout (magnitude | azimuth° | elevation° | motor_az° | motor_pitch° | spin):") +for i, arm in enumerate(valid_arms): + mag, az, el, maz, mpitch, spin = arm + console.log( + f" arm {i}: mag={mag:.3f}m az={np.degrees(az):.1f}° " + f"el={np.degrees(el):.1f}° motor_az={np.degrees(maz):.1f}° " + f"motor_pitch={np.degrees(mpitch):.1f}° spin={'CW' if spin > 0.5 else 'CCW'}" + ) + +console.rule("[bold]Done") diff --git a/examples/d_drones/2_drone_evolution.py b/examples/d_drones/2_drone_evolution.py new file mode 100644 index 000000000..1d9639ecc --- /dev/null +++ b/examples/d_drones/2_drone_evolution.py @@ -0,0 +1,201 @@ +"""Drone morphology evolution — spherical genome, configurable fitness + strategy. + +Ports airevolve's run_evolution.py to ARIEL's EA engine (SQLite persistence, +Archive post-hoc analysis). Supports the spherical arm encoding and three +fitness modes via mu+lambda or mu,lambda selection. + +Run: + python examples/d_drones/2_drone_evolution.py + python examples/d_drones/2_drone_evolution.py --fitness pure_hover --strategy plus + python examples/d_drones/2_drone_evolution.py --fitness edit_distance --workers 8 + python examples/d_drones/2_drone_evolution.py --pop 20 --budget 30 --min-arms 4 --max-arms 6 +""" + +from __future__ import annotations + +import argparse +import os +from pathlib import Path + +import numpy as np +from rich.console import Console + +os.environ.setdefault("OMP_NUM_THREADS", "1") +os.environ.setdefault("OPENBLAS_NUM_THREADS", "1") +os.environ.setdefault("MKL_NUM_THREADS", "1") + +from airevolve.evolution_tools.genome_handlers.spherical_angular_genome_handler import ( + SphericalAngularDroneGenomeHandler, +) +from ariel.body_phenotypes.drone import ( + crossover_drones, + deserialize_genome, + evaluate_drones, + initialize_drones, + mutate_drones, + parent_tag, + truncation_select, +) +from ariel.ec import EA, Individual, Population +from ariel.ec.archive import Archive + +console = Console() + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +parser = argparse.ArgumentParser(description="Drone morphology evolution (spherical genome)") +parser.add_argument("--pop", type=int, default=20, help="Population size (mu)") +parser.add_argument("--budget", type=int, default=50, help="Number of EA generations") +parser.add_argument("--workers", type=int, default=1, help="Parallel evaluation workers") +parser.add_argument("--min-arms", type=int, default=4, help="Minimum rotor arms") +parser.add_argument("--max-arms", type=int, default=6, help="Maximum rotor arms") +parser.add_argument("--append-arm-chance", type=float, default=0.1, + help="Probability of adding an arm during mutation (default 0.1)") +parser.add_argument( + "--fitness", + choices=["pure_hover", "edit_distance", "zero"], + default="pure_hover", + help="Fitness function: pure_hover (analytical hover quality [0,3]), " + "edit_distance (edit distance from target), zero (always 0)", +) +parser.add_argument( + "--strategy", + choices=["plus", "comma"], + default="plus", + help="Selection strategy: plus (mu+lambda, parents survive) or comma (mu,lambda)", +) +parser.add_argument("--seed", type=int, default=42) +args = parser.parse_args() + +POP_SIZE: int = args.pop +BUDGET: int = args.budget +N_WORKERS: int = args.workers +FITNESS_MODE: str = args.fitness +STRATEGY: str = args.strategy + +DATA = Path.cwd() / "__data__" / "drone_evolution" +DATA.mkdir(parents=True, exist_ok=True) + +np.random.seed(args.seed) + +# --------------------------------------------------------------------------- +# Genome search space +# --------------------------------------------------------------------------- + +PARAMETER_LIMITS = np.array([ + [0.055, 0.17], # arm magnitude (metres) + [-np.pi, np.pi], # arm azimuth (rad) + [-np.pi / 2, np.pi / 2], # arm elevation (rad) + [-np.pi, np.pi], # motor disc azimuth (rad) + [-np.pi, np.pi], # motor disc pitch (rad) + [0, 1], # propeller spin direction (binary) +]) + +template_handler = SphericalAngularDroneGenomeHandler( + min_max_narms=(args.min_arms, args.max_arms), + parameter_limits=PARAMETER_LIMITS, + append_arm_chance=args.append_arm_chance, + bilateral_plane_for_symmetry=None, + repair=False, + rnd=np.random.default_rng(args.seed), +) + +# --------------------------------------------------------------------------- +# Banner +# --------------------------------------------------------------------------- + +console.rule("[bold blue]Drone Evolution") +console.log( + f"pop={POP_SIZE} budget={BUDGET} workers={N_WORKERS} " + f"fitness={FITNESS_MODE} strategy={STRATEGY}" +) +console.log(f"arms=[{args.min_arms}, {args.max_arms}] db={DATA / 'database.db'}") + +# --------------------------------------------------------------------------- +# Initial population +# --------------------------------------------------------------------------- + +initial_pop = Population([Individual() for _ in range(POP_SIZE)]) + +init_op = initialize_drones(template_handler=template_handler) +eval_op = evaluate_drones(fitness_mode=FITNESS_MODE, n_workers=N_WORKERS) + +console.log("Initializing and evaluating initial population …") +initial_pop = init_op(initial_pop) +initial_pop = eval_op(initial_pop) + +best_init = initial_pop.best(sort="max", attribute="fitness_")[0] +console.log(f"Initial best fitness: {best_init.fitness_:.4f}") + +# --------------------------------------------------------------------------- +# Generation ops +# --------------------------------------------------------------------------- +# For mu,lambda (comma) strategy the offspring pool size equals POP_SIZE, so +# the crossover step produces POP_SIZE//2 children and mutation adds nothing +# extra — truncation_select then picks strictly from offspring, discarding +# all parents. For mu+lambda (plus), parents survive alongside offspring. + +offspring_n = POP_SIZE if STRATEGY == "comma" else POP_SIZE // 2 + +generation_ops = [ + parent_tag(n=POP_SIZE), + crossover_drones(template_handler=template_handler), + mutate_drones(template_handler=template_handler), + evaluate_drones(fitness_mode=FITNESS_MODE, n_workers=N_WORKERS), + truncation_select(n=POP_SIZE), +] + +ea = EA( + population=initial_pop, + operations=generation_ops, + num_steps=BUDGET, + db_file_path=DATA / "database.db", + db_handling="delete", +) + +# --------------------------------------------------------------------------- +# Run +# --------------------------------------------------------------------------- + +console.rule("[bold green]Running EA") +ea.run() + +# --------------------------------------------------------------------------- +# Post-hoc analysis +# --------------------------------------------------------------------------- + +archive = Archive(DATA / "database.db") + +console.rule("[bold yellow]Results") +console.log(f"Archive size: {archive.size} evaluated individuals") +console.log(f"Generation range: {archive.generation_range}") + +stats = archive.fitness_stats() +console.log( + f"Fitness — min: {stats['min']:.4f} mean: {stats['mean']:.4f} " + f"max: {stats['max']:.4f} std: {stats['std']:.4f}" +) + +best = archive.best_individual(fitness_mode="max") +console.rule("[bold cyan]Best Individual") +console.log( + f" id={best.id} fitness={best.fitness_:.4f} " + f"born={best.time_of_birth} died={best.time_of_death}" +) + +genome = deserialize_genome(best.genotype) +valid_mask = ~np.isnan(genome.arms[:, 0]) +valid_arms = genome.arms[valid_mask] +console.log(f" active arms: {int(valid_mask.sum())} / {genome.arms.shape[0]}") +console.log(" arm layout (magnitude | azimuth° | elevation° | motor_az° | motor_pitch° | spin):") +for i, arm in enumerate(valid_arms): + mag, az, el, maz, mpitch, spin = arm + console.log( + f" arm {i}: mag={mag:.3f}m az={np.degrees(az):.1f}° " + f"el={np.degrees(el):.1f}° motor_az={np.degrees(maz):.1f}° " + f"motor_pitch={np.degrees(mpitch):.1f}° spin={'CW' if spin > 0.5 else 'CCW'}" + ) + +console.rule("[bold]Done") diff --git a/examples/d_drones/3_neat_evolution.py b/examples/d_drones/3_neat_evolution.py new file mode 100644 index 000000000..7088379fb --- /dev/null +++ b/examples/d_drones/3_neat_evolution.py @@ -0,0 +1,168 @@ +"""NEAT-speciated drone morphology evolution using airevolve's evolve_neat strategy. + +Wraps airevolve's ``evolve_neat`` loop (which handles speciation internally) +with the same SphericalAngularDroneGenomeHandler and fitness modes as +example 2, but without ARIEL's EA engine — evolve_neat manages its own +population and does not produce an SQLite archive. + +Run: + python examples/d_drones/3_neat_evolution.py + python examples/d_drones/3_neat_evolution.py --pop 20 --gens 30 + python examples/d_drones/3_neat_evolution.py --fitness pure_hover --workers 8 + python examples/d_drones/3_neat_evolution.py --compat-threshold 2.5 --target-species 4 +""" + +from __future__ import annotations + +import argparse +import os +from pathlib import Path + +import numpy as np +from rich.console import Console + +os.environ.setdefault("OMP_NUM_THREADS", "1") +os.environ.setdefault("OPENBLAS_NUM_THREADS", "1") +os.environ.setdefault("MKL_NUM_THREADS", "1") + +from airevolve.evolution_tools.genome_handlers.spherical_angular_genome_handler import ( + SphericalAngularDroneGenomeHandler, +) +from airevolve.evolution_tools.evaluators.unified_fitness import UnifiedFitness +from airevolve.evolution_tools.strategies import evolve_neat + +console = Console() + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +parser = argparse.ArgumentParser(description="NEAT-speciated drone evolution") +parser.add_argument("--pop", type=int, default=20, help="Population size") +parser.add_argument("--gens", type=int, default=30, help="Number of generations") +parser.add_argument("--workers", type=int, default=None, + help="Parallel workers for evaluation (default: 1)") +parser.add_argument("--min-arms", type=int, default=4, help="Minimum rotor arms") +parser.add_argument("--max-arms", type=int, default=6, help="Maximum rotor arms") +parser.add_argument( + "--fitness", + choices=["pure_hover", "edit_distance", "zero"], + default="pure_hover", + help="Fitness function", +) +# NEAT-specific +parser.add_argument("--crossover-rate", type=float, default=0.75, + help="Fraction of offspring produced by crossover (default 0.75)") +parser.add_argument("--compat-threshold", type=float, default=3.0, + help="Initial compatibility distance threshold (default 3.0)") +parser.add_argument("--species-elitism", type=int, default=1, + help="Top-N per species copied unchanged each generation (default 1)") +parser.add_argument("--stagnation-limit", type=int, default=15, + help="Generations without improvement before species removal (default 15)") +parser.add_argument("--min-species-size", type=int, default=2, + help="Minimum offspring per surviving species (default 2)") +parser.add_argument("--target-species", type=int, default=5, + help="Target number of species for dynamic threshold (default 5)") +parser.add_argument("--no-adjust-threshold", action="store_true", + help="Disable dynamic compatibility threshold adjustment") +parser.add_argument("--interspecies-rate", type=float, default=0.001, + help="Probability of cross-species crossover (default 0.001)") +parser.add_argument("--seed", type=int, default=42) +args = parser.parse_args() + +DATA = Path.cwd() / "__data__" / "drone_neat_evolution" +DATA.mkdir(parents=True, exist_ok=True) + +np.random.seed(args.seed) + +# --------------------------------------------------------------------------- +# Genome handler + fitness +# --------------------------------------------------------------------------- + +PARAMETER_LIMITS = np.array([ + [0.055, 0.17], + [-np.pi, np.pi], + [-np.pi / 2, np.pi / 2], + [-np.pi, np.pi], + [-np.pi, np.pi], + [0, 1], +]) + +template_handler = SphericalAngularDroneGenomeHandler( + min_max_narms=(args.min_arms, args.max_arms), + parameter_limits=PARAMETER_LIMITS, + append_arm_chance=0.1, + bilateral_plane_for_symmetry=None, + repair=False, + rnd=np.random.default_rng(args.seed), +) + +fitness_fn = UnifiedFitness(fitness_mode=args.fitness) + +# --------------------------------------------------------------------------- +# Banner +# --------------------------------------------------------------------------- + +console.rule("[bold blue]Drone NEAT Evolution") +console.log( + f"pop={args.pop} gens={args.gens} fitness={args.fitness} workers={args.workers}" +) +console.log( + f"compat_threshold={args.compat_threshold} target_species={args.target_species} " + f"crossover_rate={args.crossover_rate}" +) +console.log(f"arms=[{args.min_arms}, {args.max_arms}]") + +# --------------------------------------------------------------------------- +# Run evolve_neat +# evolve_neat manages speciation, crossover, and mutation internally. +# It returns a DataFrame with columns: generation, id, fitness, species_id. +# --------------------------------------------------------------------------- + +console.log("Starting NEAT evolution …") + +all_individuals = evolve_neat( + handler=template_handler, + fitness_function=fitness_fn, + population_size=args.pop, + num_generations=args.gens, + crossover_rate=args.crossover_rate, + num_workers=args.workers, + compatibility_threshold=args.compat_threshold, + species_elitism=args.species_elitism, + stagnation_limit=args.stagnation_limit, + min_species_size=args.min_species_size, + target_species_count=args.target_species, + adjust_threshold=not args.no_adjust_threshold, + interspecies_mating_rate=args.interspecies_rate, + log_dir=str(DATA), +) + +# --------------------------------------------------------------------------- +# Results +# --------------------------------------------------------------------------- + +console.rule("[bold yellow]Results") +console.log(f"Total individuals evaluated: {len(all_individuals)}") + +last_gen = int(all_individuals["generation"].max()) +last_gen_df = all_individuals[all_individuals["generation"] == last_gen] +best_row = last_gen_df.sort_values("fitness", ascending=False).iloc[0] + +console.log( + f"Best (gen {last_gen}): id={best_row['id']} " + f"fitness={best_row['fitness']:.4f} " + f"species={best_row.get('species_id', 'n/a')}" +) + +# Per-generation summary +console.rule("[bold cyan]Per-generation best fitness") +for gen in sorted(all_individuals["generation"].unique()): + gen_df = all_individuals[all_individuals["generation"] == gen] + console.log( + f" gen {gen:3d}: best={gen_df['fitness'].max():.4f} " + f"mean={gen_df['fitness'].mean():.4f} " + f"species={gen_df['species_id'].nunique() if 'species_id' in gen_df else '?'}" + ) + +console.rule("[bold]Done") diff --git a/examples/d_drones/4_simulate_lee_ctrl.py b/examples/d_drones/4_simulate_lee_ctrl.py new file mode 100644 index 000000000..b5a837c96 --- /dev/null +++ b/examples/d_drones/4_simulate_lee_ctrl.py @@ -0,0 +1,243 @@ +"""3-D simulation of a 2-inch quad with Lee geometric control and B-spline gate trajectory. + +Visualises (or headlessly benchmarks) a tuned Lee controller on one of four +gate circuits. Optionally loads a JSON config produced by example 5 (tuning). + +Controller gains: attitude and rate gains are auto-scaled from the drone's inertia +(12 rad/s closed-loop bandwidth) to ensure stability at the 5 ms timestep. +Position and velocity gains default to the curriculum-tuner starting values and can +be overridden with --pos-gain / --vel-gain. + +Run: + # Headless test with default B-spline parameters: + python examples/d_drones/4_simulate_lee_ctrl.py --gates figure8 --no-viz + + # Load a tuned config and save animation: + python examples/d_drones/4_simulate_lee_ctrl.py \\ + --gates figure8 \\ + --bspline-config __data__/lee_tuning/stage3_best.json --save + + # Override position / velocity gains: + python examples/d_drones/4_simulate_lee_ctrl.py --gates circle \\ + --pos-gain 12.0 --vel-gain 8.0 +""" + +from __future__ import annotations + +import argparse +import json +import sys +import time +from pathlib import Path + +import numpy as np + +# Add the d_drones directory to sys.path so _ctrl_helpers is importable +sys.path.insert(0, str(Path(__file__).parent)) +from _ctrl_helpers import ARM_LENGTH, PROP_SIZE, GateChecker, create_2inch_quad + +from airevolve.controllers.lee_control.lee_controller import LeeGeometricControl +from airevolve.controllers.trajectory_generation.trajectory import Trajectory +from airevolve.controllers.utils.gate_configs import GATE_CONFIGS +import airevolve.controllers.utils as ctrl_utils +from airevolve.controllers.utils.wind_model import Wind + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +parser = argparse.ArgumentParser( + description="Lee geometric controller B-spline simulation for 2-inch quad", + formatter_class=argparse.RawDescriptionHelpFormatter, +) +parser.add_argument("--gates", required=True, + choices=["figure8", "circle", "slalom", "backandforth"], + help="Gate configuration") +parser.add_argument("--bspline-config", + help="Path to B-spline JSON config from tuning (stage3_best.json)") +parser.add_argument("--time", type=float, default=20.0, + help="Simulation duration in seconds (default 20)") +parser.add_argument("--dt", type=float, default=0.005, + help="Simulation time-step in seconds (default 0.005)") +parser.add_argument("--no-viz", action="store_true", + help="Disable 3-D animation (headless)") +parser.add_argument("--save", action="store_true", + help="Save animation to file") +# Position/velocity gains — defaults from the curriculum tuner starting values. +# Attitude and rate gains are auto-scaled from drone inertia (always stable at dt=5ms). +parser.add_argument("--pos-gain", type=float, default=14.3, + help="Lee position P gain (default 14.3)") +parser.add_argument("--vel-gain", type=float, default=9.0, + help="Lee velocity P gain (default 9.0)") +args = parser.parse_args() + +# --------------------------------------------------------------------------- +# Setup +# --------------------------------------------------------------------------- + +gate_config = GATE_CONFIGS[args.gates] +Tf: float = args.time +Ts: float = args.dt +Ti: float = 0.0 + +print("\n" + "=" * 70) +print("LEE CONTROLLER B-SPLINE SIMULATION — 2-INCH QUAD") +print("=" * 70) +print(f"Gate configuration : {args.gates}") +print(f"Drone : 2-inch quad (arm={ARM_LENGTH}m, prop={PROP_SIZE}\")") +print(f"Simulation time : {Tf}s at dt={Ts}s") +if args.bspline_config: + print(f"Loading config : {args.bspline_config}") +else: + print("B-spline : default parameters") +print(f"Lee gains : pos={args.pos_gain} vel={args.vel_gain} " + f"att/rate=auto-scaled from inertia") +print("=" * 70 + "\n") + +# --------------------------------------------------------------------------- +# Drone, controller, trajectory +# --------------------------------------------------------------------------- + +quad = create_2inch_quad() +wind = Wind("None", args.time) + +ctrl = LeeGeometricControl( + quad, + yawType=1, + orient="NED", + auto_scale_gains=True, # att/rate auto-derived from inertia (stable at dt=5ms) + pos_P_gain=np.array([args.pos_gain] * 3), + vel_P_gain=np.array([args.vel_gain] * 3), + # att_P_gain and rate_P_gain intentionally omitted → auto-scaled +) + +bspline_params = None +if args.bspline_config: + with open(args.bspline_config) as f: + cfg = json.load(f) + if "bspline_params" in cfg: + bspline_params = np.array(cfg["bspline_params"]) + print(f"Loaded {len(bspline_params)} B-spline parameters") + +traj = Trajectory(quad, "xyz_pos", np.array([15, 3, 1]), gate_config=gate_config) + +if bspline_params is not None: + traj.bspline_trajectory.set_parameters(bspline_params) + print("B-spline trajectory loaded from config") +else: + print("Using default B-spline trajectory") + +# Set initial drone state to match trajectory at t=0 +start_pos, _, _ = traj.bspline_trajectory.evaluate(0.0) +_, vel_050, _ = traj.bspline_trajectory.evaluate(0.05) +if np.linalg.norm(vel_050[:2]) > 0.001: + initial_yaw = np.arctan2(vel_050[1], vel_050[0]) +else: + initial_yaw = gate_config.gate_yaw[0] + +initial_euler = np.array([0.0, 0.0, initial_yaw]) +quad.drone_sim.set_state( + position=start_pos, + velocity=np.zeros(3), + attitude=initial_euler, + angular_velocity=np.zeros(3), +) +quad._update_state_variables() + +print(f"Drone start position : [{start_pos[0]:.2f}, {start_pos[1]:.2f}, {start_pos[2]:.2f}]") +print(f"Initial yaw : {np.degrees(initial_yaw):.1f}°") + +gate_checker = GateChecker(gate_config.gate_pos, gate_config.gate_yaw, gate_config.gate_size) +print(f"Gate detection : {gate_checker.num_gates} gates\n") + +# Seed first command +sDes = traj.desiredState(Ti, Ts, quad) +ctrl.controller(sDes, quad, traj.ctrlType, Ts) + +# --------------------------------------------------------------------------- +# Allocate result buffers +# --------------------------------------------------------------------------- + +num_steps = int(Tf / Ts + 1) +t_all = np.zeros(num_steps) +s_all = np.zeros((num_steps, len(quad.state))) +pos_all = np.zeros((num_steps, 3)) +vel_all = np.zeros((num_steps, 3)) +quat_all = np.zeros((num_steps, 4)) +omega_all = np.zeros((num_steps, 3)) +euler_all = np.zeros((num_steps, 3)) +sDes_traj_all = np.zeros((num_steps, len(traj.sDes))) +sDes_calc_all = np.zeros((num_steps, len(ctrl.sDesCalc))) +w_cmd_all = np.zeros((num_steps, len(ctrl.w_cmd))) +wMotor_all = np.zeros((num_steps, 4)) +thr_all = np.zeros((num_steps, 4)) +tor_all = np.zeros((num_steps, 4)) + +# --------------------------------------------------------------------------- +# Simulation loop +# --------------------------------------------------------------------------- + +print(f"Running simulation for {Tf}s …") +t0 = time.time() +t = Ti +i = 1 + +while round(t, 3) < Tf: + t_all[i] = t + s_all[i] = quad.state + pos_all[i] = quad.pos + vel_all[i] = quad.vel + quat_all[i] = quad.quat + omega_all[i] = quad.omega + euler_all[i] = quad.euler + sDes_traj_all[i] = traj.sDes + sDes_calc_all[i] = ctrl.sDesCalc + w_cmd_all[i] = ctrl.w_cmd + wMotor_all[i] = quad.wMotor + thr_all[i] = quad.thr + tor_all[i] = quad.tor + + # Advance dynamics + quad.update(t, Ts, ctrl.w_cmd, wind) + t_new = Ts * i + + # Update trajectory and controller for next step + sDes = traj.desiredState(t_new, Ts, quad) + ctrl.controller(sDes, quad, traj.ctrlType, Ts) + + # Gate detection + passed = gate_checker.check_gate_passing(quad.pos) + if passed: + print(f" *** GATE {gate_checker.gates_passed} passed at t={t:.3f}s " + f"pos=[{quad.pos[0]:.2f}, {quad.pos[1]:.2f}, {quad.pos[2]:.2f}]") + + t = t_new + i += 1 + +elapsed = time.time() - t0 +print(f"Simulated {t:.2f}s in {elapsed:.3f}s wall-clock") + +# Gate summary +print(f"\n{'=' * 70}") +print(f"GATE SUMMARY: {gate_checker.gates_passed} / {gate_checker.num_gates} passed") +print(f"{'=' * 70}\n") + +# --------------------------------------------------------------------------- +# Visualisation / animation +# --------------------------------------------------------------------------- + +if not args.no_viz: + waypoints = np.array(gate_config.gate_pos, dtype=float) + save_path = str(Path.cwd() / "__data__" / "lee_simulation.mp4") if args.save else None + + ctrl_utils.sameAxisAnimation( + t_all, waypoints, pos_all, quat_all, sDes_traj_all, Ts, + quad.params, 15, 3, int(args.save), "NED", + gate_pos=np.array(gate_config.gate_pos), + gate_yaw=np.array(gate_config.gate_yaw), + gate_size=gate_config.gate_size, + save_path=save_path, + ) + + if save_path: + print(f"Animation saved to: {save_path}") diff --git a/examples/d_drones/5_tune_lee_controller.py b/examples/d_drones/5_tune_lee_controller.py new file mode 100644 index 000000000..1ed279ace --- /dev/null +++ b/examples/d_drones/5_tune_lee_controller.py @@ -0,0 +1,409 @@ +"""Curriculum-based CMA-ES tuning of the Lee geometric controller for gate racing. + +Optimises controller gains and B-spline trajectory parameters for a 2-inch +quad in three progressive stages: + + Stage 1 (gains only) → Stage 2 (gains + timing) → Stage 3 (full) + +Requires the ``cma`` package (``uv pip install cma``). + +Run: + # All three stages automatically: + python examples/d_drones/5_tune_lee_controller.py --stage all --gates figure8 + + # Individual stages: + python examples/d_drones/5_tune_lee_controller.py --stage 1 --gates figure8 --max-evals 200 + python examples/d_drones/5_tune_lee_controller.py --stage 2 --gates figure8 \\ + --load-prev __data__/lee_tuning/stage1_best.json --max-evals 300 + python examples/d_drones/5_tune_lee_controller.py --stage 3 --gates figure8 \\ + --load-prev __data__/lee_tuning/stage2_best.json --max-evals 500 + +After tuning, visualise with: + python examples/d_drones/4_simulate_lee_ctrl.py \\ + --gates figure8 --bspline-config __data__/lee_tuning/stage3_best.json +""" + +from __future__ import annotations + +import argparse +import json +import multiprocessing +import os +import sys +import time +from concurrent.futures import ProcessPoolExecutor, TimeoutError, as_completed +from datetime import datetime +from pathlib import Path + +import numpy as np + +# Add the d_drones directory to sys.path so _ctrl_helpers is importable +sys.path.insert(0, str(Path(__file__).parent)) +from _ctrl_helpers import ARM_LENGTH, PROP_SIZE, GateChecker, create_2inch_quad + +from airevolve.controllers.lee_control.lee_controller import LeeGeometricControl +from airevolve.controllers.trajectory_generation.bspline_gate_trajectory import ( + BSplineGateTrajectory, +) +from airevolve.controllers.trajectory_generation.trajectory import Trajectory +from airevolve.controllers.utils.gate_configs import GATE_CONFIGS +from airevolve.controllers.utils.wind_model import Wind + +try: + import cma + CMA_AVAILABLE = True +except ImportError: + cma = None + CMA_AVAILABLE = False + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +parser = argparse.ArgumentParser( + description="Curriculum CMA-ES tuning for Lee controller + B-spline trajectory", + formatter_class=argparse.RawDescriptionHelpFormatter, +) +parser.add_argument("--stage", required=True, + help="Curriculum stage: 1, 2, 3, or all") +parser.add_argument("--gates", required=True, + choices=["figure8", "circle", "slalom", "backandforth"], + help="Gate configuration") +parser.add_argument("--load-prev", + help="JSON from a previous stage to seed this stage") +parser.add_argument("--max-evals", type=int, default=200, + help="Max CMA-ES evaluations (default 200)") +parser.add_argument("--max-evals-1", type=int, default=None, + help="Override --max-evals for Stage 1") +parser.add_argument("--max-evals-2", type=int, default=None, + help="Override --max-evals for Stage 2") +parser.add_argument("--max-evals-3", type=int, default=None, + help="Override --max-evals for Stage 3") +parser.add_argument("--workers", type=int, default=None, + help="Parallel workers (default: cpu_count // 2)") +parser.add_argument("--time", type=float, default=20.0, + help="Simulation time per evaluation in seconds (default 20)") +parser.add_argument("--dt", type=float, default=0.005, + help="Simulation timestep in seconds (default 0.005)") +parser.add_argument("--output", default="__data__/lee_tuning", + help="Output directory (default: __data__/lee_tuning)") +parser.add_argument("--timeout", type=float, default=30.0, + help="Timeout per evaluation in seconds (default 30)") +args = parser.parse_args() + +# --------------------------------------------------------------------------- +# Simulation helper +# --------------------------------------------------------------------------- + +def simulate_bspline( + pos_gain: float, vel_gain: float, att_gain: float, rate_gain: float, + bspline_params: np.ndarray, + gate_config, + sim_time: float = 20.0, + dt: float = 0.005, + verbose: bool = False, +) -> dict: + """Run one Lee + B-spline evaluation; return result dict.""" + try: + quad = create_2inch_quad() + ctrl = LeeGeometricControl( + quad, yawType=1, orient="NED", + auto_scale_gains=True, # att/rate auto-derived from inertia + pos_P_gain=np.array([pos_gain] * 3), + vel_P_gain=np.array([vel_gain] * 3), + # att_P_gain and rate_P_gain intentionally omitted → auto-scaled + ) + + bspline_traj = BSplineGateTrajectory(gate_config, gate_offset_scale=0.5) + bspline_traj.set_parameters(bspline_params) + + start_pos, _, _ = bspline_traj.evaluate(0.0) + _, vel_050, _ = bspline_traj.evaluate(0.05) + if np.linalg.norm(vel_050[:2]) > 0.001: + initial_yaw = np.arctan2(vel_050[1], vel_050[0]) + else: + initial_yaw = gate_config.gate_yaw[0] + initial_euler = np.array([0.0, 0.0, initial_yaw]) + quad.drone_sim.set_state( + position=start_pos, velocity=np.zeros(3), + attitude=initial_euler, angular_velocity=np.zeros(3), + ) + + from airevolve.controllers.trajectory_generation.trajectory import Trajectory + traj = Trajectory(quad, "xyz_pos", np.array([15, 3, 1]), + gate_config=gate_config) + traj.bspline_trajectory = bspline_traj + + wind = Wind("None", sim_time) + gate_checker = GateChecker(gate_config.gate_pos, gate_config.gate_yaw, + gate_config.gate_size) + + sDes = traj.desiredState(0, dt, quad) + ctrl.controller(sDes, quad, "xyz_pos", dt) + + t = 0.0 + crashed = False + num_steps = int(sim_time / dt) + for step in range(num_steps): + quad.update(t, dt, ctrl.w_cmd, wind) + t = dt * (step + 1) + sDes = traj.desiredState(t, dt, quad) + ctrl.controller(sDes, quad, "xyz_pos", dt) + gate_checker.check_gate_passing(quad.pos) + if np.linalg.norm(quad.pos - sDes[:3]) > 10.0: + crashed = True + break + + distance_bonus = gate_checker.get_normalized_distance_to_next_gate(quad.pos) + return { + "gates_passed": gate_checker.gates_passed, + "distance_bonus": distance_bonus, + "crashed": crashed, + "flight_time": t, + } + except Exception as exc: + if verbose: + print(f"Simulation error: {exc}") + return {"gates_passed": 0, "distance_bonus": 0.0, "crashed": True, "flight_time": 0.0} + + +def _eval_worker(args_tuple) -> dict: + (params, stage, gate_config, sim_time, dt, + fixed_bspline, fixed_gains, fixed_timing, fixed_offsets, + n_offset_params) = args_tuple + + # att/rate are auto-scaled — only pos and vel come from the optimizer + if stage == 1: + pos_g, vel_g = params[:2] + bspline_params = fixed_bspline + elif stage == 2: + pos_g, vel_g = params[:2] + timing = params[2:5] + bspline_params = np.concatenate([fixed_offsets, timing]) + else: # stage 3 + pos_g, vel_g = params[:2] + timing = params[2:5] + offsets = params[5:5 + n_offset_params] + bspline_params = np.concatenate([offsets, timing]) + + # att_gain and rate_gain are ignored (auto-scaled in simulate_bspline) + result = simulate_bspline(pos_g, vel_g, att_gain=0.0, rate_gain=0.0, + bspline_params=bspline_params, gate_config=gate_config, + sim_time=sim_time, dt=dt) + gates = result["gates_passed"] + bonus = result["distance_bonus"] + return {"score": gates + bonus, **result, "params": params.tolist()} + + +# --------------------------------------------------------------------------- +# CurriculumTuner +# --------------------------------------------------------------------------- + +class CurriculumTuner: + def __init__(self, gate_config, stage: int, sim_time: float = 20.0, + dt: float = 0.005, output_dir: str = "__data__/lee_tuning") -> None: + self.gate_config = gate_config + self.stage = stage + self.sim_time = sim_time + self.dt = dt + self.output_dir = output_dir + self.best_score = -float("inf") + self.best_params: dict | None = None + Path(output_dir).mkdir(parents=True, exist_ok=True) + + tmpl = BSplineGateTrajectory(gate_config, gate_offset_scale=0.5) + self.fixed_bspline = tmpl.get_default_parameters() + self.fixed_offsets = tmpl.get_gate_offset_parameters() + self.n_offset_params = tmpl.get_gate_offset_count() + self.fixed_timing = np.array([12.7, 4.6, 1.9]) + self.fixed_bspline[-3:] = self.fixed_timing + # Only pos/vel are optimised; att/rate are auto-scaled from drone inertia + self.fixed_gains = [14.3, 9.0] # [pos_P, vel_P] + + def load_previous_stage(self, config_path: str) -> None: + print(f"Loading previous stage from: {config_path}") + with open(config_path) as f: + cfg = json.load(f) + if "bspline_params" in cfg: + bp = np.array(cfg["bspline_params"]) + self.fixed_bspline = bp + self.fixed_offsets = bp[: self.n_offset_params] + self.fixed_timing = bp[-3:] + if "gains" in cfg: + g = cfg["gains"] + self.fixed_gains = [g["pos_P"], g["vel_P"]] + + def _build_config(self) -> dict: + tmpl = BSplineGateTrajectory(self.gate_config, gate_offset_scale=0.5) + bounds_by_group = tmpl.get_parameter_bounds_by_group() + gate_lower, gate_upper = bounds_by_group["gate_offsets"] + + if self.stage == 1: + ig = list(self.fixed_gains) + bounds = [[1.0, 20.0], [1.0, 20.0]] # pos_P, vel_P only + return {"initial_guess": ig, "bounds": bounds, "initial_std": 1.5, + "param_count": 2, "description": "pos/vel gains (2 params; att/rate auto-scaled)"} + elif self.stage == 2: + ig = list(self.fixed_gains) + list(self.fixed_timing) + bounds = [ + [1.0, 20.0], [1.0, 20.0], # pos_P, vel_P + [8.0, 18.0], [1.0, 10.0], [0.1, 5.0], # timing + ] + return {"initial_guess": ig, "bounds": bounds, "initial_std": 1.5, + "param_count": 5, "description": "pos/vel gains (2) + Timing (3)"} + else: # stage 3 + ig = list(self.fixed_gains) + list(self.fixed_timing) + list(self.fixed_offsets) + bounds = [ + [1.0, 20.0], [1.0, 20.0], # pos_P, vel_P + [8.0, 18.0], [1.0, 10.0], [0.1, 5.0], # timing + ] + for lo, hi in zip(gate_lower, gate_upper): + bounds.append([lo, hi]) + n = 5 + self.n_offset_params + return {"initial_guess": ig, "bounds": bounds, "initial_std": 0.1, + "param_count": n, + "description": f"pos/vel (2) + Timing (3) + Gate offsets ({self.n_offset_params})"} + + def _score(self, params: np.ndarray) -> float: + r = _eval_worker(( + params, self.stage, self.gate_config, self.sim_time, self.dt, + self.fixed_bspline, self.fixed_gains, self.fixed_timing, + self.fixed_offsets, self.n_offset_params, + )) + score = r["score"] + if score > self.best_score: + self.best_score = score + pos_g, vel_g = params[:2] + self.best_params = { + **r, + "gains": {"pos_P": pos_g, "vel_P": vel_g}, + "bspline_params": ( + self.fixed_bspline.tolist() if self.stage == 1 else + np.concatenate([self.fixed_offsets, params[2:5]]).tolist() if self.stage == 2 else + np.concatenate([params[5:5 + self.n_offset_params], params[2:5]]).tolist() + ), + } + return -score # CMA minimises + + def run_optimization(self, max_evaluations: int = 200, + num_workers: int | None = None, + timeout_per_eval: float = 30.0) -> None: + if not CMA_AVAILABLE: + print("ERROR: CMA-ES requires the 'cma' package (uv pip install cma)") + return + + cfg = self._build_config() + num_workers = num_workers or max(1, multiprocessing.cpu_count() // 2) + + print(f"\n{'=' * 70}") + print(f"CURRICULUM STAGE {self.stage} — CMA-ES OPTIMISATION") + print(f"{'=' * 70}") + print(f"Gate config : {self.gate_config.__name__}") + print(f"Optimising : {cfg['description']} ({cfg['param_count']} params)") + print(f"Max evaluations : {max_evaluations} workers={num_workers}") + print(f"{'=' * 70}\n") + + ig = np.array(cfg["initial_guess"], dtype=float) + bounds_lo = [b[0] for b in cfg["bounds"]] + bounds_hi = [b[1] for b in cfg["bounds"]] + + options = { + "maxfevals": max_evaluations, + "bounds": [bounds_lo, bounds_hi], + "verbose": -9, + "tolx": 1e-4, + "tolfun": 1e-4, + } + + t0 = time.time() + try: + es = cma.CMAEvolutionStrategy(ig, cfg["initial_std"], options) + iteration = 0 + while not es.stop(): + candidates = es.ask() + fitnesses = [self._score(np.array(c)) for c in candidates] + es.tell(candidates, fitnesses) + iteration += 1 + if iteration % 10 == 0: + print(f" iter {iteration:4d} evals {es.result.evaluations:5d} " + f"best={self.best_score:.3f}") + except KeyboardInterrupt: + print("\nInterrupted — saving current best …") + finally: + elapsed = time.time() - t0 + print(f"\nStage {self.stage} done in {elapsed / 60:.1f} min " + f"({es.result.evaluations} evals) best={self.best_score:.3f}") + self._save_results() + + def _save_results(self) -> None: + if self.best_params is None: + return + ts = datetime.now().strftime("%Y%m%d_%H%M%S") + data = { + "stage": self.stage, + "timestamp": datetime.now().isoformat(), + "fitness": self.best_score, + "gates_passed": self.best_params.get("gates_passed", 0), + "distance_bonus": self.best_params.get("distance_bonus", 0.0), + "gains": self.best_params["gains"], + "bspline_params": self.best_params["bspline_params"], + "flight_time": self.best_params.get("flight_time", 0.0), + "crashed": self.best_params.get("crashed", True), + } + best_path = os.path.join(self.output_dir, f"stage{self.stage}_best.json") + with open(best_path, "w") as f: + json.dump(data, f, indent=2) + print(f"\nStage {self.stage} best config saved: {best_path}") + if self.stage < 3: + print(f" To continue: --stage {self.stage + 1} --load-prev {best_path}") + else: + print(f" To visualise: python examples/d_drones/4_simulate_lee_ctrl.py " + f"--gates {args.gates} --bspline-config {best_path}") + + +# --------------------------------------------------------------------------- +# Main +# --------------------------------------------------------------------------- + +gate_config = GATE_CONFIGS[args.gates] +output_dir = args.output + +if args.stage.lower() == "all": + evals = [ + args.max_evals_1 or args.max_evals, + args.max_evals_2 or args.max_evals, + args.max_evals_3 or args.max_evals, + ] + prev_path = args.load_prev + tuners = [] + for stage_num, max_ev in zip([1, 2, 3], evals): + print(f"\n{'#' * 70}\n# STAGE {stage_num}\n{'#' * 70}") + tuner = CurriculumTuner(gate_config, stage=stage_num, + sim_time=args.time, dt=args.dt, + output_dir=output_dir) + if prev_path: + tuner.load_previous_stage(prev_path) + tuner.run_optimization(max_evaluations=max_ev, num_workers=args.workers, + timeout_per_eval=args.timeout) + tuners.append(tuner) + prev_path = os.path.join(output_dir, f"stage{stage_num}_best.json") + if not os.path.exists(prev_path): + print(f"Stage {stage_num} did not produce results — stopping.") + break + + print("\n" + "=" * 70) + print("ALL STAGES COMPLETE") + print("=" * 70) + for i, t in enumerate(tuners, 1): + print(f" Stage {i}: {t.best_score:.3f}") + +else: + stage_num = int(args.stage) + tuner = CurriculumTuner(gate_config, stage=stage_num, + sim_time=args.time, dt=args.dt, + output_dir=output_dir) + if args.load_prev: + tuner.load_previous_stage(args.load_prev) + tuner.run_optimization(max_evaluations=args.max_evals, + num_workers=args.workers, + timeout_per_eval=args.timeout) diff --git a/examples/d_drones/6_train_rl_figure8.py b/examples/d_drones/6_train_rl_figure8.py new file mode 100644 index 000000000..fcc9c97c9 --- /dev/null +++ b/examples/d_drones/6_train_rl_figure8.py @@ -0,0 +1,251 @@ +"""PPO training for a 2-inch X-quad on the figure-8 gate-racing task. + +Trains a 64×64 MLP policy with stable-baselines3 PPO on DroneGateEnv +(airevolve's vectorised gym environment). Saves a TensorBoard log, a +window-metrics CSV, and the trained policy checkpoint. Optionally renders +an mp4 rollout of the trained policy. + +Run: + # Quick smoke test (CPU): + python examples/d_drones/6_train_rl_figure8.py \\ + --total-steps 1e5 --num-envs 50 --device cpu + + # Full training (GPU, ~30 min): + python examples/d_drones/6_train_rl_figure8.py --total-steps 5e6 + + # Headless (no video): + python examples/d_drones/6_train_rl_figure8.py --total-steps 1e5 --no-video --device cpu + +Requires: stable-baselines3, torch (uv pip install stable-baselines3 torch) +""" + +from __future__ import annotations + +import argparse +import csv +import os +import time +from datetime import datetime +from pathlib import Path + +import numpy as np + +os.environ.setdefault("OMP_NUM_THREADS", "1") +os.environ.setdefault("OPENBLAS_NUM_THREADS", "1") +os.environ.setdefault("MKL_NUM_THREADS", "1") + +from stable_baselines3 import PPO +from stable_baselines3.common.callbacks import BaseCallback + +import torch + +from airevolve.evolution_tools.evaluators.drone_gate_env import ( + DroneGateEnv, + gate_pos as DEFAULT_GATE_POS, + gate_yaw as DEFAULT_GATE_YAW, +) +from airevolve.simulator.simulation.propeller_data import create_standard_propeller_config +import airevolve.controllers.utils as ctrl_utils + +# --------------------------------------------------------------------------- +# Window-metrics callback (vendored for self-containedness) +# --------------------------------------------------------------------------- + +class WindowMetricsCallback(BaseCallback): + """Log gate-passes and episode stats once per ``window`` env steps to CSV.""" + + def __init__(self, window: int = 100_000, csv_path: str = "window_metrics.csv", + verbose: int = 0) -> None: + super().__init__(verbose) + self.window = window + self.csv_path = csv_path + self.last_log = 0 + self.gates_in_window = 0 + self.ep_rewards: list[float] = [] + self.ep_lens: list[int] = [] + os.makedirs(os.path.dirname(csv_path) or ".", exist_ok=True) + with open(csv_path, "w", newline="") as f: + csv.writer(f).writerow( + ["timestep", "gate_passes", "mean_ep_reward", "mean_ep_length", "n_episodes"] + ) + + def _on_step(self) -> bool: + infos = self.locals.get("infos", []) + for info in infos: + self.gates_in_window += info.get("gate_passes", 0) + if "episode" in info: + self.ep_rewards.append(info["episode"]["r"]) + self.ep_lens.append(info["episode"]["l"]) + + if self.num_timesteps - self.last_log >= self.window: + mean_r = float(np.mean(self.ep_rewards)) if self.ep_rewards else float("nan") + mean_l = float(np.mean(self.ep_lens)) if self.ep_lens else float("nan") + with open(self.csv_path, "a", newline="") as f: + csv.writer(f).writerow([ + self.num_timesteps, + self.gates_in_window, + round(mean_r, 3), + round(mean_l, 1), + len(self.ep_rewards), + ]) + self.last_log = self.num_timesteps + self.gates_in_window = 0 + self.ep_rewards = [] + self.ep_lens = [] + return True + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +parser = argparse.ArgumentParser(description="PPO on figure-8 drone gate-racing task") +parser.add_argument("--total-steps", type=float, default=5e6, + help="Total PPO timesteps (default 5e6)") +parser.add_argument("--num-envs", type=int, default=100, + help="Parallel environments (default 100)") +parser.add_argument("--seed", type=int, default=None) +parser.add_argument("--prop-size", type=int, default=2, + help="Propeller size in inches (default 2)") +parser.add_argument("--arm-length", type=float, default=0.11, + help="Arm length in metres (default 0.11)") +parser.add_argument("--save-dir", default="__data__/rl", + help="Output dir for logs, policy, and rollout video (default __data__/rl)") +parser.add_argument("--device", default="cuda:0", + help="Torch device (default cuda:0; pass cpu for portability)") +parser.add_argument("--tag", default="", + help="Extra tag appended to the run name") +parser.add_argument("--no-video", action="store_true", + help="Skip post-training rollout video") +parser.add_argument("--video-seconds", type=float, default=20.0, + help="Rollout duration for video in seconds (default 20)") +args = parser.parse_args() + +total_steps = int(args.total_steps) +save_dir = Path(args.save_dir) +save_dir.mkdir(parents=True, exist_ok=True) + +run_name = f"figure8_prop{args.prop_size}" +if args.seed is not None: + run_name += f"_seed{args.seed}" +if args.tag: + run_name += f"_{args.tag}" +run_name += f"_{datetime.now().strftime('%Y%m%d-%H%M%S')}" + +print( + f"=== RL figure-8 training: prop={args.prop_size}in arm={args.arm_length}m " + f"envs={args.num_envs} steps={total_steps:_} seed={args.seed} device={args.device} ===", + flush=True, +) + +# --------------------------------------------------------------------------- +# Environment +# --------------------------------------------------------------------------- + +propeller_config = create_standard_propeller_config( + arm_length=args.arm_length, prop_size=args.prop_size +) + +env = DroneGateEnv( + propeller_config=propeller_config, + num_envs=args.num_envs, + device=args.device, + dt=0.01, + seed=args.seed, +) + +obs, _ = env.reset() +print( + f"obs shape: {obs.shape} num_motors: {env.num_motors} " + f"mass: {env.drone_sim.mass:.3f} kg motor_tau: {env.motor_tau}", + flush=True, +) + +# --------------------------------------------------------------------------- +# PPO model +# --------------------------------------------------------------------------- + +policy_kwargs = dict( + activation_fn=torch.nn.ReLU, + net_arch=dict(pi=[64, 64], vf=[64, 64]), + log_std_init=0.0, +) + +model = PPO( + "MlpPolicy", + env, + policy_kwargs=policy_kwargs, + verbose=0, + tensorboard_log=str(save_dir), + n_steps=1000, + batch_size=5000, + n_epochs=10, + gamma=0.999, + learning_rate=3e-4, + clip_range=0.2, + ent_coef=0.01, + device=args.device, +) + +csv_path = str(save_dir / f"{run_name}_window_metrics.csv") +cb = WindowMetricsCallback(window=100_000, csv_path=csv_path) + +# --------------------------------------------------------------------------- +# Training +# --------------------------------------------------------------------------- + +t0 = time.time() +model.learn( + total_timesteps=total_steps, + tb_log_name=run_name, + callback=cb, + progress_bar=True, +) +elapsed = time.time() - t0 + +policy_path = str(save_dir / f"{run_name}_policy") +model.save(policy_path) +print( + f"=== done in {elapsed:.1f}s ({total_steps / elapsed:.0f} steps/s). " + f"Policy saved: {policy_path}.zip ===", + flush=True, +) +print(f"Window-metrics CSV: {csv_path}", flush=True) + +# --------------------------------------------------------------------------- +# Post-training rollout video +# --------------------------------------------------------------------------- + +if not args.no_video: + print(f"\nRendering {args.video_seconds}s rollout …", flush=True) + dt_vid = 0.01 + n_steps = int(args.video_seconds / dt_vid) + + obs, _ = env.reset() + pos_all = np.zeros((n_steps, 3)) + quat_all = np.zeros((n_steps, 4)) + t_all = np.linspace(0, args.video_seconds, n_steps) + + for step in range(n_steps): + action, _ = model.predict(obs, deterministic=True) + obs, _, done, _, _ = env.step(action) + pos_all[step] = env.drone_sim.pos[0].cpu().numpy() if hasattr(env.drone_sim.pos, "cpu") \ + else env.drone_sim.pos[0] + quat_all[step] = env.drone_sim.quat[0].cpu().numpy() if hasattr(env.drone_sim.quat, "cpu") \ + else env.drone_sim.quat[0] + + sDes_traj_all = np.zeros((n_steps, 16)) + sDes_traj_all[:, :3] = pos_all + waypoints = DEFAULT_GATE_POS.astype(float) + + video_path = str(save_dir / f"{run_name}_rollout.mp4") + os.makedirs(os.path.dirname(video_path) or ".", exist_ok=True) + + ctrl_utils.sameAxisAnimation( + t_all, waypoints, pos_all, quat_all, sDes_traj_all, dt_vid, + env.drone_sim.get_params(), 15, 3, 1, "NED", + gate_pos=DEFAULT_GATE_POS, + gate_yaw=DEFAULT_GATE_YAW, + gate_size=1.5, + save_path=video_path, + ) + print(f"Rollout video saved: {video_path}", flush=True) diff --git a/examples/d_drones/7_visualize_genome.py b/examples/d_drones/7_visualize_genome.py new file mode 100644 index 000000000..d7ce045b1 --- /dev/null +++ b/examples/d_drones/7_visualize_genome.py @@ -0,0 +1,233 @@ +"""Drone genome visualisation demo — 2D, 3D, and blueprint views. + +Shows how to visualise evolved (spherical) and hand-crafted (cartesian) drone +genomes using airevolve's DroneVisualizer. Demonstrates: + + • 2D top-down view + • 3D isometric view + • Blueprint (4-panel) view + • Coordinate-system comparison (cartesian vs spherical) + • Multi-panel analysis dashboard + +Run: + python examples/d_drones/7_visualize_genome.py + python examples/d_drones/7_visualize_genome.py --no-show # headless, save only +""" + +from __future__ import annotations + +import argparse +import os +from pathlib import Path + +import numpy as np +import matplotlib +import matplotlib.pyplot as plt + +from airevolve.evolution_tools.genome_handlers.spherical_angular_genome_handler import ( + SphericalAngularDroneGenomeHandler, +) +from airevolve.evolution_tools.genome_handlers.cartesian_euler_genome_handler import ( + CartesianEulerDroneGenomeHandler, +) +from airevolve.evolution_tools.inspection_tools.drone_visualizer import ( + DroneVisualizer, + VisualizationConfig, +) +import airevolve.evolution_tools.inspection_tools.utils as u + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +parser = argparse.ArgumentParser(description="Drone genome visualisation demo") +parser.add_argument("--no-show", action="store_true", + help="Save figures without showing interactive windows") +args = parser.parse_args() + +if args.no_show: + matplotlib.use("Agg") + +OUTPUT_DIR = Path.cwd() / "__data__" / "visualizations" / "genome_demo" +OUTPUT_DIR.mkdir(parents=True, exist_ok=True) + +visualizer = DroneVisualizer() + +# --------------------------------------------------------------------------- +# Helper genomes +# --------------------------------------------------------------------------- + +def make_quad_cartesian() -> CartesianEulerDroneGenomeHandler: + """Classic + quad in Cartesian encoding.""" + data = np.array([ + [ 0.3, 0.0, 0.0, 0.0, 0.0, 0.0, 1], + [-0.3, 0.0, 0.0, 0.0, 0.0, 0.0, 1], + [ 0.0, 0.3, 0.0, 0.0, 0.0, 0.0, 0], + [ 0.0, -0.3, 0.0, 0.0, 0.0, 0.0, 0], + ]) + return CartesianEulerDroneGenomeHandler(genome=data, min_max_narms=(4, 4)) + + +def make_hex_cartesian() -> CartesianEulerDroneGenomeHandler: + """Regular hexacopter in Cartesian encoding.""" + angles = np.linspace(0, 2 * np.pi, 7)[:-1] + r = 0.35 + data = np.array([ + [r * np.cos(a), r * np.sin(a), 0.0, 0.0, 0.0, 0.0, float(i % 2)] + for i, a in enumerate(angles) + ]) + return CartesianEulerDroneGenomeHandler(genome=data, min_max_narms=(6, 6)) + + +def make_random_spherical() -> np.ndarray: + """Random 4-arm drone in spherical encoding (phenotype array).""" + rng = np.random.default_rng(0) + handler = SphericalAngularDroneGenomeHandler( + min_max_narms=(4, 4), + parameter_limits=np.array([ + [0.055, 0.17], [-np.pi, np.pi], [-np.pi / 2, np.pi / 2], + [-np.pi, np.pi], [-np.pi, np.pi], [0, 1], + ]), + rnd=rng, + ) + g = handler._generate_random_genome(innovation_ids=np.arange(4)) + valid = ~np.isnan(g.arms[:, 0]) + return g.arms[valid] + + +def make_tilted_cartesian() -> CartesianEulerDroneGenomeHandler: + """Quad with tilted motors (30°) in Cartesian encoding.""" + tilt = np.pi / 6 + data = np.array([ + [ 0.25, 0.25, 0.0, 0.0, tilt, 0.0, 1], + [ 0.25, -0.25, 0.0, 0.0, tilt, 0.0, 1], + [-0.25, -0.25, 0.0, 0.0, -tilt, 0.0, 0], + [-0.25, 0.25, 0.0, 0.0, -tilt, 0.0, 0], + ]) + return CartesianEulerDroneGenomeHandler(genome=data, min_max_narms=(4, 4)) + + +# --------------------------------------------------------------------------- +# Demo 1: Basic 3D and 2D +# --------------------------------------------------------------------------- + +print("=== Demo 1: Basic 3D and 2D views ===") + +fig, ax = visualizer.plot_3d(make_quad_cartesian(), title="Quadcopter — 3D View", fitness=0.95) +fig.savefig(OUTPUT_DIR / "demo_3d_quadcopter.png", dpi=150, bbox_inches="tight") +if not args.no_show: + plt.show() +plt.close(fig) + +fig, ax = visualizer.plot_2d(make_hex_cartesian(), title="Hexacopter — Top View", fitness=0.87) +fig.savefig(OUTPUT_DIR / "demo_2d_hexacopter.png", dpi=150, bbox_inches="tight") +if not args.no_show: + plt.show() +plt.close(fig) + +print(f" Saved to {OUTPUT_DIR}") + +# --------------------------------------------------------------------------- +# Demo 2: Coordinate systems — Cartesian vs spherical phenotype +# --------------------------------------------------------------------------- + +print("=== Demo 2: Coordinate system comparison ===") + +fig, axes = plt.subplots(1, 2, figsize=(16, 6)) +visualizer.plot_2d(make_quad_cartesian(), ax=axes[0], title="Cartesian coordinates") +visualizer.plot_2d(make_random_spherical(), ax=axes[1], title="Spherical phenotype") +plt.tight_layout() +fig.savefig(OUTPUT_DIR / "demo_coordinate_systems.png", dpi=150, bbox_inches="tight") +if not args.no_show: + plt.show() +plt.close(fig) + +# --------------------------------------------------------------------------- +# Demo 3: Blueprint (4-panel) +# --------------------------------------------------------------------------- + +print("=== Demo 3: Blueprint views ===") + +fig, _ = visualizer.plot_blueprint( + make_tilted_cartesian(), title="Tilted Motors Drone — Blueprint" +) +fig.savefig(OUTPUT_DIR / "demo_blueprint.png", dpi=150, bbox_inches="tight") +if not args.no_show: + plt.show() +plt.close(fig) + +# --------------------------------------------------------------------------- +# Demo 4: Complex geometry grid +# --------------------------------------------------------------------------- + +print("=== Demo 4: Complex geometry grid ===") + +configs = [ + (make_tilted_cartesian(), "Tilted Motors"), + (make_hex_cartesian(), "Hexacopter"), + (make_quad_cartesian(), "Quadcopter"), + (make_random_spherical(), "Random Spherical"), +] + +fig, axes = plt.subplots(2, 2, figsize=(16, 12), + subplot_kw={"projection": "3d"}) +for ax, (genome, title) in zip(axes.flat, configs): + visualizer.plot_3d(genome, ax=ax, title=title, elevation=45, azimuth=45) +plt.tight_layout() +fig.savefig(OUTPUT_DIR / "demo_complex_geometries.png", dpi=150, bbox_inches="tight") +if not args.no_show: + plt.show() +plt.close(fig) + +# --------------------------------------------------------------------------- +# Demo 5: Multi-panel analysis dashboard for a single genome +# --------------------------------------------------------------------------- + +print("=== Demo 5: Multi-panel analysis dashboard ===") + +genome = make_tilted_cartesian() +fig = plt.figure(figsize=(15, 10)) +fig.suptitle(f"Drone Analysis Dashboard — Tilted Motors Quad", fontsize=16) + +ax1 = plt.subplot(2, 3, 1, projection="3d") +visualizer.plot_3d(genome, ax=ax1, title="Isometric (default)", elevation=30, azimuth=45) + +ax2 = plt.subplot(2, 3, 2) +visualizer.plot_2d(genome, ax=ax2, title="Top View (2D)") + +ax3 = plt.subplot(2, 3, 3, projection="3d") +visualizer.plot_3d(genome, ax=ax3, title="Front View", elevation=0, azimuth=0) + +ax4 = plt.subplot(2, 3, 4) +cfg_detail = VisualizationConfig(include_motor_orientation_2d=1) +DroneVisualizer(cfg_detail).plot_2d(genome, ax=ax4, title="With Motor Orientations") + +ax5 = plt.subplot(2, 3, 5) +cfg_minimal = VisualizationConfig(show_limits=False) +DroneVisualizer(cfg_minimal).plot_2d(genome, ax=ax5, title="Minimalist") + +ax6 = plt.subplot(2, 3, 6, projection="3d") +visualizer.plot_3d(genome, ax=ax6, title="Alternate Angle", elevation=20, azimuth=60) + +plt.tight_layout() +fig.savefig(OUTPUT_DIR / "demo_dashboard.png", dpi=150, bbox_inches="tight") +if not args.no_show: + plt.show() +plt.close(fig) + +# --------------------------------------------------------------------------- +# Demo 6: Coordinate conversion utilities +# --------------------------------------------------------------------------- + +print("=== Demo 6: Coordinate conversion utilities ===") + +mag, azi, pit = 0.12, np.pi / 4, np.pi / 6 +x, y, z = u.convert_to_cartesian(mag, azi, pit) +mag2, azi2, pit2 = u.convert_to_spherical(x, y, z) +print( + f" Spherical ({mag:.2f}, {np.degrees(azi):.1f}°, {np.degrees(pit):.1f}°)" + f" → Cartesian ({x:.3f}, {y:.3f}, {z:.3f})" + f" → back ({mag2:.2f}, {np.degrees(azi2):.1f}°, {np.degrees(pit2):.1f}°)" +) + +print(f"\nAll figures saved to: {OUTPUT_DIR}") diff --git a/examples/d_drones/8_generate_stl.py b/examples/d_drones/8_generate_stl.py new file mode 100644 index 000000000..ca473df9f --- /dev/null +++ b/examples/d_drones/8_generate_stl.py @@ -0,0 +1,184 @@ +"""Generate fabrication-ready STL/STEP files from an evolved drone genome. + +Creates a physical assembly (arms + motor mounts + propeller discs) from a +spherical drone genome and exports it to STL (3-D printing) and optionally +STEP (CAD editing) formats. Also renders a before/after comparison of the +evolved genome vs. the evenly-distributed fabrication layout. + +Run: + # Randomly generated 4-arm genome: + python examples/d_drones/8_generate_stl.py + + # Specify arm count and output directory: + python examples/d_drones/8_generate_stl.py --arms 6 --out __data__/my_drone_stl + + # Headless (no interactive matplotlib windows): + python examples/d_drones/8_generate_stl.py --no-show +""" + +from __future__ import annotations + +import argparse +from pathlib import Path + +import numpy as np +import matplotlib +import matplotlib.pyplot as plt + +from airevolve.evolution_tools.genome_handlers.spherical_angular_genome_handler import ( + SphericalAngularDroneGenomeHandler, +) +from airevolve.evolution_tools.inspection_tools.drone_visualizer import DroneVisualizer +from airevolve.phenotype_assembly import generate_stl_files, AssemblyConfig + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +parser = argparse.ArgumentParser(description="Generate STL files from a drone genome") +parser.add_argument("--arms", type=int, default=4, + help="Number of rotor arms (default 4)") +parser.add_argument("--prop-size", type=int, default=6, + help="Propeller size in inches for STL geometry (default 6)") +parser.add_argument("--out", default="__data__/drone_stl", + help="Output directory for STL/STEP files (default __data__/drone_stl)") +parser.add_argument("--seed", type=int, default=0) +parser.add_argument("--no-show", action="store_true", + help="Save visualizations without showing interactive windows") +args = parser.parse_args() + +if args.no_show: + matplotlib.use("Agg") + +output_dir = Path(args.out) +output_dir.mkdir(parents=True, exist_ok=True) + +# --------------------------------------------------------------------------- +# Generate a random genome +# --------------------------------------------------------------------------- + +PARAMETER_LIMITS = np.array([ + [0.055, 0.17], + [-np.pi, np.pi], + [-np.pi / 2, np.pi / 2], + [-np.pi, np.pi], + [-np.pi, np.pi], + [0, 1], +]) + +handler = SphericalAngularDroneGenomeHandler( + min_max_narms=(args.arms, args.arms), + parameter_limits=PARAMETER_LIMITS, + rnd=np.random.default_rng(args.seed), +) +handler._generate_random_genome(innovation_ids=np.arange(args.arms)) + +valid_arms = handler.get_valid_arms() +num_arms = len(valid_arms) + +print("=" * 70) +print(f"Generate STL — {num_arms}-arm drone") +print("=" * 70) +print("\nArm parameters:") +for i, arm in enumerate(valid_arms): + print( + f" Arm {i + 1}: mag={arm[0]:.3f} " + f"arm_az={np.degrees(arm[1]):.1f}° arm_el={np.degrees(arm[2]):.1f}° " + f"motor_az={np.degrees(arm[3]):.1f}° motor_pitch={np.degrees(arm[4]):.1f}° " + f"spin={'CW' if arm[5] > 0.5 else 'CCW'}" + ) + +# --------------------------------------------------------------------------- +# Generate STL files +# --------------------------------------------------------------------------- + +print(f"\nGenerating STL files → {output_dir}") + +assembly_config = AssemblyConfig(propeller_size=args.prop_size) +result = generate_stl_files( + handler, + output_dir=str(output_dir), + assembly_config=assembly_config, +) + +print("Generation complete!") +print(f"Output directory: {result.output_dir}") + +# --------------------------------------------------------------------------- +# Genome comparison: evolved vs. fabrication (evenly distributed) layout +# --------------------------------------------------------------------------- + +print("\n" + "-" * 70) +print("GENOME COMPARISON: evolved vs. fabrication layout") +print("-" * 70) + +viz_genome = valid_arms.copy() +for i in range(num_arms): + viz_genome[i, 1] = (2 * np.pi / num_arms) * i # evenly distribute azimuth + +print("\nOriginal genome (as evolved):") +for i, arm in enumerate(valid_arms): + print(f" Arm {i + 1}: arm_az={np.degrees(arm[1]):.1f}° mag={arm[0]:.3f}") + +print("\nFabrication genome (evenly distributed arm azimuth):") +for i, arm in enumerate(viz_genome): + print(f" Arm {i + 1}: arm_az={np.degrees(arm[1]):.1f}° mag={arm[0]:.3f}") + +# --------------------------------------------------------------------------- +# Visualisation +# --------------------------------------------------------------------------- + +visualizer = DroneVisualizer() + +# Fabrication layout blueprint +fig, _ = visualizer.plot_blueprint( + viz_genome, + title=f"Fabrication Layout — {num_arms} Arms ({args.prop_size}-inch props)", +) +viz_path = output_dir / "drone_visualization_fabrication.png" +fig.savefig(viz_path, dpi=150, bbox_inches="tight") +print(f"\nFabrication visualisation saved: {viz_path}") +if not args.no_show: + plt.show() +plt.close(fig) + +# Original genome blueprint +fig2, _ = visualizer.plot_blueprint( + handler, + title=f"Original Evolved Genome — {num_arms} Arms", +) +viz_path_orig = output_dir / "drone_visualization_original.png" +fig2.savefig(viz_path_orig, dpi=150, bbox_inches="tight") +print(f"Original genome visualisation saved: {viz_path_orig}") +if not args.no_show: + plt.show() +plt.close(fig2) + +# 6-panel analysis dashboard +fig3 = plt.figure(figsize=(16, 12)) +fig3.suptitle(f"Drone Genome Analysis — {num_arms} Arms", fontsize=16) +for idx, (elev, azim, title) in enumerate([ + (30, 45, "Isometric"), + (0, 0, "Front"), + (0, 90, "Side"), + (90, 0, "Top (3D)"), + (20, 60, "Alternate"), +], start=1): + ax = fig3.add_subplot(2, 3, idx, projection="3d") + visualizer.plot_3d(handler, ax=ax, title=title, elevation=elev, azimuth=azim) +ax6 = fig3.add_subplot(2, 3, 6) +visualizer.plot_2d(handler, ax=ax6, title="Top View (2D)") +plt.tight_layout() +analysis_path = output_dir / "drone_detailed_analysis.png" +fig3.savefig(analysis_path, dpi=150, bbox_inches="tight") +print(f"Detailed analysis saved: {analysis_path}") +if not args.no_show: + plt.show() +plt.close(fig3) + +print("\n" + "=" * 70) +print("You can now:") +print(" 1. Open the STL files in MeshLab, Blender, or your slicer") +print(" 2. Open the STEP files in FreeCAD or Fusion 360") +print(" 3. Send the STL files to a 3-D printer") +print("=" * 70) diff --git a/examples/d_drones/9_repair_demo.py b/examples/d_drones/9_repair_demo.py new file mode 100644 index 000000000..6b0fffef6 --- /dev/null +++ b/examples/d_drones/9_repair_demo.py @@ -0,0 +1,199 @@ +"""Demonstration of the optimization-based genome repair operator. + +Shows how ``OptimizationBasedRepairOperator`` detects arm collisions (arm-arm, +arm-core) in a drone genome and repairs them via constrained optimisation +(SciPy minimize) while minimising the change to the original genome. + +Four demos: + 1. Basic collision repair + 2. Repair with a custom configuration + 3. Before/after comparison (parameter by parameter) + 4. Functional API (``optimization_repair_individual``) + +Run: + python examples/d_drones/9_repair_demo.py +""" + +from __future__ import annotations + +import numpy as np + +from airevolve.evolution_tools.genome_handlers.operators.optimization_repair_operator import ( + OptimizationBasedRepairOperator, + OptimizationRepairConfig, + optimization_repair_individual, +) +from airevolve.evolution_tools.genome_handlers.operators.repair_base import RepairConfig + + +# --------------------------------------------------------------------------- +# Test genome builders +# --------------------------------------------------------------------------- + +def create_arm_collision_genome() -> np.ndarray: + """Two arms pointing almost the same direction — they will collide.""" + return np.array([ + [0.12, 0.10, 0.0, 0.5, 0.0, 1], + [0.12, 0.15, 0.0, 0.5, 0.0, 0], + [0.12, np.pi, 0.0, -0.5, 0.0, 1], + [0.12, -np.pi / 2, 0.0, -0.5, 0.0, 0], + ], dtype=float) + + +def create_core_collision_genome() -> np.ndarray: + """Arms angled steeply inward — will intersect the central core sphere.""" + return np.array([ + [0.3, 0.0, np.pi / 6, 0.5, 0.0, 1], + [0.3, np.pi / 2, np.pi / 6, 0.5, 0.0, 1], + [0.3, np.pi, np.pi / 6, 0.5, 0.0, 1], + [0.3, -np.pi / 2, np.pi / 6, 0.5, 0.0, 1], + ], dtype=float) + + +def print_genome(genome: np.ndarray, label: str = "") -> None: + if label: + print(f"\n{label}:") + cols = ["r", "theta", "phi", "motor_pitch", "motor_yaw", "dir"] + header = " " + " ".join(f"{c:>12}" for c in cols) + print(header) + for i, row in enumerate(genome): + vals = " ".join(f"{v:>12.4f}" for v in row) + print(f" arm {i}: {vals}") + + +# --------------------------------------------------------------------------- +# Demo 1: Basic repair +# --------------------------------------------------------------------------- + +def demo_basic_repair() -> None: + print("=" * 70) + print("DEMO 1: Basic Collision Repair") + print("=" * 70) + + genome = create_arm_collision_genome() + print_genome(genome, "Original genome") + + repair_op = OptimizationBasedRepairOperator(verbose=True) + is_valid = repair_op.validate(genome) + print(f"\nOriginal genome valid: {is_valid}") + + print("\nRepairing …") + repaired = repair_op.repair(genome) + print_genome(repaired, "Repaired genome") + + is_valid_after = repair_op.validate(repaired) + print(f"\nRepaired genome valid: {is_valid_after}") + changes = np.abs(repaired - genome) + print(f"Total L2 change: {np.linalg.norm(changes):.6f}") + + +# --------------------------------------------------------------------------- +# Demo 2: Custom configuration +# --------------------------------------------------------------------------- + +def demo_custom_config() -> None: + print("\n\n" + "=" * 70) + print("DEMO 2: Repair with Custom Configuration") + print("=" * 70) + + genome = create_core_collision_genome() + print_genome(genome, "Original genome") + + opt_config = OptimizationRepairConfig( + disc_radius=0.12, + disc_height=0.0, + core_radius=0.06, + propeller_radius=0.0254, + optimization_method="SLSQP", + max_iterations=500, + constraint_tolerance=1e-6, + ) + repair_op = OptimizationBasedRepairOperator(optimization_config=opt_config, verbose=False) + + print("\nRepairing with custom config …") + repaired = repair_op.repair(genome) + print_genome(repaired, "Repaired genome") + + is_valid = repair_op.validate(repaired) + print(f"\nRepaired genome valid: {is_valid}") + + +# --------------------------------------------------------------------------- +# Demo 3: Before/after comparison +# --------------------------------------------------------------------------- + +def demo_comparison() -> None: + print("\n\n" + "=" * 70) + print("DEMO 3: Before / After Comparison") + print("=" * 70) + + genome = create_arm_collision_genome() + repair_op = OptimizationBasedRepairOperator(verbose=False) + repaired = repair_op.repair(genome) + + cols = ["r", "theta", "phi", "motor_pitch", "motor_yaw", "dir"] + print(f"\n{'Arm':<6} {'Param':<14} {'Before':>10} {'After':>10} {'|Δ|':>10}") + print("-" * 60) + for arm_i, (orig_row, rep_row) in enumerate(zip(genome, repaired)): + for col, (o, r) in zip(cols, zip(orig_row, rep_row)): + delta = abs(r - o) + marker = " ←" if delta > 1e-6 else "" + print(f"arm {arm_i} {col:<14} {o:>10.4f} {r:>10.4f} {delta:>10.6f}{marker}") + + changes = np.abs(repaired - genome) + print("\nSummary:") + print(f" Mean |Δ|: {np.mean(changes):.6f}") + print(f" Max |Δ|: {np.max(changes):.6f}") + print(f" L2 |Δ|: {np.linalg.norm(changes):.6f}") + + +# --------------------------------------------------------------------------- +# Demo 4: Functional API +# --------------------------------------------------------------------------- + +def demo_functional_api() -> None: + print("\n\n" + "=" * 70) + print("DEMO 4: Functional API") + print("=" * 70) + + genome = create_core_collision_genome() + print_genome(genome, "Original genome") + + config = OptimizationRepairConfig( + disc_radius=0.15, + core_radius=0.05, + optimization_method="SLSQP", + ) + + print("\nRepairing via functional API …") + repaired = optimization_repair_individual(genome, config=config, verbose=True) + print_genome(repaired, "Repaired genome") + + changes = np.abs(repaired - genome) + print(f"\nL2 change: {np.linalg.norm(changes):.6f}") + + +# --------------------------------------------------------------------------- +# Run all demos +# --------------------------------------------------------------------------- + +print("\n") +print("*" * 70) +print("OPTIMIZATION-BASED REPAIR OPERATOR DEMONSTRATION") +print("*" * 70) + +demo_basic_repair() +demo_custom_config() +demo_comparison() +demo_functional_api() + +print("\n" + "*" * 70) +print("DEMONSTRATION COMPLETE") +print("*" * 70) +print("\nKey takeaways:") +print(" 1. The repair minimises changes to the original genome") +print(" 2. It respects disc-based attachment geometry") +print(" 3. It eliminates cylinder-cylinder and cylinder-core collisions") +print(" 4. Configuration (disc_radius, core_radius, propeller_radius) is flexible") +print(" 5. Both class-based and functional APIs are available") +print() diff --git a/examples/d_drones/_ctrl_helpers.py b/examples/d_drones/_ctrl_helpers.py new file mode 100644 index 000000000..1178d75dd --- /dev/null +++ b/examples/d_drones/_ctrl_helpers.py @@ -0,0 +1,89 @@ +"""Shared helpers for drone simulation and controller-tuning examples. + +Extracted from airevolve's tuning example so that examples 4 (simulate) and +5 (tune) can import a common drone configuration without needing sys.path +hacks between sibling directories. +""" + +from __future__ import annotations + +import numpy as np + +from airevolve.simulator.simulation import DroneInterface + +# 2-inch quadrotor constants (60 mm arm, 2-inch propellers, ~0.08 kg total) +ARM_LENGTH: float = 0.06 # metres +PROP_SIZE: int = 2 # inches + + +def create_2inch_quad() -> DroneInterface: + """Instantiate a standard 2-inch X-configuration quadrotor.""" + propellers = [ + {"loc": [ ARM_LENGTH, ARM_LENGTH, 0], "dir": [0, 0, -1, "ccw"], "propsize": PROP_SIZE}, + {"loc": [-ARM_LENGTH, ARM_LENGTH, 0], "dir": [0, 0, -1, "cw"], "propsize": PROP_SIZE}, + {"loc": [-ARM_LENGTH, -ARM_LENGTH, 0], "dir": [0, 0, -1, "ccw"], "propsize": PROP_SIZE}, + {"loc": [ ARM_LENGTH, -ARM_LENGTH, 0], "dir": [0, 0, -1, "cw"], "propsize": PROP_SIZE}, + ] + return DroneInterface(0, propellers=propellers) + + +class GateChecker: + """Detect when the drone passes through a sequence of gates. + + A gate pass is recorded when the drone crosses the gate plane within the + gate's half-size radius (measured in the gate's local frame). + """ + + def __init__( + self, + gate_pos: np.ndarray, + gate_yaw: np.ndarray, + gate_size: float = 1.0, + max_gate_distance: float = 10.0, + ) -> None: + self.gate_pos = np.asarray(gate_pos) + self.gate_yaw = np.asarray(gate_yaw) + self.gate_size = gate_size + self.max_gate_distance = max_gate_distance + self.num_gates = len(gate_pos) + self.reset() + + def reset(self) -> None: + self.gates_passed = 0 + self._next_gate = 0 + self._prev_signed_dist: float | None = None + + def check_gate_passing(self, pos: np.ndarray) -> bool: + """Return True if *pos* has just crossed the next gate.""" + if self._next_gate >= self.num_gates: + return False + + gate_p = self.gate_pos[self._next_gate] + gate_y = self.gate_yaw[self._next_gate] + normal = np.array([np.cos(gate_y), np.sin(gate_y), 0.0]) + + signed_dist = float(np.dot(pos - gate_p, normal)) + + crossed = ( + self._prev_signed_dist is not None + and self._prev_signed_dist < 0.0 + and signed_dist >= 0.0 + ) + self._prev_signed_dist = signed_dist + + if crossed: + lateral_err = np.linalg.norm(pos[:2] - gate_p[:2] + - signed_dist * normal[:2]) + if lateral_err <= self.gate_size / 2.0: + self.gates_passed += 1 + self._next_gate = (self._next_gate + 1) % self.num_gates + self._prev_signed_dist = None + return True + return False + + def get_normalized_distance_to_next_gate(self, pos: np.ndarray) -> float: + """Return a [0,1] proximity bonus to the next gate (1 = at gate, 0 = far).""" + if self._next_gate >= self.num_gates: + return 0.0 + distance = float(np.linalg.norm(pos - self.gate_pos[self._next_gate])) + return max(0.0, min(1.0, 1.0 - distance / self.max_gate_distance)) diff --git a/src/ariel/body_phenotypes/drone/__init__.py b/src/ariel/body_phenotypes/drone/__init__.py new file mode 100644 index 000000000..691f4298d --- /dev/null +++ b/src/ariel/body_phenotypes/drone/__init__.py @@ -0,0 +1,27 @@ +"""ARIEL drone body phenotype package. + +Bridges airevolve's drone genome handlers and physics simulator into ARIEL's +EA engine. Genomes are stored as JSON in the SQLite database; airevolve's +custom ODE dynamics are used for fitness evaluation. +""" + +from ariel.body_phenotypes.drone.genome import deserialize_genome, serialize_genome +from ariel.body_phenotypes.drone.operations import ( + crossover_drones, + evaluate_drones, + initialize_drones, + mutate_drones, + parent_tag, + truncation_select, +) + +__all__ = [ + "crossover_drones", + "deserialize_genome", + "evaluate_drones", + "initialize_drones", + "mutate_drones", + "parent_tag", + "serialize_genome", + "truncation_select", +] diff --git a/src/ariel/body_phenotypes/drone/genome.py b/src/ariel/body_phenotypes/drone/genome.py new file mode 100644 index 000000000..1aa8b8763 --- /dev/null +++ b/src/ariel/body_phenotypes/drone/genome.py @@ -0,0 +1,62 @@ +"""Serialization between airevolve's SphericalNeatGenome and ARIEL's JSONIterable. + +Genome format stored in Individual.genotype_ (SQLite JSON column): + { + "arms": [[mag, theta, phi, motor_theta, motor_phi, dir], ..., null, ...], + "innovation_ids": [0, 1, -1, ...] + } + +Active arm slots are 6-element float lists; empty slots are JSON null (Python +None), avoiding the NaN-in-JSON problem while preserving exact slot positions +needed for NEAT crossover alignment. +""" + +from __future__ import annotations + +from typing import TYPE_CHECKING, Any + +import numpy as np + +if TYPE_CHECKING: + from airevolve.evolution_tools.genome_handlers.spherical_angular_genome_handler import ( + SphericalNeatGenome, + ) + + +def serialize_genome(genome: "SphericalNeatGenome") -> dict[str, Any]: + """Convert a SphericalNeatGenome to a JSON-serialisable dict. + + NaN arm slots become None (JSON null). Innovation IDs are stored + inline alongside the arm array so crossover alignment survives the + DB round-trip. + """ + arms_list: list[list[float] | None] = [] + for i in range(genome.arms.shape[0]): + if np.isnan(genome.arms[i, 0]): + arms_list.append(None) + else: + arms_list.append(genome.arms[i].tolist()) + return { + "arms": arms_list, + "innovation_ids": genome.innovation_ids.tolist(), + } + + +def deserialize_genome(data: dict[str, Any]) -> "SphericalNeatGenome": + """Reconstruct a SphericalNeatGenome from a stored dict. + + None slots become NaN-padded arm rows. Innovation IDs are restored + to their original integer array so NEAT crossover can align genes. + """ + from airevolve.evolution_tools.genome_handlers.spherical_angular_genome_handler import ( + SphericalNeatGenome, + ) + + arms_list = data["arms"] + max_narms = len(arms_list) + arms = np.full((max_narms, 6), np.nan, dtype=np.float64) + for i, arm in enumerate(arms_list): + if arm is not None: + arms[i] = arm + innovation_ids = np.array(data["innovation_ids"], dtype=int) + return SphericalNeatGenome(arms=arms, innovation_ids=innovation_ids) diff --git a/src/ariel/body_phenotypes/drone/operations.py b/src/ariel/body_phenotypes/drone/operations.py new file mode 100644 index 000000000..07a1b9308 --- /dev/null +++ b/src/ariel/body_phenotypes/drone/operations.py @@ -0,0 +1,209 @@ +"""EAOperation factories for drone morphology evolution. + +Each function is decorated with @EAOperation so it can be configured and +composed into ARIEL's EA pipeline. All operations are drone-specific; +standard survivor-selection and tagging are included for convenience. + +Typical pipeline (mu+lambda with NEAT crossover): + pre-loop: + init_op = initialize_drones(template_handler=handler) + eval_op = evaluate_drones(fitness_mode="pure_hover", n_workers=N) + initial_pop = eval_op(init_op(initial_pop)) + + per generation (passed to EA.operations): + parent_tag(n=POP_SIZE) + crossover_drones(template_handler=handler) + mutate_drones(template_handler=handler) + evaluate_drones(fitness_mode="pure_hover", n_workers=N) + truncation_select(n=POP_SIZE) +""" + +import multiprocessing as mp +import os +from typing import TYPE_CHECKING, Any + +import numpy as np + +from ariel.body_phenotypes.drone.genome import deserialize_genome, serialize_genome +from ariel.ec.ea import EAOperation +from ariel.ec.individual import Individual +from ariel.ec.population import Population + +if TYPE_CHECKING: + from airevolve.evolution_tools.genome_handlers.spherical_angular_genome_handler import ( + SphericalAngularDroneGenomeHandler, + ) + + +# --------------------------------------------------------------------------- +# Multiprocessing worker — must be a module-level function for pickling +# --------------------------------------------------------------------------- + +def _drone_eval_worker(args: tuple[dict[str, Any], str]) -> float: + """Evaluate a single drone genome; called inside a Pool worker process.""" + os.environ.setdefault("OMP_NUM_THREADS", "1") + os.environ.setdefault("OPENBLAS_NUM_THREADS", "1") + os.environ.setdefault("MKL_NUM_THREADS", "1") + + genotype_dict, fitness_mode = args + + from ariel.body_phenotypes.drone.genome import deserialize_genome as _deser + + genome = _deser(genotype_dict) + valid_mask = ~np.isnan(genome.arms[:, 0]) + phenotype = genome.arms[valid_mask] + + if fitness_mode == "pure_hover": + from airevolve.evolution_tools.evaluators.hover_fitness import ( + continuous_hover_fitness, + ) + return continuous_hover_fitness(phenotype) + + from airevolve.evolution_tools.evaluators.unified_fitness import UnifiedFitness + return UnifiedFitness(fitness_mode=fitness_mode)(phenotype, log_dir=None) + + +# --------------------------------------------------------------------------- +# Operations +# --------------------------------------------------------------------------- + +@EAOperation +def initialize_drones( + population: Population, + template_handler: "SphericalAngularDroneGenomeHandler", +) -> Population: + """Assign random drone genomes to all uninitialized individuals. + + Shares initial innovation IDs across the whole population so that + NEAT crossover can align genes from generation 0. + """ + shared_innos = np.arange(template_handler.max_narms, dtype=int) + for ind in population: + if ind.requires_init: + genome = template_handler._generate_random_genome( + innovation_ids=shared_innos.copy(), + ) + ind.genotype = serialize_genome(genome) + return population + + +@EAOperation +def parent_tag( + population: Population, + n: int, +) -> Population: + """Tag the top-n alive evaluated individuals with ``ps=True`` for crossover. + + All other alive individuals have ``ps`` cleared to False. + """ + alive_eval = population.alive.evaluated + ranked = alive_eval.sort(sort="max", attribute="fitness_") + top_ids = {ind.id for ind in ranked[:n]} + for ind in population.alive: + ind.tags["ps"] = ind.id in top_ids + return population + + +@EAOperation +def crossover_drones( + population: Population, + template_handler: "SphericalAngularDroneGenomeHandler", +) -> Population: + """Produce one offspring per ps-tagged pair via NEAT crossover. + + Reads ``ind.tags["ps"] == True`` to identify parents. Pairs them in + random order and appends one child per pair as a new Individual with + ``requires_eval=True``. Innovation-ID alignment from airevolve's + SphericalAngularDroneGenomeHandler.crossover() is preserved, with the + fitter parent's disjoint genes taking priority. + """ + parents = population.where(lambda ind: bool(ind.tags.get("ps", False))).shuffle() + for i in range(0, len(parents) - 1, 2): + pa, pb = parents[i], parents[i + 1] + + ga = deserialize_genome(pa.genotype) + gb = deserialize_genome(pb.genotype) + + ha = template_handler.copy() + ha.genome = ga + ha.fitness = pa.fitness_ or 0.0 + + hb = template_handler.copy() + hb.genome = gb + hb.fitness = pb.fitness_ or 0.0 + + child_handler = ha.crossover(hb) + + child = Individual() + child.genotype = serialize_genome(child_handler.genome) + population.append(child) + return population + + +@EAOperation +def mutate_drones( + population: Population, + template_handler: "SphericalAngularDroneGenomeHandler", +) -> Population: + """Mutate all alive unevaluated individuals in place. + + Targets freshly created offspring (from crossover_drones or any other + source) without touching already-evaluated parents. + """ + for ind in population.alive.unevaluated: + genome = deserialize_genome(ind.genotype) + h = template_handler.copy() + h.genome = genome + h.mutate() + ind.genotype = serialize_genome(h.genome) + return population + + +@EAOperation +def evaluate_drones( + population: Population, + fitness_mode: str = "pure_hover", + n_workers: int = 1, +) -> Population: + """Evaluate all unevaluated drone individuals using airevolve's physics. + + For ``fitness_mode="pure_hover"``, calls ``continuous_hover_fitness`` + directly (analytical, microseconds per individual). For other modes, + delegates to ``UnifiedFitness`` which supports ``"gate"``, + ``"edit_distance"``, and ``"zero"``. + + A ``multiprocessing.Pool`` of ``n_workers`` processes is spun up and + closed within each call. Workers set BLAS thread counts to 1 to avoid + oversubscription on multi-core machines. + """ + unevaluated = list(population.unevaluated) + if not unevaluated: + return population + + eval_args = [(ind.genotype, fitness_mode) for ind in unevaluated] + + if n_workers == 1: + fitnesses = [_drone_eval_worker(a) for a in eval_args] + else: + ctx = mp.get_context("spawn") + with ctx.Pool(processes=n_workers) as pool: + fitnesses = pool.map(_drone_eval_worker, eval_args) + + for ind, fitness in zip(unevaluated, fitnesses, strict=True): + ind.fitness = fitness + + return population + + +@EAOperation +def truncation_select( + population: Population, + n: int, +) -> Population: + """Keep the top-n fittest alive individuals; mark the rest as dead.""" + alive = population.alive.evaluated + ranked = alive.sort(sort="max", attribute="fitness_") + for i, ind in enumerate(ranked): + if i >= n: + ind.alive = False + return population diff --git a/src/ariel/body_phenotypes/robogen_lite/cppn_neat/genome.py b/src/ariel/body_phenotypes/robogen_lite/cppn_neat/genome.py index 9504e6cc8..8c0aa823d 100644 --- a/src/ariel/body_phenotypes/robogen_lite/cppn_neat/genome.py +++ b/src/ariel/body_phenotypes/robogen_lite/cppn_neat/genome.py @@ -1,4 +1,5 @@ import random +from collections import deque from .activations import ACTIVATION_FUNCTIONS, DEFAULT_ACTIVATION from .connection import Connection @@ -19,6 +20,47 @@ def __init__( self.connections = connections self.fitness = fitness self.serialized = serialized + self._invalidate_cache() + + def _invalidate_cache(self): + self._input_node_ids = None + self._output_node_ids = None + self._incoming_map = None + self._topo_order = None + self._is_recurrent = None + + def _build_cache(self): + self._input_node_ids = [_id for _id, n in self.nodes.items() if n.typ == "input"] + self._output_node_ids = [_id for _id, n in self.nodes.items() if n.typ == "output"] + self._incoming_map = {n_id: [] for n_id in self.nodes} + for conn in self.connections.values(): + if conn.enabled: + self._incoming_map[conn.out_id].append(conn) + try: + self._topo_order = self.get_node_ordering() + self._is_recurrent = False + except Exception: + self._topo_order = None + self._is_recurrent = True + + def _creates_cycle(self, in_id: int, out_id: int) -> bool: + """Returns True if adding the edge in_id->out_id would create a cycle.""" + if in_id == out_id: + return True + # DFS: can we reach in_id starting from out_id through enabled connections? + visited: set[int] = set() + stack = [out_id] + while stack: + node = stack.pop() + if node == in_id: + return True + if node in visited: + continue + visited.add(node) + for conn in self.connections.values(): + if conn.enabled and conn.in_id == node: + stack.append(conn.out_id) + return False @staticmethod def _get_random_weight(): @@ -35,16 +77,10 @@ def _get_random_activation(): def copy(self): """Returns a new Genome object with identical, deep-copied gene sets.""" - - # Deep copy nodes (Node class has a copy method) new_nodes = {_id: node.copy() for _id, node in self.nodes.items()} - - # Deep copy connections (Connection class has a copy method) new_connections = { innov_id: conn.copy() for innov_id, conn in self.connections.items() } - - # Return a new Genome instance return Genome(new_nodes, new_connections, self.fitness) @classmethod @@ -59,16 +95,13 @@ def random( Creates a new, randomly initialized Genome with a base topology. Initial topology is fully connected inputs to outputs. """ - nodes = {} connections = {} - # 1. Create Input Nodes for i in range(num_inputs): node = Node(_id=i, typ="input", activation=None, bias=0.0) nodes[i] = node - # 2. Create Output Nodes (starting ID after inputs) current_node_id = num_inputs for o in range(num_outputs): node = Node( @@ -80,7 +113,6 @@ def random( nodes[current_node_id] = node current_node_id += 1 - # 3. Create Connections (Fully connect inputs to outputs) current_innov_id = next_innov_id for in_id in range(num_inputs): for out_id in range(num_inputs, num_inputs + num_outputs): @@ -93,9 +125,7 @@ def random( innov_id=current_innov_id, ) connections[current_innov_id] = connection - current_innov_id += ( - 1 # Increment for the next unique innovation ID - ) + current_innov_id += 1 return cls(nodes, connections, fitness=0.0) @@ -103,13 +133,10 @@ def mutate( self, node_add_rate: float, conn_add_rate: float, - next_innov_id_getter, # function to get/update global innovation ID - next_node_id_getter, # function to get/update global node ID + next_innov_id_getter, + next_node_id_getter, ): - """ - Applies structural mutation (add_node or add_connection). - """ - + """Applies structural mutation (add_node or add_connection).""" if random.random() < conn_add_rate: self._mutate_add_connection(next_innov_id_getter) @@ -118,52 +145,45 @@ def mutate( def _mutate_add_connection(self, next_innov_id_getter): """Attempts to add a new connection between two existing, non-connected nodes.""" - all_nodes = list(self.nodes.keys()) - # We need at least two nodes to form a connection if len(all_nodes) < 2: return - # Pick two random distinct nodes in_id, out_id = random.sample(all_nodes, 2) - # Enforce feed-forward: source must not be output, destination must not be input + # Ensure out_id is not an input (swap if needed) if self.nodes[out_id].typ == "input": in_id, out_id = out_id, in_id + # Output nodes cannot be a source if self.nodes[in_id].typ == "output": return + # Reject input→input edges + if self.nodes[in_id].typ == "input" and self.nodes[out_id].typ == "input": + return + # Reject edges that would create a cycle + if self._creates_cycle(in_id, out_id): + return - # Check if connection already exists (using in_id and out_id) for conn in self.connections.values(): if conn.in_id == in_id and conn.out_id == out_id: - return # Connection already exists + return - # Create new connection new_innov_id = next_innov_id_getter() new_weight = self._get_random_weight() new_connection = Connection( in_id, out_id, new_weight, enabled=True, innov_id=new_innov_id ) - self.add_connection(new_connection) def _mutate_add_node(self, next_innov_id_getter, next_node_id_getter): - """ - Splits an existing connection by inserting a new (hidden) node. - """ - + """Splits an existing connection by inserting a new (hidden) node.""" if not self.connections: return - # 1. Select a random existing connection to split - conn_to_split: Connection = random.choice( - list(self.connections.values()) - ) - - # 2. Disable the old connection + conn_to_split: Connection = random.choice(list(self.connections.values())) conn_to_split.enabled = False + self._invalidate_cache() - # 3. Create the new node new_node_id = next_node_id_getter() new_node = Node( _id=new_node_id, @@ -173,63 +193,54 @@ def _mutate_add_node(self, next_innov_id_getter, next_node_id_getter): ) self.add_node(new_node) - # 4. Create the first new connection (in -> new_node) innov_id_1 = next_innov_id_getter() conn1 = Connection( in_id=conn_to_split.in_id, out_id=new_node_id, - weight=1.0, # Standard NEAT practice + weight=1.0, enabled=True, innov_id=innov_id_1, ) self.add_connection(conn1) - # 5. Create the second new connection (new_node -> out) innov_id_2 = next_innov_id_getter() conn2 = Connection( in_id=new_node_id, out_id=conn_to_split.out_id, - weight=conn_to_split.weight, # Preserve original weight + weight=conn_to_split.weight, enabled=True, innov_id=innov_id_2, ) self.add_connection(conn2) - def crossover(self, other: "Genome", is_maximisation: bool=True) -> "Genome": + def crossover(self, other: "Genome", is_maximisation: bool = True) -> "Genome": """ Creates a new offspring Genome by crossing over this Genome (parent A) and another Genome (parent B). """ - - # Determine the fitter parent if is_maximisation: if self.fitness >= other.fitness: fitter_parent = self less_fit_parent = other else: - # make the fitter parent the parent "B" fitter_parent = other + less_fit_parent = self else: if self.fitness <= other.fitness: fitter_parent = self less_fit_parent = other else: - # make the fitter parent the parent "B" fitter_parent = other - less_fit_parent = self + less_fit_parent = self - # If fitnesses are equal, the shorter genome (fewer genes) should be the 'less_fit_parent' - # to ensure symmetry in gene inheritance. - if self.fitness == other.fitness and len(self.connections) < len( - other.connections - ): + # If fitnesses are equal, the shorter genome should be the less_fit_parent + if self.fitness == other.fitness and len(self.connections) < len(other.connections): fitter_parent = other less_fit_parent = self offspring_node_genes = {} offspring_connection_genes = {} - # 1. Crossover Connection Genes (nothing fancy, just a using the set operator OR here) all_innov_ids = set(fitter_parent.connections.keys()) | set( less_fit_parent.connections.keys() ) @@ -238,99 +249,74 @@ def crossover(self, other: "Genome", is_maximisation: bool=True) -> "Genome": conn_a = fitter_parent.connections.get(innov_id) conn_b = less_fit_parent.connections.get(innov_id) - # We need matching Genes (Innovation ID's) if conn_a and conn_b: - # Inherit randomly chosen_conn = random.choice([conn_a, conn_b]) - - # Copy the chosen connection offspring_connection_genes[innov_id] = chosen_conn.copy() - - # Disjoint/Excess Genes (Innovation ID is only in one parent) elif conn_a: - # Inherit from the Fitter Parent offspring_connection_genes[innov_id] = conn_a.copy() - elif conn_b: - # Standard NEAT: Only inherit if parents are equally fit. if fitter_parent.fitness == less_fit_parent.fitness: offspring_connection_genes[innov_id] = conn_b.copy() - # Otherwise, skip inheriting the less fit parent's unique gene. - # 2. Inherit Node Genes all_inherited_node_ids = set() for conn in offspring_connection_genes.values(): all_inherited_node_ids.add(conn.in_id) all_inherited_node_ids.add(conn.out_id) - # Get the node gene from the fitter parent if possible, otherwise from the less fit parent combined_nodes = {**less_fit_parent.nodes, **fitter_parent.nodes} for node_id in all_inherited_node_ids: - # Nodes are inherited without structural change, just copy the properties node_gene = combined_nodes.get(node_id) if node_gene: offspring_node_genes[node_id] = node_gene.copy() - # 3. Create and return the new Genome - return Genome( - offspring_node_genes, offspring_connection_genes, fitness=0.0 - ) + return Genome(offspring_node_genes, offspring_connection_genes, fitness=0.0) def add_connection(self, connection: Connection): """Adds a connection gene to the genome.""" - if connection not in self.connections.values(): - self.connections[connection.innov_id] = connection - else: + if any( + c.in_id == connection.in_id and c.out_id == connection.out_id + for c in self.connections.values() + ): raise ValueError("Connection already exists in genome.") + self.connections[connection.innov_id] = connection + self._invalidate_cache() def add_node(self, node: Node): """Adds a node gene to the genome.""" - if node not in self.nodes.values(): - self.nodes[node._id] = node - else: + if node._id in self.nodes: raise ValueError("Node already exists in genome.") + self.nodes[node._id] = node + self._invalidate_cache() def get_node_ordering(self): """ Calculates a topological sort order for feed-forward activation using Kahn's algorithm. - This ensures a node is evaluated only after all its input nodes are ready. https://www.geeksforgeeks.org/dsa/topological-sorting-indegree-based-solution/ """ - # 1. Build the graph structure and count incoming connections (in-degrees) for each node. graph = {node_id: [] for node_id in self.nodes} in_degree = {node_id: 0 for node_id in self.nodes} for conn in self.connections.values(): if conn.enabled: - # An edge goes from the input node to the output node graph[conn.in_id].append(conn.out_id) - # The output node gains an incoming connection in_degree[conn.out_id] += 1 - # 2. Initialize a queue with all nodes that have no incoming connections. - # These are the network's starting points (i.e., the input nodes). - queue = [node_id for node_id in self.nodes if in_degree[node_id] == 0] - + queue: deque[int] = deque( + node_id for node_id in self.nodes if in_degree[node_id] == 0 + ) sorted_order = [] - # 3. Process nodes in the queue. while queue: - # Dequeue a node that is ready to be evaluated. - node_id = queue.pop(0) + node_id = queue.popleft() sorted_order.append(node_id) - # For the node we just processed, "remove" its outgoing edges. for neighbor_id in graph[node_id]: in_degree[neighbor_id] -= 1 - # If a neighbor's in-degree drops to 0, it's now ready to be evaluated. if in_degree[neighbor_id] == 0: queue.append(neighbor_id) - # 4. Final check: If the sorted order doesn't include all nodes, - # this means there was a cycle in the graph (a recurrent connection). if len(sorted_order) != len(self.nodes): - # For a feed-forward CPPN, this indicates an issue. raise Exception( "A cycle was detected in the genome's graph, cannot create a feed-forward order." ) @@ -339,101 +325,60 @@ def get_node_ordering(self): def activate(self, inputs: list[float]) -> list[float]: """ - Activates the neural network. - 1. Tries a topological sort (Feed-Forward) for speed and precision. - 2. If a cycle is detected, falls back to iterative relaxation (Recurrent). + Activates the neural network using cached topology. + Feed-forward preferred; falls back to iterative relaxation if a cycle exists. """ + if self._input_node_ids is None: + self._build_cache() - # 1. Identify Input/Output IDs - input_node_ids = [ - _id for _id, node in self.nodes.items() if node.typ == "input" - ] - output_node_ids = [ - _id for _id, node in self.nodes.items() if node.typ == "output" - ] - - if len(inputs) != len(input_node_ids): + if len(inputs) != len(self._input_node_ids): raise ValueError( - f"Expected {len(input_node_ids)} inputs, got {len(inputs)}" + f"Expected {len(self._input_node_ids)} inputs, got {len(inputs)}" ) - try: - # --- STRATEGY A: FEED-FORWARD (Preferred) --- - ordered_node_ids = self.get_node_ordering() - - node_outputs = {} - - # Initialize Inputs - for i, node_id in enumerate(input_node_ids): + if not self._is_recurrent: + node_outputs: dict[int, float] = {} + for i, node_id in enumerate(self._input_node_ids): node_outputs[node_id] = inputs[i] - # Build adjacency cache for speed - incoming_map = {n_id: [] for n_id in self.nodes} - for conn in self.connections.values(): - if conn.enabled: - incoming_map[conn.out_id].append(conn) - - # Activate in Order - for node_id in ordered_node_ids: + for node_id in self._topo_order: node = self.nodes[node_id] if node.typ == "input": continue - - weighted_sum = 0.0 - for conn in incoming_map[node_id]: - # In feed-forward, conn.in_id is GUARANTEED to be in node_outputs - if conn.in_id in node_outputs: - weighted_sum += node_outputs[conn.in_id] * conn.weight - + weighted_sum = sum( + node_outputs[conn.in_id] * conn.weight + for conn in self._incoming_map[node_id] + if conn.in_id in node_outputs + ) weighted_sum += node.bias node_outputs[node_id] = ACTIVATION_FUNCTIONS[node.activation]( weighted_sum ) - return [node_outputs[_id] for _id in output_node_ids] - - except Exception: - # --- STRATEGY B: RECURRENT RELAXATION (Fallback) --- - # A cycle exists. We update all nodes iteratively for N steps. + return [node_outputs[_id] for _id in self._output_node_ids] - # 1. Initialize state (all 0.0) + else: current_values = {node_id: 0.0 for node_id in self.nodes} - - # 2. Set Inputs - for i, node_id in enumerate(input_node_ids): + for i, node_id in enumerate(self._input_node_ids): current_values[node_id] = inputs[i] - # 3. Pre-calculate adjacency - incoming_map = {n_id: [] for n_id in self.nodes} - for conn in self.connections.values(): - if conn.enabled: - incoming_map[conn.out_id].append(conn) - - # 4. Iterate (Relaxation) - # Running for len(nodes) ensures signal can traverse the whole graph - # regardless of topology. n_steps = len(self.nodes) + 1 - for _ in range(n_steps): next_values = current_values.copy() - for node_id, node in self.nodes.items(): if node.typ == "input": continue - - weighted_sum = 0.0 - for conn in incoming_map[node_id]: - # Use value from PREVIOUS step - weighted_sum += current_values[conn.in_id] * conn.weight - + weighted_sum = sum( + current_values[conn.in_id] * conn.weight + for conn in self._incoming_map[node_id] + ) weighted_sum += node.bias - next_values[node_id] = ACTIVATION_FUNCTIONS[ - node.activation - ](weighted_sum) - + next_values[node_id] = ACTIVATION_FUNCTIONS[node.activation]( + weighted_sum + ) current_values = next_values - return [current_values[_id] for _id in output_node_ids] + return [current_values[_id] for _id in self._output_node_ids] def to_dict(self) -> dict: """Serializes the Genome to a dictionary.""" @@ -445,7 +390,6 @@ def to_dict(self) -> dict: "activation": v.activation, "bias": v.bias, } - # Iterate items() because self.nodes is a dict for k, v in self.nodes.items() }, "connections": [ @@ -456,7 +400,6 @@ def to_dict(self) -> dict: "enabled": c.enabled, "innov_id": c.innov_id, } - # Iterate values() because self.connections is a dict {innov_id: Connection} for c in self.connections.values() ], } @@ -464,7 +407,6 @@ def to_dict(self) -> dict: @classmethod def from_dict(cls, data: dict, fitness: float = 0.0) -> "Genome": """Reconstructs a Genome object from a dictionary.""" - # 1. Rebuild Nodes nodes = {} for nid, props in data["nodes"].items(): nodes[int(nid)] = Node( @@ -474,7 +416,6 @@ def from_dict(cls, data: dict, fitness: float = 0.0) -> "Genome": bias=props["bias"], ) - # 2. Rebuild Connections connections = {} for c in data["connections"]: new_conn = Connection( @@ -485,5 +426,4 @@ def from_dict(cls, data: dict, fitness: float = 0.0) -> "Genome": innov_id=c["innov_id"], ) connections[new_conn.innov_id] = new_conn - # 3. Return new Genome instance return cls(nodes=nodes, connections=connections, fitness=0.0) diff --git a/src/ariel/body_phenotypes/robogen_lite/decoders/cppn_best_first.py b/src/ariel/body_phenotypes/robogen_lite/decoders/cppn_best_first.py index 10cb8ef68..7664396ee 100644 --- a/src/ariel/body_phenotypes/robogen_lite/decoders/cppn_best_first.py +++ b/src/ariel/body_phenotypes/robogen_lite/decoders/cppn_best_first.py @@ -1,3 +1,5 @@ +import heapq + import networkx as nx import numpy as np import numpy.typing as npt @@ -47,92 +49,81 @@ def _get_child_coords(self, parent_pos: tuple, face: ModuleFaces) -> tuple: def decode(self) -> nx.DiGraph: robot_graph = nx.DiGraph() - occupied_coords = {} - module_data = {} - - core_id, core_pos, core_type, core_rot = ( - IDX_OF_CORE, - (0, 0, 0), - ModuleType.CORE, - ModuleRotationsIdx.DEG_0, - ) - robot_graph.add_node( - core_id, type=core_type.name, rotation=core_rot.name - ) - occupied_coords[core_pos] = core_id - module_data[core_id] = { - "pos": core_pos, - "type": core_type, - "rot": core_rot, - } + occupied_coords: dict[tuple, int] = {} + module_data: dict[int, dict] = {} - # The frontier now contains ALL modules with potential open faces. - frontier = [core_id] - next_module_id = 1 + core_id = IDX_OF_CORE + core_pos = (0, 0, 0) + core_type = ModuleType.CORE + core_rot = ModuleRotationsIdx.DEG_0 - # Check for the max module count. - while len(robot_graph) < self.max_modules: - potential_connections = [] - - # At each step, we check the ENTIRE frontier of all existing modules. - for parent_id in frontier: - parent_pos = module_data[parent_id]["pos"] - parent_type = module_data[parent_id]["type"] - for face in ModuleFaces: - if face not in ALLOWED_FACES[parent_type]: - continue - - child_pos = self._get_child_coords(parent_pos, face) - - if child_pos in occupied_coords: - continue - - cppn_inputs = list(parent_pos) + list(child_pos) - raw_outputs = self.cppn_genome.activate(cppn_inputs) - - conn_score = raw_outputs[0] - type_scores = np.array( - raw_outputs[1 : 1 + NUM_OF_TYPES_OF_MODULES] - ) - rot_scores = np.array( - raw_outputs[1 + NUM_OF_TYPES_OF_MODULES :] - ) - - type_probs = softmax(type_scores) - - type_probs[ - ModuleType.NONE.value - ] = -1.0 # Ignore NONE if that's the output - type_probs[ - ModuleType.CORE.value - ] = -1.0 # Ignore CORE if that's the output - - child_type = ModuleType(np.argmax(type_probs)) - child_rot = ModuleRotationsIdx( - np.argmax(softmax(rot_scores)) - ) - - if ( - face in ALLOWED_FACES[child_type] - and child_rot in ALLOWED_ROTATIONS[child_type] - ): - potential_connections.append({ - "score": conn_score, + robot_graph.add_node(core_id, type=core_type.name, rotation=core_rot.name) + occupied_coords[core_pos] = core_id + module_data[core_id] = {"pos": core_pos, "type": core_type, "rot": core_rot} + + # Max-heap (negate score); counter breaks ties for heap stability + heap: list[tuple] = [] + _counter = 0 + + def _enqueue_faces(parent_id: int) -> None: + nonlocal _counter + parent_pos = module_data[parent_id]["pos"] + parent_type = module_data[parent_id]["type"] + for face in ModuleFaces: + if face not in ALLOWED_FACES[parent_type]: + continue + child_pos = self._get_child_coords(parent_pos, face) + if child_pos in occupied_coords: + continue + + cppn_inputs = list(parent_pos) + list(child_pos) + raw_outputs = self.cppn_genome.activate(cppn_inputs) + + conn_score = raw_outputs[0] + type_scores = np.array(raw_outputs[1: 1 + NUM_OF_TYPES_OF_MODULES]) + rot_scores = np.array(raw_outputs[1 + NUM_OF_TYPES_OF_MODULES:]) + + type_probs = softmax(type_scores) + type_probs[ModuleType.NONE.value] = -1.0 + type_probs[ModuleType.CORE.value] = -1.0 + child_type = ModuleType(np.argmax(type_probs)) + child_rot = ModuleRotationsIdx(np.argmax(softmax(rot_scores))) + + if ( + face in ALLOWED_FACES[child_type] + and child_rot in ALLOWED_ROTATIONS[child_type] + ): + heapq.heappush(heap, ( + -conn_score, + _counter, + { "parent_id": parent_id, "child_pos": child_pos, "child_type": child_type, "child_rot": child_rot, "face": face, - }) + }, + )) + _counter += 1 + + _enqueue_faces(core_id) + next_module_id = 1 - if not potential_connections: + while len(robot_graph) < self.max_modules: + # Pop until we find a connection whose target is still unoccupied + best_conn = None + while heap: + _, _, conn = heapq.heappop(heap) + if conn["child_pos"] not in occupied_coords: + best_conn = conn + break + + if best_conn is None: console.log( "[yellow]Decoder stalled: No valid connections found anywhere on the robot.[/yellow]" ) break - best_conn = max(potential_connections, key=lambda x: x["score"]) - child_id = next_module_id robot_graph.add_node( child_id, @@ -142,7 +133,6 @@ def decode(self) -> nx.DiGraph: robot_graph.add_edge( best_conn["parent_id"], child_id, face=best_conn["face"].name ) - occupied_coords[best_conn["child_pos"]] = child_id module_data[child_id] = { "pos": best_conn["child_pos"], @@ -150,9 +140,8 @@ def decode(self) -> nx.DiGraph: "rot": best_conn["child_rot"], } - # I no longer remove the parent, I just add the new child. - # (I think this makes snakes less likely) - frontier.append(child_id) + # Only the new module has new open faces; existing frontier is already in the heap + _enqueue_faces(child_id) next_module_id += 1 return robot_graph From cf20922948e4c49430fb7f4118e0e4eca600025b Mon Sep 17 00:00:00 2001 From: A-lamo <2727043@student.vu.nl> Date: Thu, 14 May 2026 16:03:19 +0200 Subject: [PATCH 02/27] Some examples work now. --- examples/d_drones/3_neat_evolution.py | 35 +- examples/d_drones/4_visualize_best_drone.py | 292 ++++++++++++++ .../d_drones/5_record_best_drone_video.py | 367 ++++++++++++++++++ 3 files changed, 681 insertions(+), 13 deletions(-) create mode 100644 examples/d_drones/4_visualize_best_drone.py create mode 100644 examples/d_drones/5_record_best_drone_video.py diff --git a/examples/d_drones/3_neat_evolution.py b/examples/d_drones/3_neat_evolution.py index 7088379fb..b5dfa1649 100644 --- a/examples/d_drones/3_neat_evolution.py +++ b/examples/d_drones/3_neat_evolution.py @@ -29,6 +29,7 @@ SphericalAngularDroneGenomeHandler, ) from airevolve.evolution_tools.evaluators.unified_fitness import UnifiedFitness +from airevolve.evolution_tools.selectors.tournament import tournament_selection from airevolve.evolution_tools.strategies import evolve_neat console = Console() @@ -38,9 +39,9 @@ # --------------------------------------------------------------------------- parser = argparse.ArgumentParser(description="NEAT-speciated drone evolution") -parser.add_argument("--pop", type=int, default=20, help="Population size") -parser.add_argument("--gens", type=int, default=30, help="Number of generations") -parser.add_argument("--workers", type=int, default=None, +parser.add_argument("--pop", type=int, default=50, help="Population size") +parser.add_argument("--gens", type=int, default=100, help="Number of generations") +parser.add_argument("--workers", type=int, default=1, help="Parallel workers for evaluation (default: 1)") parser.add_argument("--min-arms", type=int, default=4, help="Minimum rotor arms") parser.add_argument("--max-arms", type=int, default=6, help="Maximum rotor arms") @@ -88,16 +89,23 @@ [0, 1], ]) -template_handler = SphericalAngularDroneGenomeHandler( - min_max_narms=(args.min_arms, args.max_arms), - parameter_limits=PARAMETER_LIMITS, - append_arm_chance=0.1, - bilateral_plane_for_symmetry=None, - repair=False, - rnd=np.random.default_rng(args.seed), -) -fitness_fn = UnifiedFitness(fitness_mode=args.fitness) +fitness_fn = UnifiedFitness( + brain=None, + fitness_mode=args.fitness, + hover_gradient=False, + per_individual_repair=False, + is_indirect=False, + handler_class=SphericalAngularDroneGenomeHandler, + handler_kwargs={ + "min_max_narms": (args.min_arms, args.max_arms), + "parameter_limits": PARAMETER_LIMITS, + "append_arm_chance": 0.1, + "bilateral_plane_for_symmetry": None, + "repair": False, + }, + coordinate_system="spherical", +) # --------------------------------------------------------------------------- # Banner @@ -122,11 +130,12 @@ console.log("Starting NEAT evolution …") all_individuals = evolve_neat( - handler=template_handler, fitness_function=fitness_fn, population_size=args.pop, num_generations=args.gens, crossover_rate=args.crossover_rate, + parent_selection=tournament_selection, + genome_handler=SphericalAngularDroneGenomeHandler, num_workers=args.workers, compatibility_threshold=args.compat_threshold, species_elitism=args.species_elitism, diff --git a/examples/d_drones/4_visualize_best_drone.py b/examples/d_drones/4_visualize_best_drone.py new file mode 100644 index 000000000..2e343ba00 --- /dev/null +++ b/examples/d_drones/4_visualize_best_drone.py @@ -0,0 +1,292 @@ +"""Visualize the best evolved drone from NEAT evolution. + +Loads the best individual from a NEAT evolution run and displays it in: + • 3D isometric view (matplotlib) + • 2D top-down view (matplotlib) + • Blueprint 4-panel view (matplotlib) + • Interactive 3D simulator (optional) + +Run: + python examples/d_drones/4_visualize_best_drone.py + python examples/d_drones/4_visualize_best_drone.py --no-show + python examples/d_drones/4_visualize_best_drone.py --simulate +""" + +from __future__ import annotations + +import argparse +import os +from pathlib import Path + +import numpy as np +import matplotlib +import matplotlib.pyplot as plt +from rich.console import Console + +os.environ.setdefault("OMP_NUM_THREADS", "1") +os.environ.setdefault("OPENBLAS_NUM_THREADS", "1") +os.environ.setdefault("MKL_NUM_THREADS", "1") + +from airevolve.evolution_tools.genome_handlers.spherical_angular_genome_handler import ( + SphericalAngularDroneGenomeHandler, +) +from airevolve.evolution_tools.inspection_tools.drone_visualizer import ( + DroneVisualizer, + VisualizationConfig, +) + +console = Console() + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +parser = argparse.ArgumentParser( + description="Visualize the best evolved drone from NEAT evolution" +) +parser.add_argument( + "--run-dir", + type=str, + default="__data__/drone_neat_evolution", + help="Directory containing NEAT evolution results", +) +parser.add_argument( + "--generation", + type=int, + default=None, + help="Which generation to load from (default: final generation)", +) +parser.add_argument( + "--individual-id", + type=str, + default="0600", + help="Specific individual ID to visualize (default: 0600)", +) +parser.add_argument( + "--no-show", + action="store_true", + help="Save figures without showing interactive windows", +) +parser.add_argument( + "--simulate", + action="store_true", + help="Also simulate the drone using physics simulator (if available)", +) +parser.add_argument( + "--output-dir", + type=str, + default="__data__/visualizations/neat_best_drone", + help="Output directory for saved figures", +) +args = parser.parse_args() + +if args.no_show: + matplotlib.use("Agg") + +RUN_DIR = Path.cwd() / args.run_dir +OUTPUT_DIR = Path.cwd() / args.output_dir +OUTPUT_DIR.mkdir(parents=True, exist_ok=True) + +# --------------------------------------------------------------------------- +# Load best individual +# --------------------------------------------------------------------------- + + +def find_best_individual() -> tuple[str, str, str, np.ndarray]: + """Find an individual from evolution run. + + Returns: + (generation_dir, individual_dir, individual_id, genome) + """ + if not RUN_DIR.exists(): + console.print(f"[red]Error: {RUN_DIR} not found[/red]") + raise FileNotFoundError(f"Run directory {RUN_DIR} not found") + + # List all generation directories + gen_dirs = sorted([d for d in RUN_DIR.iterdir() if d.is_dir() and d.name.startswith("generation_")]) + + if not gen_dirs: + console.print(f"[red]Error: No generation directories found in {RUN_DIR}[/red]") + raise FileNotFoundError(f"No generation directories found in {RUN_DIR}") + + # Use specified generation or last one + if args.generation is not None: + gen_name = f"generation_{args.generation:02d}" + target_gen_dir = RUN_DIR / gen_name + if not target_gen_dir.exists(): + console.print(f"[red]Error: {target_gen_dir} not found[/red]") + raise FileNotFoundError(f"Generation directory {target_gen_dir} not found") + gen_dir = target_gen_dir + else: + gen_dir = gen_dirs[-1] # Use final generation + + gen_name = gen_dir.name + console.log(f"Searching {gen_name}...") + + # Determine which individual to load + target_ind_id = args.individual_id + target_ind_dir = gen_dir / f"individual_{target_ind_id}" + + if not target_ind_dir.exists(): + # If that doesn't exist, list available individuals + ind_dirs = sorted([d for d in gen_dir.iterdir() if d.is_dir() and d.name.startswith("individual_")]) + if ind_dirs: + # Use the first one + target_ind_dir = ind_dirs[0] + target_ind_id = target_ind_dir.name.split("_")[1] + console.log(f"[yellow]ID {args.individual_id} not found, using {target_ind_id}[/yellow]") + else: + raise FileNotFoundError(f"No individuals found in {gen_dir}") + + genome_path = target_ind_dir / "genome.npy" + + if not genome_path.exists(): + raise FileNotFoundError(f"Genome not found at {genome_path}") + + # Load genome (allow_pickle=True needed for object arrays) + genome_obj = np.load(genome_path, allow_pickle=True) + + # If it's wrapped in a 0-d array, unwrap it + if genome_obj.shape == (): + genome = genome_obj.item() + else: + genome = genome_obj + + console.log(f"[green]Loaded individual:[/green]") + console.log(f" Generation: {gen_name}") + console.log(f" Individual ID: {target_ind_id}") + console.log(f" Genome path: {genome_path}") + if hasattr(genome, 'arms'): + console.log(f" Genome type: SphericalNeatGenome") + console.log(f" Arms shape: {genome.arms.shape}") + else: + console.log(f" Genome shape: {genome.shape if hasattr(genome, 'shape') else 'N/A'}") + + return gen_name, target_ind_dir.name, target_ind_id, genome + + +# --------------------------------------------------------------------------- +# Main +# --------------------------------------------------------------------------- + +console.rule("[bold blue]Drone Visualization") + +gen_name, ind_dir, ind_id, genome = find_best_individual() + +# Extract phenotype (valid arms only) +# The genome is a SphericalNeatGenome object, extract the arms +if hasattr(genome, 'arms'): + # It's a namedtuple or object with arms attribute + arms_data = genome.arms +else: + # It's already a numpy array + arms_data = genome + +valid_mask = ~np.isnan(arms_data[:, 0]) +phenotype = arms_data[valid_mask] + +console.log(f"[cyan]Phenotype shape: {phenotype.shape}[/cyan]") +console.log(f" Arms: {phenotype.shape[0]}") +console.log(f" Parameters per arm: {phenotype.shape[1]}") + +# Create visualizer +visualizer = DroneVisualizer() + +# Visualization config +config = VisualizationConfig( + circle_radius=0.0254, + scale_factor=1.2, + elevation=30, + azimuth=30, +) + +# 3D Isometric View +# --------------------------------------------------------------------------- + +console.log("\n[bold cyan]Creating 3D isometric view...[/bold cyan]") +try: + fig_3d, ax_3d = visualizer.plot_3d( + phenotype, + title=f"Best Drone (Gen {gen_name}, ID {ind_id})", + generation=int(gen_name.split("_")[1]), + ) + fig_3d.tight_layout() + fig_3d.savefig(OUTPUT_DIR / "01_3d_isometric.png", dpi=150) + console.log(f" ✓ Saved to {OUTPUT_DIR / '01_3d_isometric.png'}") +except Exception as e: + console.log(f" [red]Error creating 3D plot: {e}[/red]") + +# --------------------------------------------------------------------------- +# 2D Top-Down View +# --------------------------------------------------------------------------- + +console.log("[bold cyan]Creating 2D top-down view...[/bold cyan]") +try: + fig_2d, ax_2d = visualizer.plot_2d( + phenotype, + title=f"Best Drone - Top View (Gen {gen_name})", + xlim=(-0.5, 0.5), + ylim=(-0.5, 0.5), + ) + fig_2d.tight_layout() + fig_2d.savefig(OUTPUT_DIR / "02_2d_topdown.png", dpi=150) + console.log(f" ✓ Saved to {OUTPUT_DIR / '02_2d_topdown.png'}") +except Exception as e: + console.log(f" [red]Error creating 2D plot: {e}[/red]") + +# --------------------------------------------------------------------------- +# Blueprint (4-panel) View +# --------------------------------------------------------------------------- + +console.log("[bold cyan]Creating blueprint 4-panel view...[/bold cyan]") +try: + fig_bp, axes_bp = visualizer.plot_blueprint( + phenotype, + title=f"Best Drone Blueprint (Gen {gen_name}, ID {ind_id})", + figsize=(14, 14), + ) + fig_bp.tight_layout() + fig_bp.savefig(OUTPUT_DIR / "03_blueprint.png", dpi=150) + console.log(f" ✓ Saved to {OUTPUT_DIR / '03_blueprint.png'}") +except Exception as e: + console.log(f" [red]Error creating blueprint plot: {e}[/red]") + +# --------------------------------------------------------------------------- +# Simulation (optional) +# --------------------------------------------------------------------------- + +if args.simulate: + console.log("\n[bold cyan]Attempting physics simulation...[/bold cyan]") + try: + from airevolve.evolution_tools.evaluators.hover_fitness import ( + create_drone_simulator, + ) + import mujoco + + # Create simulator for the drone + console.log(" Creating drone simulator...") + simulator = create_drone_simulator(phenotype) + + console.log(" [green]✓ Simulator created successfully[/green]") + console.log(" (Use 'python examples/d_drones/4_simulate_lee_ctrl.py' for interactive simulation)") + + except ImportError as e: + console.log(f" [yellow]Simulator not available: {e}[/yellow]") + except Exception as e: + console.log(f" [red]Error creating simulator: {e}[/red]") + +# --------------------------------------------------------------------------- +# Summary +# --------------------------------------------------------------------------- + +console.rule("[bold green]Visualization Complete") +console.log(f"Output directory: {OUTPUT_DIR}") +console.log(f"Files generated:") +console.log(f" • 01_3d_isometric.png") +console.log(f" • 02_2d_topdown.png") +console.log(f" • 03_blueprint.png") + +if not args.no_show: + plt.show() + +console.log("[bold]Done![/bold]") diff --git a/examples/d_drones/5_record_best_drone_video.py b/examples/d_drones/5_record_best_drone_video.py new file mode 100644 index 000000000..a2db702db --- /dev/null +++ b/examples/d_drones/5_record_best_drone_video.py @@ -0,0 +1,367 @@ +"""Record a video of the best evolved drone in 3D simulation. + +Loads the best drone individual from NEAT evolution, simulates it hovering, +and records a rotating 3D visualization as an MP4 video. + +Run: + python examples/d_drones/5_record_best_drone_video.py + python examples/d_drones/5_record_best_drone_video.py --duration 10 + python examples/d_drones/5_record_best_drone_video.py --output custom_name.mp4 +""" + +from __future__ import annotations + +import argparse +import os +from pathlib import Path + +import numpy as np +import matplotlib +import matplotlib.pyplot as plt +from matplotlib.animation import FuncAnimation, FFMpegWriter +from mpl_toolkits.mplot3d import Axes3D +from rich.console import Console + +matplotlib.use("Agg") # Headless rendering + +os.environ.setdefault("OMP_NUM_THREADS", "1") +os.environ.setdefault("OPENBLAS_NUM_THREADS", "1") +os.environ.setdefault("MKL_NUM_THREADS", "1") + +console = Console() + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +parser = argparse.ArgumentParser( + description="Record video of the best evolved drone", +) +parser.add_argument( + "--run-dir", + type=str, + default="__data__/drone_neat_evolution", + help="Directory containing NEAT evolution results", +) +parser.add_argument( + "--generation", + type=int, + default=None, + help="Which generation to load from (default: final generation)", +) +parser.add_argument( + "--individual-id", + type=str, + default="0600", + help="Specific individual ID to visualize (default: 0600)", +) +parser.add_argument( + "--duration", + type=float, + default=5.0, + help="Video duration in seconds (default: 5.0)", +) +parser.add_argument( + "--output", + type=str, + default=None, + help="Output video filename (default: best_drone_gen{generation}_id{id}.mp4)", +) +parser.add_argument( + "--fps", + type=int, + default=30, + help="Video frames per second (default: 30)", +) +args = parser.parse_args() + +RUN_DIR = Path.cwd() / args.run_dir +OUTPUT_DIR = Path.cwd() / "__data__" / "videos" +OUTPUT_DIR.mkdir(parents=True, exist_ok=True) + +# --------------------------------------------------------------------------- +# Load drone genome +# --------------------------------------------------------------------------- + + +def load_drone_genome() -> tuple[str, str, np.ndarray]: + """Load drone genome from evolution run. + + Returns: + (generation_name, individual_id, phenotype_arms) + """ + if not RUN_DIR.exists(): + console.print(f"[red]Error: {RUN_DIR} not found[/red]") + raise FileNotFoundError(f"Run directory {RUN_DIR} not found") + + # List all generation directories + gen_dirs = sorted([d for d in RUN_DIR.iterdir() if d.is_dir() and d.name.startswith("generation_")]) + + if not gen_dirs: + raise FileNotFoundError(f"No generation directories found in {RUN_DIR}") + + # Use specified generation or last one + if args.generation is not None: + gen_name = f"generation_{args.generation:02d}" + gen_dir = RUN_DIR / gen_name + if not gen_dir.exists(): + raise FileNotFoundError(f"Generation directory {gen_dir} not found") + else: + gen_dir = gen_dirs[-1] + gen_name = gen_dir.name + + # Load the specific individual + target_ind_id = args.individual_id + target_ind_dir = gen_dir / f"individual_{target_ind_id}" + + if not target_ind_dir.exists(): + ind_dirs = sorted([d for d in gen_dir.iterdir() if d.is_dir() and d.name.startswith("individual_")]) + if not ind_dirs: + raise FileNotFoundError(f"No individuals found in {gen_dir}") + target_ind_dir = ind_dirs[0] + target_ind_id = target_ind_dir.name.split("_")[1] + + genome_path = target_ind_dir / "genome.npy" + if not genome_path.exists(): + raise FileNotFoundError(f"Genome not found at {genome_path}") + + # Load genome (allow_pickle=True needed for SphericalNeatGenome objects) + genome_obj = np.load(genome_path, allow_pickle=True) + if genome_obj.shape == (): + genome = genome_obj.item() + else: + genome = genome_obj + + # Extract phenotype (valid arms only) + if hasattr(genome, 'arms'): + arms_data = genome.arms + else: + arms_data = genome + + valid_mask = ~np.isnan(arms_data[:, 0]) + phenotype = arms_data[valid_mask] + + console.log(f"[green]Loaded drone:[/green]") + console.log(f" Generation: {gen_name}") + console.log(f" Individual ID: {target_ind_id}") + console.log(f" Arms: {phenotype.shape[0]}") + + return gen_name, target_ind_id, phenotype + + +# --------------------------------------------------------------------------- +# Animation & Video Recording +# --------------------------------------------------------------------------- + +def create_drone_animation(phenotype: np.ndarray, gen_name: str, ind_id: str) -> tuple[plt.Figure, FuncAnimation]: + """Create animated 3D visualization of drone. + + Args: + phenotype: Arm parameters (N, 6) where each row is [r, yaw, pitch, roll, yaw2, motor_ccw] + gen_name: Generation name for title + ind_id: Individual ID for title + + Returns: + (figure, animation) tuple + """ + # Create figure and 3D axis + fig = plt.figure(figsize=(10, 8)) + ax = fig.add_subplot(111, projection='3d') + + # Extract arm positions from spherical coordinates + # Parameters: [radius, yaw, pitch, roll, yaw2, motor_type] + # For visualization, we use radius, yaw, pitch to get 3D positions + + arms = [] + for arm_params in phenotype: + r = arm_params[0] # radius + yaw = arm_params[1] # yaw angle + pitch = arm_params[2] # pitch angle + + # Convert spherical to Cartesian + x = r * np.cos(yaw) * np.cos(pitch) + y = r * np.sin(yaw) * np.cos(pitch) + z = r * np.sin(pitch) + arms.append([x, y, z]) + + arms = np.array(arms) + + # Plot setup + def init(): + ax.clear() + ax.set_xlim(-0.3, 0.3) + ax.set_ylim(-0.3, 0.3) + ax.set_zlim(-0.3, 0.3) + ax.set_xlabel("X (m)") + ax.set_ylabel("Y (m)") + ax.set_zlabel("Z (m)") + ax.set_title(f"Best Drone (Gen {gen_name.split('_')[1]}, ID {ind_id}) - Hovering") + return [] + + def animate(frame): + ax.clear() + + # Rotating view based on frame + rotation_angle = (frame / 30) * 360 # Full rotation every 30 frames + + # Plot center (body) + ax.scatter([0], [0], [0], c='black', s=100, marker='o', label='Body') + + # Plot arms and motors + colors = plt.cm.viridis(np.linspace(0, 1, len(arms))) + for i, (arm, color) in enumerate(zip(arms, colors)): + # Draw line from center to motor + ax.plot([0, arm[0]], [0, arm[1]], [0, arm[2]], 'k-', alpha=0.3, linewidth=1) + + # Draw motor as a circle + motor_radius = 0.02 + u = np.linspace(0, 2 * np.pi, 20) + motor_x = motor_radius * np.cos(u) + arm[0] + motor_y = motor_radius * np.sin(u) + arm[1] + motor_z = np.full_like(u, arm[2]) + ax.plot(motor_x, motor_y, motor_z, color=color, linewidth=2, label=f'Motor {i+1}') + + ax.set_xlim(-0.3, 0.3) + ax.set_ylim(-0.3, 0.3) + ax.set_zlim(-0.3, 0.3) + ax.set_xlabel("X (m)") + ax.set_ylabel("Y (m)") + ax.set_zlabel("Z (m)") + ax.set_title( + f"Best Drone (Gen {gen_name.split('_')[1]}, ID {ind_id}) - Hovering\n" + f"Arms: {len(arms)} | View angle: {rotation_angle:.0f}°" + ) + + # Set viewing angle + ax.view_init(elev=20, azim=rotation_angle) + + if frame == 0: + ax.legend(loc='upper right', fontsize=8) + + return [] + + # Create animation + num_frames = int(args.duration * args.fps) + anim = FuncAnimation( + fig, + animate, + init_func=init, + frames=num_frames, + interval=1000 / args.fps, + blit=True, + repeat=False, + ) + + return fig, anim + + +# --------------------------------------------------------------------------- +# Main +# --------------------------------------------------------------------------- + +console.rule("[bold blue]Drone Video Recording") + +gen_name, ind_id, phenotype = load_drone_genome() + +console.log(f"\n[bold cyan]Creating animation...[/bold cyan]") + +fig, anim = create_drone_animation(phenotype, gen_name, ind_id) + +# Determine output file +output_file = args.output +if output_file is None: + gen_num = gen_name.split("_")[1] + output_file = f"best_drone_gen{gen_num}_id{ind_id}.mp4" + +output_path = OUTPUT_DIR / output_file + +console.log(f"[bold cyan]Recording video...[/bold cyan]") +console.log(f" Duration: {args.duration}s") +console.log(f" FPS: {args.fps}") +console.log(f" Frames: {int(args.duration * args.fps)}") +console.log(f" Output: {output_path}") + +# Write video +writer = FFMpegWriter(fps=args.fps, bitrate=1800) +try: + with writer.saving(fig, str(output_path), dpi=100): + num_frames = int(args.duration * args.fps) + for frame in range(num_frames): + # Manually update animation + ax = fig.axes[0] + ax.clear() + + # Rotating drone (not camera) - spin around Z axis + rotation_angle = (frame / 30) * 360 # Full rotation every 30 frames + rotation_rad = np.deg2rad(rotation_angle) + + # Create rotation matrix for Z-axis rotation + cos_r = np.cos(rotation_rad) + sin_r = np.sin(rotation_rad) + rotation_matrix = np.array([ + [cos_r, -sin_r, 0], + [sin_r, cos_r, 0], + [0, 0, 1] + ]) + + # Plot center + ax.scatter([0], [0], [0], c='black', s=100, marker='o') + + # Plot arms and motors (rotated) + colors = plt.cm.viridis(np.linspace(0, 1, len(phenotype))) + for i, (arm_params, color) in enumerate(zip(phenotype, colors)): + r = arm_params[0] + yaw = arm_params[1] + pitch = arm_params[2] + + # Original position + x = r * np.cos(yaw) * np.cos(pitch) + y = r * np.sin(yaw) * np.cos(pitch) + z = r * np.sin(pitch) + + # Rotate position around Z axis + pos = np.array([x, y, z]) + rotated_pos = rotation_matrix @ pos + x, y, z = rotated_pos + + # Draw line from center to motor + ax.plot([0, x], [0, y], [0, z], 'k-', alpha=0.3, linewidth=1) + + # Draw motor circle + motor_radius = 0.02 + u = np.linspace(0, 2 * np.pi, 20) + motor_x = motor_radius * np.cos(u) + x + motor_y = motor_radius * np.sin(u) + y + motor_z = np.full_like(u, z) + ax.plot(motor_x, motor_y, motor_z, color=color, linewidth=2) + + ax.set_xlim(-0.3, 0.3) + ax.set_ylim(-0.3, 0.3) + ax.set_zlim(-0.3, 0.3) + ax.set_xlabel("X (m)") + ax.set_ylabel("Y (m)") + ax.set_zlabel("Z (m)") + ax.set_title( + f"Best Drone (Gen {gen_name.split('_')[1]}, ID {ind_id}) - Hovering\n" + f"Arms: {len(phenotype)} | Rotation: {rotation_angle:.0f}°" + ) + # Fixed camera angle + ax.view_init(elev=20, azim=45) + + writer.grab_frame() + + # Progress indicator + if (frame + 1) % 10 == 0: + console.log(f" Frame {frame + 1}/{num_frames}") + + console.log(f"\n[green]✓ Video saved to {output_path}[/green]") + console.log(f" File size: {output_path.stat().st_size / (1024*1024):.1f} MB") + +except Exception as e: + console.log(f"[red]Error during video recording: {e}[/red]") + import traceback + traceback.print_exc() +finally: + plt.close(fig) + +console.rule("[bold]Done") From 4ed7e5d4f4c8dd6dd5dfa8d4b4a10a27579394a8 Mon Sep 17 00:00:00 2001 From: A-lamo <2727043@student.vu.nl> Date: Mon, 18 May 2026 18:45:39 +0200 Subject: [PATCH 03/27] Migration started. --- examples/d_drones/1_hover_evolution.py | 11 +- examples/d_drones/1_run_evolution.py | 128 ++ examples/d_drones/2_drone_evolution.py | 11 +- examples/d_drones/2_simulate_lee.py | 172 +++ examples/d_drones/3_neat_evolution.py | 20 +- examples/d_drones/3_tune_lee.py | 104 ++ examples/d_drones/4_visualize_genome.py | 105 ++ examples/d_drones/5_make_video.py | 128 ++ examples/d_drones/6_train_rl_figure8.py | 14 +- examples/d_drones/_viz_best.py | 212 +++ src/ariel/body_phenotypes/drone/genome.py | 4 +- src/ariel/body_phenotypes/drone/operations.py | 6 +- src/ariel/ec/drone/__init__.py | 1 + src/ariel/ec/drone/evaluators/__init__.py | 1 + .../ec/drone/evaluators/edit_distance.py | 224 +++ .../ec/drone/evaluators/gate_evaluator.py | 161 ++ src/ariel/ec/drone/evaluators/gate_train.py | 397 +++++ .../ec/drone/evaluators/hover_fitness.py | 52 + .../ec/drone/evaluators/lee_tune_evaluator.py | 974 ++++++++++++ .../ec/drone/evaluators/unified_fitness.py | 184 +++ src/ariel/ec/drone/evaluators/zero.py | 6 + .../ec/drone/genome_handlers/__init__.py | 26 + src/ariel/ec/drone/genome_handlers/base.py | 129 ++ .../cartesian_euler_genome_handler.py | 1088 ++++++++++++++ .../genome_handlers/conversions/__init__.py | 1 + .../conversions/arm_conversions.py | 547 +++++++ .../conversions/conversions.py | 756 ++++++++++ .../ec/drone/genome_handlers/cppn/__init__.py | 24 + .../genome_handlers/cppn/compatibility.py | 73 + .../drone/genome_handlers/cppn/crossover.py | 236 +++ .../drone/genome_handlers/cppn/evaluation.py | 105 ++ .../drone/genome_handlers/cppn/innovation.py | 45 + .../drone/genome_handlers/cppn/mutations.py | 279 ++++ .../ec/drone/genome_handlers/cppn/network.py | 134 ++ .../genome_handlers/cppn/segment_decoder.py | 86 ++ .../cppn_neat_genome_handler.py | 452 ++++++ .../hybrid_cppn_genome_handler.py | 620 ++++++++ .../drone/genome_handlers/mounting_points.py | 109 ++ .../genome_handlers/operators/__init__.py | 36 + .../operators/optimization_repair_operator.py | 1251 ++++++++++++++++ .../operators/particle_repair_operator.py | 319 ++++ .../genome_handlers/operators/repair_base.py | 420 ++++++ .../operators/repair_cartesian.py | 408 +++++ .../operators/repair_spherical.py | 387 +++++ .../operators/symmetry_base.py | 272 ++++ .../operators/symmetry_cartesian.py | 372 +++++ .../operators/symmetry_spherical.py | 350 +++++ .../drone/genome_handlers/repair_workflow.py | 700 +++++++++ .../spherical_angular_genome_handler.py | 1318 +++++++++++++++++ src/ariel/ec/drone/inspection/__init__.py | 1 + .../ec/drone/inspection/animation_utils.py | 578 ++++++++ .../behavioural_analysis/__init__.py | 1 + .../gate_based/__init__.py | 1 + .../animate_individual_with_gates.py | 144 ++ .../gate_based/animate_lee_individual.py | 189 +++ .../gate_based/calculate_stats.py | 33 + .../gate_based/combine_videos.py | 51 + .../gate_based/extract_lee_simulation_data.py | 82 + .../gate_based/extract_simulation_data.py | 101 ++ .../gate_based/plot_racing_line.py | 175 +++ .../gate_based/plot_speed_actions.py | 480 ++++++ .../ec/drone/inspection/cppn_visualizer.py | 393 +++++ .../ec/drone/inspection/create_subplot.py | 223 +++ .../ec/drone/inspection/drone_visualizer.py | 877 +++++++++++ .../ec/drone/inspection/evolution_analyzer.py | 679 +++++++++ .../ec/drone/inspection/evolution_plotters.py | 532 +++++++ .../ec/drone/inspection/grid_generators.py | 573 +++++++ .../inspection/learning_analysis/__init__.py | 1 + .../learning_analysis/learning_descriptors.py | 569 +++++++ .../morphological_descriptors/__init__.py | 1 + .../morphological_descriptors/area.py | 53 + .../avr_arm_length.py | 8 + .../biradial_symmetry.py | 125 ++ .../central_symmetry.py | 90 ++ .../centre_of_gravity.py | 2 + .../hovering_info.py | 235 +++ .../morphological_descriptors/inertia.py | 79 + .../morphological_descriptors/mass.py | 10 + .../morphological_descriptors/num_arms.py | 7 + .../morphological_descriptors/proportion.py | 62 + .../thrust_alignment.py | 95 ++ .../var_arm_length.py | 7 + .../morphological_descriptors/volume.py | 52 + .../morphological_descriptors/xyz.py | 235 +++ .../drone/inspection/number_sampled_cubes.py | 207 +++ .../ec/drone/inspection/plot_diversity.py | 76 + src/ariel/ec/drone/inspection/plot_fitness.py | 92 ++ src/ariel/ec/drone/inspection/plot_space.py | 498 +++++++ .../drone/inspection/population_filtering.py | 424 ++++++ src/ariel/ec/drone/inspection/utils.py | 416 ++++++ src/ariel/ec/drone/selectors/__init__.py | 1 + src/ariel/ec/drone/selectors/tournament.py | 14 + src/ariel/ec/drone/strategies/__init__.py | 2 + .../drone/strategies/evolution_components.py | 87 ++ src/ariel/ec/drone/strategies/neat.py | 337 +++++ src/ariel/ec/drone/strategies/speciation.py | 150 ++ src/ariel/simulation/drone/__init__.py | 3 + .../simulation/drone/controllers/__init__.py | 1 + .../drone/controllers/lee_control/__init__.py | 3 + .../lee_control/acceleration_control.py | 49 + .../lee_control/attitude_control.py | 46 + .../lee_control/base_lee_controller.py | 359 +++++ .../lee_control/fully_actuated_control.py | 43 + .../controllers/lee_control/lee_controller.py | 361 +++++ .../controllers/lee_control/lee_math_utils.py | 306 ++++ .../lee_control/position_control.py | 67 + .../controllers/lee_control/rates_control.py | 31 + .../lee_control/velocity_control.py | 54 + .../velocity_steeing_angle_controller.py | 53 + .../trajectory_generation/__init__.py | 1 + .../bspline_gate_trajectory.py | 611 ++++++++ .../trajectory_generation/bspline_utils.py | 414 ++++++ .../trajectory_generation/trajectory.py | 155 ++ .../drone/controllers/utils/__init__.py | 5 + .../drone/controllers/utils/animation.py | 250 ++++ .../drone/controllers/utils/display.py | 202 +++ .../drone/controllers/utils/gate_configs.py | 107 ++ .../controllers/utils/quaternion_functions.py | 31 + .../controllers/utils/rotation_conversion.py | 150 ++ .../controllers/utils/state_conversions.py | 54 + .../drone/controllers/utils/wind_model.py | 109 ++ .../simulation/drone/drone_configuration.py | 333 +++++ src/ariel/simulation/drone/drone_interface.py | 136 ++ src/ariel/simulation/drone/drone_simulator.py | 482 ++++++ src/ariel/simulation/drone/dynamics_params.py | 149 ++ src/ariel/simulation/drone/propeller_data.py | 276 ++++ src/ariel/simulation/drone/test_simulation.py | 12 + src/ariel/simulation/tasks/drone_gate_env.py | 554 +++++++ src/ariel/visualisation/drone/__init__.py | 2 + src/ariel/visualisation/drone/animation.py | 755 ++++++++++ .../visualisation/drone/demo_plotting.py | 402 +++++ .../drone/drone_visualization.py | 375 +++++ src/ariel/visualisation/drone/graphics_3d.py | 260 ++++ 133 files changed, 29689 insertions(+), 18 deletions(-) create mode 100644 examples/d_drones/1_run_evolution.py create mode 100644 examples/d_drones/2_simulate_lee.py create mode 100644 examples/d_drones/3_tune_lee.py create mode 100644 examples/d_drones/4_visualize_genome.py create mode 100644 examples/d_drones/5_make_video.py create mode 100644 examples/d_drones/_viz_best.py create mode 100644 src/ariel/ec/drone/__init__.py create mode 100644 src/ariel/ec/drone/evaluators/__init__.py create mode 100644 src/ariel/ec/drone/evaluators/edit_distance.py create mode 100644 src/ariel/ec/drone/evaluators/gate_evaluator.py create mode 100644 src/ariel/ec/drone/evaluators/gate_train.py create mode 100644 src/ariel/ec/drone/evaluators/hover_fitness.py create mode 100644 src/ariel/ec/drone/evaluators/lee_tune_evaluator.py create mode 100644 src/ariel/ec/drone/evaluators/unified_fitness.py create mode 100644 src/ariel/ec/drone/evaluators/zero.py create mode 100644 src/ariel/ec/drone/genome_handlers/__init__.py create mode 100644 src/ariel/ec/drone/genome_handlers/base.py create mode 100644 src/ariel/ec/drone/genome_handlers/cartesian_euler_genome_handler.py create mode 100644 src/ariel/ec/drone/genome_handlers/conversions/__init__.py create mode 100644 src/ariel/ec/drone/genome_handlers/conversions/arm_conversions.py create mode 100644 src/ariel/ec/drone/genome_handlers/conversions/conversions.py create mode 100644 src/ariel/ec/drone/genome_handlers/cppn/__init__.py create mode 100644 src/ariel/ec/drone/genome_handlers/cppn/compatibility.py create mode 100644 src/ariel/ec/drone/genome_handlers/cppn/crossover.py create mode 100644 src/ariel/ec/drone/genome_handlers/cppn/evaluation.py create mode 100644 src/ariel/ec/drone/genome_handlers/cppn/innovation.py create mode 100644 src/ariel/ec/drone/genome_handlers/cppn/mutations.py create mode 100644 src/ariel/ec/drone/genome_handlers/cppn/network.py create mode 100644 src/ariel/ec/drone/genome_handlers/cppn/segment_decoder.py create mode 100644 src/ariel/ec/drone/genome_handlers/cppn_neat_genome_handler.py create mode 100644 src/ariel/ec/drone/genome_handlers/hybrid_cppn_genome_handler.py create mode 100644 src/ariel/ec/drone/genome_handlers/mounting_points.py create mode 100644 src/ariel/ec/drone/genome_handlers/operators/__init__.py create mode 100644 src/ariel/ec/drone/genome_handlers/operators/optimization_repair_operator.py create mode 100644 src/ariel/ec/drone/genome_handlers/operators/particle_repair_operator.py create mode 100644 src/ariel/ec/drone/genome_handlers/operators/repair_base.py create mode 100644 src/ariel/ec/drone/genome_handlers/operators/repair_cartesian.py create mode 100644 src/ariel/ec/drone/genome_handlers/operators/repair_spherical.py create mode 100644 src/ariel/ec/drone/genome_handlers/operators/symmetry_base.py create mode 100644 src/ariel/ec/drone/genome_handlers/operators/symmetry_cartesian.py create mode 100644 src/ariel/ec/drone/genome_handlers/operators/symmetry_spherical.py create mode 100644 src/ariel/ec/drone/genome_handlers/repair_workflow.py create mode 100644 src/ariel/ec/drone/genome_handlers/spherical_angular_genome_handler.py create mode 100644 src/ariel/ec/drone/inspection/__init__.py create mode 100644 src/ariel/ec/drone/inspection/animation_utils.py create mode 100644 src/ariel/ec/drone/inspection/behavioural_analysis/__init__.py create mode 100644 src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/__init__.py create mode 100644 src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/animate_individual_with_gates.py create mode 100644 src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/animate_lee_individual.py create mode 100644 src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/calculate_stats.py create mode 100644 src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/combine_videos.py create mode 100644 src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/extract_lee_simulation_data.py create mode 100644 src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/extract_simulation_data.py create mode 100644 src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/plot_racing_line.py create mode 100644 src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/plot_speed_actions.py create mode 100644 src/ariel/ec/drone/inspection/cppn_visualizer.py create mode 100644 src/ariel/ec/drone/inspection/create_subplot.py create mode 100644 src/ariel/ec/drone/inspection/drone_visualizer.py create mode 100644 src/ariel/ec/drone/inspection/evolution_analyzer.py create mode 100644 src/ariel/ec/drone/inspection/evolution_plotters.py create mode 100644 src/ariel/ec/drone/inspection/grid_generators.py create mode 100644 src/ariel/ec/drone/inspection/learning_analysis/__init__.py create mode 100644 src/ariel/ec/drone/inspection/learning_analysis/learning_descriptors.py create mode 100644 src/ariel/ec/drone/inspection/morphological_descriptors/__init__.py create mode 100644 src/ariel/ec/drone/inspection/morphological_descriptors/area.py create mode 100644 src/ariel/ec/drone/inspection/morphological_descriptors/avr_arm_length.py create mode 100644 src/ariel/ec/drone/inspection/morphological_descriptors/biradial_symmetry.py create mode 100644 src/ariel/ec/drone/inspection/morphological_descriptors/central_symmetry.py create mode 100644 src/ariel/ec/drone/inspection/morphological_descriptors/centre_of_gravity.py create mode 100644 src/ariel/ec/drone/inspection/morphological_descriptors/hovering_info.py create mode 100644 src/ariel/ec/drone/inspection/morphological_descriptors/inertia.py create mode 100644 src/ariel/ec/drone/inspection/morphological_descriptors/mass.py create mode 100644 src/ariel/ec/drone/inspection/morphological_descriptors/num_arms.py create mode 100644 src/ariel/ec/drone/inspection/morphological_descriptors/proportion.py create mode 100644 src/ariel/ec/drone/inspection/morphological_descriptors/thrust_alignment.py create mode 100644 src/ariel/ec/drone/inspection/morphological_descriptors/var_arm_length.py create mode 100644 src/ariel/ec/drone/inspection/morphological_descriptors/volume.py create mode 100644 src/ariel/ec/drone/inspection/morphological_descriptors/xyz.py create mode 100644 src/ariel/ec/drone/inspection/number_sampled_cubes.py create mode 100644 src/ariel/ec/drone/inspection/plot_diversity.py create mode 100644 src/ariel/ec/drone/inspection/plot_fitness.py create mode 100644 src/ariel/ec/drone/inspection/plot_space.py create mode 100644 src/ariel/ec/drone/inspection/population_filtering.py create mode 100644 src/ariel/ec/drone/inspection/utils.py create mode 100644 src/ariel/ec/drone/selectors/__init__.py create mode 100644 src/ariel/ec/drone/selectors/tournament.py create mode 100644 src/ariel/ec/drone/strategies/__init__.py create mode 100644 src/ariel/ec/drone/strategies/evolution_components.py create mode 100644 src/ariel/ec/drone/strategies/neat.py create mode 100644 src/ariel/ec/drone/strategies/speciation.py create mode 100644 src/ariel/simulation/drone/__init__.py create mode 100644 src/ariel/simulation/drone/controllers/__init__.py create mode 100644 src/ariel/simulation/drone/controllers/lee_control/__init__.py create mode 100644 src/ariel/simulation/drone/controllers/lee_control/acceleration_control.py create mode 100644 src/ariel/simulation/drone/controllers/lee_control/attitude_control.py create mode 100644 src/ariel/simulation/drone/controllers/lee_control/base_lee_controller.py create mode 100644 src/ariel/simulation/drone/controllers/lee_control/fully_actuated_control.py create mode 100644 src/ariel/simulation/drone/controllers/lee_control/lee_controller.py create mode 100644 src/ariel/simulation/drone/controllers/lee_control/lee_math_utils.py create mode 100644 src/ariel/simulation/drone/controllers/lee_control/position_control.py create mode 100644 src/ariel/simulation/drone/controllers/lee_control/rates_control.py create mode 100644 src/ariel/simulation/drone/controllers/lee_control/velocity_control.py create mode 100644 src/ariel/simulation/drone/controllers/lee_control/velocity_steeing_angle_controller.py create mode 100644 src/ariel/simulation/drone/controllers/trajectory_generation/__init__.py create mode 100644 src/ariel/simulation/drone/controllers/trajectory_generation/bspline_gate_trajectory.py create mode 100644 src/ariel/simulation/drone/controllers/trajectory_generation/bspline_utils.py create mode 100644 src/ariel/simulation/drone/controllers/trajectory_generation/trajectory.py create mode 100644 src/ariel/simulation/drone/controllers/utils/__init__.py create mode 100644 src/ariel/simulation/drone/controllers/utils/animation.py create mode 100644 src/ariel/simulation/drone/controllers/utils/display.py create mode 100644 src/ariel/simulation/drone/controllers/utils/gate_configs.py create mode 100644 src/ariel/simulation/drone/controllers/utils/quaternion_functions.py create mode 100644 src/ariel/simulation/drone/controllers/utils/rotation_conversion.py create mode 100644 src/ariel/simulation/drone/controllers/utils/state_conversions.py create mode 100644 src/ariel/simulation/drone/controllers/utils/wind_model.py create mode 100644 src/ariel/simulation/drone/drone_configuration.py create mode 100644 src/ariel/simulation/drone/drone_interface.py create mode 100644 src/ariel/simulation/drone/drone_simulator.py create mode 100644 src/ariel/simulation/drone/dynamics_params.py create mode 100644 src/ariel/simulation/drone/propeller_data.py create mode 100644 src/ariel/simulation/drone/test_simulation.py create mode 100644 src/ariel/simulation/tasks/drone_gate_env.py create mode 100644 src/ariel/visualisation/drone/__init__.py create mode 100644 src/ariel/visualisation/drone/animation.py create mode 100644 src/ariel/visualisation/drone/demo_plotting.py create mode 100644 src/ariel/visualisation/drone/drone_visualization.py create mode 100644 src/ariel/visualisation/drone/graphics_3d.py diff --git a/examples/d_drones/1_hover_evolution.py b/examples/d_drones/1_hover_evolution.py index be5a6cebe..fc9d53f57 100644 --- a/examples/d_drones/1_hover_evolution.py +++ b/examples/d_drones/1_hover_evolution.py @@ -27,7 +27,7 @@ os.environ.setdefault("OPENBLAS_NUM_THREADS", "1") os.environ.setdefault("MKL_NUM_THREADS", "1") -from airevolve.evolution_tools.genome_handlers.spherical_angular_genome_handler import ( +from ariel.ec.drone.genome_handlers.spherical_angular_genome_handler import ( SphericalAngularDroneGenomeHandler, ) from ariel.body_phenotypes.drone import ( @@ -61,6 +61,10 @@ help="Fitness function (pure_hover: analytical hover quality [0,3])", ) parser.add_argument("--seed", type=int, default=42) +parser.add_argument("--viz", action="store_true", + help="Simulate best individual after evolution and save hover video") +parser.add_argument("--viz-duration", type=float, default=10.0, + help="Hover video duration in seconds (default 10)") args = parser.parse_args() POP_SIZE: int = args.pop @@ -147,6 +151,11 @@ console.rule("[bold green]Running EA") ea.run() +if args.viz: + import sys; sys.path.insert(0, str(Path(__file__).parent)) + from _viz_best import viz_best_from_db + viz_best_from_db(DATA / "database.db", DATA / "best_hover.mp4", duration=args.viz_duration) + # --------------------------------------------------------------------------- # Post-hoc analysis via Archive # --------------------------------------------------------------------------- diff --git a/examples/d_drones/1_run_evolution.py b/examples/d_drones/1_run_evolution.py new file mode 100644 index 000000000..ff11ab8ba --- /dev/null +++ b/examples/d_drones/1_run_evolution.py @@ -0,0 +1,128 @@ +"""Drone morphology evolution using ARIEL's EA engine. + +Evolves drone designs encoded as spherical-coordinate arm arrays, evaluated +with ``continuous_hover_fitness`` (fast, analytical) or ``UnifiedFitness`` +for gate/edit-distance modes. + +Quick start: + # Pure-hover fitness (CPU, fast smoke test): + uv run examples/d_drones/1_run_evolution.py \\ + --fitness pure_hover --population-size 20 --generations 10 + + # Gate fitness with 4 workers: + uv run examples/d_drones/1_run_evolution.py \\ + --fitness gate --population-size 50 --generations 100 --n-workers 4 + + # Edit-distance diversity measure: + uv run examples/d_drones/1_run_evolution.py \\ + --fitness edit_distance --population-size 30 --generations 50 +""" + +from __future__ import annotations + +import argparse +import os +from pathlib import Path + +os.environ.setdefault("OMP_NUM_THREADS", "1") +os.environ.setdefault("OPENBLAS_NUM_THREADS", "1") +os.environ.setdefault("MKL_NUM_THREADS", "1") + +import numpy as np + +from ariel.ec.ea import EA, EASettings +from ariel.ec.population import Population +from ariel.body_phenotypes.drone.operations import ( + initialize_drones, + crossover_drones, + mutate_drones, + evaluate_drones, + parent_tag, + truncation_select, +) +from ariel.ec.drone.genome_handlers.spherical_angular_genome_handler import ( + SphericalAngularDroneGenomeHandler, +) + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +parser = argparse.ArgumentParser(description="Drone morphology evolution") +parser.add_argument("--population-size", type=int, default=50, + help="Number of individuals in the population (default 50)") +parser.add_argument("--generations", type=int, default=100, + help="Number of EA generations (default 100)") +parser.add_argument("--fitness", + choices=["pure_hover", "gate", "edit_distance", "zero"], + default="pure_hover", + help="Fitness mode (default pure_hover)") +parser.add_argument("--n-workers", type=int, default=1, + help="Parallel evaluation workers (default 1)") +parser.add_argument("--seed", type=int, default=None, + help="Random seed for reproducibility") +parser.add_argument("--save-dir", default="__data__/drone_evolution", + help="Output directory (default __data__/drone_evolution)") +parser.add_argument("--viz", action="store_true", + help="Simulate best individual after evolution and save hover video") +parser.add_argument("--viz-duration", type=float, default=10.0, + help="Hover video duration in seconds (default 10)") +args = parser.parse_args() + +if args.seed is not None: + np.random.seed(args.seed) + rng = np.random.default_rng(args.seed) +else: + rng = np.random.default_rng() + +save_dir = Path(args.save_dir) +save_dir.mkdir(parents=True, exist_ok=True) + +print(f"=== Drone Evolution ===") +print(f" fitness={args.fitness} pop={args.population_size} gens={args.generations}" + f" workers={args.n_workers} seed={args.seed}") +print(f" save_dir={save_dir}") + +# --------------------------------------------------------------------------- +# Genome handler (template for all operations) +# --------------------------------------------------------------------------- + +handler = SphericalAngularDroneGenomeHandler( + min_max_narms=(3, 8), + append_arm_chance=0.1, + rnd=rng, +) + +# --------------------------------------------------------------------------- +# EA operations +# --------------------------------------------------------------------------- + +init_op = initialize_drones(template_handler=handler) +eval_op = evaluate_drones(fitness_mode=args.fitness, n_workers=args.n_workers) +tag_op = parent_tag(n=args.population_size) +xover_op = crossover_drones(template_handler=handler) +mutate_op = mutate_drones(template_handler=handler) +select_op = truncation_select(n=args.population_size) + +from ariel.ec.individual import Individual + +initial_pop = Population([Individual() for _ in range(args.population_size)]) +initial_pop = init_op(initial_pop) +initial_pop = eval_op(initial_pop) + +ea = EA( + population=initial_pop, + operations=[tag_op, xover_op, mutate_op, eval_op, select_op], + num_steps=args.generations, + db_file_path=save_dir / "evolution.db", + db_handling="delete", +) + +print("\nStarting evolution …") +ea.run() +print(f"\nDone. Database saved to: {save_dir / 'evolution.db'}") + +if args.viz: + import sys; sys.path.insert(0, str(Path(__file__).parent)) + from _viz_best import viz_best_from_db + viz_best_from_db(save_dir / "evolution.db", save_dir / "best_hover.mp4", duration=args.viz_duration) diff --git a/examples/d_drones/2_drone_evolution.py b/examples/d_drones/2_drone_evolution.py index 1d9639ecc..5662063aa 100644 --- a/examples/d_drones/2_drone_evolution.py +++ b/examples/d_drones/2_drone_evolution.py @@ -24,7 +24,7 @@ os.environ.setdefault("OPENBLAS_NUM_THREADS", "1") os.environ.setdefault("MKL_NUM_THREADS", "1") -from airevolve.evolution_tools.genome_handlers.spherical_angular_genome_handler import ( +from ariel.ec.drone.genome_handlers.spherical_angular_genome_handler import ( SphericalAngularDroneGenomeHandler, ) from ariel.body_phenotypes.drone import ( @@ -67,6 +67,10 @@ help="Selection strategy: plus (mu+lambda, parents survive) or comma (mu,lambda)", ) parser.add_argument("--seed", type=int, default=42) +parser.add_argument("--viz", action="store_true", + help="Simulate best individual after evolution and save hover video") +parser.add_argument("--viz-duration", type=float, default=10.0, + help="Hover video duration in seconds (default 10)") args = parser.parse_args() POP_SIZE: int = args.pop @@ -162,6 +166,11 @@ console.rule("[bold green]Running EA") ea.run() +if args.viz: + import sys; sys.path.insert(0, str(Path(__file__).parent)) + from _viz_best import viz_best_from_db + viz_best_from_db(DATA / "database.db", DATA / "best_hover.mp4", duration=args.viz_duration) + # --------------------------------------------------------------------------- # Post-hoc analysis # --------------------------------------------------------------------------- diff --git a/examples/d_drones/2_simulate_lee.py b/examples/d_drones/2_simulate_lee.py new file mode 100644 index 000000000..e93b27ffe --- /dev/null +++ b/examples/d_drones/2_simulate_lee.py @@ -0,0 +1,172 @@ +"""3D simulation of a drone with Lee Geometric Controller and B-spline gate trajectory. + +Mirrors src/airevolve/examples/simulation/run_3D_simulation_lee_ctrl.py +using ARIEL imports. + +Usage: + # Visualise with figure-8 gates (interactive animation): + uv run examples/d_drones/2_simulate_lee.py --gates figure8 + + # Headless with circle gates for 20 s: + uv run examples/d_drones/2_simulate_lee.py --gates circle --time 20 --no-viz + + # Load tuned controller from JSON produced by 3_tune_lee.py: + uv run examples/d_drones/2_simulate_lee.py \\ + --gates figure8 --bspline-config __data__/tuning/tuning_results.json + +Requires: matplotlib, numpy (bundled in the project's uv environment) +""" + +from __future__ import annotations + +import argparse +import json +import os +import sys +import time + +import numpy as np + +from ariel.simulation.drone import DroneSimulator, create_standard_propeller_config +from ariel.simulation.drone.drone_interface import DroneInterface +from ariel.simulation.drone.controllers.trajectory_generation.trajectory import Trajectory +from ariel.simulation.drone.controllers.trajectory_generation.bspline_gate_trajectory import ( + BSplineGateTrajectory, +) +from ariel.simulation.drone.controllers.utils.gate_configs import GATE_CONFIGS +import ariel.simulation.drone.controllers.utils as utils + +# Lee controller lives in the controllers sub-package (unchanged from airevolve) +try: + from airevolve.controllers.lee_control.lee_controller import LeeGeometricControl + from airevolve.controllers.utils.wind_model import Wind +except ImportError: + print("WARNING: airevolve.controllers.lee_control not available; " + "Lee controller simulation will not run.") + LeeGeometricControl = None + Wind = None + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +parser = argparse.ArgumentParser(description="Lee Controller B-Spline Simulation") +parser.add_argument("--gates", choices=["figure8", "circle", "slalom", "backandforth"], + required=True, help="Gate configuration") +parser.add_argument("--bspline-config", default=None, + help="Path to tuning_results.json (optional)") +parser.add_argument("--time", type=float, default=20.0, + help="Simulation time in seconds (default 20)") +parser.add_argument("--dt", type=float, default=0.005, + help="Time step in seconds (default 0.005)") +parser.add_argument("--arm-length", type=float, default=0.07, + help="Arm length in metres (default 0.07)") +parser.add_argument("--prop-size", type=int, default=2, + help="Propeller size in inches (default 2)") +parser.add_argument("--no-viz", action="store_true", + help="Disable matplotlib animation") +parser.add_argument("--save", action="store_true", + help="Save animation to mp4") +args = parser.parse_args() + +if LeeGeometricControl is None: + sys.exit("Lee controller not available. Aborting.") + +# --------------------------------------------------------------------------- +# Drone +# --------------------------------------------------------------------------- + +ARM_LENGTH = args.arm_length +PROP_SIZE = args.prop_size + +propellers = create_standard_propeller_config("quad", arm_length=ARM_LENGTH, prop_size=PROP_SIZE) +quad = DroneInterface(0, propellers=propellers) + +gate_config = GATE_CONFIGS[args.gates] + +# --------------------------------------------------------------------------- +# B-spline trajectory +# --------------------------------------------------------------------------- + +bspline_params = None +if args.bspline_config: + with open(args.bspline_config, "r") as f: + config = json.load(f) + if "bspline_params" in config: + bspline_params = np.array(config["bspline_params"]) + print(f"Loaded {len(bspline_params)} B-spline parameters from {args.bspline_config}") + +traj = Trajectory(quad, "xyz_pos", np.array([15, 3, 1]), gate_config=gate_config) +if bspline_params is not None: + traj.bspline_trajectory.set_parameters(bspline_params) + +# --------------------------------------------------------------------------- +# Initial drone state aligned with trajectory start +# --------------------------------------------------------------------------- + +start_pos, _, _ = traj.bspline_trajectory.evaluate(0.0) +_, vel_050, _ = traj.bspline_trajectory.evaluate(0.05) +initial_yaw = (np.arctan2(vel_050[1], vel_050[0]) + if np.linalg.norm(vel_050[:2]) > 0.001 + else gate_config.gate_yaw[0]) +initial_euler = np.array([0.0, 0.0, initial_yaw]) +quad.drone_sim.set_state(position=start_pos, velocity=np.zeros(3), + attitude=initial_euler, angular_velocity=np.zeros(3)) +quad._update_state_variables() + +print(f"Drone start: pos={np.round(start_pos, 3)} yaw={np.degrees(initial_yaw):.1f}°") + +# --------------------------------------------------------------------------- +# Lee controller +# --------------------------------------------------------------------------- + +ctrl = LeeGeometricControl(quad, yawType=3, orient="NED", auto_scale_gains=True) +wind = Wind("None", 0, "NED") +Ts = args.dt +Tf = args.time +Ti = 0.0 + +sDes = traj.desiredState(0, Ts, quad) +ctrl.controller(sDes, quad, "xyz_pos", Ts) + +# --------------------------------------------------------------------------- +# Simulation loop +# --------------------------------------------------------------------------- + +numTimeStep = int(Tf / Ts + 1) +t_all = np.zeros(numTimeStep) +pos_all = np.zeros((numTimeStep, 3)) +quat_all = np.zeros((numTimeStep, 4)) +sDes_traj_all = np.zeros((numTimeStep, len(traj.sDes))) + +t = Ti +i = 1 +start_time = time.time() + +while round(t, 3) < Tf: + t_all[i] = t + pos_all[i] = quad.pos + quat_all[i] = quad.quat + sDes_traj_all[i] = traj.sDes + + t = quad.update(t, Ts, ctrl.w_cmd, wind) + sDes = traj.desiredState(t, Ts, quad) + ctrl.controller(sDes, quad, "xyz_pos", Ts) + i += 1 + +elapsed = time.time() - start_time +print(f"Simulated {Tf}s in {elapsed:.3f}s ({Tf/elapsed:.0f}x real-time)") + +# --------------------------------------------------------------------------- +# Animation +# --------------------------------------------------------------------------- + +if not args.no_viz: + params = {"dxm": ARM_LENGTH, "dym": ARM_LENGTH, "dzm": 0.05} + utils.sameAxisAnimation( + t_all, gate_config.gate_pos, pos_all, quat_all, sDes_traj_all, + Ts, params, 15, 3, int(args.save), "NED", + gate_pos=gate_config.gate_pos, + gate_yaw=gate_config.gate_yaw, + gate_size=getattr(gate_config, "gate_size", 1.0), + ) diff --git a/examples/d_drones/3_neat_evolution.py b/examples/d_drones/3_neat_evolution.py index b5dfa1649..7e0d98895 100644 --- a/examples/d_drones/3_neat_evolution.py +++ b/examples/d_drones/3_neat_evolution.py @@ -25,12 +25,12 @@ os.environ.setdefault("OPENBLAS_NUM_THREADS", "1") os.environ.setdefault("MKL_NUM_THREADS", "1") -from airevolve.evolution_tools.genome_handlers.spherical_angular_genome_handler import ( +from ariel.ec.drone.genome_handlers.spherical_angular_genome_handler import ( SphericalAngularDroneGenomeHandler, ) -from airevolve.evolution_tools.evaluators.unified_fitness import UnifiedFitness -from airevolve.evolution_tools.selectors.tournament import tournament_selection -from airevolve.evolution_tools.strategies import evolve_neat +from ariel.ec.drone.evaluators.unified_fitness import UnifiedFitness +from ariel.ec.drone.selectors.tournament import tournament_selection +from ariel.ec.drone.strategies import evolve_neat console = Console() @@ -69,6 +69,10 @@ parser.add_argument("--interspecies-rate", type=float, default=0.001, help="Probability of cross-species crossover (default 0.001)") parser.add_argument("--seed", type=int, default=42) +parser.add_argument("--viz", action="store_true", + help="Simulate best individual after evolution and save hover video") +parser.add_argument("--viz-duration", type=float, default=10.0, + help="Hover video duration in seconds (default 10)") args = parser.parse_args() DATA = Path.cwd() / "__data__" / "drone_neat_evolution" @@ -158,6 +162,14 @@ last_gen_df = all_individuals[all_individuals["generation"] == last_gen] best_row = last_gen_df.sort_values("fitness", ascending=False).iloc[0] +if args.viz: + import sys; sys.path.insert(0, str(Path(__file__).parent)) + from _viz_best import viz_best_phenotype + _genome = best_row["genome"] + _arms = _genome.arms if hasattr(_genome, "arms") else np.asarray(_genome) + _valid = ~np.isnan(_arms[:, 0]) + viz_best_phenotype(_arms[_valid], DATA / "best_hover.mp4", duration=args.viz_duration) + console.log( f"Best (gen {last_gen}): id={best_row['id']} " f"fitness={best_row['fitness']:.4f} " diff --git a/examples/d_drones/3_tune_lee.py b/examples/d_drones/3_tune_lee.py new file mode 100644 index 000000000..336ded320 --- /dev/null +++ b/examples/d_drones/3_tune_lee.py @@ -0,0 +1,104 @@ +"""Two-stage CMA-ES tuning of Lee controller gains for a drone morphology. + +Mirrors src/airevolve/examples/tuning/tune_lee_controller_gates.py using +ARIEL imports. + +Usage: + # Tune default 2-inch quad on figure-8 (100 CMA evaluations, 4 workers): + uv run examples/d_drones/3_tune_lee.py --gates figure8 + + # Tune individual loaded from a .npy file: + uv run examples/d_drones/3_tune_lee.py \\ + --genome-file __data__/drone_evolution/genome.npy \\ + --gates circle --max-evals 200 --workers 8 + +Requires: cma (uv pip install cma) +""" + +from __future__ import annotations + +import argparse +import json +import os +from pathlib import Path + +import numpy as np + +from ariel.ec.drone.evaluators.lee_tune_evaluator import ( + evaluate_individual_with_tuning, + optimize_controller_for_morphology, +) +from ariel.simulation.drone.controllers.utils.gate_configs import GATE_CONFIGS +from ariel.simulation.drone import create_standard_propeller_config + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +parser = argparse.ArgumentParser(description="Two-stage CMA-ES Lee controller tuning") +parser.add_argument("--gates", choices=["figure8", "circle", "slalom", "backandforth"], + default="figure8", help="Gate configuration (default figure8)") +parser.add_argument("--genome-file", default=None, + help="Path to .npy genome file. If omitted, uses a default 2-inch X-quad.") +parser.add_argument("--max-evals", type=int, default=100, + help="Maximum CMA-ES evaluations (default 100)") +parser.add_argument("--workers", type=int, default=4, + help="Parallel workers for CMA-ES (default 4)") +parser.add_argument("--sim-time", type=float, default=20.0, + help="Simulation time per evaluation in seconds (default 20)") +parser.add_argument("--dt", type=float, default=0.005, + help="Simulation time step (default 0.005)") +parser.add_argument("--timeout", type=float, default=30.0, + help="Timeout per evaluation in seconds (default 30)") +parser.add_argument("--save-dir", default="__data__/tuning", + help="Output directory (default __data__/tuning)") +args = parser.parse_args() + +save_dir = Path(args.save_dir) +save_dir.mkdir(parents=True, exist_ok=True) + +# --------------------------------------------------------------------------- +# Individual +# --------------------------------------------------------------------------- + +if args.genome_file: + individual = np.load(args.genome_file, allow_pickle=True).astype(np.float32) + print(f"Loaded genome from {args.genome_file} shape={individual.shape}") +else: + # Default: 2-inch X-quad as a (4, 6) spherical genome + # [magnitude, arm_rotation, arm_pitch, motor_rotation, motor_pitch, direction] + ARM_LENGTH = 0.07 + individual = np.array([ + [ARM_LENGTH, np.pi/4, 0.0, 0.0, 0.0, 1.0], + [ARM_LENGTH, 3*np.pi/4, 0.0, 0.0, 0.0, 0.0], + [ARM_LENGTH, -3*np.pi/4, 0.0, 0.0, 0.0, 1.0], + [ARM_LENGTH, -np.pi/4, 0.0, 0.0, 0.0, 0.0], + ], dtype=np.float32) + print(f"Using default 2-inch X-quad individual shape={individual.shape}") + +# --------------------------------------------------------------------------- +# Tuning +# --------------------------------------------------------------------------- + +gate_config = GATE_CONFIGS[args.gates] +print(f"\nGate config: {args.gates} ({len(gate_config.gate_pos)} gates)") +print(f"CMA-ES: max_evals={args.max_evals} workers={args.workers}") +print(f"Output: {save_dir}\n") + +result = optimize_controller_for_morphology( + individual=individual, + gate_config=gate_config, + max_evaluations=args.max_evals, + num_workers=args.workers, + sim_time=args.sim_time, + dt=args.dt, + timeout_per_eval=args.timeout, + save_dir=str(save_dir), +) + +print("\n=== Tuning Results ===") +print(f" Gates passed : {result.get('gates_passed', 0)}") +print(f" Best gains : {result.get('best_gains')}") +print(f" Tuning time : {result.get('tuning_time_seconds', 0):.1f}s") +print(f" Success : {result.get('success', False)}") +print(f"\nResults saved to: {save_dir}") diff --git a/examples/d_drones/4_visualize_genome.py b/examples/d_drones/4_visualize_genome.py new file mode 100644 index 000000000..74466b13f --- /dev/null +++ b/examples/d_drones/4_visualize_genome.py @@ -0,0 +1,105 @@ +"""Visualise a drone genome as 3D blueprint and propeller diagrams. + +Mirrors src/airevolve/examples/visualization/genome_visualizer_demo.py and +draw_blueprint.py using ARIEL imports. + +Usage: + # Visualise a random 2-inch quad genome: + uv run examples/d_drones/4_visualize_genome.py + + # Visualise a genome saved to .npy: + uv run examples/d_drones/4_visualize_genome.py \\ + --genome-file __data__/drone_evolution/genome.npy + + # Save figures without displaying: + uv run examples/d_drones/4_visualize_genome.py --save --no-show +""" + +from __future__ import annotations + +import argparse +from pathlib import Path + +import matplotlib.pyplot as plt +import numpy as np + +from ariel.ec.drone.inspection.drone_visualizer import DroneVisualizer +from ariel.ec.drone.genome_handlers.spherical_angular_genome_handler import ( + SphericalAngularDroneGenomeHandler, +) + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +parser = argparse.ArgumentParser(description="Drone genome visualizer") +parser.add_argument("--genome-file", default=None, + help="Path to .npy genome file (optional; uses random genome if omitted)") +parser.add_argument("--save", action="store_true", + help="Save figures to the output directory") +parser.add_argument("--no-show", action="store_true", + help="Do not display interactive figures (useful for headless runs)") +parser.add_argument("--save-dir", default="__data__/genome_viz", + help="Output directory for saved figures (default __data__/genome_viz)") +args = parser.parse_args() + +save_dir = Path(args.save_dir) +if args.save: + save_dir.mkdir(parents=True, exist_ok=True) + +# --------------------------------------------------------------------------- +# Load or generate genome +# --------------------------------------------------------------------------- + +if args.genome_file: + individual = np.load(args.genome_file, allow_pickle=True).astype(np.float64) + # Remove NaN rows to get valid arms + valid_mask = ~np.isnan(individual[:, 0]) if individual.ndim == 2 else ~np.isnan(individual) + individual = individual[valid_mask] + print(f"Loaded genome from {args.genome_file} ({len(individual)} arms)") +else: + # Generate a random 4-arm spherical genome + handler = SphericalAngularDroneGenomeHandler(min_max_narms=(4, 8)) + genome = handler._generate_random_genome() + # Extract the valid (non-NaN) arms + valid_mask = ~np.isnan(genome.arms[:, 0]) + individual = genome.arms[valid_mask] + print(f"Generated random genome ({len(individual)} arms)") + +print(f"Genome shape: {individual.shape}") +print(f"Arms (mag, arm_rot, arm_pitch, mot_rot, mot_pitch, dir):") +for i, arm in enumerate(individual): + print(f" [{i}] {np.round(arm, 3)}") + +# --------------------------------------------------------------------------- +# Blueprint visualisation +# --------------------------------------------------------------------------- + +visualizer = DroneVisualizer() + +print("\nRendering blueprint …") +fig_bp, axes_bp = visualizer.plot_blueprint(individual, title="Drone Blueprint") + +if args.save: + path = save_dir / "blueprint.png" + fig_bp.savefig(path, dpi=150, bbox_inches="tight") + print(f"Blueprint saved: {path}") + +# --------------------------------------------------------------------------- +# 3D visualisation +# --------------------------------------------------------------------------- + +print("Rendering 3D view …") +fig_3d = plt.figure(figsize=(8, 7)) +ax_3d = fig_3d.add_subplot(111, projection="3d") +visualizer.plot_3d(individual, ax=ax_3d, title="Drone 3D View") + +if args.save: + path = save_dir / "3d_view.png" + fig_3d.savefig(path, dpi=150, bbox_inches="tight") + print(f"3D view saved: {path}") + +if not args.no_show: + plt.show() +else: + plt.close("all") diff --git a/examples/d_drones/5_make_video.py b/examples/d_drones/5_make_video.py new file mode 100644 index 000000000..ae1554250 --- /dev/null +++ b/examples/d_drones/5_make_video.py @@ -0,0 +1,128 @@ +"""Create visualisation videos for a trained drone individual. + +Mirrors src/airevolve/examples/videos/make_video.py using ARIEL imports. + +Expects an ``individual_dir`` containing: + - ``individual.npy`` (or ``genome.npy``) — drone genome + - ``policy.zip`` — trained SB3 PPO policy + +Usage: + uv run examples/d_drones/5_make_video.py __data__/my_individual \\ + --gate-cfg figure8 + + # With explicit device: + uv run examples/d_drones/5_make_video.py __data__/my_individual \\ + --gate-cfg circle --device cpu +""" + +from __future__ import annotations + +import argparse +import os +from pathlib import Path + +import numpy as np + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +parser = argparse.ArgumentParser(description="Create drone visualisation videos") +parser.add_argument("individual_dir", nargs="?", default="__data__/drone_individual", + help="Directory with individual.npy/genome.npy and policy.zip") +parser.add_argument("--gate-cfg", + choices=["slalom", "figure8", "circle", "backandforth"], + default="figure8", + help="Gate configuration used during training (default figure8)") +parser.add_argument("--device", default=None, + help="Compute device (e.g. cpu, cuda:0). Auto-detected if omitted.") +parser.add_argument("--fps", type=int, default=100, + help="Frames per second (default 100)") +parser.add_argument("--width", type=int, default=864, help="Video width (default 864)") +parser.add_argument("--height", type=int, default=700, help="Video height (default 700)") +parser.add_argument("--color", default="blue", help="Primary trajectory color") +args = parser.parse_args() + +individual_dir = Path(args.individual_dir) +if not individual_dir.exists(): + raise SystemExit(f"Directory not found: {individual_dir}") + +# --------------------------------------------------------------------------- +# Load individual +# --------------------------------------------------------------------------- + +body_file = individual_dir / "individual.npy" +if not body_file.exists(): + body_file = individual_dir / "genome.npy" +if not body_file.exists(): + raise SystemExit(f"No individual.npy or genome.npy found in {individual_dir}") + +policy_file = individual_dir / "policy.zip" +if not policy_file.exists(): + raise SystemExit(f"No policy.zip found in {individual_dir}") + +individual = np.load(body_file, allow_pickle=True).astype(np.float32) +print(f"Loaded individual: {body_file} shape={individual.shape}") +print(f"Gate cfg: {args.gate_cfg}") +print(f"Device: {args.device or 'auto'}") + +# --------------------------------------------------------------------------- +# Animate (uses DroneGateEnv from ariel.simulation.tasks) +# --------------------------------------------------------------------------- + +from ariel.simulation.tasks.drone_gate_env import DroneGateEnv +from ariel.ec.drone.inspection.behavioural_analysis.gate_based.animate_individual_with_gates import ( + animate_individual, +) +from ariel.ec.drone.inspection.behavioural_analysis.gate_based.combine_videos import ( + combine_videos_from_directory, +) +from ariel.ec.drone.inspection.behavioural_analysis.gate_based.calculate_stats import ( + calculate_stats, +) + +vid_dir = individual_dir / "videos" +vid_dir.mkdir(exist_ok=True) + +motor_colors = ["red", "blue", "green", "orange", "purple", "brown"] + +print("\nRendering top-view animation …") +try: + animate_individual( + gate_cfg=args.gate_cfg, + individual_dir=str(individual_dir), + save_dir=str(vid_dir), + file_name="/top_view.mp4", + device=args.device, + view_type="top", + follow=True, + draw_forces=False, + draw_path=True, + auto_play=True, + record=True, + motor_colors=motor_colors, + ) + + print("Rendering iso-view animation …") + animate_individual( + gate_cfg=args.gate_cfg, + individual_dir=str(individual_dir), + save_dir=str(vid_dir), + file_name="/iso_view.mp4", + device=args.device, + view_type="iso", + follow=True, + draw_forces=False, + draw_path=True, + auto_play=True, + record=True, + motor_colors=motor_colors, + ) + + print("Combining videos …") + combine_videos_from_directory(str(vid_dir)) + print(f"Videos saved to: {vid_dir}") + +except Exception as exc: + print(f"Warning: Animation failed: {exc}") + print("Check that OpenCV, ffmpeg, and the policy dependencies are installed.") diff --git a/examples/d_drones/6_train_rl_figure8.py b/examples/d_drones/6_train_rl_figure8.py index fcc9c97c9..b98a3f0c9 100644 --- a/examples/d_drones/6_train_rl_figure8.py +++ b/examples/d_drones/6_train_rl_figure8.py @@ -39,13 +39,13 @@ import torch -from airevolve.evolution_tools.evaluators.drone_gate_env import ( +from ariel.simulation.tasks.drone_gate_env import ( DroneGateEnv, gate_pos as DEFAULT_GATE_POS, gate_yaw as DEFAULT_GATE_YAW, ) -from airevolve.simulator.simulation.propeller_data import create_standard_propeller_config -import airevolve.controllers.utils as ctrl_utils +from ariel.simulation.drone.propeller_data import create_standard_propeller_config +import ariel.simulation.drone.controllers.utils as ctrl_utils # --------------------------------------------------------------------------- # Window-metrics callback (vendored for self-containedness) @@ -142,18 +142,18 @@ def _on_step(self) -> bool: # --------------------------------------------------------------------------- propeller_config = create_standard_propeller_config( - arm_length=args.arm_length, prop_size=args.prop_size + "quad", arm_length=args.arm_length, prop_size=args.prop_size ) env = DroneGateEnv( - propeller_config=propeller_config, + propellers=propeller_config, num_envs=args.num_envs, device=args.device, dt=0.01, seed=args.seed, ) -obs, _ = env.reset() +obs = env.reset() print( f"obs shape: {obs.shape} num_motors: {env.num_motors} " f"mass: {env.drone_sim.mass:.3f} kg motor_tau: {env.motor_tau}", @@ -220,7 +220,7 @@ def _on_step(self) -> bool: dt_vid = 0.01 n_steps = int(args.video_seconds / dt_vid) - obs, _ = env.reset() + obs = env.reset() pos_all = np.zeros((n_steps, 3)) quat_all = np.zeros((n_steps, 4)) t_all = np.linspace(0, args.video_seconds, n_steps) diff --git a/examples/d_drones/_viz_best.py b/examples/d_drones/_viz_best.py new file mode 100644 index 000000000..58c7f1b1c --- /dev/null +++ b/examples/d_drones/_viz_best.py @@ -0,0 +1,212 @@ +"""Shared hover-simulation + video helper for evolution examples. + +Imported by evolution scripts when ``--viz`` is passed. Not intended to be +run directly. + +Public API: + viz_best_from_db(db_path, video_path, duration, dt) -- ARIEL SQLite EA runs + viz_best_phenotype(phenotype, video_path, duration, dt) -- any (N,6) arm array +""" +from __future__ import annotations + +import os +from pathlib import Path + +import numpy as np + + +def _phenotype_to_propellers(phenotype: np.ndarray) -> list[dict]: + """Convert (N, 6) arm array to propeller config list (NED frame). + + Column order: [magnitude, arm_yaw, arm_pitch, mot_pitch, mot_yaw, spin_dir] + Matches the coordinate conventions in DroneGateEnv._convert_individual_to_propellers. + """ + propellers = [] + for row in phenotype: + magnitude, arm_yaw, arm_pitch, mot_pitch, mot_yaw, direction = row + # Spherical → ENU cartesian + enu_x = magnitude * np.cos(arm_pitch) * np.cos(arm_yaw) + enu_y = magnitude * np.cos(arm_pitch) * np.sin(arm_yaw) + enu_z = magnitude * np.sin(arm_pitch) + # ENU → NED + x, y, z = enu_y, enu_x, -enu_z + # Thrust direction in NED + sp, cp = np.sin(mot_pitch), np.cos(mot_pitch) + sy, cy = np.sin(mot_yaw), np.cos(mot_yaw) + propellers.append({ + "loc": [x, y, z], + "dir": [-sy * sp, -cy * sp, cp, "cw" if direction > 0.5 else "ccw"], + "propsize": 2, + }) + return propellers + + +def _tune_hover_gains( + propellers: list[dict], + hover_pos: np.ndarray, + dt: float = 0.005, + n_eval_steps: int = 600, +) -> tuple[float, float]: + """Find pos_P and vel_P gains that minimise z-axis hover error. + + Runs a short Nelder-Mead search (≈40 evaluations × n_eval_steps steps each). + Starting point is taken from the Stage-1 gate-racing guess which has been + empirically validated for small evolved morphologies. + + Returns (pos_P, vel_P) scalars to use for all three axes. + """ + from scipy.optimize import minimize + from ariel.simulation.drone.controllers.lee_control.lee_controller import LeeGeometricControl + from ariel.simulation.drone.controllers.utils.wind_model import Wind + from ariel.simulation.drone.drone_interface import DroneInterface + + wind = Wind("None") + sDes = np.zeros(19) + sDes[:3] = hover_pos + + def _hover_cost(log_gains: np.ndarray) -> float: + pos_g = float(np.exp(np.clip(log_gains[0], -2, 5))) + vel_g = float(np.exp(np.clip(log_gains[1], -2, 5))) + try: + quad = DroneInterface(0, propellers=propellers) + quad.drone_sim.set_state( + position=hover_pos.copy(), + velocity=np.zeros(3), + attitude=np.zeros(3), + angular_velocity=np.zeros(3), + ) + quad._update_state_variables() + ctrl = LeeGeometricControl( + quad, yawType=1, orient="NED", auto_scale_gains=True, + pos_P_gain=np.array([pos_g] * 3), + vel_P_gain=np.array([vel_g] * 3), + ) + ctrl.controller(sDes, quad, "xyz_pos", dt) + t = 0.0 + total_cost = 0.0 + for _ in range(n_eval_steps): + t = quad.update(t, dt, ctrl.w_cmd, wind) + ctrl.controller(sDes, quad, "xyz_pos", dt) + err = quad.pos - hover_pos + total_cost += float(np.dot(err, err)) + return total_cost / n_eval_steps + except Exception: + return 1e6 + + # Stage-1 gate-racing best guess as warm start (empirically validated) + x0 = np.array([np.log(14.3), np.log(9.0)]) + result = minimize( + _hover_cost, x0, method="Nelder-Mead", + options={"maxiter": 60, "xatol": 0.05, "fatol": 1e-3, "disp": False}, + ) + pos_P = float(np.exp(np.clip(result.x[0], -2, 5))) + vel_P = float(np.exp(np.clip(result.x[1], -2, 5))) + return pos_P, vel_P + + +def viz_best_phenotype( + phenotype: np.ndarray, + video_path: str | Path, + duration: float = 10.0, + dt: float = 0.005, +) -> None: + """Simulate a hover for the given (N,6) phenotype and save to MP4.""" + import warnings + warnings.filterwarnings("ignore", message=".*render_mode.*") + + import ariel.simulation.drone.controllers.utils as ctrl_utils + from ariel.simulation.drone.controllers.lee_control.lee_controller import LeeGeometricControl + from ariel.simulation.drone.controllers.utils.wind_model import Wind + from ariel.simulation.drone.drone_interface import DroneInterface + + propellers = _phenotype_to_propellers(phenotype) + hover_pos = np.array([0.0, 0.0, -1.0]) # 1 m above origin in NED + + print("[viz] Tuning hover gains …", end=" ", flush=True) + pos_P, vel_P = _tune_hover_gains(propellers, hover_pos, dt=dt) + print(f"pos_P={pos_P:.2f} vel_P={vel_P:.2f}") + + quad = DroneInterface(0, propellers=propellers) + quad.drone_sim.set_state( + position=hover_pos, + velocity=np.zeros(3), + attitude=np.zeros(3), + angular_velocity=np.zeros(3), + ) + quad._update_state_variables() + + ctrl = LeeGeometricControl( + quad, yawType=1, orient="NED", auto_scale_gains=True, + pos_P_gain=np.array([pos_P] * 3), + vel_P_gain=np.array([vel_P] * 3), + ) + wind = Wind("None") + + n_steps = int(duration / dt) + 1 + t_all = np.zeros(n_steps) + pos_all = np.zeros((n_steps, 3)) + quat_all = np.zeros((n_steps, 4)) + sDes_all = np.zeros((n_steps, 19)) + sDes_all[:, :3] = hover_pos + + sDes = np.zeros(19) + sDes[:3] = hover_pos + ctrl.controller(sDes, quad, "xyz_pos", dt) + + t = 0.0 + for i in range(n_steps): + t_all[i] = t + pos_all[i] = quad.pos.copy() + quat_all[i] = quad.quat.copy() + t = quad.update(t, dt, ctrl.w_cmd, wind) + ctrl.controller(sDes, quad, "xyz_pos", dt) + + arm_len = float(np.mean([np.linalg.norm(p["loc"]) for p in propellers])) + params = {"dxm": arm_len, "dym": arm_len, "dzm": 0.05} + + video_path = Path(video_path) + video_path.parent.mkdir(parents=True, exist_ok=True) + + ctrl_utils.sameAxisAnimation( + t_all, hover_pos.reshape(1, 3), pos_all, quat_all, sDes_all, + dt, params, 0, 0, 1, "NED", + save_path=str(video_path), + ) + + +def viz_best_from_db( + db_path: str | Path, + video_path: str | Path, + duration: float = 10.0, + dt: float = 0.005, +) -> None: + """Load the highest-fitness individual from an ARIEL SQLite db and record a hover video.""" + from sqlalchemy import create_engine + from sqlmodel import Session, select + + from ariel.body_phenotypes.drone.genome import deserialize_genome + from ariel.ec.individual import Individual + + engine = create_engine(f"sqlite:///{db_path}") + with Session(engine) as session: + stmt = ( + select(Individual) + .where(Individual.requires_eval == False) # noqa: E712 + .order_by(Individual.fitness_.desc()) + .limit(1) + ) + best = session.exec(stmt).first() + + if best is None: + print(f"[viz] No evaluated individuals found in {db_path}.") + return + + genome = deserialize_genome(best.genotype) + valid_mask = ~np.isnan(genome.arms[:, 0]) + phenotype = genome.arms[valid_mask] + + print( + f"[viz] Best: id={best.id} fitness={best.fitness_:.4f} " + f"arms={int(valid_mask.sum())} → {video_path}" + ) + viz_best_phenotype(phenotype, video_path, duration=duration, dt=dt) diff --git a/src/ariel/body_phenotypes/drone/genome.py b/src/ariel/body_phenotypes/drone/genome.py index 1aa8b8763..5858bca74 100644 --- a/src/ariel/body_phenotypes/drone/genome.py +++ b/src/ariel/body_phenotypes/drone/genome.py @@ -18,7 +18,7 @@ import numpy as np if TYPE_CHECKING: - from airevolve.evolution_tools.genome_handlers.spherical_angular_genome_handler import ( + from ariel.ec.drone.genome_handlers.spherical_angular_genome_handler import ( SphericalNeatGenome, ) @@ -48,7 +48,7 @@ def deserialize_genome(data: dict[str, Any]) -> "SphericalNeatGenome": None slots become NaN-padded arm rows. Innovation IDs are restored to their original integer array so NEAT crossover can align genes. """ - from airevolve.evolution_tools.genome_handlers.spherical_angular_genome_handler import ( + from ariel.ec.drone.genome_handlers.spherical_angular_genome_handler import ( SphericalNeatGenome, ) diff --git a/src/ariel/body_phenotypes/drone/operations.py b/src/ariel/body_phenotypes/drone/operations.py index 07a1b9308..70224b713 100644 --- a/src/ariel/body_phenotypes/drone/operations.py +++ b/src/ariel/body_phenotypes/drone/operations.py @@ -30,7 +30,7 @@ from ariel.ec.population import Population if TYPE_CHECKING: - from airevolve.evolution_tools.genome_handlers.spherical_angular_genome_handler import ( + from ariel.ec.drone.genome_handlers.spherical_angular_genome_handler import ( SphericalAngularDroneGenomeHandler, ) @@ -54,12 +54,12 @@ def _drone_eval_worker(args: tuple[dict[str, Any], str]) -> float: phenotype = genome.arms[valid_mask] if fitness_mode == "pure_hover": - from airevolve.evolution_tools.evaluators.hover_fitness import ( + from ariel.ec.drone.evaluators.hover_fitness import ( continuous_hover_fitness, ) return continuous_hover_fitness(phenotype) - from airevolve.evolution_tools.evaluators.unified_fitness import UnifiedFitness + from ariel.ec.drone.evaluators.unified_fitness import UnifiedFitness return UnifiedFitness(fitness_mode=fitness_mode)(phenotype, log_dir=None) diff --git a/src/ariel/ec/drone/__init__.py b/src/ariel/ec/drone/__init__.py new file mode 100644 index 000000000..45143a995 --- /dev/null +++ b/src/ariel/ec/drone/__init__.py @@ -0,0 +1 @@ +"""Drone-specific EC components for ARIEL.""" diff --git a/src/ariel/ec/drone/evaluators/__init__.py b/src/ariel/ec/drone/evaluators/__init__.py new file mode 100644 index 000000000..3dc23cb1a --- /dev/null +++ b/src/ariel/ec/drone/evaluators/__init__.py @@ -0,0 +1 @@ +# Fitness evaluation functions \ No newline at end of file diff --git a/src/ariel/ec/drone/evaluators/edit_distance.py b/src/ariel/ec/drone/evaluators/edit_distance.py new file mode 100644 index 000000000..68235e915 --- /dev/null +++ b/src/ariel/ec/drone/evaluators/edit_distance.py @@ -0,0 +1,224 @@ +"""Evaluator functions for edit distance calculations.""" + +import numpy as np +import scipy + +from ariel.ec.drone.genome_handlers.base import GenomeHandler + +def normalize(individual_or_population, min_vals, max_vals): + """ + Normalize the parameters of each motor in each individual in the population. + + Args: + - individual_or_population (numpy.ndarray): The population array of shape (num_individuals, num_motors, num_parameters), + or individual array of shape (num_motors, num_parameters). + - min_vals (numpy.ndarray): Minimum values for normalization. + - max_vals (numpy.ndarray): Maximum values for normalization. + + Returns: + - numpy.ndarray: The normalized population or individual array. + """ + ranges = max_vals - min_vals + return (individual_or_population - min_vals) / ranges + + +def compute_euclidean_distance(ind1, ind2, min_vals, max_vals): + """ + Compute the Euclidean distance between two individuals. + + Args: + - ind1 (numpy.ndarray): First individual array of shape (num_motors, num_parameters). + - ind2 (numpy.ndarray): Second individual array of shape (num_motors, num_parameters). + - min_vals (numpy.ndarray): Minimum values for normalization. + - max_vals (numpy.ndarray): Maximum values for normalization. + + Returns: + - float: The minimum matching cost based on Euclidean distance. + """ + ind1 = normalize(ind1, min_vals, max_vals) + ind2 = normalize(ind2, min_vals, max_vals) + + valid_mask_ind1 = ~np.isnan(ind1).all(axis=1) + valid_mask_ind2 = ~np.isnan(ind2).all(axis=1) + + valid_ind1 = ind1[valid_mask_ind1] + valid_ind2 = ind2[valid_mask_ind2] + + diff = valid_ind1[:, np.newaxis, :] - valid_ind2[np.newaxis, :, :] + cost_matrix = np.sqrt(np.nansum(diff ** 2, axis=2)) + + row_ind, col_ind = scipy.optimize.linear_sum_assignment(cost_matrix) + return cost_matrix[row_ind, col_ind].sum() + + +def compute_euclidean_distance_for_pop(population, target, min_vals, max_vals): + """ + Compute the Euclidean distance between a target individual and a population. + + Args: + - population (numpy.ndarray): Population array of shape (num_individuals, num_motors, num_parameters). + - target (numpy.ndarray): Target individual array of shape (num_motors, num_parameters). + - min_vals (numpy.ndarray): Minimum values for normalization. + - max_vals (numpy.ndarray): Maximum values for normalization. + + Returns: + - numpy.ndarray: Array of distances for each individual in the population. + """ + pop_size = len(population) + dists = np.empty(pop_size) + for i in range(pop_size): + dists[i] = compute_euclidean_distance(target, population[i], min_vals, max_vals) + return dists + + +def compute_arm_cost(ind1, ind2): + """ + Compute the arm cost difference between two individuals. + + Args: + - ind1 (numpy.ndarray): First individual array of shape (num_motors, num_parameters). + - ind2 (numpy.ndarray): Second individual array of shape (num_motors, num_parameters). + + Returns: + - int: The absolute difference in the number of valid arms. + """ + ind1_num_arms = np.sum(~np.isnan(ind1).all(axis=1)) + ind2_num_arms = np.sum(~np.isnan(ind2).all(axis=1)) + return np.abs(ind1_num_arms - ind2_num_arms) + + +def compute_arm_cost_for_population(population, target): + """ + Compute the arm cost difference between a target individual and a population. + + Args: + - population (numpy.ndarray): Population array of shape (num_individuals, num_motors, num_parameters). + - target (numpy.ndarray): Target individual array of shape (num_motors, num_parameters). + + Returns: + - numpy.ndarray: Array of arm cost differences for each individual in the population. + """ + target_num_arms = np.sum(~np.isnan(target).all(axis=1)) + num_arms_per_individual = np.sum(~np.isnan(population).all(axis=2), axis=1) + return np.abs(num_arms_per_individual - target_num_arms) + + + +def compute_edit_distance(ind1, ind2, min_vals, max_vals, ins_del_cost=1.0): + """ + Compute the edit distance between two individuals. + + Args: + - ind1 (numpy.ndarray): First individual array of shape (num_motors, num_parameters). + - ind2 (numpy.ndarray): Second individual array of shape (num_motors, num_parameters). + - min_vals (numpy.ndarray): Minimum values for normalization. + - max_vals (numpy.ndarray): Maximum values for normalization. + - ins_del_cost (float): Cost of insertion or deletion. + + Returns: + - float: The edit distance. + """ + distance_cost = compute_euclidean_distance(ind1, ind2, min_vals, max_vals) + arm_cost = compute_arm_cost(ind1, ind2) * ins_del_cost + return distance_cost + arm_cost + + + +def compute_edit_distances_for_population(population, target, min_vals, max_vals, ins_del_cost=1.0): + """ + Compute the edit distances between a target individual and a population. + + Args: + - population (numpy.ndarray): Population array of shape (num_individuals, num_motors, num_parameters). + - target (numpy.ndarray): Target individual array of shape (num_motors, num_parameters). + - min_vals (numpy.ndarray): Minimum values for normalization. + - max_vals (numpy.ndarray): Maximum values for normalization. + - ins_del_cost (float): Cost of insertion or deletion. + + Returns: + - numpy.ndarray: Array of edit distances for each individual in the population. + """ + distance_cost = compute_euclidean_distance_for_pop(population, target, min_vals, max_vals) + arm_cost = compute_arm_cost_for_population(population, target) * ins_del_cost + return distance_cost + arm_cost + +def compute_population_edit_distances(population, min_vals, max_vals, ins_del_cost=1.0): + """ + Compute the average edit distances for each individual in a population. + + Args: + - population (numpy.ndarray): Population array of shape (num_individuals, num_motors, num_parameters). + - min_vals (numpy.ndarray): Minimum values for normalization. + - max_vals (numpy.ndarray): Maximum values for normalization. + - ins_del_cost (float): Cost of insertion or deletion. + + Returns: + - numpy.ndarray: Array of average edit distances for each individual in the population. + """ + pop_size = len(population) + dists = np.empty(pop_size) + + for i, ind1 in enumerate(population): + ind1_dists = np.empty(pop_size) + for j, ind2 in enumerate(population): + ind1_dists[j] = compute_edit_distance(ind1, ind2, min_vals, max_vals, ins_del_cost) + dists[i] = np.mean(ind1_dists) + + return dists + + +def compute_individual_population_edit_distance(individual, population, min_vals, max_vals): + """ + Compute the average edit distance between an individual and a population. + + Args: + - individual (numpy.ndarray): Individual array of shape (num_motors, num_parameters). + - population (numpy.ndarray): Population array of shape (num_individuals, num_motors, num_parameters). + - min_vals (numpy.ndarray): Minimum values for normalization. + - max_vals (numpy.ndarray): Maximum values for normalization. + + Returns: + - float: The average edit distance. + """ + pop_size = len(population) + distance_cost = np.empty(pop_size) + for i in range(pop_size): + distance_cost[i] = compute_euclidean_distance(individual, population[i], min_vals, max_vals) + + target_num_arms = np.sum(~np.isnan(individual).all(axis=1)) + num_arms_per_individual = np.sum(~np.isnan(population).all(axis=2), axis=1) + arm_cost = np.abs(num_arms_per_individual - target_num_arms) + + return np.mean(distance_cost + arm_cost) + + +def evaluate_individual(individual : GenomeHandler, log_dir, target, min_vals, max_vals): + """ + Evaluate the fitness of an individual based on its edit distance to the target. + + Args: + - individual (numpy.ndarray): Individual array of shape (num_motors, num_parameters). + - target (numpy.ndarray): Target individual array of shape (num_motors, num_parameters). + - min_vals (numpy.ndarray): Minimum values for normalization. + - max_vals (numpy.ndarray): Maximum values for normalization. + + Returns: + - float: The fitness value (negative edit distance). + """ + return -compute_edit_distance(target, individual.body, min_vals, max_vals) + +def evaluate_population(population, target, min_vals, max_vals, ins_del_cost=1.0): + """ + Evaluate the fitness of a population based on their edit distances to the target. + + Args: + - population (numpy.ndarray): Population array of shape (num_individuals, num_motors, num_parameters). + - target (numpy.ndarray): Target individual array of shape (num_motors, num_parameters). + - min_vals (numpy.ndarray): Minimum values for normalization. + - max_vals (numpy.ndarray): Maximum values for normalization. + - ins_del_cost (float): Cost of insertion or deletion. + + Returns: + - numpy.ndarray: Array of fitness values (negative edit distances) for the population. + """ + return -compute_edit_distances_for_population(population, target, min_vals, max_vals, ins_del_cost) \ No newline at end of file diff --git a/src/ariel/ec/drone/evaluators/gate_evaluator.py b/src/ariel/ec/drone/evaluators/gate_evaluator.py new file mode 100644 index 000000000..c100f67d3 --- /dev/null +++ b/src/ariel/ec/drone/evaluators/gate_evaluator.py @@ -0,0 +1,161 @@ + + +"""Evaluator class.""" + +import numpy as np + + +# library imports +import os +import sys +import time +import subprocess +import pandas as pd +import matplotlib.pyplot as plt +from datetime import datetime + +class GateEvaluator(): + + def __init__(self, gate_cfg, training_ts=1E8, num_envs=100, device="cuda:0") -> None: + self.gate_cfg = gate_cfg + + self.training_ts = training_ts + self.num_envs = num_envs + + self.id_counter = 0 + self.evaluation_file = os.path.abspath(os.path.join(os.path.dirname(__file__), "gate_train.py")) + + self.device = device + + def run_subprocess(self, individual_save_dir, num=None): + env = os.environ.copy() + + # Make sure the subprocess gets the same PYTHONPATH and venv path + venv_bin = os.path.dirname(sys.executable) + env["PATH"] = f"{venv_bin}:{env['PATH']}" + + # Add site-packages if needed (important for editable installs) + site_packages_path = os.path.join(venv_bin, "..", "lib", "python3.10", "site-packages") + env["PYTHONPATH"] = f"{site_packages_path}:{env.get('PYTHONPATH', '')}" + + # print(env) + # Spawn a subprocess to evaluate the morphology + if num is not None: + process = subprocess.Popen( + ["python3", self.evaluation_file, individual_save_dir, "--training_timesteps", str(self.training_ts), "--num_envs", str(self.num_envs), "--gate_cfg", self.gate_cfg, "--device", self.device, "--num", str(num)], + env=env, + stdout=subprocess.PIPE, + stderr=subprocess.PIPE, + text=True + ) + else: + process = subprocess.Popen( + ["python3", self.evaluation_file, individual_save_dir, "--training_timesteps", str(self.training_ts), "--num_envs", str(self.num_envs), "--gate_cfg", self.gate_cfg, "--device", self.device], + stdout=subprocess.PIPE, + stderr=subprocess.PIPE, + text=True + ) + return process + + def evaluate_population(self, population, gen_save_dir=None): + individual_save_dirs = [] + for i in range(len(population)): + individual = population[i] + individual_save_dir = gen_save_dir + f"ind{self.id_counter + i}/" + individual_save_dirs.append(individual_save_dir) + + if not os.path.exists(individual_save_dir): + os.makedirs(individual_save_dir) + np.save(individual_save_dir + "individual.npy", individual) + + self.id_counter += len(population) + + batch_size = 3 + batches = [individual_save_dirs[i:i + batch_size] for i in range(0, len(individual_save_dirs), batch_size)] + results = [] + for batch in batches: + start = time.time() + processes = [] + for individual_save_dir in batch: + processes.append((individual_save_dir, self.run_subprocess(individual_save_dir))) + + for individual_save_dir, process in processes: + stdout, stderr = process.communicate() # Wait for process to complete and get output + if process.returncode == 0: + results.append((individual_save_dir, stdout.strip())) + else: + print("Return code: ", process.returncode) + print(individual_save_dir) + print(stdout.strip()) + raise Exception(f"Error: {stderr.strip()}") + end = time.time() + print(f"Batch time: {end-start} Seconds", flush=True) + # Sort results by individual_save_dir using numpy + results = np.array(sorted(results, key=lambda x: x[0])) + fitnesses = np.array(results[:,1], dtype=float) + + return fitnesses + + +class NSGAIIGateEvaluator(): + + def __init__(self, task1, task2, training_ts1=1E8, num_envs1=100, training_ts2=1E8, num_envs2=100, device="cuda:0") -> None: + self.device = device + self.evaluator1 = GateEvaluator(gate_cfg=task1, training_ts=training_ts1, num_envs=num_envs1, device=device) + self.evaluator2 = GateEvaluator(gate_cfg=task2, training_ts=training_ts2, num_envs=num_envs2, device=device) + + self.id_counter = 0 + + def evaluate_population(self, population, gen_save_dir=None): + + individual_save_dirs = [] + for i in range(len(population)): + individual = population[i] + individual_save_dir = gen_save_dir + f"ind{self.id_counter + i}/" + individual_save_dirs.append(individual_save_dir) + + if not os.path.exists(individual_save_dir): + os.makedirs(individual_save_dir) + np.save(individual_save_dir + "individual.npy", individual) + + self.id_counter += len(population) + + batch_size = 4 + batches = [individual_save_dirs[i:i + batch_size] for i in range(0, len(individual_save_dirs), batch_size)] + results = [] + for batch in batches: + start = time.time() + task_fitnesses = [] + for task_num in range(2): + + if task_num == 0: + evaluator = self.evaluator1 + else: + evaluator = self.evaluator2 + + processes = [] + for individual_save_dir in batch: + + processes.append((individual_save_dir, evaluator.run_subprocess(individual_save_dir, num=task_num))) + + for individual_save_dir, process in processes: + stdout, stderr = process.communicate() + if process.returncode == 0: + task_fitnesses.append(stdout.strip()) + + else: + raise Exception(f"Error: {stderr.strip()}") + task_fitnesses = np.array(task_fitnesses, dtype=float).reshape(2, -1).T + for individual_save_dir, fitnesses in zip(batch, task_fitnesses): + results.append([individual_save_dir, fitnesses]) + + end = time.time() + print(f"Batch time: {end-start} Seconds", flush=True) + + results = sorted(results, key=lambda x: x[0]) + sorted_results = np.array([result[1] for result in results]) + + fitnesses1 = sorted_results[:, 0] + fitnesses2 = sorted_results[:, 1] + + return fitnesses1, fitnesses2, np.zeros_like(fitnesses1) \ No newline at end of file diff --git a/src/ariel/ec/drone/evaluators/gate_train.py b/src/ariel/ec/drone/evaluators/gate_train.py new file mode 100644 index 000000000..cea978776 --- /dev/null +++ b/src/ariel/ec/drone/evaluators/gate_train.py @@ -0,0 +1,397 @@ +# library imports +import os +import sys +import time +import pandas as pd +import matplotlib.pyplot as plt +import numpy as np +import torch +import warnings +from stable_baselines3 import PPO +from datetime import datetime +from stable_baselines3.common.vec_env import VecMonitor +from stable_baselines3.common.callbacks import EvalCallback, CallbackList +from stable_baselines3.common.callbacks import BaseCallback +from stable_baselines3.common.logger import configure + +# Suppress the render_mode warning from stable_baselines3 +warnings.filterwarnings("ignore", message="The `render_mode` attribute is not defined in your environment") + +sys.path.append(os.path.abspath(os.path.join(os.path.dirname(__file__), "../.."))) + +from ariel.simulation.tasks.drone_gate_env import DroneGateEnv +from ariel.visualisation.drone.animation import view as animation_view +from ariel.ec.drone.inspection.morphological_descriptors.hovering_info import get_sim +from ariel.ec.drone.inspection.drone_visualizer import DroneVisualizer + +import argparse + +# Track configurations. +# Conventions match optimal_quad_control_RL: NED frame (z+ down), gates set +# at GATE_ALT m above the ground plane (z=-1.5). Vertical bounds give the +# policy enough exploration room: ground at z=0, ceiling at z=-7. Horizontal +# bounds are widened to ±5 m where sensible. The earlier z=0 / z_bounds=[-1,1] +# layout was too tight for any drone with TWR > ~3 to learn from. +GATE_ALT = -1.5 + +class backandforth(): + gate_pos = np.array([ + [ 2.0, 0.0, GATE_ALT], + [ 8.0, 0.0, GATE_ALT], + [ 8.0, 0.0, GATE_ALT], + [ 2.0, 0.0, GATE_ALT], + ], dtype=np.float32) + gate_yaw = np.array([0,0,2,2], dtype=np.float32) * np.pi / 2 + x_bounds = np.array([-2, 12], dtype=np.float32) + y_bounds = np.array([-5, 5], dtype=np.float32) + z_bounds = np.array([-7, 0], dtype=np.float32) + starting_pos = np.array([0.0, 0.0, GATE_ALT]) + +class figure8(): + gate_pos = np.array([ + [ 1.5, -1.5, GATE_ALT], + [ 3.0, 0.0, GATE_ALT], + [ 1.5, 1.5, GATE_ALT], + [ 0.0, 0.0, GATE_ALT], + [ -1.5, -1.5, GATE_ALT], + [ -3.0, 0.0, GATE_ALT], + [ -1.5, 1.5, GATE_ALT], + [ 0.0, 0.0, GATE_ALT], + ], dtype=np.float32) + gate_yaw = np.array([0,-1,0,1,2,-1,2,1], dtype=np.float32) * np.pi / 2 + x_bounds = np.array([-5, 5], dtype=np.float32) + y_bounds = np.array([-5, 5], dtype=np.float32) + z_bounds = np.array([-7, 0], dtype=np.float32) + starting_pos = np.array([0.0, -1.5, GATE_ALT]) + +class circle(): + gate_pos = np.array([ + [ 0.0, -1.5, GATE_ALT], + [ 1.5, 0.0, GATE_ALT], + [ 0.0, 1.5, GATE_ALT], + [ -1.5, 0.0, GATE_ALT] + ], dtype=np.float32) + gate_yaw = np.array([0,1,2,3], dtype=np.float32) * np.pi / 2 + x_bounds = np.array([-5, 5], dtype=np.float32) + y_bounds = np.array([-5, 5], dtype=np.float32) + z_bounds = np.array([-7, 0], dtype=np.float32) + starting_pos = np.array([-1.5, -1.5, GATE_ALT]) + +class slalom(): + gate_pos = np.array( + [[x, (i % 2) * (1 if i % 4 == 1 else -1), GATE_ALT] for i, x in enumerate(range(0, 82, 2))], + dtype=np.float32, + ) + ng = len(gate_pos) + gate_yaw = np.tile([1, 0, -1, 0], ng) * np.pi / 2 + x_bounds = np.array([-2, 82+1], dtype=np.float32) + y_bounds = np.array([-5, 5], dtype=np.float32) + z_bounds = np.array([-7, 0], dtype=np.float32) + starting_pos = np.array([0, -1, GATE_ALT]) + +# ANIMATION FUNCTION +def animate_policy(individual, model, env, deterministic=False, log_times=False, print_vel=False, log=None, view_type="top", + motor_colors=['red', 'blue', 'green', 'orange', 'purple', 'brown'], **kwargs): + env.reset() + + # Convert individual to propellers configuration + propellers, _ = env._convert_individual_to_propellers(individual) + + def get_drone_state(): + actions, _ = model.predict(env.states, deterministic=deterministic) + + states, rewards, dones, infos = env.step(actions) + if log != None: + log(states) + if print_vel: + # compute mean velocity + vels = env.world_states[:,3:6] + mean_vel = np.linalg.norm(vels, axis=1).mean() + print(mean_vel) + if log_times: + if rewards[0] == 10: + print(env.step_counts[0]*env.dt) + + # Return drone state in the format expected by the view function + world_state = env.world_states[0] # Get first environment + num_motors = len(propellers) + drone_state = { + 'x': world_state[0], + 'y': world_state[1], + 'z': world_state[2], + 'phi': world_state[6], + 'theta': world_state[7], + 'psi': world_state[8] + } + + # Add motor thrust values + for i in range(num_motors): + if i < env.prev_actions.shape[1]: + drone_state[f'u{i+1}'] = env.prev_actions[0][i] + else: + drone_state[f'u{i+1}'] = 0 + + return drone_state + + animation_view(propellers, get_drone_state, gate_pos=env.gate_pos, gate_yaw=env.gate_yaw, view_type=view_type, motor_colors=motor_colors, **kwargs) + +class FullStatsCallback(BaseCallback): + def __init__(self, verbose=0): + super().__init__(verbose) + self.tags = [ + 'rollout/ep_len_mean', 'rollout/ep_rew_mean', 'time/fps', + 'train/approx_kl', 'train/clip_fraction', 'train/clip_range', + 'train/entropy_loss', 'train/explained_variance', 'train/learning_rate', + 'train/loss', 'train/policy_gradient_loss', 'train/std', 'train/value_loss' + ] + + def _on_step(self) -> bool: + for tag in self.tags: + if tag in self.logger.name_to_value: + self.logger.record(f"monitor/{tag}", self.logger.name_to_value[tag]) + return True + + def _on_rollout_end(self) -> None: + # for tag in self.tags: + # if tag in self.logger.name_to_value: + # self.logger.record(f"monitor/{tag}", self.logger.name_to_value[tag]) + # Force flush for debugging; can remove later + self.logger.dump(self.num_timesteps) + +def train(individual, gate_cfg, total_timesteps=int(1E8), save_dir="./logs", num_envs=100, device="cuda:0", num=None, max_steps=1200): + + if gate_cfg == "backandforth": + gate_pos = backandforth.gate_pos + gate_yaw = backandforth.gate_yaw + start_pos = backandforth.starting_pos + x_bounds = backandforth.x_bounds + y_bounds = backandforth.y_bounds + z_bounds = backandforth.z_bounds + elif gate_cfg == "figure8": + gate_pos = figure8.gate_pos + gate_yaw = figure8.gate_yaw + start_pos = figure8.starting_pos + x_bounds = figure8.x_bounds + y_bounds = figure8.y_bounds + z_bounds = figure8.z_bounds + elif gate_cfg == "circle": + gate_pos = circle.gate_pos + gate_yaw = circle.gate_yaw + start_pos = circle.starting_pos + x_bounds = circle.x_bounds + y_bounds = circle.y_bounds + z_bounds = circle.z_bounds + elif gate_cfg == "slalom": + gate_pos = slalom.gate_pos + gate_yaw = slalom.gate_yaw + start_pos = slalom.starting_pos + x_bounds = slalom.x_bounds + y_bounds = slalom.y_bounds + z_bounds = slalom.z_bounds + else: + raise ValueError("Invalid gate configuration") + + # SETUP LOGGING + save_dir = save_dir+"/" + # models_dir = save_dir+'/models/' + # log_dir = save_dir+'/logs/' + # video_dir = save_dir+'/videos/' + + if not os.path.exists(save_dir): + os.makedirs(save_dir) + # if not os.path.exists(models_dir): + # os.makedirs(models_dir) + # if not os.path.exists(log_dir): + # os.makedirs(log_dir) + + env = DroneGateEnv( + num_envs=num_envs, + individual=individual, + gates_pos=gate_pos, + gate_yaw=gate_yaw, + start_pos=start_pos, + x_bounds=x_bounds, + y_bounds=y_bounds, + z_bounds=z_bounds, + gates_ahead=1, + num_state_history=0, + num_action_history=0, + history_step_size=1, + render_mode=None, + device=device, + max_steps=max_steps, + ) + test_env = DroneGateEnv( + num_envs=1, + individual=individual, + gates_pos=gate_pos, + gate_yaw=gate_yaw, + start_pos=start_pos, + x_bounds=x_bounds, + y_bounds=y_bounds, + z_bounds=z_bounds, + initialize_at_random_gates=False, + gates_ahead=1, + num_state_history=0, + num_action_history=0, + history_step_size=1, + render_mode=None, + device=device, + max_steps=max_steps, + ) + + # Wrap the environment in a Monitor wrapper + # Make monitor1 folder + if num is not None: + monitor_file = save_dir+f"m{num}" + else: + monitor_file = save_dir + + env = VecMonitor(env, filename=monitor_file) + # custom_logger = configure(save_dir, ["stdout", "csv", "tensorboard"]) + + # MODEL DEFINITION (matches optimal_quad_control_RL/train.py:149-161). + policy_kwargs = dict( + activation_fn=torch.nn.ReLU, + net_arch=dict(pi=[64, 64], vf=[64, 64]), + log_std_init=0.0, + ) + model = PPO( + "MlpPolicy", + env, + policy_kwargs=policy_kwargs, + verbose=0, + tensorboard_log=save_dir, + n_steps=1000, + batch_size=5000, + n_epochs=10, + gamma=0.999, + device=device, + ) + # model.set_logger(custom_logger) + + # TRAINING + model.learn(total_timesteps=total_timesteps, reset_num_timesteps=False, log_interval=100, callback=FullStatsCallback()) + if num is None: + model.save(save_dir + '/' + "policy") + else: + model.save(save_dir + '/' + f"policy{num}") + # model_path = save_dir + "/"+"best_model.zip" + # PPO_model = PPO.load(model_path) + + # Plotting the training curve + try: + data = pd.read_csv(monitor_file+".monitor.csv", skiprows=1) # Skip the first row (comments) + except: + data = pd.read_csv(monitor_file+"monitor.csv", skiprows=1) + episode_rewards = data["r"] # Rewards per episode + time_steps = data["t"] # Timesteps at each episode + plt.figure(figsize=(10, 6)) + plt.plot(time_steps, episode_rewards, label="Episode Reward") + # plt.fill_between(time_steps[:,0], episode_rewards_mean - episode_rewards_std, episode_rewards_mean + episode_rewards_std, alpha=0.2) + plt.xlabel("Timesteps") + plt.ylabel("Reward") + plt.title("Reward per Episode") + plt.legend() + if num is None: + plt.savefig(save_dir+"/figure.png") + else: + plt.savefig(save_dir+f"/figure{num}.png") + plt.close() + # plt.show() + # TESTING + test_env.reset() + # if num is None: + # animate_policy(individual, model, test_env, deterministic=False, log_times=False, print_vel=False, log=None, + # record_steps=1200, record_file=save_dir + f'v.mp4', + # show_window=False) + # else: + # animate_policy(individual, model, test_env, deterministic=False, log_times=False, print_vel=False, log=None, + # record_steps=1200, record_file=save_dir + f'v{num}.mp4', + # show_window=False) + + test_env.reset() + # do 1200 steps and print state and action + for i in range(1000): + num = test_env.num_state_history+1 + state_len = int(len(test_env.states[0])/num) + actions, _ = model.predict(test_env.states, deterministic=True) + states, rewards, dones, infos = test_env.step(actions) + + return infos[0]["num_gates_passed"][0] + +def evaluate_individual(individual, ind_save_dir, training_ts, num_envs, gate_cfg, device="cuda:0", num=None, max_steps=1200) -> list: + start_time = time.time() + sim = get_sim(individual) + sim.compute_hover(verbose=False) + if sim.static_success == False: + spinning_success = sim.spinning_success + else: + spinning_success = False + + success = sim.static_success# or spinning_success + if not success: + try: + fig = plt.figure(figsize=plt.figaspect(0.5)) + ax = fig.add_subplot(111, projection='3d') + visualizer = DroneVisualizer() + visualizer.plot_3d(individual, ax=ax, title=f"Failed Individual (Gen {num})", fitness=0, generation=num) + if num is not None: + plt.savefig(ind_save_dir + f"/morphology{num}.png") + else: + plt.savefig(ind_save_dir + "/morphology.png") + plt.close() + except: + print(f"Failed to plot:\n {individual}") + return 0 + + fig = plt.figure(figsize=plt.figaspect(0.5)) + ax = fig.add_subplot(111, projection='3d') + visualizer = DroneVisualizer() + visualizer.plot_3d(individual, ax=ax, title=f"Pre-training (Gen {num})", fitness=np.nan, generation=num) + if num is not None: + plt.savefig(ind_save_dir + f"/morphology{num}.png") + else: + plt.savefig(ind_save_dir + "/morphology.png") + plt.close() + + num_gates_passed = train(individual, gate_cfg, total_timesteps=int(float(training_ts)), save_dir=ind_save_dir, num_envs=int(num_envs), device=device, num=num, max_steps=max_steps) + + fig = plt.figure(figsize=plt.figaspect(0.5)) + ax = fig.add_subplot(111, projection='3d') + visualizer = DroneVisualizer() + visualizer.plot_3d(individual, ax=ax, title=f"Post-training (Gen {num})", fitness=num_gates_passed, generation=num) + if num is not None: + plt.savefig(ind_save_dir + f"/morphology{num}.png") + else: + plt.savefig(ind_save_dir + "/morphology.png") + plt.close() + + end_time = time.time() + # print(f"{end_time-start_time} seconds to evaluate, fitness={num_gates_passed}") + return num_gates_passed + +if __name__ == "__main__": + import warnings + warnings.filterwarnings("ignore") + + parser = argparse.ArgumentParser() + parser.add_argument('filename') + parser.add_argument('--training_timesteps', default=1E8) + parser.add_argument('--num_envs', default=100) + parser.add_argument('--gate_cfg', default='figure8') + parser.add_argument('--device', default='cuda:0') + parser.add_argument('--num', default=None) + args = parser.parse_args() + + # Load Bf and Bm from directory + individual = np.load(args.filename + "/individual.npy", allow_pickle=True) + individual = individual.astype(np.float32) + + if args.num is None: + num = None + else: + num = int(args.num) + num_gates_passed = evaluate_individual(individual, args.filename, args.training_timesteps, args.num_envs, args.gate_cfg, args.device, num=num) + + print(num_gates_passed) diff --git a/src/ariel/ec/drone/evaluators/hover_fitness.py b/src/ariel/ec/drone/evaluators/hover_fitness.py new file mode 100644 index 000000000..d4d208b4d --- /dev/null +++ b/src/ariel/ec/drone/evaluators/hover_fitness.py @@ -0,0 +1,52 @@ +"""Continuous hover fitness — gradient signal in [0, 3] for non-hoverable drones. + +Ported from experimentation/run_combined_hover_gate_evolution.py +(ppsn_2026_submission branch, lines 279-325). +""" +import numpy as np +from numpy.linalg import norm, eig + +G = 9.81 +C_AUTHORITY = 300.0 # sqrt(lambda_min) half-saturation constant + + +def continuous_hover_fitness(phenotype) -> float: + """Continuous hover fitness in [0, 3]. Higher = closer to hoverable. + + Sum of three [0, 1] terms: + - rank feasibility: (rank(Bf) + rank(Bm)) / 6 + - force capability: min(||Bf @ 1|| / G, 2) / 2 + - torque balance: (lambda_min / lambda_max) * sqrt(lambda_min) / (sqrt(lambda_min) + C) + """ + from ariel.ec.drone.inspection.morphological_descriptors.hovering_info import get_sim + + sim = get_sim(phenotype) + if sim is None: + return 0.0 + + Bf = sim.Bf # (3, n_props) + Bm = sim.Bm # (3, n_props) + + rank_f = np.linalg.matrix_rank(Bf) + rank_m = np.linalg.matrix_rank(Bm) + f_rank = (rank_f + rank_m) / 6.0 + + n_props = Bf.shape[1] + eta_max = np.ones(n_props) + f_vec = Bf @ eta_max + thrust_ratio = norm(f_vec) / G + f_force = min(thrust_ratio, 2.0) / 2.0 + + gram_m = Bm @ Bm.T + eigs = np.real(eig(gram_m)[0]) + eigs = np.maximum(eigs, 0.0) + + lambda_min = np.min(eigs) + lambda_max = np.max(eigs) + + condition = lambda_min / (lambda_max + 1e-12) + authority = np.sqrt(lambda_min) + authority_sat = authority / (authority + C_AUTHORITY) + f_torque = condition * authority_sat + + return float(f_rank + f_force + f_torque) diff --git a/src/ariel/ec/drone/evaluators/lee_tune_evaluator.py b/src/ariel/ec/drone/evaluators/lee_tune_evaluator.py new file mode 100644 index 000000000..b5ee8a975 --- /dev/null +++ b/src/ariel/ec/drone/evaluators/lee_tune_evaluator.py @@ -0,0 +1,974 @@ +""" +Lee Controller Tuning Evaluator for Evolutionary Algorithm + +This evaluator uses a 2-stage CMA-ES pipeline to optimize controller parameters +for each evolved morphology. Each individual's fitness is determined by the maximum +number of gates passed during controller tuning. + +If controller tuning fails to pass any gates, the individual receives fitness of 0. + +Design: +- Takes an evolved drone morphology +- Converts it to DroneInterface +- Stage 1: Optimise gains + timing (7 params: pos_P, vel_P, att_P, rate_P, + total_time, velocity_scale, startup_time) with fixed default trajectory +- Stage 2: Optimise gains + timing + gate offset control points + (7 + n_gates*3 params) to refine the trajectory shape +- Returns max gates passed as fitness + +This integrates the tune_lee_controller_gates.py pipeline into the evolutionary loop. +""" + +import numpy as np +import os +import sys +import time +import json +from datetime import datetime +from pathlib import Path +from concurrent.futures import ProcessPoolExecutor, as_completed, TimeoutError +import multiprocessing + +# Import drone simulation components +from ariel.simulation.drone import DroneInterface +from ariel.simulation.drone.controllers.trajectory_generation.bspline_gate_trajectory import BSplineGateTrajectory +from ariel.simulation.drone.controllers.lee_control.lee_controller import LeeGeometricControl +from ariel.simulation.drone.controllers.utils.wind_model import Wind +from ariel.simulation.drone.controllers.utils.gate_configs import GATE_CONFIGS +from ariel.ec.drone.inspection.utils import convert_to_cartesian, ENU_to_NED +from ariel.ec.drone.inspection.morphological_descriptors.hovering_info import orientation_to_unit_vector + +# Try to import CMA-ES +try: + import cma + CMA_AVAILABLE = True +except ImportError: + CMA_AVAILABLE = False + print("WARNING: 'cma' package not found. Install with: pip install cma") + + +# ============================================================================ +# GATE CHECKING LOGIC (from tune_lee_controller_gates.py) +# ============================================================================ + +class GateChecker: + """Handles gate passing detection""" + + def __init__(self, gate_pos, gate_yaw, gate_size=1.0): + """ + Initialize gate checker + + Args: + gate_pos: Array of gate positions [N, 3] + gate_yaw: Array of gate yaw angles [N] + gate_size: Size of gates in meters + """ + self.gate_pos = gate_pos + self.gate_yaw = gate_yaw + self.gate_size = gate_size + self.num_gates = len(gate_pos) + self.current_gate_idx = 0 + self.gates_passed = 0 + self.last_pos = None + self.max_gate_distance = self._calculate_max_gate_distance() + + def reset(self): + """Reset gate checker state""" + self.current_gate_idx = 0 + self.gates_passed = 0 + self.last_pos = None + + def check_gate_passing(self, pos): + """ + Check if drone passed through current gate + + Args: + pos: Current position [x, y, z] + + Returns: + True if gate was passed + """ + if self.last_pos is None: + self.last_pos = pos.copy() + return False + + # Get current gate + gate_idx = self.current_gate_idx % self.num_gates + gate_pos = self.gate_pos[gate_idx] + gate_yaw = self.gate_yaw[gate_idx] + + # Gate normal vector (direction perpendicular to gate plane) + normal = np.array([np.cos(gate_yaw), np.sin(gate_yaw), 0.0]) + + # Project positions onto normal direction + pos_old_proj = np.dot(self.last_pos - gate_pos, normal) + pos_new_proj = np.dot(pos - gate_pos, normal) + + # Check if crossed gate plane + crossed_plane = ((pos_old_proj < 0) and (pos_new_proj > 0)) or \ + ((pos_old_proj > 0) and (pos_new_proj < 0)) + + if crossed_plane: + # Find intersection point + t = -pos_old_proj / (pos_new_proj - pos_old_proj) + intersection = self.last_pos + t * (pos - self.last_pos) + + # Transform to gate's local frame + rel_pos = intersection - gate_pos + + # Create gate's local coordinate system + if abs(normal[2]) < 0.9: + up = np.array([0.0, 0.0, 1.0]) + else: + up = np.array([0.0, 1.0, 0.0]) + + right = np.cross(normal, up) + right = right / np.linalg.norm(right) + actual_up = np.cross(right, normal) + + # Project onto gate plane + lateral = np.dot(rel_pos, right) + vertical = np.dot(rel_pos, actual_up) + + # Check if within gate opening + half_size = self.gate_size / 2.0 + within_bounds = (abs(lateral) <= half_size) and (abs(vertical) <= half_size) + + if within_bounds: + self.gates_passed += 1 + self.current_gate_idx += 1 + self.last_pos = pos.copy() + return True + + self.last_pos = pos.copy() + return False + + def _calculate_max_gate_distance(self): + """ + Calculate the maximum distance between consecutive gates in the sequence + + Returns: + Maximum distance between any two consecutive gates + """ + max_dist = 0.0 + for i in range(self.num_gates): + next_idx = (i + 1) % self.num_gates + dist = np.linalg.norm(self.gate_pos[next_idx] - self.gate_pos[i]) + max_dist = max(max_dist, dist) + return max_dist + + def get_normalized_distance_to_next_gate(self, pos): + """ + Calculate normalized distance to the next gate (current target) + + Args: + pos: Current position [x, y, z] + + Returns: + Normalized distance bonus in [0, 1], where: + - 1.0 means at the gate position + - 0.0 means at or beyond max_gate_distance away + - Values capped at 0.0 if distance > max_gate_distance + """ + # Get the next gate to pass + gate_idx = self.current_gate_idx % self.num_gates + gate_pos = self.gate_pos[gate_idx] + + # Calculate distance to next gate + distance = np.linalg.norm(pos - gate_pos) + + # Normalize: closer = higher score, capped at 0 if too far + if distance >= self.max_gate_distance: + return 0.0 + + normalized = 1.0 - (distance / self.max_gate_distance) + return max(0.0, min(1.0, normalized)) + + +# ============================================================================ +# SIMULATION (adapted from tune_lee_controller_gates.py) +# ============================================================================ + +def simulate_with_gains(individual, pos_gain, vel_gain, att_gain, rate_gain, + gate_config, sim_time=20.0, dt=0.005, + bspline_timing=None, gate_offsets=None, + verbose=False, record_trajectory=False): + """ + Run simulation with Lee controller for a given morphology and gains + + Args: + individual: Evolved drone morphology (genome array) + pos_gain, vel_gain, att_gain, rate_gain: Controller gains + gate_config: Gate configuration class + sim_time: Simulation time in seconds + dt: Time step in seconds + bspline_timing: Optional array of [total_time, velocity_scale, startup_time]. + If None, uses BSplineGateTrajectory defaults (20.0, 1.0, 3.0). + gate_offsets: Optional flat array of gate offset parameters (n_gates * 3 elements). + If None, uses default zero offsets. + verbose: If True, show debug output + record_trajectory: If True, record full trajectory data at each timestep + + Returns: + Dictionary with gates_passed, crashed, completed, flight_time. + If record_trajectory=True, also includes 'trajectory' dict with numpy arrays: + positions, velocities, euler_angles, angular_velocities, motor_commands, gate_passes + """ + try: + # Convert genome to DroneInterface + # Individual format: N x 6 array [r, theta, phi, pitch, yaw, direction] + propellers = [] + for arm in individual: + r, theta, phi, motor_pitch, motor_yaw, direction = arm + + # Position: genome spherical (elevation convention, ENU) -> Cartesian NED + ex, ey, ez = convert_to_cartesian(r, theta, phi) + x, y, z = ENU_to_NED(ex, ey, ez) + + # Motor rotation direction + rot = "ccw" if direction < 0.5 else "cw" + + # Motor direction: orientation_to_unit_vector returns the motor force + # direction in NED. Use directly — same convention as the hover check + # (hovering_info.get_sim) which validates that the drone can hover. + # Do NOT negate: negation inverts force directions, making hoverable + # drones produce downward force in the simulation. + motor_dir = orientation_to_unit_vector(0.0, motor_pitch, motor_yaw) + + propellers.append({ + "loc": [float(x), float(y), float(z)], + "dir": [float(motor_dir[0]), float(motor_dir[1]), float(motor_dir[2]), rot], + "propsize": 2 + }) + + quad = DroneInterface(0, propellers=propellers) + + # Create Lee controller with specified gains + lee_gains = { + 'pos_P_gain': np.array([pos_gain] * 3), + 'vel_P_gain': np.array([vel_gain] * 3), + 'att_P_gain': np.array([att_gain] * 3), + 'rate_P_gain': np.array([rate_gain] * 3) + } + ctrl = LeeGeometricControl(quad, yawType=1, orient='NED', + auto_scale_gains=False, **lee_gains) + + # Create B-spline trajectory + bspline_traj = BSplineGateTrajectory(gate_config, gate_offset_scale=0.5) + bspline_params = bspline_traj.get_default_parameters() + bspline_traj.set_parameters(bspline_params) + + # Override timing if provided + if bspline_timing is not None: + bspline_traj.set_timing_parameters(np.asarray(bspline_timing)) + + # Override gate offsets if provided + if gate_offsets is not None: + bspline_traj.set_gate_offset_parameters(np.asarray(gate_offsets)) + + # CRITICAL: Set drone initial state to match trajectory at t=0 + # This eliminates startup transients from position/velocity/yaw errors + start_pos, _, _ = bspline_traj.evaluate(0.0) + + # Compute initial yaw from trajectory's heading direction at t=0.05s + # (t=0 has zero velocity due to quintic startup ramp) + _, vel_050, _ = bspline_traj.evaluate(0.05) + if np.linalg.norm(vel_050[:2]) > 0.001: # If horizontal velocity > 0.001 m/s + initial_yaw = np.arctan2(vel_050[1], vel_050[0]) + else: + # Fallback to first gate direction if velocity is too small + initial_yaw = gate_config.gate_yaw[0] + + initial_euler = np.array([0.0, 0.0, initial_yaw]) + + # Set drone state: position from t=0, zero velocity (trajectory starts from rest), + # yaw from trajectory heading to prevent yaw error torque spike + quad.drone_sim.set_state(position=start_pos, velocity=np.zeros(3), + attitude=initial_euler, angular_velocity=np.zeros(3)) + + # Create Trajectory wrapper (xyzType=15 for B-spline) + from ariel.simulation.drone.controllers.trajectory_generation.trajectory import Trajectory + traj = Trajectory(quad, "xyz_pos", np.array([15, 3, 1]), + gate_config=gate_config) + traj.bspline_trajectory = bspline_traj + + # Create wind model (no wind) + wind = Wind('None', 2.0, 90, -15) + + # Initialize gate checker + gate_checker = GateChecker(gate_config.gate_pos, gate_config.gate_yaw, + gate_config.gate_size) + + # Get initial desired state and command + sDes = traj.desiredState(0, dt, quad) + ctrl.controller(sDes, quad, "xyz_pos", dt) + + # Run simulation + t = 0 + crashed = False + num_steps = int(sim_time / dt) + + # Trajectory recording + if record_trajectory: + traj_positions = [] + traj_velocities = [] + traj_euler = [] + traj_omega = [] + traj_w_cmd = [] + traj_gate_passes = [] + + for step in range(num_steps): + # Update dynamics + try: + quad.update(t, dt, ctrl.w_cmd, wind) + except RuntimeError: + crashed = True + break + t += dt + + # Get desired state + sDes = traj.desiredState(t, dt, quad) + + # Generate control commands + ctrl.controller(sDes, quad, "xyz_pos", dt) + + # Check gate passing + gate_passed = gate_checker.check_gate_passing(quad.pos) + + # Record trajectory data + if record_trajectory: + traj_positions.append(quad.pos.copy()) + traj_velocities.append(quad.vel.copy()) + traj_euler.append(quad.euler.copy()) + traj_omega.append(quad.omega.copy()) + traj_w_cmd.append(ctrl.w_cmd.copy()) + traj_gate_passes.append(gate_passed) + + # Check bounds + if (quad.pos[0] < gate_config.x_bounds[0] or + quad.pos[0] > gate_config.x_bounds[1] or + quad.pos[1] < gate_config.y_bounds[0] or + quad.pos[1] > gate_config.y_bounds[1] or + quad.pos[2] < gate_config.z_bounds[0] or + quad.pos[2] > gate_config.z_bounds[1]): + crashed = True + break + + # Check for excessive error (instability) + pos_error = np.linalg.norm(quad.pos - sDes[0:3]) + if pos_error > 10.0: + crashed = True + break + + # Calculate normalized distance to next gate at end of simulation + distance_bonus = gate_checker.get_normalized_distance_to_next_gate(quad.pos) + + result = { + 'gates_passed': gate_checker.gates_passed, + 'distance_bonus': distance_bonus, + 'crashed': crashed, + 'completed': not crashed, + 'flight_time': t, + 'success': True + } + + if record_trajectory: + result['trajectory'] = { + 'positions': np.array(traj_positions), + 'velocities': np.array(traj_velocities), + 'euler_angles': np.array(traj_euler), + 'angular_velocities': np.array(traj_omega), + 'motor_commands': np.array(traj_w_cmd), + 'gate_passes': np.array(traj_gate_passes), + } + + return result + + except Exception as e: + if verbose: + print(f"Simulation terminated early: {e}") + return { + 'gates_passed': 0, + 'distance_bonus': 0.0, + 'crashed': True, + 'completed': False, + 'flight_time': 0, + 'success': False, + 'error': str(e) + } + + +# ============================================================================ +# MULTIPROCESSING WRAPPER +# ============================================================================ + +def _evaluate_solution_wrapper(args): + """Wrapper function for parallel evaluation. + + Supports variable-length solution vectors: + - 4 params: gains only (pos_P, vel_P, att_P, rate_P) + - 7 params: gains + timing (+ total_time, velocity_scale, startup_time) + - 7+N params: gains + timing + gate offsets (N = n_gates * 3) + """ + (params, individual, gate_config, sim_time, dt, bspline_timing) = args + + pos_g, vel_g, att_g, rate_g = params[0:4] + + # If solution vector includes timing params, use them + if len(params) >= 7: + bspline_timing = params[4:7] + + # If solution vector includes gate offsets, extract them + gate_offsets = None + if len(params) > 7: + gate_offsets = params[7:] + + # Run simulation + result = simulate_with_gains( + individual, pos_g, vel_g, att_g, rate_g, + gate_config, sim_time, dt, + bspline_timing=bspline_timing, + gate_offsets=gate_offsets, + verbose=False + ) + + if result['success']: + gates = result['gates_passed'] + distance_bonus = result['distance_bonus'] + penalty = 100 if result['crashed'] else 0 + + # Fitness includes gates passed + normalized distance to next gate + fitness = gates + distance_bonus + score = -fitness + penalty + + result['score'] = score + result['fitness'] = fitness + result['gains'] = { + 'pos_P': pos_g, + 'vel_P': vel_g, + 'att_P': att_g, + 'rate_P': rate_g + } + if len(params) >= 7: + result['bspline_timing'] = list(params[4:7]) + if gate_offsets is not None: + result['gate_offsets'] = list(gate_offsets) + + return (score, result) + else: + return (1000.0, None) + + +# ============================================================================ +# TWO-STAGE CMA-ES WITH EARLY STOPPING (shared utility functions) +# ============================================================================ + +def _run_cma_stage( + individual, gate_config, initial_guess, bounds, initial_std, + max_evaluations, num_workers, sim_time, dt, timeout_per_eval, + gates_threshold, bspline_timing, +): + """Run a single CMA-ES optimisation stage with early stopping. + + The wrapper auto-detects whether the solution vector contains timing + params (len >= 7) so this works for both Stage 1 (4 params) and + Stage 2 (7 params). + + Returns: + Tuple of (best_result, total_evals, early_stopped, elapsed_seconds, iteration_fitnesses) + """ + if not CMA_AVAILABLE: + return None, 0, False, 0.0, [] + + best_fitness = -float("inf") + best_result = None + total_evals = 0 + early_stopped = False + iteration_fitnesses = [] + start_time = time.time() + + options = { + "bounds": [list(b) for b in zip(*bounds)], + "maxfevals": max_evaluations, + "verb_disp": 0, + "verb_log": 0, + "tolx": 1e-11, + "tolfun": 0, + "tolfunhist": 0, + "tolflatfitness": max_evaluations, + "tolstagnation": max_evaluations, + } + + try: + import warnings + with warnings.catch_warnings(): + warnings.simplefilter("ignore", UserWarning) + es = cma.CMAEvolutionStrategy(initial_guess, initial_std, options) + + executor = ProcessPoolExecutor(max_workers=num_workers) if num_workers > 1 else None + try: + while not es.stop(): + solutions = es.ask() + + if executor is not None: + eval_args = [ + (sol, individual, gate_config, sim_time, dt, bspline_timing) + for sol in solutions + ] + future_to_sol = { + executor.submit(_evaluate_solution_wrapper, a): a[0] + for a in eval_args + } + results_dict = {} + for future in as_completed(future_to_sol): + sol = future_to_sol[future] + try: + score, result = future.result(timeout=timeout_per_eval) + results_dict[tuple(sol)] = score + if result is not None and result["fitness"] > best_fitness and not result["crashed"]: + best_fitness = result["fitness"] + best_result = result + except (TimeoutError, Exception): + results_dict[tuple(sol)] = 1000.0 + + fitness_values = [results_dict[tuple(sol)] for sol in solutions] + else: + fitness_values = [] + for sol in solutions: + score, result = _evaluate_solution_wrapper( + (sol, individual, gate_config, sim_time, dt, bspline_timing) + ) + fitness_values.append(score) + if result is not None and result["fitness"] > best_fitness and not result["crashed"]: + best_fitness = result["fitness"] + best_result = result + + total_evals += len(solutions) + es.tell(solutions, fitness_values) + iteration_fitnesses.append(best_fitness if best_fitness > -float("inf") else 0.0) + + if best_result is not None and best_result["gates_passed"] >= gates_threshold: + early_stopped = True + break + finally: + if executor is not None: + executor.shutdown(wait=False) + + except Exception as e: + print(f" CMA-ES error: {e}") + + elapsed = time.time() - start_time + return best_result, total_evals, early_stopped, elapsed, iteration_fitnesses + + +def optimize_controller_with_early_stop( + individual, gate_config, max_evaluations=200, num_workers=4, + sim_time=20.0, dt=0.005, timeout_per_eval=30.0, gates_threshold=9, + bspline_timing=None, +): + """ + Two-stage CMA-ES optimisation with early stopping. + + Stage 1: Optimise gains + timing (7 params) with zero gate offsets. + Stage 2: Optimise gains + timing + gate offsets (7 + n_gates*3 params), + seeded from Stage 1 best. + + Returns dict with tuning results including eval count, timing, best gains, + and best gate offsets. + """ + _empty = { + "gates_passed": 0, "n_evaluations": 0, "tuning_time_seconds": 0.0, + "best_gains": None, "early_stopped": False, "distance_bonus": 0.0, + "crashed": True, "best_bspline_timing": None, "best_gate_offsets": None, + } + if not CMA_AVAILABLE: + return _empty + + if bspline_timing is None: + bspline_timing = np.array([12.7, 4.6, 1.9]) + + # Get gate offset bounds from BSplineGateTrajectory + bspline_traj = BSplineGateTrajectory(gate_config, gate_offset_scale=0.5) + n_gates = bspline_traj.n_gates + offset_bounds = bspline_traj.get_parameter_bounds_by_group()['gate_offsets'] + n_offset_params = n_gates * 3 + default_offsets = bspline_traj.get_default_parameters()[:n_offset_params] + + # Split budget: 40% Stage 1, 60% Stage 2 + stage1_evals = max(20, int(max_evaluations * 0.4)) + stage2_evals = max(20, max_evaluations - stage1_evals) + + # ------------------------------------------------------------------ + # Stage 1: Optimise gains + timing (7 params), zero gate offsets + # ------------------------------------------------------------------ + stage1_guess = [14.3, 9.0, 2.9, -0.02, 12.7, 4.6, 1.9] + stage1_bounds = [ + [10.0, 25.0], # pos_P + [0.1, 15.0], # vel_P + [0.1, 10.0], # att_P + [-1.0, -0.01], # rate_P + [5.0, 30.0], # total_time + [0.5, 10.0], # velocity_scale + [0.1, 5.0], # startup_time + ] + + best_result, evals1, early1, time1, _ = _run_cma_stage( + individual, gate_config, stage1_guess, stage1_bounds, 1.5, + stage1_evals, num_workers, sim_time, dt, timeout_per_eval, + gates_threshold, bspline_timing, + ) + + if early1 and best_result is not None: + # Already hit the gates threshold — skip Stage 2 + return { + "gates_passed": best_result["gates_passed"], + "n_evaluations": evals1, + "tuning_time_seconds": round(time1, 2), + "best_gains": best_result["gains"], + "early_stopped": True, + "distance_bonus": best_result.get("distance_bonus", 0.0), + "crashed": best_result["crashed"], + "best_bspline_timing": best_result.get("bspline_timing", list(bspline_timing)), + "best_gate_offsets": list(default_offsets), + } + + # ------------------------------------------------------------------ + # Stage 2: Optimise gains + timing + gate offsets (7 + n_gates*3 params) + # ------------------------------------------------------------------ + if best_result is not None: + g = best_result["gains"] + stage2_gains_timing = [g["pos_P"], g["vel_P"], g["att_P"], g["rate_P"]] + stage2_gains_timing += list(best_result.get("bspline_timing", bspline_timing)) + else: + stage2_gains_timing = list(stage1_guess) + + stage2_guess = stage2_gains_timing + list(default_offsets) + stage2_bounds = list(stage1_bounds) + [ + [float(default_offsets[i] + lo), float(default_offsets[i] + hi)] + for i, (lo, hi) in enumerate(zip(offset_bounds[0], offset_bounds[1])) + ] + + best2, evals2, early2, time2, _ = _run_cma_stage( + individual, gate_config, stage2_guess, stage2_bounds, 0.3, + stage2_evals, num_workers, sim_time, dt, timeout_per_eval, + gates_threshold, bspline_timing, + ) + + # Pick best across both stages + total_evals = evals1 + evals2 + total_time = time1 + time2 + + if best2 is not None and (best_result is None or best2["fitness"] > best_result["fitness"]): + best_result = best2 + + if best_result is not None: + return { + "gates_passed": best_result["gates_passed"], + "n_evaluations": total_evals, + "tuning_time_seconds": round(total_time, 2), + "best_gains": best_result["gains"], + "early_stopped": early2, + "distance_bonus": best_result.get("distance_bonus", 0.0), + "crashed": best_result["crashed"], + "best_bspline_timing": best_result.get("bspline_timing", list(bspline_timing)), + "best_gate_offsets": best_result.get("gate_offsets", [0.0] * n_offset_params), + } + else: + _empty["n_evaluations"] = total_evals + _empty["tuning_time_seconds"] = round(total_time, 2) + return _empty + + +# ============================================================================ +# TWO-STAGE TUNER FOR SINGLE MORPHOLOGY (used by evolutionary loop) +# ============================================================================ + +def optimize_controller_for_morphology(individual, gate_config, max_evaluations=100, + num_workers=None, sim_time=20.0, dt=0.005, + timeout_per_eval=30.0, save_dir=None, + bspline_timing=None): + """ + Run 2-stage CMA-ES optimization to tune controller for a morphology. + + Stage 1: Optimise gains + timing (7 params) with zero gate offsets. + Stage 2: Optimise gains + timing + gate offsets (7 + n_gates*3 params), + seeded from Stage 1 best. + + Always runs both stages (no early stopping) for maximum quality. + + Args: + individual: Evolved drone morphology (genome array) + gate_config: Gate configuration class + max_evaluations: Maximum CMA-ES evaluations (split across stages) + num_workers: Number of parallel workers + sim_time: Simulation time in seconds + dt: Time step in seconds + timeout_per_eval: Timeout per evaluation in seconds + save_dir: Directory to save results (optional) + bspline_timing: Optional array of [total_time, velocity_scale, startup_time] + + Returns: + dict with: + - fitness: max gates passed (0 if failed) + - best_gains: dict of best gains found + - best_bspline_timing: best timing parameters + - best_gate_offsets: best gate offset parameters + - gates_passed: number of gates passed + - success: True if optimization succeeded + """ + if not CMA_AVAILABLE: + print("ERROR: CMA-ES requires the 'cma' package") + return {'fitness': 0, 'best_gains': None, 'gates_passed': 0, 'success': False} + + # Set up parallel workers + if num_workers is None: + num_workers = max(1, multiprocessing.cpu_count() // 2) + + if bspline_timing is None: + bspline_timing = np.array([12.7, 4.6, 1.9]) + + # Get gate offset bounds from BSplineGateTrajectory + bspline_traj = BSplineGateTrajectory(gate_config, gate_offset_scale=0.5) + n_gates = bspline_traj.n_gates + offset_bounds = bspline_traj.get_parameter_bounds_by_group()['gate_offsets'] + n_offset_params = n_gates * 3 + default_offsets = bspline_traj.get_default_parameters()[:n_offset_params] + + # Split budget: 40% Stage 1, 60% Stage 2 + stage1_evals = max(20, int(max_evaluations * 0.4)) + stage2_evals = max(20, max_evaluations - stage1_evals) + + # No early stopping — always run both stages for max quality + no_early_stop = 999999 + + # ------------------------------------------------------------------ + # Stage 1: Optimise gains + timing (7 params), zero gate offsets + # ------------------------------------------------------------------ + stage1_guess = [14.3, 9.0, 2.9, -0.02, 12.7, 4.6, 1.9] + stage1_bounds = [ + [10.0, 25.0], # pos_P + [0.1, 15.0], # vel_P + [0.1, 10.0], # att_P + [-1.0, -0.01], # rate_P + [5.0, 30.0], # total_time + [0.5, 10.0], # velocity_scale + [0.1, 5.0], # startup_time + ] + + best_result, evals1, _, time1, stage1_fitnesses = _run_cma_stage( + individual, gate_config, stage1_guess, stage1_bounds, 1.5, + stage1_evals, num_workers, sim_time, dt, timeout_per_eval, + no_early_stop, bspline_timing, + ) + + # ------------------------------------------------------------------ + # Stage 2: Optimise gains + timing + gate offsets (7 + n_gates*3 params) + # ------------------------------------------------------------------ + if best_result is not None: + g = best_result["gains"] + stage2_gains_timing = [g["pos_P"], g["vel_P"], g["att_P"], g["rate_P"]] + stage2_gains_timing += list(best_result.get("bspline_timing", bspline_timing)) + else: + stage2_gains_timing = list(stage1_guess) + + stage2_guess = stage2_gains_timing + list(default_offsets) + stage2_bounds = list(stage1_bounds) + [ + [float(default_offsets[i] + lo), float(default_offsets[i] + hi)] + for i, (lo, hi) in enumerate(zip(offset_bounds[0], offset_bounds[1])) + ] + + best2, evals2, _, time2, stage2_fitnesses = _run_cma_stage( + individual, gate_config, stage2_guess, stage2_bounds, 0.3, + stage2_evals, num_workers, sim_time, dt, timeout_per_eval, + no_early_stop, bspline_timing, + ) + + # Pick best across both stages + total_evals = evals1 + evals2 + total_time = time1 + time2 + best_score = -float('inf') + + if best_result is not None: + best_score = best_result.get("fitness", 0) + + if best2 is not None and (best_result is None or best2["fitness"] > best_result["fitness"]): + best_result = best2 + best_score = best2["fitness"] + + # Build combined learning curve (Stage 2 fitnesses carry forward Stage 1 best) + s1_best = stage1_fitnesses[-1] if stage1_fitnesses else 0.0 + combined = list(stage1_fitnesses) + [max(s1_best, f) for f in stage2_fitnesses] + + # Save results if save_dir provided + if save_dir is not None: + Path(save_dir).mkdir(parents=True, exist_ok=True) + + # Always save genome + np.save(os.path.join(save_dir, "genome.npy"), individual) + + # Save learning curve data with per-stage breakdown + learning_curve_data = { + "stage1": stage1_fitnesses, + "stage2": stage2_fitnesses, + "combined": combined, + } + with open(os.path.join(save_dir, "learning_curve.json"), 'w') as f: + json.dump(learning_curve_data, f, indent=2) + + # Effective bspline_timing. Default gate_offsets come from the + # B-spline's tension-based initialisation — this is what Stage 1 + # actually runs against (it passes gate_offsets=None to + # simulate_with_gains). Saving zeros here would misrepresent the + # trajectory Stage 1 winners were evaluated on. + effective_timing = list(bspline_timing) + effective_gate_offsets = list(default_offsets) + + # Enhanced tuning_results.json + if best_result is not None: + effective_timing = best_result.get('bspline_timing', effective_timing) + if isinstance(effective_timing, np.ndarray): + effective_timing = effective_timing.tolist() + effective_gate_offsets = best_result.get('gate_offsets', effective_gate_offsets) + if isinstance(effective_gate_offsets, np.ndarray): + effective_gate_offsets = effective_gate_offsets.tolist() + + config = { + 'timestamp': datetime.now().isoformat(), + 'fitness': best_score, + 'gates_passed': best_result.get('gates_passed', 0), + 'distance_bonus': best_result.get('distance_bonus', 0.0), + 'gains': best_result['gains'], + 'bspline_timing': effective_timing, + 'gate_offsets': effective_gate_offsets, + 'brain': { + 'gains': best_result['gains'], + 'bspline_timing': effective_timing, + 'gate_offsets': effective_gate_offsets, + }, + 'flight_time': best_result['flight_time'], + 'crashed': best_result['crashed'], + 'n_cma_iterations_stage1': len(stage1_fitnesses), + 'n_cma_iterations_stage2': len(stage2_fitnesses), + 'n_evaluations_stage1': evals1, + 'n_evaluations_stage2': evals2, + } + else: + config = { + 'timestamp': datetime.now().isoformat(), + 'fitness': 0, + 'gates_passed': 0, + 'bspline_timing': list(bspline_timing), + 'gate_offsets': list(default_offsets), + 'crashed': True, + 'success': False, + 'n_cma_iterations_stage1': len(stage1_fitnesses), + 'n_cma_iterations_stage2': len(stage2_fitnesses), + 'n_evaluations_stage1': evals1, + 'n_evaluations_stage2': evals2, + } + + with open(os.path.join(save_dir, "tuning_results.json"), 'w') as f: + json.dump(config, f, indent=2) + + # Save plots (blueprint + learning curve) + try: + import matplotlib + matplotlib.use('Agg') + import matplotlib.pyplot as plt + from ariel.ec.drone.inspection.drone_visualizer import DroneVisualizer + + # Blueprint + viz = DroneVisualizer() + fig, _ = viz.plot_blueprint(individual, title="Morphology Blueprint") + fig.savefig(os.path.join(save_dir, "blueprint.png"), dpi=150, bbox_inches='tight') + plt.close(fig) + + # Learning curve with stage boundary marker + if len(combined) > 0: + fig_lc, ax = plt.subplots(figsize=(8, 5)) + ax.plot(range(1, len(combined) + 1), combined, 'b-o', markersize=3) + + # Add vertical line at stage boundary + if len(stage1_fitnesses) > 0 and len(stage2_fitnesses) > 0: + boundary = len(stage1_fitnesses) + 0.5 + ax.axvline(x=boundary, color='red', linestyle='--', linewidth=1.5, + label='Stage 1 -> 2') + ax.legend() + + ax.set_xlabel('CMA-ES Iteration') + ax.set_ylabel('Best Fitness (gates + distance bonus)') + ax.set_title('Controller Tuning Learning Curve (2-Stage)') + ax.grid(True, alpha=0.3) + fig_lc.savefig(os.path.join(save_dir, "learning_curve.png"), dpi=150, bbox_inches='tight') + plt.close(fig_lc) + except Exception as e: + print(f"Warning: Could not save plots: {e}") + + # Return results + if best_result is not None: + return { + 'fitness': best_score, + 'best_gains': best_result['gains'], + 'best_bspline_timing': best_result.get('bspline_timing', list(bspline_timing)), + 'best_gate_offsets': best_result.get('gate_offsets', [0.0] * n_offset_params), + 'gates_passed': best_result['gates_passed'], + 'distance_bonus': best_result.get('distance_bonus', 0.0), + 'success': True + } + else: + return { + 'fitness': 0, + 'best_gains': None, + 'best_bspline_timing': None, + 'best_gate_offsets': None, + 'gates_passed': 0, + 'distance_bonus': 0.0, + 'success': False + } + + +# ============================================================================ +# EVALUATOR FOR EVOLUTIONARY ALGORITHM +# ============================================================================ + +def evaluate_individual_with_tuning(individual, ind_save_dir, gate_cfg='circle', + max_evals=100, num_workers=4, sim_time=20.0, + dt=0.005, timeout=30.0, num=None): + """ + Evaluate individual by tuning its controller via 2-stage CMA-ES. + + This is the main fitness function for evolution with Lee controller tuning. + Stage 1 optimises gains + timing (7 params), Stage 2 adds gate offset + control points (7 + n_gates*3 params) to refine the trajectory shape. + + Args: + individual: Evolved drone morphology (genome array) + ind_save_dir: Directory to save results for this individual + gate_cfg: Gate configuration ('circle', 'figure8', 'slalom', 'backandforth') + max_evals: Maximum CMA-ES evaluations (split across both stages) + num_workers: Number of parallel workers for CMA-ES + sim_time: Simulation time in seconds + dt: Time step in seconds + timeout: Timeout per evaluation in seconds + num: Individual number (for logging) + + Returns: + int: Number of gates passed (0 if tuning failed) + """ + # Get gate configuration + gate_config = GATE_CONFIGS[gate_cfg] + + # Run 2-stage CMA-ES optimization + result = optimize_controller_for_morphology( + individual=individual, + gate_config=gate_config, + max_evaluations=max_evals, + num_workers=num_workers, + sim_time=sim_time, + dt=dt, + timeout_per_eval=timeout, + save_dir=ind_save_dir + ) + + # Return integer fitness (gates passed) + return int(result['gates_passed']) diff --git a/src/ariel/ec/drone/evaluators/unified_fitness.py b/src/ariel/ec/drone/evaluators/unified_fitness.py new file mode 100644 index 000000000..625d9c6b9 --- /dev/null +++ b/src/ariel/ec/drone/evaluators/unified_fitness.py @@ -0,0 +1,184 @@ +"""Unified fitness wrapper for evolution. + +Subsumes the prior `_RepairAndEvaluateFitness` (formerly in the deleted +`examples/evolution/run_evolution_with_lee_tuning.py`) and +`_CombinedHoverGateFitness` (`experimentation/run_combined_hover_gate_evolution.py`, +`ppsn_2026_submission` branch). Picklable so it works inside multiprocessing +Pool workers. + +Modes: + - 'gate': run brain (rl/lee), return gates_passed. + With hover_gradient=True: skip brain on non-hoverable + drones and return continuous_hover_fitness ∈ [0, 3]. + - 'pure_hover': return continuous_hover_fitness, no brain. + - 'edit_distance': return -edit_distance to STANDARD_HEXACOPTER target. + - 'zero': return 0.0. +""" +import os +import pickle + +import numpy as np + +from ariel.ec.drone.evaluators.hover_fitness import continuous_hover_fitness +from ariel.ec.drone.genome_handlers.repair_workflow import ( + stage1_optimization_repair, + stage2_hover_check, + stage3_hover_repair, +) +from ariel.ec.drone.genome_handlers.operators.optimization_repair_operator import ( + OptimizationRepairConfig, +) + + +# Standard hexacopter target for edit-distance fitness. +# 6 arms equally spaced at 60°, magnitude 0.13, motors pointing up +# (motor_pitch=π → upward thrust in NED), alternating CCW/CW. +STANDARD_HEXACOPTER = np.array([ + [0.13, 0.0, 0.0, np.pi, 0.0, 0], # 0° + [0.13, np.pi / 3.0, 0.0, np.pi, 0.0, 1], # 60° + [0.13, 2 * np.pi / 3.0, 0.0, np.pi, 0.0, 0], # 120° + [0.13, np.pi, 0.0, np.pi, 0.0, 1], # 180° + [0.13, -2 * np.pi / 3.0, 0.0, np.pi, 0.0, 0], # 240° + [0.13, -np.pi / 3.0, 0.0, np.pi, 0.0, 1], # 300° +]) + +# Per-parameter [min, max] bounds matching shared_params in +# get_genome_handler_config (examples/evolution/run_evolution.py). +EDIT_DISTANCE_MIN = np.array([0.055, -np.pi, -np.pi / 2, -np.pi, -np.pi, 0]) +EDIT_DISTANCE_MAX = np.array([0.17, np.pi, np.pi / 2, np.pi, np.pi, 1]) + + +class UnifiedFitness: + """Picklable fitness wrapper. Owns decode, repair, and fitness dispatch.""" + + def __init__( + self, + *, + brain, # 'rl' | 'lee' | None + fitness_mode, # 'gate' | 'pure_hover' | 'edit_distance' | 'zero' + hover_gradient, # bool + per_individual_repair, # bool + is_indirect, # cppn / hybrid-cppn + handler_class, # for re-decoding indirect genomes + handler_kwargs, + coordinate_system, # 'spherical' | 'cartesian' | 'cppn' | 'hybrid-cppn' + brain_kwargs=None, + ): + self.brain = brain + self.fitness_mode = fitness_mode + self.hover_gradient = hover_gradient + self.per_individual_repair = per_individual_repair + self.is_indirect = is_indirect + self.handler_class = handler_class + self.handler_kwargs = handler_kwargs + self.coordinate_system = coordinate_system + self.brain_kwargs = brain_kwargs or {} + + def __call__(self, genome, ind_save_dir): + # 1. Save genome. + if ind_save_dir is not None: + os.makedirs(ind_save_dir, exist_ok=True) + if self.is_indirect: + with open(os.path.join(ind_save_dir, "genotype.pkl"), "wb") as f: + pickle.dump(genome, f) + else: + np.save(os.path.join(ind_save_dir, "genome.npy"), genome) + + # 2. Decode indirect → phenotype. + if self.is_indirect: + handler = self.handler_class(genome=genome, **self.handler_kwargs) + phenotype = handler.get_phenotype() + repair_coord = "spherical" # CPPN/hybrid-cppn decode to spherical + else: + # Mutation returns a SphericalNeatGenome wrapper (or similar) whose + # arm matrix is in `.arms`; the EA hands these back to fitness + # functions verbatim. Initial-pop genomes are already plain ndarrays. + arms = genome.arms if hasattr(genome, "arms") else genome + phenotype = np.asarray(arms, dtype=np.float64) + repair_coord = self.coordinate_system + + # 3. Per-individual 3-stage repair. On failure: + # - hover_gradient on → fall back to hover_fit on the raw phenotype + # so the gradient signal isn't lost. + # - hover_gradient off → return 0 (matches _RepairAndEvaluateFitness). + if self.per_individual_repair: + raw_phenotype = phenotype + phenotype = self._repair(phenotype, repair_coord) + if phenotype is None: + if self.hover_gradient and self.fitness_mode == "gate": + return continuous_hover_fitness(raw_phenotype) + return 0.0 + + # 4. Dispatch by fitness_mode. + if self.fitness_mode == "zero": + return 0.0 + + if self.fitness_mode == "pure_hover": + return continuous_hover_fitness(phenotype) + + if self.fitness_mode == "edit_distance": + from ariel.ec.drone.evaluators.edit_distance import compute_edit_distance + return -compute_edit_distance( + STANDARD_HEXACOPTER, phenotype, + EDIT_DISTANCE_MIN, EDIT_DISTANCE_MAX, + ) + + if self.fitness_mode == "gate": + if self.hover_gradient: + hover_fit = continuous_hover_fitness(phenotype) + can_hover, _ = stage2_hover_check( + phenotype, verbose=False, allow_spinning=False, + ) + if not can_hover: + return hover_fit + return hover_fit + self._run_brain(phenotype, ind_save_dir) + return self._run_brain(phenotype, ind_save_dir) + + raise ValueError(f"Unknown fitness_mode: {self.fitness_mode}") + + def _repair(self, phenotype, repair_coord): + """3-stage repair: hover_check → opt_repair → hover_repair. None on fail.""" + can_hover, _ = stage2_hover_check( + phenotype, verbose=False, allow_spinning=False, + ) + if not can_hover: + return None + + repair_config = OptimizationRepairConfig(fixed_params=[3, 4]) + repaired, _ = stage1_optimization_repair( + phenotype, coordinate_system=repair_coord, + config=repair_config, verbose=False, + ) + if repaired is None: + return None + + final, _ = stage3_hover_repair( + repaired, coordinate_system=repair_coord, verbose=False, + ) + return final + + def _run_brain(self, phenotype, ind_save_dir): + if self.brain == "rl": + from ariel.ec.drone.evaluators import gate_train + return gate_train.evaluate_individual( + phenotype, ind_save_dir, + self.brain_kwargs["training_ts"], + self.brain_kwargs["num_envs"], + self.brain_kwargs["gate_cfg"], + self.brain_kwargs["device"], + max_steps=self.brain_kwargs.get("max_steps", 1200), + ) + if self.brain == "lee": + from ariel.ec.drone.evaluators import lee_tune_evaluator + return lee_tune_evaluator.evaluate_individual_with_tuning( + phenotype, ind_save_dir, + gate_cfg=self.brain_kwargs["gate_cfg"], + max_evals=self.brain_kwargs["max_evals"], + num_workers=self.brain_kwargs["cma_workers"], + sim_time=self.brain_kwargs["sim_time"], + dt=self.brain_kwargs["dt"], + timeout=self.brain_kwargs["timeout"], + ) + raise ValueError( + f"fitness_mode='gate' requires brain in ('rl','lee'), got {self.brain!r}" + ) diff --git a/src/ariel/ec/drone/evaluators/zero.py b/src/ariel/ec/drone/evaluators/zero.py new file mode 100644 index 000000000..4c45ff809 --- /dev/null +++ b/src/ariel/ec/drone/evaluators/zero.py @@ -0,0 +1,6 @@ + +from ariel.ec.drone.genome_handlers.base import GenomeHandler + + +def fitness_function(member: GenomeHandler, log_dir=None) -> float: + return 0 \ No newline at end of file diff --git a/src/ariel/ec/drone/genome_handlers/__init__.py b/src/ariel/ec/drone/genome_handlers/__init__.py new file mode 100644 index 000000000..f05a51ff1 --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/__init__.py @@ -0,0 +1,26 @@ +# Genome handlers for different coordinate representations + +from .base import GenomeHandler +from .cartesian_euler_genome_handler import CartesianEulerDroneGenomeHandler +from .spherical_angular_genome_handler import SphericalAngularDroneGenomeHandler +from .cppn_neat_genome_handler import CPPNNeatDroneGenomeHandler +from .hybrid_cppn_genome_handler import HybridCPPNDroneGenomeHandler + +# Optional MLP handler (requires PyTorch) +try: + from .mlp_genome_handler import MLPDroneGenomeHandler + MLP_AVAILABLE = True +except ImportError: + MLP_AVAILABLE = False + MLPDroneGenomeHandler = None + +__all__ = [ + 'GenomeHandler', + 'CartesianEulerDroneGenomeHandler', + 'SphericalAngularDroneGenomeHandler', + 'CPPNNeatDroneGenomeHandler', + 'HybridCPPNDroneGenomeHandler', +] + +if MLP_AVAILABLE: + __all__.append('MLPDroneGenomeHandler') \ No newline at end of file diff --git a/src/ariel/ec/drone/genome_handlers/base.py b/src/ariel/ec/drone/genome_handlers/base.py new file mode 100644 index 000000000..501361fb8 --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/base.py @@ -0,0 +1,129 @@ +from __future__ import annotations +from abc import ABC, abstractmethod +from typing import Any, List +import numpy as np +import numpy.typing as npt + + +class GenomeHandler(ABC): + """Abstract base class for all genotype implementations.""" + + def __init__(self, genome: npt.NDArray[Any] | None = None) -> None: + """ + Initialize the genotype. + + Args: + genome: The genome array. If None, creates empty genome. + """ + self.fitness: float | None = None + if genome is None: + self.genome = self._generate_random_genome() + else: + self.genome = genome.copy() + + @abstractmethod + def _generate_random_genome(self) -> npt.NDArray[Any]: + """ + Generate a random genome. + + Returns: + Randomly initialized genome array + """ + pass + + @abstractmethod + def generate_random_population(self, population_size: int) -> List[GenomeHandler]: + """ + Generate a population of random genotypes. + + Args: + population_size: Number of individuals to generate + + Returns: + List of random genotype instances + """ + pass + + @abstractmethod + def crossover(self, other: GenomeHandler) -> GenomeHandler: + """ + Perform crossover with another genotype to produce offspring. + + Args: + other: The other parent genotype + + Returns: + Child genotype from crossover + """ + pass + + def crossover_population( + self, + population1: List[GenomeHandler], + population2: List[GenomeHandler] + ) -> List[GenomeHandler]: + """ + Perform crossover on two populations. + + Args: + population1: First parent population + population2: Second parent population + + Returns: + List of offspring genotypes + """ + assert len(population1) == len(population2), "Populations must have same size" + + children = [] + for parent1, parent2 in zip(population1, population2): + child = parent1.crossover(parent2) + children.append(child) + return children + + @abstractmethod + def mutate(self) -> None: + """Mutate this genotype in place.""" + pass + + def mutate_population(self, population: List[GenomeHandler]) -> None: + """ + Mutate all individuals in a population. + + Args: + population: List of genotypes to mutate + """ + for individual in population: + individual.mutate() + + @abstractmethod + def copy(self) -> GenomeHandler: + """ + Create a deep copy of this genotype. + + Returns: + Copy of this genotype + """ + pass + + @abstractmethod + def is_valid(self) -> bool: + """ + Check if the genotype represents a valid individual. + + Returns: + True if valid, False otherwise + """ + pass + + def repair(self) -> None: + """ + Repair the genotype to make it valid. + Default implementation does nothing. + """ + pass + + def compatibility_distance(self, other: GenomeHandler) -> float: + """Compute compatibility distance to another genome for speciation.""" + raise NotImplementedError( + f"{type(self).__name__} does not implement compatibility_distance" + ) \ No newline at end of file diff --git a/src/ariel/ec/drone/genome_handlers/cartesian_euler_genome_handler.py b/src/ariel/ec/drone/genome_handlers/cartesian_euler_genome_handler.py new file mode 100644 index 000000000..00828d570 --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/cartesian_euler_genome_handler.py @@ -0,0 +1,1088 @@ +from __future__ import annotations + +from typing import Any, List, Tuple, Optional + +import numpy as np +import numpy.typing as npt + +from .base import GenomeHandler +from .operators import ( + CartesianSymmetryOperator, + CartesianRepairOperator, + SymmetryConfig, + RepairConfig +) + + +class CartesianEulerDroneGenomeHandler(GenomeHandler): + """ + Genome handler for drone designs using Cartesian coordinates and Euler angles. + + Genome is defined by an n by m matrix, where n is the maximum number of arms/motors + and m is the number of parameters (7 total): + - 3 for motor position (x, y, z) in Cartesian coordinates + - 3 for motor orientation (roll, pitch, yaw) in Euler angles + - 1 for propeller direction of spin (0 or 1) + + Uses NaN masking for variable arm counts, where inactive arms are marked with NaN. + """ + + def __init__( + self, + genome: npt.NDArray[Any] | None = None, + min_max_narms: Tuple[int, int] | None = None, + parameter_limits: npt.NDArray[Any] | None = None, + append_arm_chance: float = 0.0, + mutation_probs: Optional[List[float] | npt.NDArray[Any]] = None, + mutation_scales_percentage: Optional[npt.NDArray[Any]] = None, + bilateral_plane_for_symmetry: str | None = None, + repair: bool = True, + enable_collision_repair: bool = True, + propeller_radius: float = 0.0254, # 2-inch propeller radius in meters + inner_boundary_radius: float = 0.09, + outer_boundary_radius: float = 0.4, + max_repair_iterations: int = 100, + repair_step_size: float = 1.0, + propeller_tolerance: float = 0.1, + rnd: np.random.Generator | None = None, + ) -> None: + """ + Initialize the Cartesian Euler genome handler. + + Args: + genome: Pre-existing genome array of shape (narms, 7) + min_max_narms: Tuple of (min_arms, max_arms). If None, defaults to (4, 4) + parameter_limits: Array of shape (7, 2) with [min, max] for each parameter. If None, uses defaults + append_arm_chance: Probability of adding/removing arms during mutation (not used for fixed arms) + mutation_probs: Custom mutation probabilities for each parameter. If None, uses defaults + mutation_scales_percentage: Mutation scales as percentage of parameter ranges. If None, uses defaults + bilateral_plane_for_symmetry: Plane for bilateral symmetry ("xy", "xz", "yz", or None) + repair: Whether to apply repair operations + enable_collision_repair: Whether to enable collision detection and repair + propeller_radius: Radius of propellers for collision detection + inner_boundary_radius: Minimum distance from origin + outer_boundary_radius: Maximum distance from origin + max_repair_iterations: Maximum iterations for collision repair + repair_step_size: Step size multiplier for collision resolution + propeller_tolerance: Additional clearance tolerance for propellers + rnd: Random number generator + """ + self.rnd = rnd if rnd is not None else np.random.default_rng() + + # Set basic attributes from standardized parameters + if min_max_narms is None: + self.min_narms, self.max_narms = 3, 8 # Variable number of arms by default + else: + self.min_narms, self.max_narms = min_max_narms + + # Setup parameter limits + if parameter_limits is None: + # Default limits: [x, y, z, roll, pitch, yaw, direction] + self.parameter_limits = np.array([ + [-0.4, 0.4], # x position + [-0.4, 0.4], # y position + [-0.4, 0.4], # z position + [-np.pi, np.pi], # roll + [-np.pi, np.pi], # pitch + [-np.pi, np.pi], # yaw + [0, 1] # direction + ]) + else: + self.parameter_limits = np.asarray(parameter_limits) + if self.parameter_limits.shape != (7, 2): + raise ValueError("parameter_limits must have shape (7, 2)") + + # Validate inputs + self._validate_initialization_parameters( + (self.min_narms, self.max_narms), self.parameter_limits, append_arm_chance, + mutation_probs, mutation_scales_percentage + ) + + self.append_arm_chance = append_arm_chance + if self.min_narms == self.max_narms and self.append_arm_chance != 0: + raise ValueError("When min_narms == max_narms, append_arm_chance must be 0!") + + self.repair_enabled = repair + + # Store collision repair parameters + self.enable_collision_repair = enable_collision_repair + self.propeller_radius = propeller_radius + self.inner_boundary_radius = inner_boundary_radius + self.outer_boundary_radius = outer_boundary_radius + self.max_repair_iterations = max_repair_iterations + self.repair_step_size = repair_step_size + self.propeller_tolerance = propeller_tolerance + + # Validate and store bilateral symmetry plane + valid_planes = {"xy", "xz", "yz", None} + if bilateral_plane_for_symmetry not in valid_planes: + raise ValueError(f"bilateral_plane_for_symmetry must be one of {valid_planes}") + + # Check for odd arms with bilateral symmetry + if bilateral_plane_for_symmetry is not None and self.max_narms % 2 != 0: + raise ValueError("Bilateral symmetry requires an even number of arms") + + self.bilateral_plane_for_symmetry = bilateral_plane_for_symmetry + + # Setup mutation parameters + self._setup_mutation_parameters(mutation_probs, mutation_scales_percentage) + + # Store original mutation_probs for later access (before normalization) + if mutation_probs is not None: + self.mutation_probs = np.asarray(mutation_probs) + else: + # Default uniform probabilities for 7 parameters + self.mutation_probs = np.array([1/7, 1/7, 1/7, 1/7, 1/7, 1/7, 1/7]) + + # Initialize operators + self._setup_operators() + + # Initialize genome using parent class + super().__init__(genome) + + def _validate_initialization_parameters( + self, + min_max_narms: Tuple[int, int], + parameter_limits: npt.NDArray[Any], + append_arm_chance: float, + mutation_probs: Optional[List[float] | npt.NDArray[Any]], + mutation_scales_percentage: Optional[npt.NDArray[Any]] + ) -> None: + """Validate initialization parameters.""" + min_narms, max_narms = min_max_narms + + if min_narms < 1: + raise ValueError("min_narms must be at least 1") + if max_narms < min_narms: + raise ValueError("max_narms must be >= min_narms") + if not (0 <= append_arm_chance <= 0.5): + raise ValueError("append_arm_chance must be between 0 and 0.5") + + parameter_limits = np.asarray(parameter_limits) + if parameter_limits.shape != (7, 2): + raise ValueError("parameter_limits must have shape (7, 2)") + if np.any(parameter_limits[:, 0] >= parameter_limits[:, 1]): + raise ValueError("parameter_limits: min values must be < max values") + + if mutation_probs is not None: + mutation_probs = np.asarray(mutation_probs) + if len(mutation_probs) != 7: + raise ValueError("mutation_probs must have length 7") + if np.any(mutation_probs < 0): + raise ValueError("mutation_probs must be non-negative") + + if mutation_scales_percentage is not None: + mutation_scales_percentage = np.asarray(mutation_scales_percentage) + if len(mutation_scales_percentage) != 7: + raise ValueError("mutation_scales_percentage must have length 7") + if np.any(mutation_scales_percentage < 0): + raise ValueError("mutation_scales_percentage must be non-negative") + + def _setup_mutation_parameters( + self, + mutation_probs: Optional[List[float] | npt.NDArray[Any]], + mutation_scales_percentage: Optional[npt.NDArray[Any]] + ) -> None: + """Setup mutation probabilities and scales.""" + nparms = 7 + mutation_window = 1 - 2 * self.append_arm_chance + + # Setup mutation probabilities + if mutation_probs is None: + # Uniform distribution across parameters + param_prob = mutation_window / nparms + mutation_probs = np.repeat(param_prob, nparms) + else: + mutation_probs = np.asarray(mutation_probs) + # Normalize to fit in mutation window + total_prob = np.sum(mutation_probs) + if total_prob > 0: + mutation_probs = mutation_probs * (mutation_window / total_prob) + + # Combine with add/remove probabilities + self.mutation_probabilities = np.array([ + self.append_arm_chance, # Add arm probability + self.append_arm_chance, # Remove arm probability + *mutation_probs # Parameter mutation probabilities + ]) + + # Validate probabilities sum to 1 + prob_sum = np.sum(self.mutation_probabilities) + if not np.isclose(prob_sum, 1.0, rtol=1e-6): + raise ValueError(f"Mutation probabilities must sum to 1, got {prob_sum}") + + # Setup mutation scales + if mutation_scales_percentage is None: + mutation_scales_percentage = np.array([0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.0]) + + # Convert percentages to absolute scales based on parameter ranges + parameter_ranges = self.parameter_limits[:, 1] - self.parameter_limits[:, 0] + self.mutation_scales = parameter_ranges * mutation_scales_percentage + + def _setup_operators(self) -> None: + """Initialize the symmetry and repair operators.""" + # Setup symmetry operator + symmetry_config = SymmetryConfig( + plane=self.bilateral_plane_for_symmetry, + enabled=self.bilateral_plane_for_symmetry is not None + ) + self.symmetry_operator = CartesianSymmetryOperator( + config=symmetry_config + ) + + # Setup repair operator + repair_config = RepairConfig( + apply_symmetry=self.bilateral_plane_for_symmetry is not None, + enable_collision_repair=self.enable_collision_repair, + propeller_radius=self.propeller_radius, + inner_boundary_radius=self.inner_boundary_radius, + outer_boundary_radius=self.outer_boundary_radius, + max_repair_iterations=self.max_repair_iterations, + repair_step_size=self.repair_step_size, + propeller_tolerance=self.propeller_tolerance + ) + self.repair_operator = CartesianRepairOperator( + config=repair_config, + parameter_limits=self.parameter_limits, + min_narms=self.min_narms, + max_narms=self.max_narms, + symmetry_operator=self.symmetry_operator, + rng=self.rnd + ) + + def _generate_random_genome(self) -> npt.NDArray[Any]: + """Generate a random genome with variable arm count using NaN masking.""" + # Determine the number of arms to generate (can be variable) + if self.min_narms == self.max_narms: + num_arms = self.max_narms + else: + num_arms = self.rnd.integers(self.min_narms, self.max_narms + 1) + + # If symmetry is enabled, only generate half the arms initially + if self.bilateral_plane_for_symmetry is not None: + num_arms_to_generate = self.max_narms // 2 + else: + num_arms_to_generate = num_arms + + # Create genome with max_narms rows, filled with NaN initially + genome = np.full((self.max_narms, 7), np.nan) + + if num_arms_to_generate > 0: + # Motor positions: random uniform within parameter limits + motor_positions = self.rnd.uniform( + low=self.parameter_limits[:3, 0], + high=self.parameter_limits[:3, 1], + size=(num_arms_to_generate, 3), + ) + + # Motor orientations: random uniform within parameter limits + motor_orientations = self.rnd.uniform( + low=self.parameter_limits[3:6, 0], + high=self.parameter_limits[3:6, 1], + size=(num_arms_to_generate, 3), + ) + + # Propeller directions: random choice within parameter limits + propeller_directions = self.rnd.integers( + low=int(self.parameter_limits[6, 0]), + high=int(self.parameter_limits[6, 1]) + 1, + size=(num_arms_to_generate, 1), + ) + + # Fill in the valid arms + valid_genome = np.concatenate( + (motor_positions, motor_orientations, propeller_directions), + axis=1, + ) + genome[:num_arms_to_generate] = valid_genome + + if self.bilateral_plane_for_symmetry is not None: + # If symmetry is enabled, apply symmetry to the genome + genome = self.symmetry_operator.apply_symmetry(genome) + # Apply repair if enabled (this will handle symmetry application) + if self.repair_enabled: + genome = self.repair_operator.repair(genome) + + return genome + + def generate_random_population(self, population_size: int) -> List[CartesianEulerDroneGenomeHandler]: + """ + Generate a population of random genome handlers. + + Args: + population_size: Number of individuals to generate + + Returns: + List of random genome handler instances + """ + population = [] + for _ in range(population_size): + random_genome = self._generate_random_genome() + individual = CartesianEulerDroneGenomeHandler( + genome=random_genome, + min_max_narms=(self.min_narms, self.max_narms), + parameter_limits=self.parameter_limits, + append_arm_chance=self.append_arm_chance, + mutation_probs=self.mutation_probs, + mutation_scales_percentage=(self.mutation_scales / (self.parameter_limits[:, 1] - self.parameter_limits[:, 0])), + bilateral_plane_for_symmetry=self.bilateral_plane_for_symmetry, + repair=self.repair_enabled, + enable_collision_repair=self.enable_collision_repair, + propeller_radius=self.propeller_radius, + inner_boundary_radius=self.inner_boundary_radius, + outer_boundary_radius=self.outer_boundary_radius, + max_repair_iterations=self.max_repair_iterations, + repair_step_size=self.repair_step_size, + propeller_tolerance=self.propeller_tolerance, + rnd=self.rnd, + ) + population.append(individual) + return population + + def random_population(self, pop_size: int) -> npt.NDArray[Any]: + """ + Generate a random population as a numpy array (vectorized version). + + Args: + pop_size: Size of the population to generate + + Returns: + Population array of shape (pop_size, max_narms, 7) + """ + array_shape = (pop_size, self.max_narms, 7) + population = np.empty(array_shape) + + # Generate random arms for all individuals + population[:, :, :6] = self.rnd.uniform( + low=self.parameter_limits[:6, 0], + high=self.parameter_limits[:6, 1], + size=(pop_size, self.max_narms, 6) + ) + population[:, :, 6] = self.rnd.integers(0, 2, size=(pop_size, self.max_narms)) + + if self.bilateral_plane_for_symmetry is not None: + # If symmetry is enabled, only keep half of the genome + population[:, self.max_narms // 2:, :] = np.nan + else: + # Remove random arms from each drone to create variable arm counts + num_arms_to_remove = self.rnd.integers( + 0, self.max_narms + 1 - self.min_narms, + size=pop_size + ) + + # Create mask for arms to remove + arms_to_remove_mask = np.zeros(array_shape, dtype=bool) + for i in range(pop_size): + if num_arms_to_remove[i] > 0: + indices_to_remove = self.rnd.choice( + self.max_narms, + num_arms_to_remove[i], + replace=False + ) + arms_to_remove_mask[i, indices_to_remove, :] = True + + # Apply mask (set removed arms to NaN) + population[arms_to_remove_mask] = np.nan + + # Apply post-processing + if self.repair_enabled: + population = self.repair_population(population) + + return population + + def crossover(self, other: CartesianEulerDroneGenomeHandler) -> CartesianEulerDroneGenomeHandler: + """ + Perform crossover with another genome handler to produce offspring. + + Args: + other: The other parent genome handler + + Returns: + Child genome handler from crossover + """ + if not isinstance(other, CartesianEulerDroneGenomeHandler): + raise TypeError("Other parent must be CartesianEulerDroneGenomeHandler") + + if self.genome.shape != other.genome.shape: + raise ValueError("Parents must have the same genome shape") + + # Create child with same parameters as parents + child = CartesianEulerDroneGenomeHandler( + genome=None, # Will be set below + min_max_narms=(self.min_narms, self.max_narms), + parameter_limits=self.parameter_limits, + append_arm_chance=self.append_arm_chance, + mutation_probs=self.mutation_probs, + mutation_scales_percentage=(self.mutation_scales / (self.parameter_limits[:, 1] - self.parameter_limits[:, 0])), + bilateral_plane_for_symmetry=self.bilateral_plane_for_symmetry, + repair=self.repair_enabled, + enable_collision_repair=self.enable_collision_repair, + propeller_radius=self.propeller_radius, + inner_boundary_radius=self.inner_boundary_radius, + outer_boundary_radius=self.outer_boundary_radius, + max_repair_iterations=self.max_repair_iterations, + repair_step_size=self.repair_step_size, + propeller_tolerance=self.propeller_tolerance, + rnd=self.rnd, + ) + + # Arm-wise crossover: randomly select each arm from either parent + random_choices = self.rnd.choice([0, 1], size=self.max_narms) + child_genome = np.where( + random_choices[:, np.newaxis] == 0, + self.genome, + other.genome + ) + + child.genome = child_genome + + # Apply bilateral symmetry if specified + if self.bilateral_plane_for_symmetry is not None: + child.apply_symmetry() + + return child + + def crossover_vectorized( + self, + population: npt.NDArray[Any], + mating_pool1: npt.NDArray[Any], + mating_pool2: npt.NDArray[Any] + ) -> npt.NDArray[Any]: + """ + Vectorized crossover operation for efficiency. + + Args: + population: Population array of shape (pop_size, max_narms, 7) + mating_pool1: Indices of first parents + mating_pool2: Indices of second parents + + Returns: + Children population array + """ + pop_size, max_narms, nparms = population.shape + + # Shuffle arms of each individual for genetic diversity + shuffle_indices = np.array([ + self.rnd.permutation(max_narms) for _ in range(pop_size) + ]) + population_shuffled = population[np.arange(pop_size)[:, None], shuffle_indices] + + # Select parents + parent1s = population_shuffled[mating_pool1] + parent2s = population_shuffled[mating_pool2] + + if parent1s.shape != parent2s.shape: + raise ValueError("Parent populations must have the same shape") + + # Generate random choices for arm selection + random_choices = self.rnd.choice([0, 1], size=parent1s.shape[:-1]) + + # Perform crossover + children = np.where( + random_choices[..., np.newaxis] == 0, + parent1s, + parent2s + ) + + # Apply repair if needed + if self.repair_enabled: + children = self.repair_population(children) + + return children + + def _mutate_add_arm(self, genome: npt.NDArray[Any]) -> None: + """Add a random arm to the genome.""" + # Find empty slots (NaN values) + empty_mask = np.isnan(genome[:, 0]) + + if not np.any(empty_mask) or (self.bilateral_plane_for_symmetry is not None and not np.any(empty_mask[:self.max_narms // 2])): + return # No empty slots available + + # Select random empty slot + empty_indices = np.where(empty_mask)[0] + selected_index = self.rnd.choice(empty_indices) + + # Generate new arm parameters + new_arm = np.zeros(7) + new_arm[:6] = self.rnd.uniform( + low=self.parameter_limits[:6, 0], + high=self.parameter_limits[:6, 1] + ) + new_arm[6] = self.rnd.integers(0, 2) + + genome[selected_index] = new_arm + + return genome + + def _mutate_remove_arm(self, genome: npt.NDArray[Any]) -> None: + """Remove a random arm from the genome.""" + # Find non-empty slots + non_empty_mask = ~np.isnan(genome[:, 0]) + if not np.any(non_empty_mask): + return # No arms to remove + + # Select random non-empty slot + non_empty_indices = np.where(non_empty_mask)[0] + selected_index = self.rnd.choice(non_empty_indices) + + genome[selected_index] = np.nan + + return genome + + def _mutate_parameter(self, genome: npt.NDArray[Any], param_index: int) -> None: + """Mutate a specific parameter of a random arm.""" + # Find non-empty arms + non_empty_mask = ~np.isnan(genome[:, 0]) + if not np.any(non_empty_mask): + return # No arms to mutate + + # Select random arm + non_empty_indices = np.where(non_empty_mask)[0] + selected_arm = self.rnd.choice(non_empty_indices) + + if param_index == 6: + # Flip direction parameter + genome[selected_arm, param_index] = 1 - genome[selected_arm, param_index] + else: + # Add Gaussian perturbation + perturbation = self.rnd.normal(0, self.mutation_scales[param_index]) + genome[selected_arm, param_index] += perturbation + + # Clip to parameter limits + genome[selected_arm, param_index] = np.clip( + genome[selected_arm, param_index], + self.parameter_limits[param_index, 0], + self.parameter_limits[param_index, 1] + ) + + return genome + + def mutate(self) -> None: + """Mutate this genome in place.""" + + if self.bilateral_plane_for_symmetry is not None: + # Temporarily remove symmetry for mutation + self.apply_symmetry() + genome_half = self.genome.copy() + else: + genome_half = self.genome.copy() + + # Choose mutation type + mutation_type = self.rnd.choice( + len(self.mutation_probabilities), + p=self.mutation_probabilities + ) + + if mutation_type == 0: + # Add arm mutation + genome_half = self._mutate_add_arm(genome_half) + elif mutation_type == 1: + # Remove arm mutation + genome_half = self._mutate_remove_arm(genome_half) + else: + # Parameter mutation + param_index = mutation_type - 2 + genome_half = self._mutate_parameter(genome_half, param_index) + + # Update genome + self.genome = genome_half + + if self.bilateral_plane_for_symmetry is not None: + # Reapply symmetry after mutation + self.apply_symmetry() + # Apply repair if enabled (this will handle symmetry application) + if self.repair_enabled: + self.repair() + def mutation_vectorized(self, population: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Vectorized mutation operation for efficiency. + + Args: + population: Population array to mutate + + Returns: + Mutated population array + """ + if self.bilateral_plane_for_symmetry is not None: + population = self.unapply_symmetry_pop(population) + + pop_size, max_narms, nparms = population.shape + pop = population.copy() + + # Choose mutation type for each individual + mutation_choices = np.nonzero(self.mutation_probabilities)[0] + mutations = self.rnd.choice( + mutation_choices, + size=pop_size, + p=self.mutation_probabilities[self.mutation_probabilities != 0] + ) + + # Apply different mutation types + self._apply_add_mutations(pop, mutations) + self._apply_remove_mutations(pop, mutations) + self._apply_parameter_mutations(pop, mutations) + + # Apply post-processing + if self.repair_enabled: + pop = self.repair_population(pop) + elif self.bilateral_plane_for_symmetry is not None: + pop = self.apply_symmetry_pop(pop) + + return pop + + def _apply_add_mutations( + self, + population: npt.NDArray[Any], + mutations: npt.NDArray[Any] + ) -> None: + """Apply add arm mutations to population.""" + add_mask = (mutations == 0) + if not np.any(add_mask): + return + + # Find individuals with empty slots + empty_indices = np.isnan(population[:, :, 0]) + valid_add_mask = np.any(empty_indices, axis=1) + add_mask &= valid_add_mask + + if not np.any(add_mask): + return + + # Get available indices for adding + available_indices = np.argwhere(empty_indices[add_mask]) + if len(available_indices) == 0: + return + + # Select random indices + selected_indices = self.rnd.choice( + len(available_indices), + size=np.sum(add_mask), + replace=True + ) + + # Generate new arms + num_new_arms = np.sum(add_mask) + new_arms = np.zeros((num_new_arms, 7)) + new_arms[:, :6] = self.rnd.uniform( + low=self.parameter_limits[:6, 0], + high=self.parameter_limits[:6, 1], + size=(num_new_arms, 6) + ) + new_arms[:, 6] = self.rnd.integers(0, 2, size=num_new_arms) + + # Apply new arms + for i, idx in enumerate(selected_indices): + pop_idx, arm_idx = available_indices[idx] + actual_pop_idx = np.where(add_mask)[0][pop_idx] + population[actual_pop_idx, arm_idx] = new_arms[i] + + def _apply_remove_mutations( + self, + population: npt.NDArray[Any], + mutations: npt.NDArray[Any] + ) -> None: + """Apply remove arm mutations to population.""" + remove_mask = (mutations == 1) + if not np.any(remove_mask): + return + + # Find individuals with non-empty arms + non_empty_indices = ~np.isnan(population[:, :, 0]) + valid_remove_mask = np.any(non_empty_indices, axis=1) + remove_mask &= valid_remove_mask + + if not np.any(remove_mask): + return + + # Get available indices for removal + available_indices = np.argwhere(non_empty_indices[remove_mask]) + if len(available_indices) == 0: + return + + # Select random indices + selected_indices = self.rnd.choice( + len(available_indices), + size=np.sum(remove_mask), + replace=True + ) + + # Remove arms + for idx in selected_indices: + pop_idx, arm_idx = available_indices[idx] + actual_pop_idx = np.where(remove_mask)[0][pop_idx] + population[actual_pop_idx, arm_idx] = np.nan + + def _apply_parameter_mutations( + self, + population: npt.NDArray[Any], + mutations: npt.NDArray[Any] + ) -> None: + """Apply parameter mutations to population.""" + perturb_mask = (mutations >= 2) + if not np.any(perturb_mask): + return + + drone_indices = np.where(perturb_mask)[0] + + # Find non-empty motors for each drone + non_empty_mask = ~np.isnan(population[drone_indices, :, 0]) + num_non_empty = non_empty_mask.sum(axis=1) + + # Filter out drones with no motors + valid_drones = num_non_empty > 0 + if not np.any(valid_drones): + return + + valid_drone_indices = drone_indices[valid_drones] + valid_non_empty_mask = non_empty_mask[valid_drones] + valid_num_non_empty = num_non_empty[valid_drones] + + # Select random motor for each valid drone + random_indices = self.rnd.integers(0, valid_num_non_empty) + cumsum_non_empty = np.cumsum(valid_non_empty_mask, axis=1) + selected_motors = np.argmax( + cumsum_non_empty == (random_indices[:, None] + 1), + axis=1 + ) + + # Get parameter indices + selected_params = mutations[perturb_mask][valid_drones] - 2 + + # Apply mutations + for i, (drone_idx, motor_idx, param_idx) in enumerate( + zip(valid_drone_indices, selected_motors, selected_params) + ): + if param_idx == 6: + # Flip direction + population[drone_idx, motor_idx, param_idx] = \ + 1 - population[drone_idx, motor_idx, param_idx] + else: + # Add perturbation + perturbation = self.rnd.normal(0, self.mutation_scales[param_idx]) + population[drone_idx, motor_idx, param_idx] += perturbation + + # Clip to limits + population[drone_idx, motor_idx, param_idx] = np.clip( + population[drone_idx, motor_idx, param_idx], + self.parameter_limits[param_idx, 0], + self.parameter_limits[param_idx, 1] + ) + + def copy(self) -> CartesianEulerDroneGenomeHandler: + """ + Create a deep copy of this genome handler. + + Returns: + Copy of this genome handler + """ + return CartesianEulerDroneGenomeHandler( + genome=self.genome.copy(), + min_max_narms=(self.min_narms, self.max_narms), + parameter_limits=self.parameter_limits.copy(), + append_arm_chance=self.append_arm_chance, + mutation_probs=None, # Will use default + mutation_scales_percentage=None, # Will use default + bilateral_plane_for_symmetry=self.bilateral_plane_for_symmetry, + repair=self.repair_enabled, + enable_collision_repair=self.enable_collision_repair, + propeller_radius=self.propeller_radius, + inner_boundary_radius=self.inner_boundary_radius, + outer_boundary_radius=self.outer_boundary_radius, + max_repair_iterations=self.max_repair_iterations, + repair_step_size=self.repair_step_size, + propeller_tolerance=self.propeller_tolerance, + rnd=self.rnd, + ) + + def is_valid(self) -> bool: + """ + Check if the genome represents a valid drone configuration. + + Returns: + True if valid, False otherwise + """ + # Check that genome has the expected shape + if self.genome.shape != (self.max_narms, 7): + return False + + # Use the repair operator to validate the genome + return self.repair_operator.validate(self.genome) + + def repair(self) -> None: + """ + Repair the genome to make it valid by clipping out-of-bounds values. + """ + # Use the repair operator to repair the genome + self.genome = self.repair_operator.repair(self.genome) + + def get_motor_positions(self, include_nans=False) -> npt.NDArray[Any]: + """ + Get the motor positions as a (valid_narms, 3) array. + + Returns: + Array of motor positions [x, y, z] for valid arms only + """ + if include_nans: + # Return all positions including NaNs + return self.genome[:, :3].copy() + + valid_arms_mask = ~np.isnan(self.genome[:, 0]) + return self.genome[valid_arms_mask, :3].copy() + + def get_motor_orientations(self) -> npt.NDArray[Any]: + """ + Get the motor orientations as a (valid_narms, 3) array. + + Returns: + Array of motor orientations [roll, pitch, yaw] for valid arms only + """ + valid_arms_mask = ~np.isnan(self.genome[:, 0]) + return self.genome[valid_arms_mask, 3:6].copy() + + def get_propeller_directions(self) -> npt.NDArray[Any]: + """ + Get the propeller directions as a (valid_narms,) array. + + Returns: + Array of propeller directions (0 or 1) for valid arms only + """ + valid_arms_mask = ~np.isnan(self.genome[:, 0]) + return self.genome[valid_arms_mask, 6].copy() + + def set_motor_position(self, arm_index: int, position: npt.NDArray[Any]) -> None: + """ + Set the position of a specific motor. + + Args: + arm_index: Index of the arm/motor + position: New position [x, y, z] + """ + if not (0 <= arm_index < self.max_narms): + raise ValueError(f"arm_index must be between 0 and {self.max_narms-1}") + + if len(position) != 3: + raise ValueError("position must have exactly 3 elements") + + self.genome[arm_index, :3] = position + + def set_motor_orientation(self, arm_index: int, orientation: npt.NDArray[Any]) -> None: + """ + Set the orientation of a specific motor. + + Args: + arm_index: Index of the arm/motor + orientation: New orientation [roll, pitch, yaw] + """ + if not (0 <= arm_index < self.max_narms): + raise ValueError(f"arm_index must be between 0 and {self.max_narms-1}") + + if len(orientation) != 3: + raise ValueError("orientation must have exactly 3 elements") + + self.genome[arm_index, 3:6] = orientation + + def set_propeller_direction(self, arm_index: int, direction: int) -> None: + """ + Set the propeller direction of a specific motor. + + Args: + arm_index: Index of the arm/motor + direction: Propeller direction (0 or 1) + """ + if not (0 <= arm_index < self.max_narms): + raise ValueError(f"arm_index must be between 0 and {self.max_narms-1}") + + if direction not in [0, 1]: + raise ValueError("direction must be 0 or 1") + + self.genome[arm_index, 6] = direction + + def apply_symmetry(self) -> None: + """ + Apply bilateral symmetry to the genome based on the specified plane. + + This method enforces that the drone design is symmetric across the + specified plane by mirroring the first half of the arms to the second half. + For odd number of arms, the middle arm remains unchanged. + """ + if self.bilateral_plane_for_symmetry is None: + return + + # Use the symmetry operator to apply symmetry + self.genome = self.symmetry_operator.apply_symmetry(self.genome) + + def unapply_symmetry(self) -> None: + """ + Remove bilateral symmetry from the genome. + + This method restores the genome to a non-symmetric state by removing + any enforced symmetry constraints. + """ + if self.bilateral_plane_for_symmetry is None: + return + + # Use the symmetry operator to remove symmetry + self.genome = self.symmetry_operator.unapply_symmetry(self.genome) + + def repair_population(self, population): + """ + Repair a population of genome handlers or population array. + + Args: + population: List of genome handlers or population array to repair + + Returns: + Repaired population (same type as input) + """ + if isinstance(population, list): + # Handle list of genome handlers + repaired_population = [] + for individual in population: + repaired_individual = individual.copy() + repaired_individual.repair() + repaired_population.append(repaired_individual) + return repaired_population + else: + # Handle numpy array + repaired_pop = self.repair_operator.repair_population(population) + return repaired_pop + + def apply_symmetry_pop(self, population: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Apply symmetry to a population. + + Args: + population: Population array to make symmetric + + Returns: + Symmetric population array + """ + if self.bilateral_plane_for_symmetry is None: + return population + + # Use the symmetry operator to apply symmetry to population + return self.symmetry_operator.apply_symmetry_population(population) + + def unapply_symmetry_pop(self, population: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Remove symmetry from a population. + + Args: + population: Symmetric population array + + Returns: + Population array with symmetry removed + """ + if self.bilateral_plane_for_symmetry is None: + return population + + # Use the symmetry operator to remove symmetry from population + return self.symmetry_operator.unapply_symmetry_population(population) + + def validate_symmetry(self) -> bool: + """ + Check if the genome satisfies symmetry constraints. + + Returns: + True if genome satisfies symmetry constraints + """ + if self.bilateral_plane_for_symmetry is None: + return True + return self.symmetry_operator.validate_symmetry(self.genome) + + def get_symmetry_pairs(self) -> List[tuple]: + """ + Get pairs of indices that should be symmetric. + + Returns: + List of (source_index, target_index) tuples + """ + return self.symmetry_operator.get_symmetry_pairs(self.genome) + + def get_arm_count(self) -> int: + """ + Get the number of valid arms in the genome. + + Returns: + Number of valid (non-NaN) arms + """ + valid_arms_mask = ~np.isnan(self.genome[:, 0]) + return np.sum(valid_arms_mask) + + def get_max_arm_count(self) -> int: + """ + Get the maximum number of arms this genome can support. + + Returns: + Maximum number of arms + """ + return self.max_narms + + def get_valid_arms(self) -> npt.NDArray[Any]: + """ + Get only the valid (non-NaN) arms from the genome. + + Returns: + Array of valid arms with shape (num_valid_arms, 7) + """ + valid_mask = ~np.isnan(self.genome[:, 0]) + return self.genome[valid_mask].copy() + + def add_random_arm(self) -> bool: + """ + Add a random arm to an empty slot. + + Returns: + True if arm was added, False if no empty slots available + """ + empty_mask = np.isnan(self.genome[:, 0]) + if not np.any(empty_mask): + return False + + empty_indices = np.where(empty_mask)[0] + selected_index = self.rnd.choice(empty_indices) + + new_arm = np.zeros(7) + new_arm[:6] = self.rnd.uniform( + low=self.parameter_limits[:6, 0], + high=self.parameter_limits[:6, 1] + ) + new_arm[6] = self.rnd.integers(0, 2) + + self.genome[selected_index] = new_arm + return True + + def remove_arm(self, arm_index: int) -> None: + """ + Remove an arm by setting it to NaN. + + Args: + arm_index: Index of the arm to remove + """ + if not (0 <= arm_index < self.max_narms): + raise ValueError(f"arm_index must be between 0 and {self.max_narms-1}") + + self.genome[arm_index] = np.nan + + def compact_genome(self) -> npt.NDArray[Any]: + """ + Get a compact representation with only valid arms. + + Returns: + Array containing only non-NaN arms + """ + return self.get_valid_arms() + + def __str__(self) -> str: + """String representation of the genome handler.""" + symmetry_str = f", symmetry={self.bilateral_plane_for_symmetry}" if self.bilateral_plane_for_symmetry else "" + return f"CartesianEulerDroneGenomeHandler(max_narms={self.max_narms}, shape={self.genome.shape}{symmetry_str})" + + def __repr__(self) -> str: + """Detailed string representation of the genome handler.""" + return (f"CartesianEulerDroneGenomeHandler(" + f"min_max_narms=({self.min_narms}, {self.max_narms}), " + f"append_arm_chance={self.append_arm_chance}, " + f"bilateral_plane_for_symmetry={self.bilateral_plane_for_symmetry}, " + f"repair={self.repair_enabled}, " + f"genome_shape={self.genome.shape})") \ No newline at end of file diff --git a/src/ariel/ec/drone/genome_handlers/conversions/__init__.py b/src/ariel/ec/drone/genome_handlers/conversions/__init__.py new file mode 100644 index 000000000..85e6a0a1b --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/conversions/__init__.py @@ -0,0 +1 @@ +# Coordinate system conversion utilities \ No newline at end of file diff --git a/src/ariel/ec/drone/genome_handlers/conversions/arm_conversions.py b/src/ariel/ec/drone/genome_handlers/conversions/arm_conversions.py new file mode 100644 index 000000000..922b77df2 --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/conversions/arm_conversions.py @@ -0,0 +1,547 @@ +import numpy as np +from scipy.spatial.transform import Rotation +from typing import Optional, Union, Dict, Any, Tuple, List +import numpy.typing as npt +from dataclasses import dataclass + +from ariel.ec.drone.genome_handlers.conversions.conversions import ( + spherical_to_cartesian, + cartesian_to_spherical, + euler_to_quaternion, + quaternion_to_euler, +) + +from ariel.ec.drone.inspection.utils import ( + create_rotation_matrix_quaternion +) + +@dataclass(frozen=True) +class Cylinder: + """Immutable cylinder representation for visualization and collision detection.""" + + radius: float + height: float + position: npt.NDArray[Any] + orientation: npt.NDArray[Any] # Quaternion [qw, qx, qy, qz] + + def __post_init__(self): + """Initialize computed properties after dataclass initialization.""" + # Convert to numpy arrays and freeze them + object.__setattr__(self, 'position', np.array(self.position, dtype=float)) + object.__setattr__(self, 'orientation', np.array(self.orientation, dtype=float)) + object.__setattr__(self, 'radius', float(self.radius)) + object.__setattr__(self, 'height', float(self.height)) + + # Create computed properties + rotation_matrix = create_rotation_matrix_quaternion(self.orientation) + transform = np.eye(4) + transform[:3, 3] = self.position + transform[:3, :3] = rotation_matrix + + object.__setattr__(self, 'rotation_matrix', rotation_matrix) + object.__setattr__(self, 'transform', transform) + + def get_endpoints(self) -> Tuple[npt.NDArray[Any], npt.NDArray[Any]]: + """Get the two endpoints of the cylinder axis. + + Returns: + Tuple of (endpoint1, endpoint2) arrays + """ + half_height = self.height / 2 + axis_vector = np.array([0, 0, half_height]) + endpoint1 = self.rotation_matrix @ axis_vector + self.position + endpoint2 = self.rotation_matrix @ -axis_vector + self.position + return endpoint1, endpoint2 + + def sample_points(self, num_points: int) -> npt.NDArray[Any]: + """Sample points along the cylinder axis. + + Args: + num_points: Number of points to sample + + Returns: + Array of sampled points + """ + endpoint1, endpoint2 = self.get_endpoints() + points = np.linspace(endpoint1, endpoint2, num_points) + return points + + def with_position(self, new_position: npt.NDArray[Any]) -> 'Cylinder': + """Create a new Cylinder instance with modified position. + + Args: + new_position: New position [x, y, z] + + Returns: + New Cylinder instance with updated position + """ + return Cylinder( + radius=self.radius, + height=self.height, + position=new_position, + orientation=self.orientation + ) + + def with_orientation(self, new_orientation: npt.NDArray[Any]) -> 'Cylinder': + """Create a new Cylinder instance with modified orientation. + + Args: + new_orientation: New orientation quaternion [qx, qy, qz, qw] + + Returns: + New Cylinder instance with updated orientation + """ + return Cylinder( + radius=self.radius, + height=self.height, + position=self.position, + orientation=new_orientation + ) + + def __repr__(self): + return (f"Cylinder(radius={self.radius}, height={self.height}, " + f"position={self.position.tolist()}, orientation={self.orientation.tolist()})") + +def spherical_angular_arms_to_cylinders(individual, propeller_radius, cylinder_height): + """ + Convert arms to cylinder representations using vectorized operations. + + Parameters: + - individual: numpy array of shape (N, 5) with columns [r, theta, phi, pitch, yaw] + - propeller_radius: float, radius of the propeller/cylinder + - cylinder_height: float, height of the cylinder + + Returns: + - List of cylinder dictionaries with keys: 'position', 'radius', 'height', 'orientation' + """ + cylinders = [] + + # Extract spherical coordinates (r, theta, phi) - shape (N, 3) + spherical_coordinates = individual[:, :3] + + # Vectorized conversion from spherical to Cartesian coordinates - shape (N, 3) + positions = spherical_to_cartesian(spherical_coordinates) + + # Extract pitch and yaw angles - shape (N, 2) + pitchs, yaws = individual[:, 3:5].T + + # Create Euler angles array with roll=0 - shape (N, 3) + euler_angles = np.column_stack([np.zeros(len(individual)), pitchs, yaws]) + + # Vectorized conversion from Euler angles to quaternions - shape (N, 4) + orientations = euler_to_quaternion(euler_angles) + + # Create 4x4 transformation matrix + # Convert quaternion to rotation matrix + + for i in range(len(individual)): + cylinders.append(Cylinder( + radius=propeller_radius, + height=cylinder_height, + position=positions[i], + orientation=orientations[i] + )) + return cylinders + + return cylinders + +def cylinders_to_spherical_angular_arms(cylinders): + """ + Convert cylinder representations back to arms using vectorized operations. + + Parameters: + - cylinders: list of cylinder dictionaries with keys: 'position', 'radius', 'height', 'orientation' + + Returns: + - numpy array of shape (N, 5) with columns [r, theta, phi, pitch, yaw] + """ + # Extract positions and orientations into arrays + positions = np.array([cyl.position for cyl in cylinders]) + orientations = np.array([cyl.orientation for cyl in cylinders]) + + # Vectorized conversion from Cartesian to spherical coordinates - shape (N, 3) + spherical_coordinates = cartesian_to_spherical(positions) + + # Vectorized conversion from quaternions to Euler angles - shape (N, 3) + euler_angles = quaternion_to_euler(orientations) + + # Extract pitch and yaw angles (ignore roll) - shape (N, 2) + motor_yaw_pitch = euler_angles[:, 1:3] # [pitch, yaw] + + # Combine spherical coordinates with motor angles - shape (N, 5) + arms_without_dir = np.hstack((spherical_coordinates, motor_yaw_pitch)) + + return arms_without_dir + +def spherical_angular_arms_to_cartesian_positions_and_quaternions(arms): + """ + Convert spherical angular arms to Cartesian positions and quaternions. + + Parameters: + - arms: numpy array of shape (N, 5) with columns [r, theta, phi, pitch, yaw] + + Returns: + - tuple: (positions, quaternions) where: + - positions: numpy array of shape (N, 3) with Cartesian coordinates [x, y, z] + - quaternions: numpy array of shape (N, 4) with quaternion components [w, x, y, z] + """ + # Extract spherical coordinates (r, theta, phi) - shape (N, 3) + spherical_coordinates = arms[:, :3] + + # Vectorized conversion from spherical to Cartesian coordinates - shape (N, 3) + positions = spherical_to_cartesian(spherical_coordinates) + + # Extract pitch and yaw angles - shape (N, 2) + pitchs, yaws = arms[:, 3:5].T + + # Create Euler angles array with roll=0 - shape (N, 3) + euler_angles = np.column_stack([np.zeros(len(arms)), pitchs, yaws]) + + # Vectorized conversion from Euler angles to quaternions - shape (N, 4) + quaternions = euler_to_quaternion(euler_angles) + + return positions, quaternions + +def cartesian_positions_and_quaternions_to_spherical_angular_arms(positions, quaternions): + """ + Convert Cartesian positions and quaternions to spherical angular arms. + + Parameters: + - positions: numpy array of shape (N, 3) with Cartesian coordinates [x, y, z] + - quaternions: numpy array of shape (N, 4) with quaternion components [w, x, y, z] + + Returns: + - numpy array of shape (N, 5) with columns [r, theta, phi, pitch, yaw] + """ + # Vectorized conversion from Cartesian to spherical coordinates - shape (N, 3) + spherical_coordinates = cartesian_to_spherical(positions) + + # Vectorized conversion from quaternions to Euler angles - shape (N, 3) + euler_angles = quaternion_to_euler(quaternions) + + # Extract pitch and yaw angles (ignore roll) - shape (N, 2) + motor_angles = euler_angles[:, 1:3] # [pitch, yaw] + + # Wrap motor angles to valid ranges for spherical coordinates + # pitch: Handle both positive and negative values to map to [0, π] + # For values outside [-π/2, π/2], use absolute value and wrap appropriately + pitch = motor_angles[:, 0] + + # Normalize pitch to [-π, π] range + # Use proper angle wrapping to maintain continuity + normalized_pitch = ((pitch + np.pi) % (2*np.pi)) - np.pi + motor_angles[:, 0] = normalized_pitch + + # yaw: normalize to [-π, π] range + normalized_yaw = ((motor_angles[:, 1] + np.pi) % (2*np.pi)) - np.pi + motor_angles[:, 1] = normalized_yaw + + # Combine spherical coordinates with motor angles - shape (N, 5) + arms = np.hstack((spherical_coordinates, motor_angles)) + + return arms + +# ============================================================================ +# UTILITY FUNCTIONS +# ============================================================================ + +def validate_arms_format(arms, expected_shape_cols=5): + """ + Validate that the arms array has the expected format. + + Parameters: + - arms: numpy array to validate + - expected_shape_cols: expected number of columns (default 5 for [r, theta, phi, pitch, yaw]) + + Returns: + - bool: True if valid format + + Raises: + - ValueError: If format is invalid + """ + arms = np.asarray(arms) + + if arms.ndim != 2: + raise ValueError(f"Arms array must be 2D, got {arms.ndim}D") + + if arms.shape[1] != expected_shape_cols: + raise ValueError(f"Arms array must have {expected_shape_cols} columns, got {arms.shape[1]}") + + # Check for valid spherical coordinates + r_values = arms[:, 0] + if np.any(r_values < 0): + raise ValueError("Radial distances (r) must be non-negative") + + theta_values = arms[:, 1] + if np.any(theta_values < -np.pi) or np.any(theta_values > np.pi): + raise ValueError("Azimuthal angles (theta) must be in range [-π, π]") + + phi_values = arms[:, 2] + if np.any(phi_values < -np.pi) or np.any(phi_values > np.pi): + raise ValueError("Polar angles (phi) must be in range [-π, π]") + + return True + +def create_arm_from_components(r, theta, phi, pitch, yaw): + """ + Create a single arm array from individual components. + + Parameters: + - r: radial distance + - theta: azimuthal angle + - phi: polar angle + - pitch: pitch angle + - yaw: yaw angle + + Returns: + - numpy array of shape (1, 5) + """ + return np.array([[r, theta, phi, pitch, yaw]]) + +def extract_arm_components(arms): + """ + Extract individual components from arms array. + + Parameters: + - arms: numpy array of shape (N, 5) + + Returns: + - tuple: (r, theta, phi, pitch, yaw) where each is a 1D array of length N + """ + arms = np.asarray(arms) + validate_arms_format(arms) + + return arms[:, 0], arms[:, 1], arms[:, 2], arms[:, 3], arms[:, 4] + +# ============================================================================ +# EXAMPLE USAGE AND TESTING +# ============================================================================ + +if __name__ == "__main__": + print("=== Enhanced Arm Conversions Testing ===") + + # Create test data: 3 arms with different configurations + test_arms = np.array([ + [1.0, 0.0, np.pi/2, 0.1, 0.0], # Arm 1: r=1, theta=0, phi=π/2, pitch=0.1, yaw=0 + [1.5, np.pi/2, np.pi/3, 0.0, 0.2], # Arm 2: r=1.5, theta=π/2, phi=π/3, pitch=0, yaw=0.2 + [2.0, np.pi, np.pi/4, -0.1, 0.5] # Arm 3: r=2, theta=π, phi=π/4, pitch=-0.1, yaw=0.5 + ]) + + print("Original arms (r, theta, phi, pitch, yaw):") + print(test_arms) + + # Test conversion to cylinders + print("\n--- Converting to Cylinders ---") + cylinders = spherical_angular_arms_to_cylinders(test_arms, propeller_radius=0.0254, cylinder_height=0.3048) + + print(f"Created {len(cylinders)} cylinders") + for i, cyl in enumerate(cylinders): + print(f"Cylinder {i+1}:") + print(f" Position: {cyl['position']}") + print(f" Orientation: {cyl['orientation']}") + print(f" Radius: {cyl['radius']}, Height: {cyl['height']}") + + # Test round-trip conversion + print("\n--- Round-trip Conversion Test ---") + arms_reconstructed = cylinders_to_spherical_angular_arms(cylinders) + print("Reconstructed arms:") + print(arms_reconstructed) + + print("Difference from original:") + print(np.abs(test_arms - arms_reconstructed)) + print(f"Max difference: {np.max(np.abs(test_arms - arms_reconstructed)):.6f}") + + # Test Cartesian position and quaternion conversion + print("\n--- Cartesian Position and Quaternion Conversion ---") + positions, quaternions = spherical_angular_arms_to_cartesian_positions_and_quaternions(test_arms) + print("Positions:") + print(positions) + print("Quaternions:") + print(quaternions) + + # Test reverse conversion + print("\n--- Reverse Cartesian Conversion ---") + arms_from_cart = cartesian_positions_and_quaternions_to_spherical_angular_arms(positions, quaternions) + print("Arms from Cartesian:") + print(arms_from_cart) + + print("Difference from original:") + print(np.abs(test_arms - arms_from_cart)) + print(f"Max difference: {np.max(np.abs(test_arms - arms_from_cart)):.6f}") + + # Test validation + print("\n--- Validation Test ---") + try: + validate_arms_format(test_arms) + print("✓ Arms format validation passed") + except ValueError as e: + print(f"✗ Validation failed: {e}") + + # Test utility functions + print("\n--- Utility Functions Test ---") + single_arm = create_arm_from_components(1.0, 0.5, 1.0, 0.1, 0.2) + print(f"Single arm created: {single_arm}") + + r, theta, phi, pitch, yaw = extract_arm_components(test_arms) + print(f"Extracted components:") + print(f" r: {r}") + print(f" theta: {theta}") + print(f" phi: {phi}") + print(f" pitch: {pitch}") + print(f" yaw: {yaw}") + + print("\n=== All tests completed ===") + +# ============================================================================ +# CARTESIAN EULER GENOME CONVERSIONS +# ============================================================================ + +def cartesian_euler_arms_to_cylinders(individual, propeller_radius, cylinder_height): + """ + Convert Cartesian Euler arms to cylinder representations using vectorized operations. + + Parameters: + - individual: numpy array of shape (N, 7) with columns [x, y, z, roll, pitch, yaw, direction] + - propeller_radius: float, radius of the propeller/cylinder + - cylinder_height: float, height of the cylinder + + Returns: + - List of Cylinder instances + """ + cylinders = [] + + # Extract Cartesian positions (x, y, z) - shape (N, 3) + positions = individual[:, :3] + + # Extract Euler angles (roll, pitch, yaw) - shape (N, 3) + euler_angles = individual[:, 3:6] + + # Vectorized conversion from Euler angles to quaternions - shape (N, 4) + orientations = euler_to_quaternion(euler_angles) + + # Create Cylinder instances + for i in range(len(individual)): + # Create 4x4 transformation matrix + # First create rotation matrix from quaternion + qw, qx, qy, qz = orientations[i] + + # Convert quaternion to rotation matrix + rot_matrix = np.array([ + [1 - 2*(qy**2 + qz**2), 2*(qx*qy - qw*qz), 2*(qx*qz + qw*qy)], + [2*(qx*qy + qw*qz), 1 - 2*(qx**2 + qz**2), 2*(qy*qz - qw*qx)], + [2*(qx*qz - qw*qy), 2*(qy*qz + qw*qx), 1 - 2*(qx**2 + qy**2)] + ]) + + # Create 4x4 transformation matrix + transform = np.eye(4) + transform[:3, :3] = rot_matrix + transform[:3, 3] = positions[i] + + # Create Cylinder instance + cylinder = Cylinder( + position=positions[i], + radius=propeller_radius, + height=cylinder_height, + orientation=orientations[i], # quaternion [w, x, y, z] + ) + cylinders.append(cylinder) + + return cylinders + +def cylinders_to_cartesian_euler_arms(cylinders): + """ + Convert Cylinder instances back to Cartesian Euler arms using vectorized operations. + + Parameters: + - cylinders: list of Cylinder instances + + Returns: + - numpy array of shape (N, 6) with columns [x, y, z, roll, pitch, yaw] (without direction) + """ + # Extract positions and orientations into arrays + positions = np.array([cylinder.position for cylinder in cylinders]) + orientations = np.array([cylinder.orientation for cylinder in cylinders]) + + # Vectorized conversion from quaternions to Euler angles - shape (N, 3) + euler_angles = quaternion_to_euler(orientations) + + # Combine Cartesian positions with Euler angles - shape (N, 6) + arms_without_dir = np.hstack((positions, euler_angles)) + + return arms_without_dir + +def cartesian_euler_arms_to_cartesian_positions_and_quaternions(arms): + """ + Convert Cartesian Euler arms to Cartesian positions and quaternions. + + Parameters: + - arms: numpy array of shape (N, 7) with columns [x, y, z, roll, pitch, yaw, direction] + + Returns: + - tuple: (positions, quaternions) where: + - positions: numpy array of shape (N, 3) with Cartesian coordinates [x, y, z] + - quaternions: numpy array of shape (N, 4) with quaternion components [w, x, y, z] + """ + # Extract Cartesian positions (x, y, z) - shape (N, 3) + positions = arms[:, :3] + + # Extract Euler angles (roll, pitch, yaw) - shape (N, 3) + euler_angles = arms[:, 3:6] + + # Vectorized conversion from Euler angles to quaternions - shape (N, 4) + quaternions = euler_to_quaternion(euler_angles) + + return positions, quaternions + +def cartesian_positions_and_quaternions_to_cartesian_euler_arms(positions, quaternions): + """ + Convert Cartesian positions and quaternions to Cartesian Euler arms. + + Parameters: + - positions: numpy array of shape (N, 3) with Cartesian coordinates [x, y, z] + - quaternions: numpy array of shape (N, 4) with quaternion components [w, x, y, z] + + Returns: + - numpy array of shape (N, 6) with columns [x, y, z, roll, pitch, yaw] (without direction) + """ + # Vectorized conversion from quaternions to Euler angles - shape (N, 3) + euler_angles = quaternion_to_euler(quaternions) + + # Combine Cartesian positions with Euler angles - shape (N, 6) + arms = np.hstack((positions, euler_angles)) + + return arms + +# ============================================================================ +# ALIAS FUNCTIONS FOR BACKWARD COMPATIBILITY +# ============================================================================ + +# Create aliases that match the existing pattern used in particle_repair_operator.py +def arms_to_cylinders_cartesian_euler(individual, propeller_radius=0.0254, cylinder_height=None): + """Alias for cartesian_euler_arms_to_cylinders with default parameters.""" + if cylinder_height is None: + cylinder_height = 8 * propeller_radius + valid_arms = ~np.isnan(individual).any(axis=-1) + if not np.any(valid_arms): + return [] + valid_arm_params = individual[valid_arms] + return cartesian_euler_arms_to_cylinders(valid_arm_params, propeller_radius, cylinder_height) + +def cylinders_to_arms_cartesian_euler(cylinders): + """Alias for cylinders_to_cartesian_euler_arms.""" + return cylinders_to_cartesian_euler_arms(cylinders) + +# Create aliases that match the existing pattern used in particle_repair_operator.py for polar angular +def arms_to_cylinders_polar_angular(individual, propeller_radius=0.0254, cylinder_height=None): + """Alias for spherical_angular_arms_to_cylinders with default parameters.""" + if cylinder_height is None: + cylinder_height = 8 * propeller_radius + valid_arms = ~np.isnan(individual).any(axis=-1) + if not np.any(valid_arms): + return [] + valid_arm_params = individual[valid_arms] + return spherical_angular_arms_to_cylinders(valid_arm_params, propeller_radius, cylinder_height) + +def cylinders_to_arms_polar_angular(cylinders): + """Alias for cylinders_to_spherical_angular_arms.""" + return cylinders_to_spherical_angular_arms(cylinders) \ No newline at end of file diff --git a/src/ariel/ec/drone/genome_handlers/conversions/conversions.py b/src/ariel/ec/drone/genome_handlers/conversions/conversions.py new file mode 100644 index 000000000..0e4dd6352 --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/conversions/conversions.py @@ -0,0 +1,756 @@ +import numpy as np +import math + +# ============================================================================ +# COORDINATE SYSTEM CONVERSIONS +# ============================================================================ + +def cartesian_to_spherical(x, y=None, z=None): + """ + Convert Cartesian coordinates to spherical coordinates. + + Args: + x: Either x-coordinate (scalar) or array of coordinates + y: y-coordinate (if x is scalar) + z: z-coordinate (if x is scalar) + + Array formats: + - 1D array: [x, y, z] + - 2D array: [[x1,y1,z1], [x2,y2,z2], ...] shape (N, 3) + + Returns: + tuple or numpy.ndarray: + - If scalar input: (r, theta, phi) + - If array input: array of shape (N, 3) with columns [r, theta, phi] + """ + # Handle array inputs + if y is None and z is None: + coords = np.asarray(x) + if coords.ndim == 1: + # 1D array case + x, y, z = coords[0], coords[1], coords[2] + elif coords.ndim == 2: + # 2D array case - vectorized computation + x_arr, y_arr, z_arr = coords[:, 0], coords[:, 1], coords[:, 2] + r = np.sqrt(x_arr**2 + y_arr**2 + z_arr**2) + theta = np.arctan2(y_arr, x_arr) + # Keep theta in [-π, π] range (arctan2 already provides this) + phi = np.where(r > 0, np.arccos(z_arr / r), 0) + return np.column_stack([r, theta, phi]) + else: + raise ValueError("Input array must be 1D or 2D") + + # Scalar computation + r = math.sqrt(x**2 + y**2 + z**2) + theta = math.atan2(y, x) + # Keep theta in [-π, π] range (atan2 already provides this) + phi = math.acos(z / r) if r > 0 else 0 + return r, theta, phi + +def spherical_to_cartesian(r, theta=None, phi=None): + """ + Convert spherical coordinates to Cartesian coordinates. + + Args: + r: Either radial distance (scalar) or array of coordinates + theta: azimuthal angle in radians (if r is scalar) + phi: polar angle in radians (if r is scalar) + + Array formats: + - 1D array: [r, theta, phi] + - 2D array: [[r1,theta1,phi1], [r2,theta2,phi2], ...] shape (N, 3) + + Returns: + tuple or numpy.ndarray: + - If scalar input: (x, y, z) + - If array input: array of shape (N, 3) with columns [x, y, z] + """ + # Handle array inputs + if theta is None and phi is None: + coords = np.asarray(r) + if coords.ndim == 1: + # 1D array case + r, theta, phi = coords[0], coords[1], coords[2] + elif coords.ndim == 2: + # 2D array case - vectorized computation + r_arr, theta_arr, phi_arr = coords[:, 0], coords[:, 1], coords[:, 2] + x = r_arr * np.sin(phi_arr) * np.cos(theta_arr) + y = r_arr * np.sin(phi_arr) * np.sin(theta_arr) + z = r_arr * np.cos(phi_arr) + return np.column_stack([x, y, z]) + else: + raise ValueError("Input array must be 1D or 2D") + + # Scalar computation + x = r * math.sin(phi) * math.cos(theta) + y = r * math.sin(phi) * math.sin(theta) + z = r * math.cos(phi) + return x, y, z + +# ============================================================================ +# ROTATION CONVERSIONS +# ============================================================================ + +def spherical_to_quaternion(theta, phi=None): + """ + Convert spherical coordinates to quaternion (assuming theta is yaw, phi is pitch). + + Args: + theta: Either azimuthal angle (scalar) or array of coordinates + phi: polar angle in radians (if theta is scalar) + + Array formats: + - 1D array: [theta, phi] + - 2D array: [[theta1,phi1], [theta2,phi2], ...] shape (N, 2) + + Returns: + tuple or numpy.ndarray: + - If scalar input: (w, x, y, z) + - If array input: array of shape (N, 4) with columns [w, x, y, z] + """ + # Handle array inputs + if phi is None: + coords = np.asarray(theta) + if coords.ndim == 1: + # 1D array case + theta, phi = coords[0], coords[1] + elif coords.ndim == 2: + # 2D array case - vectorized computation + theta_arr, phi_arr = coords[:, 0], coords[:, 1] + cy = np.cos(theta_arr * 0.5) + sy = np.sin(theta_arr * 0.5) + cp = np.cos(phi_arr * 0.5) + sp = np.sin(phi_arr * 0.5) + + w = cy * cp + x = cy * sp + y = sy * cp + z = sy * sp + + return np.column_stack([w, x, y, z]) + else: + raise ValueError("Input array must be 1D or 2D") + + # Scalar computation + cy = math.cos(theta * 0.5) + sy = math.sin(theta * 0.5) + cp = math.cos(phi * 0.5) + sp = math.sin(phi * 0.5) + + w = cy * cp + x = cy * sp + y = sy * cp + z = sy * sp + + return w, x, y, z + +def quaternion_to_spherical(w, x=None, y=None, z=None): + """ + Convert quaternion to spherical coordinates (assuming quaternion represents yaw and pitch). + + Args: + w: Either w component (scalar) or array of quaternions + x, y, z: quaternion components (if w is scalar) + + Array formats: + - 1D array: [w, x, y, z] + - 2D array: [[w1,x1,y1,z1], [w2,x2,y2,z2], ...] shape (N, 4) + + Returns: + tuple or numpy.ndarray: + - If scalar input: (theta, phi) + - If array input: array of shape (N, 2) with columns [theta, phi] + """ + # Handle array inputs + if x is None and y is None and z is None: + coords = np.asarray(w) + if coords.ndim == 1: + # 1D array case + w, x, y, z = coords[0], coords[1], coords[2], coords[3] + elif coords.ndim == 2: + # 2D array case - vectorized computation + w_arr, x_arr, y_arr, z_arr = coords[:, 0], coords[:, 1], coords[:, 2], coords[:, 3] + # Normalize quaternions + norm = np.sqrt(w_arr**2 + x_arr**2 + y_arr**2 + z_arr**2) + w_arr, x_arr, y_arr, z_arr = w_arr/norm, x_arr/norm, y_arr/norm, z_arr/norm + + # Calculate yaw (theta) + theta = np.arctan2(2 * (w_arr * z_arr + x_arr * y_arr), 1 - 2 * (y_arr**2 + z_arr**2)) + + # Calculate pitch (phi) + phi = np.arcsin(2 * (w_arr * y_arr - z_arr * x_arr)) + + return np.column_stack([theta, phi]) + else: + raise ValueError("Input array must be 1D or 2D") + + # Scalar computation + # Normalize quaternion + norm = math.sqrt(w*w + x*x + y*y + z*z) + w, x, y, z = w/norm, x/norm, y/norm, z/norm + + # Calculate yaw (theta) + theta = math.atan2(2 * (w * z + x * y), 1 - 2 * (y * y + z * z)) + + # Calculate pitch (phi) + phi = math.asin(2 * (w * y - z * x)) + + return theta, phi + +def euler_to_quaternion(roll, pitch=None, yaw=None): + """ + Convert Euler angles to quaternion (ZYX rotation order). + + Args: + roll: Either roll angle (scalar) or array of Euler angles + pitch: pitch angle (if roll is scalar) + yaw: yaw angle (if roll is scalar) + + Array formats: + - 1D array: [roll, pitch, yaw] + - 2D array: [[roll1,pitch1,yaw1], [roll2,pitch2,yaw2], ...] shape (N, 3) + + Returns: + tuple or numpy.ndarray: + - If scalar input: (w, x, y, z) + - If array input: array of shape (N, 4) with columns [w, x, y, z] + """ + # Handle array inputs + if pitch is None and yaw is None: + coords = np.asarray(roll) + if coords.ndim == 1: + # 1D array case + roll, pitch, yaw = coords[0], coords[1], coords[2] + elif coords.ndim == 2: + # 2D array case - vectorized computation + roll_arr, pitch_arr, yaw_arr = coords[:, 0], coords[:, 1], coords[:, 2] + cr = np.cos(roll_arr * 0.5) + sr = np.sin(roll_arr * 0.5) + cp = np.cos(pitch_arr * 0.5) + sp = np.sin(pitch_arr * 0.5) + cy = np.cos(yaw_arr * 0.5) + sy = np.sin(yaw_arr * 0.5) + + w = cr * cp * cy + sr * sp * sy + x = sr * cp * cy - cr * sp * sy + y = cr * sp * cy + sr * cp * sy + z = cr * cp * sy - sr * sp * cy + + return np.column_stack([w, x, y, z]) + else: + raise ValueError("Input array must be 1D or 2D") + + # Scalar computation + cr = math.cos(roll * 0.5) + sr = math.sin(roll * 0.5) + cp = math.cos(pitch * 0.5) + sp = math.sin(pitch * 0.5) + cy = math.cos(yaw * 0.5) + sy = math.sin(yaw * 0.5) + + w = cr * cp * cy + sr * sp * sy + x = sr * cp * cy - cr * sp * sy + y = cr * sp * cy + sr * cp * sy + z = cr * cp * sy - sr * sp * cy + + return w, x, y, z + +def quaternion_to_euler(w, x=None, y=None, z=None): + """ + Convert quaternion to Euler angles (ZYX rotation order). + + Args: + w: Either w component (scalar) or array of quaternions + x, y, z: quaternion components (if w is scalar) + + Array formats: + - 1D array: [w, x, y, z] + - 2D array: [[w1,x1,y1,z1], [w2,x2,y2,z2], ...] shape (N, 4) + + Returns: + tuple or numpy.ndarray: + - If scalar input: (roll, pitch, yaw) + - If array input: array of shape (N, 3) with columns [roll, pitch, yaw] + """ + # Handle array inputs + if x is None and y is None and z is None: + coords = np.asarray(w) + if coords.ndim == 1: + # 1D array case + w, x, y, z = coords[0], coords[1], coords[2], coords[3] + elif coords.ndim == 2: + # 2D array case - vectorized computation + w_arr, x_arr, y_arr, z_arr = coords[:, 0], coords[:, 1], coords[:, 2], coords[:, 3] + + # Roll (x-axis rotation) + sinr_cosp = 2 * (w_arr * x_arr + y_arr * z_arr) + cosr_cosp = 1 - 2 * (x_arr**2 + y_arr**2) + roll = np.arctan2(sinr_cosp, cosr_cosp) + + # Pitch (y-axis rotation) + sinp = 2 * (w_arr * y_arr - z_arr * x_arr) + pitch = np.where(np.abs(sinp) >= 1, np.copysign(np.pi / 2, sinp), np.arcsin(sinp)) + + # Yaw (z-axis rotation) + siny_cosp = 2 * (w_arr * z_arr + x_arr * y_arr) + cosy_cosp = 1 - 2 * (y_arr**2 + z_arr**2) + yaw = np.arctan2(siny_cosp, cosy_cosp) + + return np.column_stack([roll, pitch, yaw]) + else: + raise ValueError("Input array must be 1D or 2D") + + # Scalar computation + # Roll (x-axis rotation) + sinr_cosp = 2 * (w * x + y * z) + cosr_cosp = 1 - 2 * (x * x + y * y) + roll = math.atan2(sinr_cosp, cosr_cosp) + + # Pitch (y-axis rotation) + sinp = 2 * (w * y - z * x) + if abs(sinp) >= 1: + pitch = math.copysign(math.pi / 2, sinp) # Use 90 degrees if out of range + else: + pitch = math.asin(sinp) + + # Yaw (z-axis rotation) + siny_cosp = 2 * (w * z + x * y) + cosy_cosp = 1 - 2 * (y * y + z * z) + yaw = math.atan2(siny_cosp, cosy_cosp) + + return roll, pitch, yaw + +def quaternion_to_rotation_matrix(w, x=None, y=None, z=None): + """ + Convert quaternion to 3x3 rotation matrix. + + Args: + w: Either w component (scalar) or array of quaternions + x, y, z: quaternion components (if w is scalar) + + Array formats: + - 1D array: [w, x, y, z] + - 2D array: [[w1,x1,y1,z1], [w2,x2,y2,z2], ...] shape (N, 4) + + Returns: + numpy.ndarray: + - If scalar input: 3x3 rotation matrix + - If array input: array of shape (N, 3, 3) with rotation matrices + """ + # Handle array inputs + if x is None and y is None and z is None: + coords = np.asarray(w) + if coords.ndim == 1: + # 1D array case + w, x, y, z = coords[0], coords[1], coords[2], coords[3] + elif coords.ndim == 2: + # 2D array case - vectorized computation + w_arr, x_arr, y_arr, z_arr = coords[:, 0], coords[:, 1], coords[:, 2], coords[:, 3] + # Normalize quaternions + norm = np.sqrt(w_arr**2 + x_arr**2 + y_arr**2 + z_arr**2) + w_arr, x_arr, y_arr, z_arr = w_arr/norm, x_arr/norm, y_arr/norm, z_arr/norm + + # Create rotation matrices + R = np.zeros((len(coords), 3, 3)) + R[:, 0, 0] = 1 - 2*(y_arr**2 + z_arr**2) + R[:, 0, 1] = 2*(x_arr*y_arr - w_arr*z_arr) + R[:, 0, 2] = 2*(x_arr*z_arr + w_arr*y_arr) + R[:, 1, 0] = 2*(x_arr*y_arr + w_arr*z_arr) + R[:, 1, 1] = 1 - 2*(x_arr**2 + z_arr**2) + R[:, 1, 2] = 2*(y_arr*z_arr - w_arr*x_arr) + R[:, 2, 0] = 2*(x_arr*z_arr - w_arr*y_arr) + R[:, 2, 1] = 2*(y_arr*z_arr + w_arr*x_arr) + R[:, 2, 2] = 1 - 2*(x_arr**2 + y_arr**2) + + return R + else: + raise ValueError("Input array must be 1D or 2D") + + # Scalar computation + # Normalize quaternion + norm = math.sqrt(w*w + x*x + y*y + z*z) + w, x, y, z = w/norm, x/norm, y/norm, z/norm + + R = np.array([ + [1 - 2*(y*y + z*z), 2*(x*y - w*z), 2*(x*z + w*y)], + [2*(x*y + w*z), 1 - 2*(x*x + z*z), 2*(y*z - w*x)], + [2*(x*z - w*y), 2*(y*z + w*x), 1 - 2*(x*x + y*y)] + ]) + + return R + +def euler_to_unit_vector(roll, pitch=None, yaw=None): + """ + Convert Euler angles to unit vector pointing in the direction of rotation. + + Args: + roll: Either roll angle (scalar) or array of Euler angles + pitch: pitch angle (if roll is scalar) + yaw: yaw angle (if roll is scalar) + + Array formats: + - 1D array: [roll, pitch, yaw] + - 2D array: [[roll1,pitch1,yaw1], [roll2,pitch2,yaw2], ...] shape (N, 3) + + Returns: + tuple or numpy.ndarray: + - If scalar input: (x, y, z) + - If array input: array of shape (N, 3) with columns [x, y, z] + """ + # Handle array inputs + if pitch is None and yaw is None: + coords = np.asarray(roll) + if coords.ndim == 1: + # 1D array case + roll, pitch, yaw = coords[0], coords[1], coords[2] + elif coords.ndim == 2: + # 2D array case - vectorized computation + roll_arr, pitch_arr, yaw_arr = coords[:, 0], coords[:, 1], coords[:, 2] + # Apply rotations to the initial forward vector [1, 0, 0] + x = np.cos(pitch_arr) * np.cos(yaw_arr) + y = np.cos(pitch_arr) * np.sin(yaw_arr) + z = -np.sin(pitch_arr) + + return np.column_stack([x, y, z]) + else: + raise ValueError("Input array must be 1D or 2D") + + # Scalar computation + # Apply rotations to the initial forward vector [1, 0, 0] + x = math.cos(pitch) * math.cos(yaw) + y = math.cos(pitch) * math.sin(yaw) + z = -math.sin(pitch) + + return x, y, z + +def unit_vector_to_euler(x, y=None, z=None): + """ + Convert unit vector to Euler angles. + + Args: + x: Either x component (scalar) or array of vectors + y, z: vector components (if x is scalar) + + Array formats: + - 1D array: [x, y, z] + - 2D array: [[x1,y1,z1], [x2,y2,z2], ...] shape (N, 3) + + Returns: + tuple or numpy.ndarray: + - If scalar input: (roll, pitch, yaw) + - If array input: array of shape (N, 3) with columns [roll, pitch, yaw] + """ + # Handle array inputs + if y is None and z is None: + coords = np.asarray(x) + if coords.ndim == 1: + # 1D array case + x, y, z = coords[0], coords[1], coords[2] + elif coords.ndim == 2: + # 2D array case - vectorized computation + x_arr, y_arr, z_arr = coords[:, 0], coords[:, 1], coords[:, 2] + # Normalize the vectors + norm = np.sqrt(x_arr**2 + y_arr**2 + z_arr**2) + mask = norm > 0 + x_arr = np.where(mask, x_arr/norm, 0) + y_arr = np.where(mask, y_arr/norm, 0) + z_arr = np.where(mask, z_arr/norm, 0) + + # Calculate pitch and yaw from the vector + pitch = -np.arcsin(z_arr) + yaw = np.arctan2(y_arr, x_arr) + + # Roll cannot be determined from direction vector alone + # Set to 0 as a convention + roll = np.zeros_like(pitch) + + return np.column_stack([roll, pitch, yaw]) + else: + raise ValueError("Input array must be 1D or 2D") + + # Scalar computation + # Normalize the vector + norm = math.sqrt(x*x + y*y + z*z) + if norm == 0: + return 0, 0, 0 + x, y, z = x/norm, y/norm, z/norm + + # Calculate pitch and yaw from the vector + pitch = -math.asin(z) + yaw = math.atan2(y, x) + + # Roll cannot be determined from direction vector alone + # Set to 0 as a convention + roll = 0 + + return roll, pitch, yaw + +# ============================================================================ +# COORDINATE FRAME CONVERSIONS (NED <-> ENU) +# ============================================================================ + +def ned_to_enu_coordinates(x_ned, y_ned=None, z_ned=None): + """ + Convert coordinates from NED (North-East-Down) to ENU (East-North-Up). + + Args: + x_ned: Either x coordinate (scalar) or array of coordinates + y_ned, z_ned: coordinates (if x_ned is scalar) + + Array formats: + - 1D array: [x_ned, y_ned, z_ned] + - 2D array: [[x1,y1,z1], [x2,y2,z2], ...] shape (N, 3) + + Returns: + tuple or numpy.ndarray: + - If scalar input: (x_enu, y_enu, z_enu) + - If array input: array of shape (N, 3) with columns [x_enu, y_enu, z_enu] + """ + # Handle array inputs + if y_ned is None and z_ned is None: + coords = np.asarray(x_ned) + if coords.ndim == 1: + # 1D array case + x_ned, y_ned, z_ned = coords[0], coords[1], coords[2] + elif coords.ndim == 2: + # 2D array case - vectorized computation + x_ned_arr, y_ned_arr, z_ned_arr = coords[:, 0], coords[:, 1], coords[:, 2] + x_enu = y_ned_arr # East = North_NED + y_enu = x_ned_arr # North = East_NED + z_enu = -z_ned_arr # Up = -Down_NED + + return np.column_stack([x_enu, y_enu, z_enu]) + else: + raise ValueError("Input array must be 1D or 2D") + + # Scalar computation + x_enu = y_ned # East = North_NED + y_enu = x_ned # North = East_NED + z_enu = -z_ned # Up = -Down_NED + + return x_enu, y_enu, z_enu + +def enu_to_ned_coordinates(x_enu, y_enu=None, z_enu=None): + """ + Convert coordinates from ENU (East-North-Up) to NED (North-East-Down). + + Args: + x_enu: Either x coordinate (scalar) or array of coordinates + y_enu, z_enu: coordinates (if x_enu is scalar) + + Array formats: + - 1D array: [x_enu, y_enu, z_enu] + - 2D array: [[x1,y1,z1], [x2,y2,z2], ...] shape (N, 3) + + Returns: + tuple or numpy.ndarray: + - If scalar input: (x_ned, y_ned, z_ned) + - If array input: array of shape (N, 3) with columns [x_ned, y_ned, z_ned] + """ + # Handle array inputs + if y_enu is None and z_enu is None: + coords = np.asarray(x_enu) + if coords.ndim == 1: + # 1D array case + x_enu, y_enu, z_enu = coords[0], coords[1], coords[2] + elif coords.ndim == 2: + # 2D array case - vectorized computation + x_enu_arr, y_enu_arr, z_enu_arr = coords[:, 0], coords[:, 1], coords[:, 2] + x_ned = y_enu_arr # North = North_ENU + y_ned = x_enu_arr # East = East_ENU + z_ned = -z_enu_arr # Down = -Up_ENU + + return np.column_stack([x_ned, y_ned, z_ned]) + else: + raise ValueError("Input array must be 1D or 2D") + + # Scalar computation + x_ned = y_enu # North = North_ENU + y_ned = x_enu # East = East_ENU + z_ned = -z_enu # Down = -Up_ENU + + return x_ned, y_ned, z_ned + +def ned_to_enu_euler(roll_ned, pitch_ned=None, yaw_ned=None): + """ + Convert Euler angles from NED to ENU frame. + + Args: + roll_ned: Either roll angle (scalar) or array of Euler angles + pitch_ned, yaw_ned: Euler angles (if roll_ned is scalar) + + Array formats: + - 1D array: [roll_ned, pitch_ned, yaw_ned] + - 2D array: [[roll1,pitch1,yaw1], [roll2,pitch2,yaw2], ...] shape (N, 3) + + Returns: + tuple or numpy.ndarray: + - If scalar input: (roll_enu, pitch_enu, yaw_enu) + - If array input: array of shape (N, 3) with columns [roll_enu, pitch_enu, yaw_enu] + """ + # Handle array inputs + if pitch_ned is None and yaw_ned is None: + coords = np.asarray(roll_ned) + if coords.ndim == 1: + # 1D array case + roll_ned, pitch_ned, yaw_ned = coords[0], coords[1], coords[2] + elif coords.ndim == 2: + # 2D array case - vectorized computation + roll_ned_arr, pitch_ned_arr, yaw_ned_arr = coords[:, 0], coords[:, 1], coords[:, 2] + roll_enu = pitch_ned_arr # Roll_ENU = Pitch_NED + pitch_enu = roll_ned_arr # Pitch_ENU = Roll_NED + yaw_enu = -yaw_ned_arr + math.pi/2 # Yaw_ENU = -Yaw_NED + 90° + + # Normalize yaw to [-π, π] + yaw_enu = np.where(yaw_enu > math.pi, yaw_enu - 2*math.pi, yaw_enu) + yaw_enu = np.where(yaw_enu < -math.pi, yaw_enu + 2*math.pi, yaw_enu) + + return np.column_stack([roll_enu, pitch_enu, yaw_enu]) + else: + raise ValueError("Input array must be 1D or 2D") + + # Scalar computation + roll_enu = pitch_ned # Roll_ENU = Pitch_NED + pitch_enu = roll_ned # Pitch_ENU = Roll_NED + yaw_enu = -yaw_ned + math.pi/2 # Yaw_ENU = -Yaw_NED + 90° + + # Normalize yaw to [-π, π] + while yaw_enu > math.pi: + yaw_enu -= 2 * math.pi + while yaw_enu < -math.pi: + yaw_enu += 2 * math.pi + + return roll_enu, pitch_enu, yaw_enu + +def enu_to_ned_euler(roll_enu, pitch_enu=None, yaw_enu=None): + """ + Convert Euler angles from ENU to NED frame. + + Args: + roll_enu: Either roll angle (scalar) or array of Euler angles + pitch_enu, yaw_enu: Euler angles (if roll_enu is scalar) + + Array formats: + - 1D array: [roll_enu, pitch_enu, yaw_enu] + - 2D array: [[roll1,pitch1,yaw1], [roll2,pitch2,yaw2], ...] shape (N, 3) + + Returns: + tuple or numpy.ndarray: + - If scalar input: (roll_ned, pitch_ned, yaw_ned) + - If array input: array of shape (N, 3) with columns [roll_ned, pitch_ned, yaw_ned] + """ + # Handle array inputs + if pitch_enu is None and yaw_enu is None: + coords = np.asarray(roll_enu) + if coords.ndim == 1: + # 1D array case + roll_enu, pitch_enu, yaw_enu = coords[0], coords[1], coords[2] + elif coords.ndim == 2: + # 2D array case - vectorized computation + roll_enu_arr, pitch_enu_arr, yaw_enu_arr = coords[:, 0], coords[:, 1], coords[:, 2] + roll_ned = pitch_enu_arr # Roll_NED = Pitch_ENU + pitch_ned = roll_enu_arr # Pitch_NED = Roll_ENU + yaw_ned = -(yaw_enu_arr - math.pi/2) # Yaw_NED = -(Yaw_ENU - 90°) + + # Normalize yaw to [-π, π] + yaw_ned = np.where(yaw_ned > math.pi, yaw_ned - 2*math.pi, yaw_ned) + yaw_ned = np.where(yaw_ned < -math.pi, yaw_ned + 2*math.pi, yaw_ned) + + return np.column_stack([roll_ned, pitch_ned, yaw_ned]) + else: + raise ValueError("Input array must be 1D or 2D") + + # Scalar computation + roll_ned = pitch_enu # Roll_NED = Pitch_ENU + pitch_ned = roll_enu # Pitch_NED = Roll_ENU + yaw_ned = -(yaw_enu - math.pi/2) # Yaw_NED = -(Yaw_ENU - 90°) + + # Normalize yaw to [-π, π] + while yaw_ned > math.pi: + yaw_ned -= 2 * math.pi + while yaw_ned < -math.pi: + yaw_ned += 2 * math.pi + + return roll_ned, pitch_ned, yaw_ned + +# ============================================================================ +# EXAMPLE USAGE AND TESTING +# ============================================================================ + +if __name__ == "__main__": + print("=== Enhanced Coordinate Conversions with Array Support ===") + + # Test scalar inputs (original functionality) + print("\n--- Scalar Input Tests ---") + x, y, z = 1, 1, 1 + r, theta, phi = cartesian_to_spherical(x, y, z) + print(f"Cartesian ({x}, {y}, {z}) -> Spherical ({r:.3f}, {theta:.3f}, {phi:.3f})") + + # Test 1D array inputs + print("\n--- 1D Array Input Tests ---") + cartesian_1d = [1, 1, 1] + spherical_result = cartesian_to_spherical(cartesian_1d) + print(f"1D Array {cartesian_1d} -> Spherical {spherical_result}") + + # Test 2D array inputs (batch processing) + print("\n--- 2D Array Input Tests (Batch Processing) ---") + cartesian_batch = np.array([[1, 1, 1], [2, 0, 0], [0, 3, 4]]) + spherical_batch = cartesian_to_spherical(cartesian_batch) + print(f"Batch Cartesian:\n{cartesian_batch}") + print(f"Batch Spherical:\n{spherical_batch}") + + # Test round-trip conversion + cartesian_roundtrip = spherical_to_cartesian(spherical_batch) + print(f"Round-trip back to Cartesian:\n{cartesian_roundtrip}") + + # Test Euler to Quaternion batch conversion + print("\n--- Euler to Quaternion Batch Test ---") + euler_batch = np.array([[0.1, 0.2, 0.3], [0.5, 0.0, 1.0], [1.57, 0.78, 2.35]]) + quat_batch = euler_to_quaternion(euler_batch) + print(f"Batch Euler:\n{euler_batch}") + print(f"Batch Quaternion:\n{quat_batch}") + + # Test rotation matrix batch conversion + print("\n--- Quaternion to Rotation Matrix Batch Test ---") + rotation_matrices = quaternion_to_rotation_matrix(quat_batch) + print(f"Batch Rotation Matrices shape: {rotation_matrices.shape}") + print(f"First rotation matrix:\n{rotation_matrices[0]}") + + # Test NED/ENU frame conversions + print("\n--- Frame Conversion Tests ---") + ned_coords = np.array([[1, 2, 3], [4, 5, 6]]) + enu_coords = ned_to_enu_coordinates(ned_coords) + print(f"NED coordinates:\n{ned_coords}") + print(f"ENU coordinates:\n{enu_coords}") + + # Performance comparison example + print("\n--- Performance Test Setup ---") + print("For large datasets, vectorized operations will be significantly faster.") + print("Example: Converting 1000 coordinate sets at once vs. one by one.") + + # Generate test data + np.random.seed(42) + large_batch = np.random.rand(1000, 3) * 10 + + import time + + # Time the vectorized approach + start_time = time.time() + result_vectorized = cartesian_to_spherical(large_batch) + vectorized_time = time.time() - start_time + + # Time the loop approach + start_time = time.time() + result_loop = [] + for i in range(len(large_batch)): + x, y, z = large_batch[i] + result_loop.append(cartesian_to_spherical(x, y, z)) + result_loop = np.array(result_loop) + loop_time = time.time() - start_time + + print(f"Vectorized approach: {vectorized_time:.4f} seconds") + print(f"Loop approach: {loop_time:.4f} seconds") + print(f"Speedup: {loop_time/vectorized_time:.1f}x faster") + + # Verify results are equivalent + print(f"Results match: {np.allclose(result_vectorized, result_loop)}") \ No newline at end of file diff --git a/src/ariel/ec/drone/genome_handlers/cppn/__init__.py b/src/ariel/ec/drone/genome_handlers/cppn/__init__.py new file mode 100644 index 000000000..5d5ad6ea5 --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/cppn/__init__.py @@ -0,0 +1,24 @@ +"""CPPN-NEAT module for indirect genome encoding.""" + +from .network import ActivationFunction, NodeType, NodeGene, ConnectionGene, CPPNNetwork +from .innovation import InnovationCounter +from .evaluation import topological_sort, evaluate_cppn +from .segment_decoder import decode_cppn_to_phenotype +from .mutations import mutate_cppn +from .crossover import crossover_cppn +from .compatibility import cppn_compatibility_distance + +__all__ = [ + 'ActivationFunction', + 'NodeType', + 'NodeGene', + 'ConnectionGene', + 'CPPNNetwork', + 'InnovationCounter', + 'topological_sort', + 'evaluate_cppn', + 'decode_cppn_to_phenotype', + 'mutate_cppn', + 'crossover_cppn', + 'cppn_compatibility_distance', +] diff --git a/src/ariel/ec/drone/genome_handlers/cppn/compatibility.py b/src/ariel/ec/drone/genome_handlers/cppn/compatibility.py new file mode 100644 index 000000000..556d9394b --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/cppn/compatibility.py @@ -0,0 +1,73 @@ +"""NEAT-style compatibility distance for CPPN networks.""" + +from __future__ import annotations + +import numpy as np + +from .network import CPPNNetwork + + +def cppn_compatibility_distance( + net1: CPPNNetwork, + net2: CPPNNetwork, + c1: float = 1.0, + c2: float = 1.0, + c3: float = 0.4, +) -> float: + """Compute the NEAT compatibility distance between two CPPN networks. + + Parameters + ---------- + net1, net2 : CPPNNetwork + Networks to compare. + c1 : float + Excess gene coefficient. + c2 : float + Disjoint gene coefficient. + c3 : float + Mean weight difference coefficient (matching connection genes only). + + Returns + ------- + float + Compatibility distance. + """ + keys1 = set(net1.connections.keys()) + keys2 = set(net2.connections.keys()) + + if not keys1 and not keys2: + return 0.0 + + max_innov1 = max(keys1, default=-1) + max_innov2 = max(keys2, default=-1) + + matching = keys1 & keys2 + excess = 0 + disjoint = 0 + + for inn in keys1 - keys2: + if inn > max_innov2: + excess += 1 + else: + disjoint += 1 + + for inn in keys2 - keys1: + if inn > max_innov1: + excess += 1 + else: + disjoint += 1 + + # Mean absolute weight difference of matching connection genes only + weight_diffs: list[float] = [] + for inn in matching: + weight_diffs.append( + abs(net1.connections[inn].weight - net2.connections[inn].weight) + ) + + avg_weight_diff = float(np.mean(weight_diffs)) if weight_diffs else 0.0 + + N = max(len(net1.connections), len(net2.connections)) + if N < 20: + N = 1 + + return (c1 * excess / N) + (c2 * disjoint / N) + (c3 * avg_weight_diff) diff --git a/src/ariel/ec/drone/genome_handlers/cppn/crossover.py b/src/ariel/ec/drone/genome_handlers/cppn/crossover.py new file mode 100644 index 000000000..4d834e746 --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/cppn/crossover.py @@ -0,0 +1,236 @@ +"""NEAT-style crossover for CPPN networks.""" + +from __future__ import annotations + +import copy +from collections import defaultdict, deque +from typing import Optional + +import numpy as np + +from .network import ( + CPPNNetwork, + ConnectionGene, + NodeGene, + NodeType, +) + + +def crossover_cppn( + net1: CPPNNetwork, + net2: CPPNNetwork, + fitness1: Optional[float], + fitness2: Optional[float], + rng: np.random.Generator, + disable_gene_prob: float = 0.75, +) -> CPPNNetwork: + """Produce a child network by NEAT-style aligned crossover. + + Matching genes (same innovation number) are inherited randomly from either + parent. Disjoint and excess genes are inherited only from the fitter + parent. When fitnesses are equal or unknown, each disjoint/excess gene + is randomly included with 50% probability (per the original NEAT paper). + + Parameters + ---------- + net1, net2 : CPPNNetwork + Parent networks. + fitness1, fitness2 : float | None + Fitness of each parent. ``None`` is treated as equal. + rng : np.random.Generator + Random number generator. + disable_gene_prob : float + Probability that a matching gene is disabled in the child when it is + disabled in *either* parent. + """ + keys1 = set(net1.connections.keys()) + keys2 = set(net2.connections.keys()) + all_keys = keys1 | keys2 + + # Determine fitter parent (None / equal -> treat as equal) + if fitness1 is None or fitness2 is None or fitness1 == fitness2: + fitter = 0 # 0 = equal + elif fitness1 > fitness2: + fitter = 1 + else: + fitter = 2 + + max_innov1 = max(keys1, default=-1) + max_innov2 = max(keys2, default=-1) + + child_connections: dict[int, ConnectionGene] = {} + # Track which parent contributed each connection (for node inheritance) + node_source: dict[int, CPPNNetwork] = {} # node_id -> source network + + for inn in all_keys: + in1 = inn in keys1 + in2 = inn in keys2 + + if in1 and in2: + # Matching gene — inherit randomly + if rng.random() < 0.5: + conn = copy.deepcopy(net1.connections[inn]) + src_net = net1 + else: + conn = copy.deepcopy(net2.connections[inn]) + src_net = net2 + # Disable with probability if disabled in either parent + if not net1.connections[inn].enabled or not net2.connections[inn].enabled: + if rng.random() < disable_gene_prob: + conn.enabled = False + child_connections[inn] = conn + node_source.setdefault(conn.source_id, src_net) + node_source.setdefault(conn.target_id, src_net) + + elif in1 and not in2: + # Gene only in net1 — disjoint or excess + if fitter == 1: + include = True + elif fitter == 0: + include = rng.random() < 0.5 + else: + include = False + if include: + conn = copy.deepcopy(net1.connections[inn]) + child_connections[inn] = conn + node_source.setdefault(conn.source_id, net1) + node_source.setdefault(conn.target_id, net1) + + else: # in2 and not in1 + if fitter == 2: + include = True + elif fitter == 0: + include = rng.random() < 0.5 + else: + include = False + if include: + conn = copy.deepcopy(net2.connections[inn]) + child_connections[inn] = conn + node_source.setdefault(conn.source_id, net2) + node_source.setdefault(conn.target_id, net2) + + # Remove connections that would create cycles in the child. This can + # happen when disjoint/excess genes from different parents imply + # contradictory topological orderings (e.g. A→B from one parent and + # B→A from the other). + child_connections = _remove_cyclic_connections(child_connections) + + # Collect required node IDs from inherited connections + all input/output + # nodes from the fitter parent (or net1 when equal). + required_node_ids: set[int] = set() + for conn in child_connections.values(): + required_node_ids.add(conn.source_id) + required_node_ids.add(conn.target_id) + + # Always include input and output nodes from the fitter parent + if fitter == 2: + ref_net = net2 + else: + ref_net = net1 + for node in ref_net.nodes.values(): + if node.node_type in (NodeType.INPUT, NodeType.OUTPUT): + required_node_ids.add(node.node_id) + + # Build child nodes — prefer the network that contributed the connection + child_nodes: dict[int, NodeGene] = {} + for nid in required_node_ids: + src_net = node_source.get(nid) + if src_net is not None and nid in src_net.nodes: + child_nodes[nid] = copy.deepcopy(src_net.nodes[nid]) + elif nid in net1.nodes: + child_nodes[nid] = copy.deepcopy(net1.nodes[nid]) + elif nid in net2.nodes: + child_nodes[nid] = copy.deepcopy(net2.nodes[nid]) + # else: node referenced by connection but missing — skip (shouldn't happen) + + next_node_id = max(child_nodes.keys(), default=-1) + 1 + + return CPPNNetwork( + nodes=child_nodes, + connections=child_connections, + next_node_id=next_node_id, + ) + + +def _remove_cyclic_connections( + connections: dict[int, ConnectionGene], +) -> dict[int, ConnectionGene]: + """Drop enabled connections that participate in cycles (Kahn's algorithm). + + Disabled connections are ignored for cycle detection since they don't + affect evaluation. Among the connections that form a cycle, the ones + with the highest innovation numbers (most recently evolved) are removed + first, preserving older / more established structure. + """ + enabled = {inn: c for inn, c in connections.items() if c.enabled} + + # Build adjacency and in-degree + node_ids: set[int] = set() + in_degree: dict[int, int] = defaultdict(int) + children: dict[int, list[int]] = defaultdict(list) + for c in enabled.values(): + node_ids.add(c.source_id) + node_ids.add(c.target_id) + children[c.source_id].append(c.target_id) + in_degree.setdefault(c.source_id, 0) + in_degree[c.target_id] += 1 + + # Kahn's to find acyclic subset + queue = deque(nid for nid in node_ids if in_degree.get(nid, 0) == 0) + visited: set[int] = set() + while queue: + nid = queue.popleft() + visited.add(nid) + for child in children[nid]: + in_degree[child] -= 1 + if in_degree[child] == 0: + queue.append(child) + + if len(visited) == len(node_ids): + return connections # no cycles + + # Nodes still with in_degree > 0 are in cycles. Remove enabled + # connections whose target is in a cycle, preferring to drop higher + # innovation numbers first (newest genes). + cycle_nodes = node_ids - visited + to_drop: set[int] = set() + # Iteratively remove connections until acyclic + remaining = dict(enabled) + while True: + # Rebuild in-degree for remaining + in_deg: dict[int, int] = defaultdict(int) + ch: dict[int, list[tuple[int, int]]] = defaultdict(list) # node -> [(inn, target)] + r_nodes: set[int] = set() + for inn, c in remaining.items(): + r_nodes.add(c.source_id) + r_nodes.add(c.target_id) + ch[c.source_id].append((inn, c.target_id)) + in_deg.setdefault(c.source_id, 0) + in_deg[c.target_id] += 1 + + q = deque(n for n in r_nodes if in_deg.get(n, 0) == 0) + vis: set[int] = set() + while q: + n = q.popleft() + vis.add(n) + for inn, tgt in ch[n]: + in_deg[tgt] -= 1 + if in_deg[tgt] == 0: + q.append(tgt) + + if len(vis) == len(r_nodes): + break # acyclic now + + # Drop the highest-innovation enabled connection in the cycle + cycle_conns = [ + inn for inn, c in remaining.items() + if c.source_id not in vis or c.target_id not in vis + ] + if not cycle_conns: + break + drop = max(cycle_conns) + to_drop.add(drop) + del remaining[drop] + + # Build result: keep all original connections except dropped ones + return {inn: c for inn, c in connections.items() if inn not in to_drop} diff --git a/src/ariel/ec/drone/genome_handlers/cppn/evaluation.py b/src/ariel/ec/drone/genome_handlers/cppn/evaluation.py new file mode 100644 index 000000000..efc5a0949 --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/cppn/evaluation.py @@ -0,0 +1,105 @@ +"""Feed-forward evaluation of a CPPN network.""" + +from __future__ import annotations + +from collections import defaultdict, deque +from typing import Dict, List + +import numpy as np + +from .network import CPPNNetwork, NodeType, apply_activation + + +def topological_sort(network: CPPNNetwork) -> List[int]: + """Return node IDs in topological (feed-forward) evaluation order. + + Uses Kahn's algorithm on enabled connections only. + + Raises: + ValueError: If a cycle is detected among enabled connections. + """ + enabled = network.get_enabled_connections() + + # Build adjacency and in-degree info for nodes reachable via enabled edges + in_degree: Dict[int, int] = {nid: 0 for nid in network.nodes} + children: Dict[int, List[int]] = defaultdict(list) + + for conn in enabled: + children[conn.source_id].append(conn.target_id) + in_degree[conn.target_id] += 1 + + queue = deque(nid for nid, deg in in_degree.items() if deg == 0) + order: List[int] = [] + + while queue: + nid = queue.popleft() + order.append(nid) + for child in children[nid]: + in_degree[child] -= 1 + if in_degree[child] == 0: + queue.append(child) + + if len(order) != len(network.nodes): + raise ValueError( + "Cycle detected in CPPN network; topological sort failed." + ) + return order + + +def evaluate_cppn( + network: CPPNNetwork, + inputs: np.ndarray, +) -> np.ndarray: + """Evaluate the CPPN in feed-forward mode. + + Args: + network: The CPPN to evaluate. + inputs: Array of shape ``(n_inputs,)`` or ``(batch, n_inputs)``. + + Returns: + Array of shape ``(n_outputs,)`` or ``(batch, n_outputs)`` with output + node values ordered by ``output_index``. + """ + inputs = np.asarray(inputs, dtype=np.float64) + single = inputs.ndim == 1 + if single: + inputs = inputs[np.newaxis, :] # (1, n_inputs) + + batch_size = inputs.shape[0] + + # Map input nodes to columns of ``inputs`` + input_nodes = network.get_input_nodes() # sorted by node_id + output_nodes = network.get_output_nodes() # sorted by output_index + + activations: Dict[int, np.ndarray] = {} + for idx, node in enumerate(input_nodes): + activations[node.node_id] = inputs[:, idx] # (batch,) + + # Build incoming connections index + incoming: Dict[int, list] = defaultdict(list) + for conn in network.get_enabled_connections(): + incoming[conn.target_id].append(conn) + + order = topological_sort(network) + + for nid in order: + node = network.nodes[nid] + if node.node_type == NodeType.INPUT: + continue # already set + + # Weighted sum of incoming activations + bias + total = np.full(batch_size, node.bias, dtype=np.float64) + for conn in incoming[nid]: + if conn.source_id in activations: + total += conn.weight * activations[conn.source_id] + + activations[nid] = apply_activation(node.activation, total) + + # Gather outputs in order + result = np.column_stack( + [activations.get(n.node_id, np.zeros(batch_size)) for n in output_nodes] + ) + + if single: + return result[0] # (n_outputs,) + return result diff --git a/src/ariel/ec/drone/genome_handlers/cppn/innovation.py b/src/ariel/ec/drone/genome_handlers/cppn/innovation.py new file mode 100644 index 000000000..3405dff4f --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/cppn/innovation.py @@ -0,0 +1,45 @@ +"""Innovation counter for NEAT-style structural mutations.""" + +from __future__ import annotations + +from typing import Dict, Tuple + + +class InnovationCounter: + """Tracks structural innovation numbers across a population within a generation. + + Same structural mutation (same source → target pair) within a generation + receives the same innovation number so that genomes can be aligned for + crossover. + """ + + def __init__(self) -> None: + self._global_counter: int = 0 + self._generation_cache: Dict[Tuple[int, int], int] = {} + + @property + def current(self) -> int: + """The next innovation number that will be assigned.""" + return self._global_counter + + def get_innovation(self, source_id: int, target_id: int) -> int: + """Return innovation number for a connection, creating one if new.""" + key = (source_id, target_id) + if key not in self._generation_cache: + self._generation_cache[key] = self._global_counter + self._global_counter += 1 + return self._generation_cache[key] + + def next_innovation(self) -> int: + """Return the next innovation number without caching. + + Use this for structural mutations that have no natural cache key + (e.g. arm additions in the spherical encoding). + """ + inno = self._global_counter + self._global_counter += 1 + return inno + + def reset_generation(self) -> None: + """Clear the per-generation cache. Call at the start of each generation.""" + self._generation_cache.clear() diff --git a/src/ariel/ec/drone/genome_handlers/cppn/mutations.py b/src/ariel/ec/drone/genome_handlers/cppn/mutations.py new file mode 100644 index 000000000..6dab4db64 --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/cppn/mutations.py @@ -0,0 +1,279 @@ +"""NEAT-style mutation operators for CPPN networks.""" + +from __future__ import annotations + +from collections import defaultdict +from typing import List, Optional + +import numpy as np + +from .network import ( + ActivationFunction, + CPPNNetwork, + ConnectionGene, + NodeGene, + NodeType, +) +from .innovation import InnovationCounter + + +# --------------------------------------------------------------------------- +# Public entry point +# --------------------------------------------------------------------------- + +def mutate_cppn( + network: CPPNNetwork, + innovation_counter: InnovationCounter, + rng: np.random.Generator, + prob_add_node: float = 0.03, + prob_add_connection: float = 0.05, + prob_remove_node: float = 0.01, + prob_remove_connection: float = 0.02, + prob_mutate_weights: float = 0.80, + prob_mutate_activation: float = 0.05, + prob_toggle_connection: float = 0.02, + weight_perturb_std: float = 0.5, + weight_replace_prob: float = 0.1, + weight_range: float = 3.0, + bias_perturb_std: float = 0.3, + bias_replace_prob: float = 0.1, + bias_range: float = 3.0, +) -> None: + """Select and apply one mutation to *network* in-place.""" + probs = np.array([ + prob_add_node, + prob_add_connection, + prob_remove_node, + prob_remove_connection, + prob_mutate_weights, + prob_mutate_activation, + prob_toggle_connection, + ]) + # Remainder goes to "no mutation" + remainder = max(0.0, 1.0 - probs.sum()) + probs = np.append(probs, remainder) + probs /= probs.sum() # normalise to handle floating-point drift + + choice = rng.choice(len(probs), p=probs) + + if choice == 0: + _add_node(network, innovation_counter, rng) + elif choice == 1: + _add_connection(network, innovation_counter, rng, weight_range=weight_range) + elif choice == 2: + _remove_node(network, rng) + elif choice == 3: + _remove_connection(network, rng) + elif choice == 4: + _mutate_weights( + network, rng, + perturb_std=weight_perturb_std, + replace_prob=weight_replace_prob, + weight_range=weight_range, + bias_perturb_std=bias_perturb_std, + bias_replace_prob=bias_replace_prob, + bias_range=bias_range, + ) + elif choice == 5: + _mutate_activation(network, rng) + elif choice == 6: + _toggle_connection(network, rng) + # else: no mutation + + +# --------------------------------------------------------------------------- +# Individual mutation operators +# --------------------------------------------------------------------------- + +def _add_node( + network: CPPNNetwork, + innovation_counter: InnovationCounter, + rng: np.random.Generator, +) -> None: + """Split a random enabled connection by inserting a hidden node.""" + enabled = network.get_enabled_connections() + if not enabled: + return + + conn = enabled[rng.integers(len(enabled))] + conn.enabled = False + + new_id = network.next_node_id + network.next_node_id += 1 + + activation = rng.choice(list(ActivationFunction)) + new_node = NodeGene( + node_id=new_id, + node_type=NodeType.HIDDEN, + activation=activation, + bias=0.0, + ) + network.nodes[new_id] = new_node + + inn1 = innovation_counter.get_innovation(conn.source_id, new_id) + inn2 = innovation_counter.get_innovation(new_id, conn.target_id) + + network.connections[inn1] = ConnectionGene( + innovation_number=inn1, + source_id=conn.source_id, + target_id=new_id, + weight=1.0, + enabled=True, + ) + network.connections[inn2] = ConnectionGene( + innovation_number=inn2, + source_id=new_id, + target_id=conn.target_id, + weight=conn.weight, + enabled=True, + ) + + +def _add_connection( + network: CPPNNetwork, + innovation_counter: InnovationCounter, + rng: np.random.Generator, + max_attempts: int = 50, + weight_range: float = 3.0, +) -> None: + """Add a new connection between two previously unconnected nodes.""" + node_ids = list(network.nodes.keys()) + existing_pairs = { + (c.source_id, c.target_id) for c in network.connections.values() + } + + for _ in range(max_attempts): + src_id = node_ids[rng.integers(len(node_ids))] + tgt_id = node_ids[rng.integers(len(node_ids))] + + if src_id == tgt_id: + continue + src_node = network.nodes[src_id] + tgt_node = network.nodes[tgt_id] + if src_node.node_type == NodeType.OUTPUT: + continue + if tgt_node.node_type == NodeType.INPUT: + continue + if (src_id, tgt_id) in existing_pairs: + continue + if _would_create_cycle(network, src_id, tgt_id): + continue + + inn = innovation_counter.get_innovation(src_id, tgt_id) + network.connections[inn] = ConnectionGene( + innovation_number=inn, + source_id=src_id, + target_id=tgt_id, + weight=rng.uniform(-weight_range, weight_range), + enabled=True, + ) + return + + +def _remove_node(network: CPPNNetwork, rng: np.random.Generator) -> None: + """Remove a random hidden node and all connections involving it.""" + hidden = network.get_hidden_nodes() + if not hidden: + return + + node = hidden[rng.integers(len(hidden))] + nid = node.node_id + + # Remove connections involving the node + to_remove = [ + inn for inn, c in network.connections.items() + if c.source_id == nid or c.target_id == nid + ] + for inn in to_remove: + del network.connections[inn] + + del network.nodes[nid] + + +def _remove_connection(network: CPPNNetwork, rng: np.random.Generator) -> None: + """Disable a random enabled connection.""" + enabled = network.get_enabled_connections() + if not enabled: + return + conn = enabled[rng.integers(len(enabled))] + conn.enabled = False + + +def _mutate_weights( + network: CPPNNetwork, + rng: np.random.Generator, + perturb_std: float = 0.5, + replace_prob: float = 0.1, + weight_range: float = 3.0, + bias_perturb_std: float = 0.3, + bias_replace_prob: float = 0.1, + bias_range: float = 3.0, +) -> None: + """Perturb or replace all connection weights and node biases.""" + for conn in network.connections.values(): + if rng.random() < replace_prob: + conn.weight = rng.uniform(-weight_range, weight_range) + else: + conn.weight += rng.normal(0.0, perturb_std) + conn.weight = np.clip(conn.weight, -weight_range, weight_range) + + for node in network.nodes.values(): + if node.node_type == NodeType.INPUT: + continue + if rng.random() < bias_replace_prob: + node.bias = rng.uniform(-bias_range, bias_range) + else: + node.bias += rng.normal(0.0, bias_perturb_std) + node.bias = np.clip(node.bias, -bias_range, bias_range) + + +def _mutate_activation(network: CPPNNetwork, rng: np.random.Generator) -> None: + """Change the activation function of a random hidden node.""" + hidden = network.get_hidden_nodes() + if not hidden: + return + + node = hidden[rng.integers(len(hidden))] + options = [a for a in ActivationFunction if a != node.activation] + if options: + node.activation = options[rng.integers(len(options))] + + +def _toggle_connection(network: CPPNNetwork, rng: np.random.Generator) -> None: + """Toggle enabled/disabled on a random connection.""" + conns = list(network.connections.values()) + if not conns: + return + conn = conns[rng.integers(len(conns))] + if not conn.enabled and _would_create_cycle(network, conn.source_id, conn.target_id): + return # Don't re-enable if it would create a cycle + conn.enabled = not conn.enabled + + +# --------------------------------------------------------------------------- +# Cycle detection helper +# --------------------------------------------------------------------------- + +def _would_create_cycle( + network: CPPNNetwork, + source_id: int, + target_id: int, +) -> bool: + """Return True if adding source→target would create a cycle (DFS).""" + # Check: is *source_id* reachable from *target_id* via enabled connections? + visited = set() + stack = [target_id] + children = defaultdict(list) + for conn in network.get_enabled_connections(): + children[conn.source_id].append(conn.target_id) + + while stack: + nid = stack.pop() + if nid == source_id: + return True + if nid in visited: + continue + visited.add(nid) + stack.extend(children[nid]) + + return False diff --git a/src/ariel/ec/drone/genome_handlers/cppn/network.py b/src/ariel/ec/drone/genome_handlers/cppn/network.py new file mode 100644 index 000000000..e82bbb72e --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/cppn/network.py @@ -0,0 +1,134 @@ +"""CPPN network data structures: nodes, connections, activation functions.""" + +from __future__ import annotations + +import copy +from dataclasses import dataclass, field +from enum import Enum +from typing import Callable, Dict, List, Optional + +import numpy as np + + +class ActivationFunction(Enum): + """Activation functions available for CPPN nodes.""" + IDENTITY = "identity" + SIGMOID = "sigmoid" + TANH = "tanh" + SIN = "sin" + COS = "cos" + GAUSSIAN = "gaussian" + ABS = "abs" + RELU = "relu" + STEP = "step" + + +def _identity(x: np.ndarray) -> np.ndarray: + return x + +def _sigmoid(x: np.ndarray) -> np.ndarray: + return 1.0 / (1.0 + np.exp(-np.clip(x, -60, 60))) + +def _tanh(x: np.ndarray) -> np.ndarray: + return np.tanh(x) + +def _sin(x: np.ndarray) -> np.ndarray: + return np.sin(x) + +def _cos(x: np.ndarray) -> np.ndarray: + return np.cos(x) + +def _gaussian(x: np.ndarray) -> np.ndarray: + return np.exp(-x * x / 2.0) + +def _abs(x: np.ndarray) -> np.ndarray: + return np.abs(x) + +def _relu(x: np.ndarray) -> np.ndarray: + return np.maximum(0.0, x) + +def _step(x: np.ndarray) -> np.ndarray: + return np.where(x > 0, 1.0, 0.0) + + +ACTIVATION_FUNCTIONS: Dict[ActivationFunction, Callable] = { + ActivationFunction.IDENTITY: _identity, + ActivationFunction.SIGMOID: _sigmoid, + ActivationFunction.TANH: _tanh, + ActivationFunction.SIN: _sin, + ActivationFunction.COS: _cos, + ActivationFunction.GAUSSIAN: _gaussian, + ActivationFunction.ABS: _abs, + ActivationFunction.RELU: _relu, + ActivationFunction.STEP: _step, +} + + +def apply_activation(activation: ActivationFunction, x: np.ndarray) -> np.ndarray: + """Apply an activation function to an array.""" + return ACTIVATION_FUNCTIONS[activation](x) + + +class NodeType(Enum): + """Types of nodes in a CPPN.""" + INPUT = "input" + OUTPUT = "output" + HIDDEN = "hidden" + + +@dataclass +class NodeGene: + """A node in the CPPN graph.""" + node_id: int + node_type: NodeType + activation: ActivationFunction + bias: float = 0.0 + output_index: Optional[int] = None # For output nodes: index in output array + input_label: Optional[str] = None # For input nodes: descriptive label + + +@dataclass +class ConnectionGene: + """A connection (edge) in the CPPN graph.""" + innovation_number: int + source_id: int + target_id: int + weight: float + enabled: bool = True + + +@dataclass +class CPPNNetwork: + """A CPPN represented as a directed acyclic graph of nodes and connections.""" + nodes: Dict[int, NodeGene] = field(default_factory=dict) + connections: Dict[int, ConnectionGene] = field(default_factory=dict) # keyed by innovation number + next_node_id: int = 0 + + def copy(self) -> CPPNNetwork: + """Deep copy of the network.""" + return copy.deepcopy(self) + + def get_input_nodes(self) -> List[NodeGene]: + """Return input nodes sorted by node_id.""" + return sorted( + [n for n in self.nodes.values() if n.node_type == NodeType.INPUT], + key=lambda n: n.node_id, + ) + + def get_output_nodes(self) -> List[NodeGene]: + """Return output nodes sorted by output_index.""" + return sorted( + [n for n in self.nodes.values() if n.node_type == NodeType.OUTPUT], + key=lambda n: (n.output_index if n.output_index is not None else 0), + ) + + def get_hidden_nodes(self) -> List[NodeGene]: + """Return hidden nodes sorted by node_id.""" + return sorted( + [n for n in self.nodes.values() if n.node_type == NodeType.HIDDEN], + key=lambda n: n.node_id, + ) + + def get_enabled_connections(self) -> List[ConnectionGene]: + """Return all enabled connections.""" + return [c for c in self.connections.values() if c.enabled] diff --git a/src/ariel/ec/drone/genome_handlers/cppn/segment_decoder.py b/src/ariel/ec/drone/genome_handlers/cppn/segment_decoder.py new file mode 100644 index 000000000..f7cc088da --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/cppn/segment_decoder.py @@ -0,0 +1,86 @@ +"""Decode a CPPN network into a phenotype array of arm parameters.""" + +from __future__ import annotations + +import numpy as np +import numpy.typing as npt + +from .network import CPPNNetwork +from .evaluation import evaluate_cppn + + +def _map_tanh_to_range(tanh_val: float, low: float, high: float) -> float: + """Map a value in [-1, 1] to [low, high].""" + return low + (tanh_val + 1.0) * 0.5 * (high - low) + + +def decode_cppn_to_phenotype( + network: CPPNNetwork, + num_segments: int, + arm_limit: int, + parameter_limits: npt.NDArray, +) -> npt.NDArray: + """Decode a CPPN to phenotype array by evaluating it over azimuthal segments. + + Args: + network: The CPPN to decode. + num_segments: Number of azimuthal segments to evaluate. + arm_limit: Maximum number of arms (rows in output array). + parameter_limits: Array of shape ``(6, 2)`` with ``[min, max]`` per + parameter: ``[magnitude, arm_yaw, arm_pitch, motor_pitch, + motor_yaw, direction]``. + + Returns: + Array of shape ``(arm_limit, 6)`` with NaN for unused rows. + Columns: ``[magnitude, arm_yaw, arm_pitch, motor_pitch, motor_yaw, + direction]``. + """ + phenotype = np.full((arm_limit, 6), np.nan) + arms_placed = 0 + segment_angle_width = 2.0 * np.pi / num_segments + + for seg_idx in range(num_segments): + if arms_placed >= arm_limit: + break # Rule 1: arm limit reached + + remaining_segments = num_segments - seg_idx + remaining_slots = arm_limit - arms_placed + + # Normalise segment index to [-1, 1] + if num_segments > 1: + seg_normalized = 2.0 * seg_idx / (num_segments - 1) - 1.0 + else: + seg_normalized = 0.0 + + outputs = evaluate_cppn(network, np.array([seg_normalized, 1.0])) + # outputs has 7 elements (all tanh-range from output activations) + + # Rule 2: force arm if remaining segments <= remaining slots + if remaining_segments <= remaining_slots: + place_arm = True + else: + place_arm = outputs[0] >= 0.0 + + if place_arm: + segment_center = seg_idx * segment_angle_width - np.pi + half_width = segment_angle_width / 2.0 + + mag_min, mag_max = parameter_limits[0] + pitch_min, pitch_max = parameter_limits[2] + motor_pitch_min, motor_pitch_max = parameter_limits[3] + motor_yaw_min, motor_yaw_max = parameter_limits[4] + + magnitude = _map_tanh_to_range(outputs[1], mag_min, mag_max) + arm_yaw = segment_center + outputs[2] * half_width + arm_pitch = _map_tanh_to_range(outputs[3], pitch_min, pitch_max) + motor_yaw = _map_tanh_to_range(outputs[4], motor_yaw_min, motor_yaw_max) + motor_pitch = _map_tanh_to_range(outputs[5], motor_pitch_min, motor_pitch_max) + direction = 0.0 if outputs[6] < 0.0 else 1.0 + + phenotype[arms_placed] = [ + magnitude, arm_yaw, arm_pitch, + motor_pitch, motor_yaw, direction, + ] + arms_placed += 1 + + return phenotype diff --git a/src/ariel/ec/drone/genome_handlers/cppn_neat_genome_handler.py b/src/ariel/ec/drone/genome_handlers/cppn_neat_genome_handler.py new file mode 100644 index 000000000..5e3d0e7a5 --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/cppn_neat_genome_handler.py @@ -0,0 +1,452 @@ +"""CPPN-NEAT indirect-encoding genome handler for drone evolution.""" + +from __future__ import annotations + +from typing import Any, List, Optional, Tuple + +import numpy as np +import numpy.typing as npt + +from .base import GenomeHandler +from .cppn.network import ( + ActivationFunction, + CPPNNetwork, + ConnectionGene, + NodeGene, + NodeType, +) +from .cppn.innovation import InnovationCounter +from .cppn.evaluation import evaluate_cppn +from .cppn.segment_decoder import decode_cppn_to_phenotype +from .cppn.mutations import mutate_cppn +from .cppn.crossover import crossover_cppn +from .cppn.compatibility import cppn_compatibility_distance +from .operators import SphericalRepairOperator, RepairConfig + + +# Number of CPPN input nodes (segment_normalized, bias) +_N_INPUTS = 2 +# Number of CPPN output nodes +_N_OUTPUTS = 7 +# Labels for the output nodes +_OUTPUT_LABELS = [ + "arm_present", "magnitude", "arm_yaw", "arm_pitch", + "motor_yaw", "motor_pitch", "direction", +] + + +class CPPNNeatDroneGenomeHandler(GenomeHandler): + """Genome handler that uses a CPPN-NEAT indirect encoding. + + The genome is a :class:`CPPNNetwork` (directed acyclic graph). The CPPN + takes a normalised segment index and a bias as input and produces 7 outputs + used to decide arm placement and parameters. + """ + + # Shared across the entire population so that structural mutations within + # the same generation receive matching innovation numbers. + _innovation_counter: InnovationCounter = InnovationCounter() + + def __init__( + self, + genome: Optional[CPPNNetwork] = None, + num_segments: int = 8, + min_max_narms: Optional[Tuple[int, int]] = None, + parameter_limits: Optional[npt.NDArray[Any]] = None, + # Mutation probabilities + prob_add_node: float = 0.03, + prob_add_connection: float = 0.05, + prob_remove_node: float = 0.01, + prob_remove_connection: float = 0.02, + prob_mutate_weights: float = 0.80, + prob_mutate_activation: float = 0.05, + prob_toggle_connection: float = 0.02, + # Initial topology complexity + initial_hidden_nodes: int = 0, + init_topology: str = "empty", # "empty" or "seeded" + # Weight / bias mutation parameters + weight_perturb_std: float = 0.5, + weight_replace_prob: float = 0.1, + weight_range: float = 3.0, + bias_perturb_std: float = 0.3, + bias_replace_prob: float = 0.1, + bias_range: float = 3.0, + # Repair + repair: bool = False, + enable_collision_repair: bool = False, + propeller_radius: float = 0.0508 / 2, + inner_boundary_radius: float = 0.0055, + outer_boundary_radius: float = 0.11, + max_repair_iterations: int = 100, + repair_step_size: float = 1.0, + propeller_tolerance: float = 0.1, + # RNG + rng: Optional[np.random.Generator] = None, + ) -> None: + # --- Do NOT call super().__init__() --- + self.fitness: float | None = None + self.rng = rng if rng is not None else np.random.default_rng() + + self.num_segments = num_segments + + if min_max_narms is None: + self.min_narms, self.max_narms = 6, 6 + else: + self.min_narms, self.max_narms = min_max_narms + + if parameter_limits is None: + self.parameter_limits = np.array([ + [0.055, 0.17], # magnitude + [-np.pi, np.pi], # arm yaw (azimuth) + [-np.pi / 2, np.pi / 2], # arm pitch (elevation) + [-np.pi, np.pi], # motor pitch + [-np.pi, np.pi], # motor yaw + [0, 1], # direction + ]) + else: + self.parameter_limits = np.asarray(parameter_limits) + + # Initial topology + self.initial_hidden_nodes = initial_hidden_nodes + self.init_topology = init_topology + + # Mutation hyperparameters + self.prob_add_node = prob_add_node + self.prob_add_connection = prob_add_connection + self.prob_remove_node = prob_remove_node + self.prob_remove_connection = prob_remove_connection + self.prob_mutate_weights = prob_mutate_weights + self.prob_mutate_activation = prob_mutate_activation + self.prob_toggle_connection = prob_toggle_connection + self.weight_perturb_std = weight_perturb_std + self.weight_replace_prob = weight_replace_prob + self.weight_range = weight_range + self.bias_perturb_std = bias_perturb_std + self.bias_replace_prob = bias_replace_prob + self.bias_range = bias_range + + # Repair settings + self.repair_enabled = repair + self.enable_collision_repair = enable_collision_repair + self.propeller_radius = propeller_radius + self.inner_boundary_radius = inner_boundary_radius + self.outer_boundary_radius = outer_boundary_radius + self.max_repair_iterations = max_repair_iterations + self.repair_step_size = repair_step_size + self.propeller_tolerance = propeller_tolerance + + self._setup_repair_operator() + + # Genome + if genome is None: + self.genome: CPPNNetwork = self._generate_random_genome() + else: + self.genome = genome.copy() + + # ------------------------------------------------------------------ + # Repair operator setup + # ------------------------------------------------------------------ + + def _setup_repair_operator(self) -> None: + repair_config = RepairConfig( + apply_symmetry=False, + enable_collision_repair=self.enable_collision_repair, + propeller_radius=self.propeller_radius, + inner_boundary_radius=self.inner_boundary_radius, + outer_boundary_radius=self.outer_boundary_radius, + max_repair_iterations=self.max_repair_iterations, + repair_step_size=self.repair_step_size, + propeller_tolerance=self.propeller_tolerance, + ) + self.repair_operator = SphericalRepairOperator( + config=repair_config, + min_narms=self.min_narms, + max_narms=self.max_narms, + parameter_limits=self.parameter_limits, + symmetry_operator=None, + rng=self.rng, + ) + + # ------------------------------------------------------------------ + # Random genome generation + # ------------------------------------------------------------------ + + # Activation functions that introduce useful spatial variation + _HIDDEN_ACTIVATIONS = [ + ActivationFunction.SIN, + ActivationFunction.COS, + ActivationFunction.GAUSSIAN, + ActivationFunction.TANH, + ActivationFunction.ABS, + ] + + # Activation functions used when seeding initial hidden nodes + _SEED_ACTIVATIONS = [ + ActivationFunction.SIGMOID, + ActivationFunction.TANH, + ActivationFunction.GAUSSIAN, + ] + + def _generate_random_genome(self) -> CPPNNetwork: + """Create a CPPN with input and output nodes. + + If ``init_topology == "seeded"``, adds 2–5 hidden nodes with + sigmoid/tanh/gaussian activations and ~10–20 random feed-forward + connections. Otherwise the network starts empty (classic NEAT + complexification). + """ + net = CPPNNetwork() + + # --- Input nodes --- + for i in range(_N_INPUTS): + label = "seg_normalized" if i == 0 else "bias" + net.nodes[i] = NodeGene( + node_id=i, + node_type=NodeType.INPUT, + activation=ActivationFunction.IDENTITY, + bias=0.0, + input_label=label, + ) + + # --- Output nodes (zero bias so all initial individuals are identical) --- + for j in range(_N_OUTPUTS): + nid = _N_INPUTS + j + net.nodes[nid] = NodeGene( + node_id=nid, + node_type=NodeType.OUTPUT, + activation=ActivationFunction.SIN, + bias=0.0, + output_index=j, + ) + + net.next_node_id = _N_INPUTS + _N_OUTPUTS + + if self.init_topology == "seeded": + self._seed_topology(net, _N_INPUTS, _N_OUTPUTS) + + return net + + def _seed_topology( + self, net: CPPNNetwork, n_inputs: int, n_outputs: int, + ) -> None: + """Add 2–5 hidden nodes and ~10–20 random feed-forward connections.""" + n_hidden = int(self.rng.integers(2, 6)) + + input_ids = list(range(n_inputs)) + output_ids = list(range(n_inputs, n_inputs + n_outputs)) + hidden_ids = [] + + for _ in range(n_hidden): + nid = net.next_node_id + net.next_node_id += 1 + activation = self.rng.choice(self._SEED_ACTIVATIONS) + net.nodes[nid] = NodeGene( + node_id=nid, + node_type=NodeType.HIDDEN, + activation=activation, + bias=float(self.rng.uniform(-1.0, 1.0)), + ) + hidden_ids.append(nid) + + # Valid feed-forward connections (input→hidden, input→output, + # hidden→output, hidden→higher-hidden to keep DAG) + possible = [] + for src in input_ids: + for tgt in hidden_ids + output_ids: + possible.append((src, tgt)) + for src in hidden_ids: + for tgt in output_ids: + possible.append((src, tgt)) + for i, src in enumerate(hidden_ids): + for tgt in hidden_ids[i + 1:]: + possible.append((src, tgt)) + + n_target = int(self.rng.integers(10, 21)) + n_conns = min(n_target, len(possible)) + chosen = self.rng.choice(len(possible), size=n_conns, replace=False) + + for idx in chosen: + src, tgt = possible[idx] + inn = self._innovation_counter.get_innovation(src, tgt) + net.connections[inn] = ConnectionGene( + innovation_number=inn, + source_id=src, + target_id=tgt, + weight=float(self.rng.uniform(-1.0, 1.0)), + enabled=True, + ) + + # ------------------------------------------------------------------ + # Phenotype decoding + # ------------------------------------------------------------------ + + def get_phenotype(self) -> npt.NDArray[Any]: + """Decode the CPPN into a ``(max_narms, 6)`` phenotype array. + + Applies repair to the decoded phenotype if enabled. + """ + phenotype = decode_cppn_to_phenotype( + self.genome, + num_segments=self.num_segments, + arm_limit=self.max_narms, + parameter_limits=self.parameter_limits, + ) + if self.repair_enabled: + phenotype = self.repair_operator.repair(phenotype) + return phenotype + + # ------------------------------------------------------------------ + # GenomeHandler interface + # ------------------------------------------------------------------ + + def generate_random_population( + self, population_size: int + ) -> List[CPPNNeatDroneGenomeHandler]: + population: List[CPPNNeatDroneGenomeHandler] = [] + for _ in range(population_size): + handler = CPPNNeatDroneGenomeHandler( + genome=None, + num_segments=self.num_segments, + min_max_narms=(self.min_narms, self.max_narms), + parameter_limits=self.parameter_limits, + initial_hidden_nodes=self.initial_hidden_nodes, + init_topology=self.init_topology, + prob_add_node=self.prob_add_node, + prob_add_connection=self.prob_add_connection, + prob_remove_node=self.prob_remove_node, + prob_remove_connection=self.prob_remove_connection, + prob_mutate_weights=self.prob_mutate_weights, + prob_mutate_activation=self.prob_mutate_activation, + prob_toggle_connection=self.prob_toggle_connection, + weight_perturb_std=self.weight_perturb_std, + weight_replace_prob=self.weight_replace_prob, + weight_range=self.weight_range, + bias_perturb_std=self.bias_perturb_std, + bias_replace_prob=self.bias_replace_prob, + bias_range=self.bias_range, + repair=self.repair_enabled, + enable_collision_repair=self.enable_collision_repair, + propeller_radius=self.propeller_radius, + inner_boundary_radius=self.inner_boundary_radius, + outer_boundary_radius=self.outer_boundary_radius, + max_repair_iterations=self.max_repair_iterations, + repair_step_size=self.repair_step_size, + propeller_tolerance=self.propeller_tolerance, + rng=self.rng, + ) + population.append(handler) + return population + + def crossover(self, other: CPPNNeatDroneGenomeHandler) -> CPPNNeatDroneGenomeHandler: + """NEAT-style aligned crossover of two CPPN genomes.""" + child_net = crossover_cppn( + self.genome, other.genome, + self.fitness, other.fitness, + self.rng, + ) + return CPPNNeatDroneGenomeHandler( + genome=child_net, + num_segments=self.num_segments, + min_max_narms=(self.min_narms, self.max_narms), + parameter_limits=self.parameter_limits, + initial_hidden_nodes=self.initial_hidden_nodes, + init_topology=self.init_topology, + prob_add_node=self.prob_add_node, + prob_add_connection=self.prob_add_connection, + prob_remove_node=self.prob_remove_node, + prob_remove_connection=self.prob_remove_connection, + prob_mutate_weights=self.prob_mutate_weights, + prob_mutate_activation=self.prob_mutate_activation, + prob_toggle_connection=self.prob_toggle_connection, + weight_perturb_std=self.weight_perturb_std, + weight_replace_prob=self.weight_replace_prob, + weight_range=self.weight_range, + bias_perturb_std=self.bias_perturb_std, + bias_replace_prob=self.bias_replace_prob, + bias_range=self.bias_range, + repair=self.repair_enabled, + enable_collision_repair=self.enable_collision_repair, + propeller_radius=self.propeller_radius, + inner_boundary_radius=self.inner_boundary_radius, + outer_boundary_radius=self.outer_boundary_radius, + max_repair_iterations=self.max_repair_iterations, + repair_step_size=self.repair_step_size, + propeller_tolerance=self.propeller_tolerance, + rng=self.rng, + ) + + def crossover_population( + self, + population1: List[GenomeHandler], + population2: List[GenomeHandler], + ) -> List[GenomeHandler]: + """Perform NEAT crossover on paired populations.""" + assert len(population1) == len(population2) + return [p1.crossover(p2) for p1, p2 in zip(population1, population2)] + + def mutate(self) -> None: + """Mutate the CPPN genome in-place.""" + mutate_cppn( + self.genome, + self._innovation_counter, + self.rng, + prob_add_node=self.prob_add_node, + prob_add_connection=self.prob_add_connection, + prob_remove_node=self.prob_remove_node, + prob_remove_connection=self.prob_remove_connection, + prob_mutate_weights=self.prob_mutate_weights, + prob_mutate_activation=self.prob_mutate_activation, + prob_toggle_connection=self.prob_toggle_connection, + weight_perturb_std=self.weight_perturb_std, + weight_replace_prob=self.weight_replace_prob, + weight_range=self.weight_range, + bias_perturb_std=self.bias_perturb_std, + bias_replace_prob=self.bias_replace_prob, + bias_range=self.bias_range, + ) + + def copy(self) -> CPPNNeatDroneGenomeHandler: + return CPPNNeatDroneGenomeHandler( + genome=self.genome, + num_segments=self.num_segments, + min_max_narms=(self.min_narms, self.max_narms), + parameter_limits=self.parameter_limits, + initial_hidden_nodes=self.initial_hidden_nodes, + init_topology=self.init_topology, + prob_add_node=self.prob_add_node, + prob_add_connection=self.prob_add_connection, + prob_remove_node=self.prob_remove_node, + prob_remove_connection=self.prob_remove_connection, + prob_mutate_weights=self.prob_mutate_weights, + prob_mutate_activation=self.prob_mutate_activation, + prob_toggle_connection=self.prob_toggle_connection, + weight_perturb_std=self.weight_perturb_std, + weight_replace_prob=self.weight_replace_prob, + weight_range=self.weight_range, + bias_perturb_std=self.bias_perturb_std, + bias_replace_prob=self.bias_replace_prob, + bias_range=self.bias_range, + repair=self.repair_enabled, + enable_collision_repair=self.enable_collision_repair, + propeller_radius=self.propeller_radius, + inner_boundary_radius=self.inner_boundary_radius, + outer_boundary_radius=self.outer_boundary_radius, + max_repair_iterations=self.max_repair_iterations, + repair_step_size=self.repair_step_size, + propeller_tolerance=self.propeller_tolerance, + rng=self.rng, + ) + + def is_valid(self) -> bool: + """Decode the CPPN to phenotype and check validity.""" + phenotype = self.get_phenotype() + arm_count = int(np.sum(~np.isnan(phenotype[:, 0]))) + return self.min_narms <= arm_count <= self.max_narms + + def compatibility_distance(self, other: CPPNNeatDroneGenomeHandler) -> float: + """NEAT compatibility distance based on CPPN topology and weights.""" + return cppn_compatibility_distance(self.genome, other.genome) + + def repair(self) -> None: + """No-op — repair is applied to the decoded phenotype in get_phenotype().""" + pass diff --git a/src/ariel/ec/drone/genome_handlers/hybrid_cppn_genome_handler.py b/src/ariel/ec/drone/genome_handlers/hybrid_cppn_genome_handler.py new file mode 100644 index 000000000..d17108302 --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/hybrid_cppn_genome_handler.py @@ -0,0 +1,620 @@ +"""Hybrid direct + CPPN genome handler for drone evolution. + +Arm geometry (magnitude, yaw, pitch) is directly encoded while motor +parameters (motor_yaw, motor_pitch, spin_direction) are produced by a CPPN +conditioned on each arm's geometry. +""" + +from __future__ import annotations + +import copy +from dataclasses import dataclass, field +from typing import Any, List, Optional, Tuple + +import numpy as np +import numpy.typing as npt + +from .base import GenomeHandler +from .cppn.network import ( + ActivationFunction, + CPPNNetwork, + ConnectionGene, + NodeGene, + NodeType, +) +from .cppn.innovation import InnovationCounter +from .cppn.evaluation import evaluate_cppn +from .cppn.mutations import mutate_cppn +from .cppn.crossover import crossover_cppn +from .cppn.compatibility import cppn_compatibility_distance +from .operators import SphericalRepairOperator, RepairConfig + + +# CPPN topology constants +_N_CPPN_INPUTS = 4 # norm_magnitude, norm_arm_yaw, norm_arm_pitch, bias +_N_CPPN_OUTPUTS = 3 # motor_yaw, motor_pitch, direction +_INPUT_LABELS = ["norm_magnitude", "norm_arm_yaw", "norm_arm_pitch", "bias"] +_OUTPUT_LABELS = ["motor_yaw", "motor_pitch", "direction"] + + +@dataclass +class HybridGenome: + """Two-part genome: direct arm parameters + CPPN for motor parameters.""" + + direct: npt.NDArray[Any] # shape (narms, 3): magnitude, arm_yaw, arm_pitch + cppn: CPPNNetwork + + def copy(self) -> HybridGenome: + return HybridGenome( + direct=self.direct.copy(), + cppn=self.cppn.copy(), + ) + + +class HybridCPPNDroneGenomeHandler(GenomeHandler): + """Hybrid genome handler: direct arm geometry + CPPN motor parameters. + + The genome consists of two parts: + + 1. **Direct encoding** — ``(narms, 3)`` array of ``[magnitude, arm_yaw, + arm_pitch]`` per arm. All rows are always active (fixed arm count). + 2. **CPPN** — A ``CPPNNetwork`` with 4 inputs (normalised arm params + + bias) and 3 tanh outputs mapped to motor parameter ranges. + + The phenotype is the standard ``(narms, 6)`` array where columns 0–2 come + from the direct encoding and columns 3–5 from CPPN evaluation. + """ + + # Shared innovation counter across the population + _innovation_counter: InnovationCounter = InnovationCounter() + + # Activation functions for hidden nodes + _HIDDEN_ACTIVATIONS = [ + ActivationFunction.SIN, + ActivationFunction.COS, + ActivationFunction.GAUSSIAN, + ActivationFunction.TANH, + ActivationFunction.ABS, + ] + + # Activation functions used when seeding initial hidden nodes + _SEED_ACTIVATIONS = [ + ActivationFunction.SIGMOID, + ActivationFunction.TANH, + ActivationFunction.GAUSSIAN, + ] + + def __init__( + self, + genome: Optional[HybridGenome] = None, + min_max_narms: Optional[Tuple[int, int]] = None, + parameter_limits: Optional[npt.NDArray[Any]] = None, + # Direct mutation parameters + prob_mutate_direct: float = 0.5, + direct_mutation_scale_pct: float = 0.05, + # CPPN mutation probabilities + prob_add_node: float = 0.03, + prob_add_connection: float = 0.05, + prob_remove_node: float = 0.01, + prob_remove_connection: float = 0.02, + prob_mutate_weights: float = 0.80, + prob_mutate_activation: float = 0.05, + prob_toggle_connection: float = 0.02, + # Initial topology complexity + initial_hidden_nodes: int = 0, + init_topology: str = "empty", # "empty" or "seeded" + # Weight / bias mutation parameters + weight_perturb_std: float = 0.5, + weight_replace_prob: float = 0.1, + weight_range: float = 3.0, + bias_perturb_std: float = 0.3, + bias_replace_prob: float = 0.1, + bias_range: float = 3.0, + # Repair + repair: bool = False, + enable_collision_repair: bool = False, + propeller_radius: float = 0.0508 / 2, + inner_boundary_radius: float = 0.0055, + outer_boundary_radius: float = 0.11, + max_repair_iterations: int = 100, + repair_step_size: float = 1.0, + propeller_tolerance: float = 0.1, + # RNG + rng: Optional[np.random.Generator] = None, + ) -> None: + # --- Do NOT call super().__init__() --- + self.fitness: float | None = None + self.rng = rng if rng is not None else np.random.default_rng() + + if min_max_narms is None: + self.min_narms, self.max_narms = 6, 6 + else: + self.min_narms, self.max_narms = min_max_narms + + if parameter_limits is None: + self.parameter_limits = np.array([ + [0.055, 0.17], # magnitude + [-np.pi, np.pi], # arm yaw (azimuth) + [-np.pi / 2, np.pi / 2], # arm pitch (elevation) + [-np.pi, np.pi], # motor pitch + [-np.pi, np.pi], # motor yaw + [0, 1], # direction + ]) + else: + self.parameter_limits = np.asarray(parameter_limits) + + # Direct mutation hyperparameters + self.prob_mutate_direct = prob_mutate_direct + self.direct_mutation_scale_pct = direct_mutation_scale_pct + + # Initial topology + self.initial_hidden_nodes = initial_hidden_nodes + self.init_topology = init_topology + + # CPPN mutation hyperparameters + self.prob_add_node = prob_add_node + self.prob_add_connection = prob_add_connection + self.prob_remove_node = prob_remove_node + self.prob_remove_connection = prob_remove_connection + self.prob_mutate_weights = prob_mutate_weights + self.prob_mutate_activation = prob_mutate_activation + self.prob_toggle_connection = prob_toggle_connection + self.weight_perturb_std = weight_perturb_std + self.weight_replace_prob = weight_replace_prob + self.weight_range = weight_range + self.bias_perturb_std = bias_perturb_std + self.bias_replace_prob = bias_replace_prob + self.bias_range = bias_range + + # Repair settings + self.repair_enabled = repair + self.enable_collision_repair = enable_collision_repair + self.propeller_radius = propeller_radius + self.inner_boundary_radius = inner_boundary_radius + self.outer_boundary_radius = outer_boundary_radius + self.max_repair_iterations = max_repair_iterations + self.repair_step_size = repair_step_size + self.propeller_tolerance = propeller_tolerance + + self._setup_repair_operator() + + # Genome + if genome is None: + self.genome: HybridGenome = self._generate_random_genome() + else: + self.genome = genome.copy() + + # ------------------------------------------------------------------ + # Repair operator setup + # ------------------------------------------------------------------ + + def _setup_repair_operator(self) -> None: + repair_config = RepairConfig( + apply_symmetry=False, + enable_collision_repair=self.enable_collision_repair, + propeller_radius=self.propeller_radius, + inner_boundary_radius=self.inner_boundary_radius, + outer_boundary_radius=self.outer_boundary_radius, + max_repair_iterations=self.max_repair_iterations, + repair_step_size=self.repair_step_size, + propeller_tolerance=self.propeller_tolerance, + ) + self.repair_operator = SphericalRepairOperator( + config=repair_config, + min_narms=self.min_narms, + max_narms=self.max_narms, + parameter_limits=self.parameter_limits, + symmetry_operator=None, + rng=self.rng, + ) + + # ------------------------------------------------------------------ + # Random genome generation + # ------------------------------------------------------------------ + + def _generate_random_genome(self) -> HybridGenome: + """Create a random hybrid genome. + + Direct part: uniform sampling for magnitude/yaw, arcsin sampling for + pitch (uniform coverage on the sphere), binary direction. + + CPPN part: fully-connected 4→3 network with optional initial hidden + nodes. + """ + narms = self.rng.integers(self.min_narms, self.max_narms + 1) + direct = np.empty((narms, 3)) + + mag_lo, mag_hi = self.parameter_limits[0] + yaw_lo, yaw_hi = self.parameter_limits[1] + pitch_lo, pitch_hi = self.parameter_limits[2] + + direct[:, 0] = self.rng.uniform(mag_lo, mag_hi, size=narms) + direct[:, 1] = self.rng.uniform(yaw_lo, yaw_hi, size=narms) + # Arcsin sampling for uniform sphere coverage + direct[:, 2] = np.arcsin( + self.rng.uniform( + np.sin(pitch_lo), np.sin(pitch_hi), size=narms + ) + ) + + cppn = self._create_initial_cppn() + return HybridGenome(direct=direct, cppn=cppn) + + def _create_initial_cppn(self) -> CPPNNetwork: + """Build a 4-input, 3-output CPPN. + + If ``init_topology == "seeded"``, adds 2–5 hidden nodes with + sigmoid/tanh/gaussian activations and ~10–20 random feed-forward + connections. Otherwise the network starts empty (classic NEAT + complexification). + """ + net = CPPNNetwork() + + # --- Input nodes --- + for i in range(_N_CPPN_INPUTS): + net.nodes[i] = NodeGene( + node_id=i, + node_type=NodeType.INPUT, + activation=ActivationFunction.IDENTITY, + bias=0.0, + input_label=_INPUT_LABELS[i], + ) + + # --- Output nodes (tanh, zero bias so all initial CPPNs are identical) --- + for j in range(_N_CPPN_OUTPUTS): + nid = _N_CPPN_INPUTS + j + net.nodes[nid] = NodeGene( + node_id=nid, + node_type=NodeType.OUTPUT, + activation=ActivationFunction.TANH, + bias=0.0, + output_index=j, + ) + + net.next_node_id = _N_CPPN_INPUTS + _N_CPPN_OUTPUTS + + if self.init_topology == "seeded": + self._seed_topology(net, _N_CPPN_INPUTS, _N_CPPN_OUTPUTS) + + return net + + def _seed_topology( + self, net: CPPNNetwork, n_inputs: int, n_outputs: int, + ) -> None: + """Add 2–5 hidden nodes and ~10–20 random feed-forward connections.""" + n_hidden = int(self.rng.integers(2, 6)) + + input_ids = list(range(n_inputs)) + output_ids = list(range(n_inputs, n_inputs + n_outputs)) + hidden_ids = [] + + for _ in range(n_hidden): + nid = net.next_node_id + net.next_node_id += 1 + activation = self.rng.choice(self._SEED_ACTIVATIONS) + net.nodes[nid] = NodeGene( + node_id=nid, + node_type=NodeType.HIDDEN, + activation=activation, + bias=float(self.rng.uniform(-1.0, 1.0)), + ) + hidden_ids.append(nid) + + possible = [] + for src in input_ids: + for tgt in hidden_ids + output_ids: + possible.append((src, tgt)) + for src in hidden_ids: + for tgt in output_ids: + possible.append((src, tgt)) + for i, src in enumerate(hidden_ids): + for tgt in hidden_ids[i + 1:]: + possible.append((src, tgt)) + + n_target = int(self.rng.integers(10, 21)) + n_conns = min(n_target, len(possible)) + chosen = self.rng.choice(len(possible), size=n_conns, replace=False) + + for idx in chosen: + src, tgt = possible[idx] + inn = self._innovation_counter.get_innovation(src, tgt) + net.connections[inn] = ConnectionGene( + innovation_number=inn, + source_id=src, + target_id=tgt, + weight=float(self.rng.uniform(-1.0, 1.0)), + enabled=True, + ) + + # ------------------------------------------------------------------ + # Phenotype decoding + # ------------------------------------------------------------------ + + def get_phenotype(self) -> npt.NDArray[Any]: + """Decode the hybrid genome into a ``(narms, 6)`` phenotype array. + + Columns 0–2 come from the direct encoding. Columns 3–5 are produced + by evaluating the CPPN with normalised arm parameters as input and + mapping the tanh outputs to the motor parameter ranges. + """ + narms = self.genome.direct.shape[0] + phenotype = np.empty((narms, 6)) + + # Columns 0–2: direct arm geometry + phenotype[:, :3] = self.genome.direct + + # Normalise direct params to [-1, 1] for CPPN input + limits = self.parameter_limits[:3] # (3, 2) for magnitude, yaw, pitch + lo = limits[:, 0] # (3,) + hi = limits[:, 1] # (3,) + ranges = hi - lo + # Avoid division by zero for degenerate limits + ranges = np.where(ranges == 0, 1.0, ranges) + normalised = 2.0 * (self.genome.direct - lo) / ranges - 1.0 # (narms, 3) + + # Build CPPN input: [norm_mag, norm_yaw, norm_pitch, bias=1.0] + cppn_input = np.column_stack([ + normalised, + np.ones(narms), + ]) # (narms, 4) + + # Evaluate CPPN (batch mode) + cppn_output = evaluate_cppn(self.genome.cppn, cppn_input) # (narms, 3) + + # Map tanh outputs [-1, 1] to motor parameter ranges + # CPPN outputs: [motor_yaw, motor_pitch, direction] + # Phenotype cols 3-4: [motor_pitch, motor_yaw] — swap to match convention + motor_limits = self.parameter_limits[3:] # (3, 2): [pitch_lim, yaw_lim, dir_lim] + motor_lo = motor_limits[:, 0] + motor_hi = motor_limits[:, 1] + # tanh output in [-1, 1] → [lo, hi], reorder CPPN outputs to [pitch, yaw] + cppn_motor_reordered = cppn_output[:, [1, 0]] + phenotype[:, 3:5] = ( + motor_lo[:2] + + (cppn_motor_reordered + 1.0) * 0.5 * (motor_hi[:2] - motor_lo[:2]) + ) + # Direction: threshold at 0 + phenotype[:, 5] = np.where(cppn_output[:, 2] >= 0.0, 1.0, 0.0) + + if self.repair_enabled: + phenotype = self.repair_operator.repair(phenotype) + + return phenotype + + # ------------------------------------------------------------------ + # Mutation + # ------------------------------------------------------------------ + + def mutate(self) -> None: + """Mutate either the direct or CPPN part of the genome.""" + if self.rng.random() < self.prob_mutate_direct: + self._mutate_direct() + else: + self._mutate_cppn() + + def _mutate_direct(self) -> None: + """Gaussian perturbation of one parameter of one random arm.""" + narms = self.genome.direct.shape[0] + arm_idx = self.rng.integers(narms) + param_idx = self.rng.integers(3) # 0=magnitude, 1=yaw, 2=pitch + + lo, hi = self.parameter_limits[param_idx] + scale = (hi - lo) * self.direct_mutation_scale_pct + perturbation = self.rng.normal(0, scale) + + new_val = self.genome.direct[arm_idx, param_idx] + perturbation + + if param_idx in (1, 2): + # Angle wrapping to [lo, hi] using modular arithmetic + span = hi - lo + new_val = lo + (new_val - lo) % span + else: + new_val = np.clip(new_val, lo, hi) + + self.genome.direct[arm_idx, param_idx] = new_val + + def _mutate_cppn(self) -> None: + """Delegate to NEAT-style CPPN mutation.""" + mutate_cppn( + self.genome.cppn, + self._innovation_counter, + self.rng, + prob_add_node=self.prob_add_node, + prob_add_connection=self.prob_add_connection, + prob_remove_node=self.prob_remove_node, + prob_remove_connection=self.prob_remove_connection, + prob_mutate_weights=self.prob_mutate_weights, + prob_mutate_activation=self.prob_mutate_activation, + prob_toggle_connection=self.prob_toggle_connection, + weight_perturb_std=self.weight_perturb_std, + weight_replace_prob=self.weight_replace_prob, + weight_range=self.weight_range, + bias_perturb_std=self.bias_perturb_std, + bias_replace_prob=self.bias_replace_prob, + bias_range=self.bias_range, + ) + + # ------------------------------------------------------------------ + # GenomeHandler interface + # ------------------------------------------------------------------ + + def generate_random_population( + self, population_size: int + ) -> List[HybridCPPNDroneGenomeHandler]: + population: List[HybridCPPNDroneGenomeHandler] = [] + for _ in range(population_size): + handler = HybridCPPNDroneGenomeHandler( + genome=None, + min_max_narms=(self.min_narms, self.max_narms), + parameter_limits=self.parameter_limits, + prob_mutate_direct=self.prob_mutate_direct, + direct_mutation_scale_pct=self.direct_mutation_scale_pct, + initial_hidden_nodes=self.initial_hidden_nodes, + init_topology=self.init_topology, + prob_add_node=self.prob_add_node, + prob_add_connection=self.prob_add_connection, + prob_remove_node=self.prob_remove_node, + prob_remove_connection=self.prob_remove_connection, + prob_mutate_weights=self.prob_mutate_weights, + prob_mutate_activation=self.prob_mutate_activation, + prob_toggle_connection=self.prob_toggle_connection, + weight_perturb_std=self.weight_perturb_std, + weight_replace_prob=self.weight_replace_prob, + weight_range=self.weight_range, + bias_perturb_std=self.bias_perturb_std, + bias_replace_prob=self.bias_replace_prob, + bias_range=self.bias_range, + repair=self.repair_enabled, + enable_collision_repair=self.enable_collision_repair, + propeller_radius=self.propeller_radius, + inner_boundary_radius=self.inner_boundary_radius, + outer_boundary_radius=self.outer_boundary_radius, + max_repair_iterations=self.max_repair_iterations, + repair_step_size=self.repair_step_size, + propeller_tolerance=self.propeller_tolerance, + rng=self.rng, + ) + population.append(handler) + return population + + def crossover(self, other: HybridCPPNDroneGenomeHandler) -> HybridCPPNDroneGenomeHandler: + """Crossover hybrid genomes: NEAT crossover for CPPN, arm-wise for direct.""" + # CPPN part: NEAT-style aligned crossover + child_cppn = crossover_cppn( + self.genome.cppn, other.genome.cppn, + self.fitness, other.fitness, + self.rng, + ) + + # Direct part: arm-wise random selection from fitter parent's arm count + # Determine which parent is fitter to inherit arm count + if self.fitness is not None and other.fitness is not None: + if self.fitness >= other.fitness: + fitter_direct, other_direct = self.genome.direct, other.genome.direct + else: + fitter_direct, other_direct = other.genome.direct, self.genome.direct + else: + fitter_direct, other_direct = self.genome.direct, other.genome.direct + + narms_child = fitter_direct.shape[0] + narms_other = other_direct.shape[0] + child_direct = np.empty((narms_child, 3)) + + for i in range(narms_child): + if i < narms_other and self.rng.random() < 0.5: + child_direct[i] = other_direct[i] + else: + child_direct[i] = fitter_direct[i] + + child_genome = HybridGenome(direct=child_direct, cppn=child_cppn) + return HybridCPPNDroneGenomeHandler( + genome=child_genome, + min_max_narms=(self.min_narms, self.max_narms), + parameter_limits=self.parameter_limits, + prob_mutate_direct=self.prob_mutate_direct, + direct_mutation_scale_pct=self.direct_mutation_scale_pct, + initial_hidden_nodes=self.initial_hidden_nodes, + init_topology=self.init_topology, + prob_add_node=self.prob_add_node, + prob_add_connection=self.prob_add_connection, + prob_remove_node=self.prob_remove_node, + prob_remove_connection=self.prob_remove_connection, + prob_mutate_weights=self.prob_mutate_weights, + prob_mutate_activation=self.prob_mutate_activation, + prob_toggle_connection=self.prob_toggle_connection, + weight_perturb_std=self.weight_perturb_std, + weight_replace_prob=self.weight_replace_prob, + weight_range=self.weight_range, + bias_perturb_std=self.bias_perturb_std, + bias_replace_prob=self.bias_replace_prob, + bias_range=self.bias_range, + repair=self.repair_enabled, + enable_collision_repair=self.enable_collision_repair, + propeller_radius=self.propeller_radius, + inner_boundary_radius=self.inner_boundary_radius, + outer_boundary_radius=self.outer_boundary_radius, + max_repair_iterations=self.max_repair_iterations, + repair_step_size=self.repair_step_size, + propeller_tolerance=self.propeller_tolerance, + rng=self.rng, + ) + + def crossover_population( + self, + population1: List[GenomeHandler], + population2: List[GenomeHandler], + ) -> List[GenomeHandler]: + """Perform crossover on paired populations.""" + assert len(population1) == len(population2) + return [p1.crossover(p2) for p1, p2 in zip(population1, population2)] + + def copy(self) -> HybridCPPNDroneGenomeHandler: + return HybridCPPNDroneGenomeHandler( + genome=self.genome, + min_max_narms=(self.min_narms, self.max_narms), + parameter_limits=self.parameter_limits, + prob_mutate_direct=self.prob_mutate_direct, + direct_mutation_scale_pct=self.direct_mutation_scale_pct, + initial_hidden_nodes=self.initial_hidden_nodes, + init_topology=self.init_topology, + prob_add_node=self.prob_add_node, + prob_add_connection=self.prob_add_connection, + prob_remove_node=self.prob_remove_node, + prob_remove_connection=self.prob_remove_connection, + prob_mutate_weights=self.prob_mutate_weights, + prob_mutate_activation=self.prob_mutate_activation, + prob_toggle_connection=self.prob_toggle_connection, + weight_perturb_std=self.weight_perturb_std, + weight_replace_prob=self.weight_replace_prob, + weight_range=self.weight_range, + bias_perturb_std=self.bias_perturb_std, + bias_replace_prob=self.bias_replace_prob, + bias_range=self.bias_range, + repair=self.repair_enabled, + enable_collision_repair=self.enable_collision_repair, + propeller_radius=self.propeller_radius, + inner_boundary_radius=self.inner_boundary_radius, + outer_boundary_radius=self.outer_boundary_radius, + max_repair_iterations=self.max_repair_iterations, + repair_step_size=self.repair_step_size, + propeller_tolerance=self.propeller_tolerance, + rng=self.rng, + ) + + def is_valid(self) -> bool: + """Check that the arm count falls within bounds.""" + narms = self.genome.direct.shape[0] + return self.min_narms <= narms <= self.max_narms + + def compatibility_distance(self, other: HybridCPPNDroneGenomeHandler) -> float: + """Compatibility distance combining CPPN topology and direct parameter distance.""" + cppn_dist = cppn_compatibility_distance(self.genome.cppn, other.genome.cppn) + direct_dist = self._direct_parameter_distance(other) + return cppn_dist + direct_dist + + def _direct_parameter_distance(self, other: HybridCPPNDroneGenomeHandler) -> float: + """Normalized Euclidean distance between direct parameter arrays.""" + d1 = self.genome.direct + d2 = other.genome.direct + # Normalize by parameter ranges + ranges = self.parameter_limits[:3, 1] - self.parameter_limits[:3, 0] + ranges = np.where(ranges == 0, 1.0, ranges) + + min_arms = min(d1.shape[0], d2.shape[0]) + max_arms = max(d1.shape[0], d2.shape[0]) + + if min_arms == 0: + return float(max_arms) + + # Distance over overlapping arms + norm1 = d1[:min_arms] / ranges + norm2 = d2[:min_arms] / ranges + overlap_dist = float(np.mean(np.sqrt(np.sum((norm1 - norm2) ** 2, axis=1)))) + + # Penalty for arm count difference + arm_penalty = (max_arms - min_arms) / max_arms + return overlap_dist + arm_penalty + + def repair(self) -> None: + """No-op — repair is applied to the decoded phenotype in get_phenotype().""" + pass diff --git a/src/ariel/ec/drone/genome_handlers/mounting_points.py b/src/ariel/ec/drone/genome_handlers/mounting_points.py new file mode 100644 index 000000000..d5becaaad --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/mounting_points.py @@ -0,0 +1,109 @@ +""" +Mounting Point Generator + +This module provides utilities for generating mounting points on a central disc structure. +Used for realistic inertia calculations where drone arms attach to a central body/disc +rather than all emanating from a single origin point. +""" + +import numpy as np + + +def generate_disc_mounting_points(num_points=8, diameter=0.060, z_offset=0.0): + """ + Generate equally-spaced mounting points around a disc. + + This creates mounting points on a flat disc in the XY plane, representing + where drone arms attach to a central body structure. Points are evenly + distributed in a circular pattern. + + Args: + num_points (int): Number of mounting points to generate (default: 8) + diameter (float): Disc diameter in meters (default: 0.060 = 60mm) + z_offset (float): Z-coordinate offset for all points (default: 0.0) + + Returns: + list: List of np.array([x, y, z]) mounting point coordinates + + Example: + >>> # Generate 8 mounting points on 60mm diameter disc + >>> points = generate_disc_mounting_points(8, 0.060) + >>> len(points) + 8 + >>> # Points are evenly spaced at 45 degree intervals + >>> angles = [0, π/4, π/2, 3π/4, π, 5π/4, 3π/2, 7π/4] + """ + radius = diameter / 2.0 + mounting_points = [] + + for i in range(num_points): + angle = 2 * np.pi * i / num_points + x = radius * np.cos(angle) + y = radius * np.sin(angle) + z = z_offset + mounting_points.append(np.array([x, y, z])) + + return mounting_points + + +def assign_nearest_mounting_point(propeller_positions, mounting_points): + """ + Assign each propeller to its nearest mounting point. + + For each propeller location, finds the closest mounting point on the disc. + This simulates realistic attachment where arms connect to the nearest + available mounting point on the central body. + + Args: + propeller_positions (list or np.ndarray): List of [x, y, z] propeller locations + mounting_points (list): List of np.array mounting point coordinates + + Returns: + list: List of np.array mounting points, one per propeller (same order) + + Example: + >>> prop_locs = [[0.10, 0.10, 0], [-0.10, 0.10, 0]] + >>> mount_pts = generate_disc_mounting_points(8, 0.060) + >>> assigned = assign_nearest_mounting_point(prop_locs, mount_pts) + >>> len(assigned) == len(prop_locs) + True + """ + propeller_positions = np.array(propeller_positions) + assigned_points = [] + + for prop_pos in propeller_positions: + # Calculate distances to all mounting points (XY plane only) + distances = [] + for mount_pt in mounting_points: + # Use XY distance only (ignore Z for assignment) + dist = np.sqrt((prop_pos[0] - mount_pt[0])**2 + + (prop_pos[1] - mount_pt[1])**2) + distances.append(dist) + + # Find nearest mounting point + nearest_idx = np.argmin(distances) + assigned_points.append(mounting_points[nearest_idx].copy()) + + return assigned_points + + +def get_default_mounting_points(num_propellers): + """ + Get default mounting points configuration for a given number of propellers. + + Uses an 8-point disc (60mm diameter) and assigns each propeller to the + nearest mounting point. This is the standard configuration for evolved drones. + + Args: + num_propellers (int): Number of propellers on the drone + + Returns: + list: List of mounting points, one per propeller (all at origin for backwards compatibility) + To use disc mounting, call generate_disc_mounting_points() directly + + Note: + For backward compatibility, this returns origin points by default. + Use generate_disc_mounting_points() for disc-based mounting. + """ + # Return origin points for backward compatibility + return [np.array([0.0, 0.0, 0.0]) for _ in range(num_propellers)] diff --git a/src/ariel/ec/drone/genome_handlers/operators/__init__.py b/src/ariel/ec/drone/genome_handlers/operators/__init__.py new file mode 100644 index 000000000..31a5c4639 --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/operators/__init__.py @@ -0,0 +1,36 @@ +""" +Operators module for genome handlers. + +This module provides standardized symmetry and repair operators that can be used +across different genome handler implementations. +""" + +from .symmetry_base import SymmetryOperator, SymmetryConfig, SymmetryPlane, SymmetryUtilities +from .repair_base import RepairOperator, RepairConfig, RepairStrategy, RepairUtilities +from .symmetry_cartesian import CartesianSymmetryOperator +from .symmetry_spherical import SphericalSymmetryOperator +from .repair_cartesian import CartesianRepairOperator +from .repair_spherical import SphericalRepairOperator +from .optimization_repair_operator import ( + OptimizationBasedRepairOperator, + OptimizationRepairConfig, + optimization_repair_individual +) + +__all__ = [ + 'SymmetryOperator', + 'SymmetryConfig', + 'SymmetryPlane', + 'SymmetryUtilities', + 'RepairOperator', + 'RepairConfig', + 'RepairStrategy', + 'RepairUtilities', + 'CartesianSymmetryOperator', + 'SphericalSymmetryOperator', + 'CartesianRepairOperator', + 'SphericalRepairOperator', + 'OptimizationBasedRepairOperator', + 'OptimizationRepairConfig', + 'optimization_repair_individual' +] \ No newline at end of file diff --git a/src/ariel/ec/drone/genome_handlers/operators/optimization_repair_operator.py b/src/ariel/ec/drone/genome_handlers/operators/optimization_repair_operator.py new file mode 100644 index 000000000..d70f6d1fb --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/operators/optimization_repair_operator.py @@ -0,0 +1,1251 @@ +""" +Optimization-based repair operator for drone genomes. + +This module implements a deterministic optimization-based repair operator that +formulates collision repair as a constrained optimization problem. It minimizes +changes to the original genome while ensuring: +- Cylinders don't collide with each other +- Cylinders don't intersect the central core sphere +- Arms attach to a disc base (not at the origin) +- All spatial constraints are satisfied + +The disc-based attachment model: +- Arms attach at the edge of a disc perpendicular to the z-axis +- The disc has radius > core_radius, allowing arms to tilt inward +- The arm base point is computed as the closest point on the disc edge to the target position +""" + +from __future__ import annotations + +import numpy as np +import numpy.typing as npt +from typing import Any, Optional, Dict, List, Tuple, Callable +from dataclasses import dataclass +from scipy.optimize import minimize, Bounds +import warnings + +from ariel.ec.drone.genome_handlers.conversions.arm_conversions import ( + Cylinder, + arms_to_cylinders_polar_angular, + cylinders_to_arms_polar_angular, + arms_to_cylinders_cartesian_euler, + cylinders_to_arms_cartesian_euler, +) +from .repair_base import RepairOperator, RepairConfig + + +# ============================================================================ +# CONFIGURATION +# ============================================================================ + +@dataclass +class OptimizationRepairConfig: + """Configuration for optimization-based repair.""" + + # Disc parameters + disc_radius: float = 0.15 # Radius of disc (> core_radius) + disc_height: float = 0.0 # Z-coordinate of disc plane + + # Core sphere parameters + core_radius: float = 0.05 # Radius of central core sphere + + # Optimization parameters + optimization_method: str = 'SLSQP' # 'SLSQP' or 'trust-constr' + max_iterations: int = 1000 + constraint_tolerance: float = 1e-6 + optimization_tolerance: float = 1e-6 + + # Multi-start optimization parameters + use_multi_start: bool = True # Enable multi-start optimization + n_starts: int = 3 # Number of starting points to try + multi_start_perturbation: float = 0.1 # Perturbation magnitude for additional starts + + # Angle normalization + normalize_angles: bool = True # Wrap angles to [-π, π] before optimization + + # Clearance parameters + propeller_radius: float = 0.0254 # 2-inch propeller radius in meters + propeller_tolerance: float = 0.1 + cylinder_height: float = None # Will be set to 8 * propeller_radius in __post_init__ + + # Boundary constraints + inner_boundary_radius: float = 0.09 + outer_boundary_radius: float = 0.4 + + # Singularity handling (avoid targets directly above disc center) + min_xy_projection: float = 0.01 + + # Parameter bounds (for spherical coordinates) + r_bounds: Tuple[float, float] = (0.09, 0.4) + theta_bounds: Tuple[float, float] = (-np.pi, np.pi) + phi_bounds: Tuple[float, float] = (-np.pi, np.pi) + pitch_bounds: Tuple[float, float] = (-2*np.pi/3, 2*np.pi/3) # ±120° (was ±180°) + yaw_bounds: Tuple[float, float] = (-np.pi, np.pi) + + # Fixed parameters (parameters that should not be modified during optimization) + # List of parameter indices to fix: 0=r, 1=theta, 2=phi, 3=pitch, 4=yaw + # For example, [1, 2] will fix theta and phi + fixed_params: List[int] = None # None means all parameters can be optimized + + def __post_init__(self): + """Validate configuration parameters and set derived values.""" + # Set cylinder_height to 8 * propeller_radius if not explicitly set + if self.cylinder_height is None: + object.__setattr__(self, 'cylinder_height', 8 * self.propeller_radius) + + assert self.disc_radius > self.core_radius, \ + "Disc radius must be greater than core radius" + assert self.core_radius > 0, "Core radius must be positive" + assert self.propeller_radius > 0, "Propeller radius must be positive" + assert self.cylinder_height > 0, "Cylinder height must be positive" + assert self.inner_boundary_radius < self.outer_boundary_radius, \ + "Inner boundary must be less than outer boundary" + assert self.n_starts >= 1, "Must have at least one starting point" + assert 0.0 <= self.multi_start_perturbation <= 1.0, \ + "Perturbation magnitude must be in [0, 1]" + + +# ============================================================================ +# GEOMETRIC UTILITY FUNCTIONS +# ============================================================================ + +def compute_base_point( + target_position: npt.NDArray[Any], + disc_radius: float, + disc_height: float, + min_xy_projection: float = 0.01 +) -> npt.NDArray[Any]: + """ + Compute the base attachment point on the disc edge for a given target position. + + The base point is the point on the disc edge (circle at z=disc_height with + radius=disc_radius) that is closest to the target position in the xy-plane. + + Parameters: + ----------- + target_position : array-like of shape (3,) + Target position [x, y, z] from genome + disc_radius : float + Radius of the disc + disc_height : float + Z-coordinate of the disc plane + min_xy_projection : float + Minimum xy-projection to avoid singularity + + Returns: + -------- + base_point : ndarray of shape (3,) + Base attachment point [x, y, z] on disc edge + """ + x, y, z = target_position + r_xy = np.sqrt(x**2 + y**2) + + # Handle singularity: target directly above/below disc center + if r_xy < min_xy_projection: + # Default to arbitrary point on disc edge (along x-axis) + return np.array([disc_radius, 0.0, disc_height]) + + # Compute base point on disc edge + base_x = disc_radius * (x / r_xy) + base_y = disc_radius * (y / r_xy) + base_z = disc_height + + return np.array([base_x, base_y, base_z]) + + +def closest_point_on_line_segment_to_point( + p1: npt.NDArray[Any], + p2: npt.NDArray[Any], + point: npt.NDArray[Any] +) -> Tuple[npt.NDArray[Any], float]: + """ + Find the closest point on a line segment to a given point. + + Parameters: + ----------- + p1 : array-like of shape (3,) + First endpoint of line segment + p2 : array-like of shape (3,) + Second endpoint of line segment + point : array-like of shape (3,) + Query point + + Returns: + -------- + closest_point : ndarray of shape (3,) + Closest point on line segment to query point + t : float + Parameter t ∈ [0, 1] where closest_point = p1 + t*(p2-p1) + """ + p1 = np.asarray(p1) + p2 = np.asarray(p2) + point = np.asarray(point) + + segment_vec = p2 - p1 + segment_length_sq = np.dot(segment_vec, segment_vec) + + # Handle degenerate case: p1 == p2 + if segment_length_sq < 1e-12: + return p1.copy(), 0.0 + + # Project point onto infinite line + t = np.dot(point - p1, segment_vec) / segment_length_sq + + # Clamp to segment + t = np.clip(t, 0.0, 1.0) + + closest_point = p1 + t * segment_vec + + return closest_point, t + + +def line_segment_to_point_distance( + p1: npt.NDArray[Any], + p2: npt.NDArray[Any], + point: npt.NDArray[Any] +) -> float: + """ + Compute minimum distance from a line segment to a point. + + Parameters: + ----------- + p1, p2 : array-like of shape (3,) + Endpoints of line segment + point : array-like of shape (3,) + Query point + + Returns: + -------- + distance : float + Minimum distance from line segment to point + """ + closest_point, _ = closest_point_on_line_segment_to_point(p1, p2, point) + return np.linalg.norm(closest_point - point) + + +def line_segment_to_sphere_distance( + p1: npt.NDArray[Any], + p2: npt.NDArray[Any], + sphere_center: npt.NDArray[Any], + sphere_radius: float +) -> float: + """ + Compute the signed distance from a line segment to a sphere surface. + + Returns: + -------- + distance : float + Signed distance to sphere surface: + - Positive: line segment is outside sphere (no collision) + - Zero: line segment touches sphere surface + - Negative: line segment intersects sphere (collision) + """ + min_dist_to_center = line_segment_to_point_distance(p1, p2, sphere_center) + return min_dist_to_center - sphere_radius + + +def line_segment_to_line_segment_distance( + p1: npt.NDArray[Any], + p2: npt.NDArray[Any], + q1: npt.NDArray[Any], + q2: npt.NDArray[Any] +) -> float: + """ + Compute minimum distance between two line segments in 3D. + + Uses the algorithm from: + http://geomalgorithms.com/a07-_distance.html + + Parameters: + ----------- + p1, p2 : array-like of shape (3,) + Endpoints of first line segment + q1, q2 : array-like of shape (3,) + Endpoints of second line segment + + Returns: + -------- + distance : float + Minimum distance between the two line segments + """ + p1 = np.asarray(p1) + p2 = np.asarray(p2) + q1 = np.asarray(q1) + q2 = np.asarray(q2) + + u = p2 - p1 # Direction of segment 1 + v = q2 - q1 # Direction of segment 2 + w = p1 - q1 # Vector from q1 to p1 + + a = np.dot(u, u) # |u|^2 + b = np.dot(u, v) + c = np.dot(v, v) # |v|^2 + d = np.dot(u, w) + e = np.dot(v, w) + + denominator = a * c - b * b # Always >= 0 + + # Handle parallel/degenerate segments + if denominator < 1e-12: + # Segments are parallel or degenerate + # Use distance from p1 to segment q1-q2 + s = 0.0 + t = (b > c) and (d / b) or (e / c) if c > 1e-12 else 0.0 + t = np.clip(t, 0.0, 1.0) + else: + # General case: compute closest points + s = (b * e - c * d) / denominator + t = (a * e - b * d) / denominator + + # Clamp s and t to [0, 1] + s = np.clip(s, 0.0, 1.0) + t = np.clip(t, 0.0, 1.0) + + # Re-clamp after first clamping (handles edge cases) + if s == 0.0 or s == 1.0: + t = np.clip((b * s + e) / c, 0.0, 1.0) if c > 1e-12 else 0.0 + if t == 0.0 or t == 1.0: + s = np.clip((b * t - d) / a, 0.0, 1.0) if a > 1e-12 else 0.0 + + # Compute closest points + closest_p = p1 + s * u + closest_q = q1 + t * v + + return np.linalg.norm(closest_p - closest_q) + + +def cylinder_to_cylinder_distance( + cyl1_p1: npt.NDArray[Any], + cyl1_p2: npt.NDArray[Any], + cyl1_radius: float, + cyl2_p1: npt.NDArray[Any], + cyl2_p2: npt.NDArray[Any], + cyl2_radius: float +) -> float: + """ + Compute the minimum distance between two cylinders (as capsules). + + Parameters: + ----------- + cyl1_p1, cyl1_p2 : array-like of shape (3,) + Endpoints of first cylinder axis + cyl1_radius : float + Radius of first cylinder + cyl2_p1, cyl2_p2 : array-like of shape (3,) + Endpoints of second cylinder axis + cyl2_radius : float + Radius of second cylinder + + Returns: + -------- + distance : float + Minimum surface-to-surface distance between cylinders + (positive = no collision, zero/negative = collision) + """ + axis_distance = line_segment_to_line_segment_distance( + cyl1_p1, cyl1_p2, cyl2_p1, cyl2_p2 + ) + return axis_distance - (cyl1_radius + cyl2_radius) + + +# ============================================================================ +# CONVERSION FUNCTIONS WITH DISC BASE +# ============================================================================ + +def genome_to_arm_cylinders_with_disc_base( + genome: npt.NDArray[Any], + config: OptimizationRepairConfig, + arms_to_cylinders_func: Callable = arms_to_cylinders_polar_angular +) -> List[Tuple[npt.NDArray[Any], npt.NDArray[Any], Cylinder]]: + """ + Convert genome to arm cylinder representations with disc-based attachment. + + Parameters: + ----------- + genome : array-like of shape (n_arms, 6) + Genome with parameters [r, theta, phi, pitch, yaw, direction] + config : OptimizationRepairConfig + Configuration with disc and cylinder parameters + arms_to_cylinders_func : callable + Function to convert genome to cylinder target positions + + Returns: + -------- + arm_cylinders : list of tuples + Each tuple contains (endpoint1, endpoint2, cylinder) + where endpoint1 and endpoint2 are the actual cylinder axis endpoints + """ + # Convert genome to cylinders (to get positions and orientations) + cylinders = arms_to_cylinders_func( + genome, + propeller_radius=config.propeller_radius, + cylinder_height=config.cylinder_height + ) + + arm_cylinders = [] + + for cyl in cylinders: + # Get the actual cylinder endpoints + endpoint1, endpoint2 = cyl.get_endpoints() + arm_cylinders.append((endpoint1, endpoint2, cyl)) + + return arm_cylinders + + +# ============================================================================ +# GEOMETRY CACHE FOR CONSTRAINT EVALUATIONS +# ============================================================================ + +class GeometryCache: + """ + Cache for arm cylinder geometry to avoid redundant conversions. + + During optimization, many constraint functions need the same geometry. + This cache ensures we only compute it once per unique parameter vector. + """ + + def __init__(self): + self._cache_key = None + self._arm_cylinders = None + self._hit_count = 0 + self._miss_count = 0 + + def get_arm_cylinders( + self, + x_flat: npt.NDArray[Any], + config: OptimizationRepairConfig, + arms_to_cylinders_func: Callable, + n_params: int, + direction_column: npt.NDArray[Any] + ) -> List[Tuple[npt.NDArray[Any], npt.NDArray[Any], Cylinder]]: + """ + Get arm cylinders for given parameters, using cache when possible. + + Parameters: + ----------- + x_flat : array + Flattened parameter vector + config : OptimizationRepairConfig + Configuration + arms_to_cylinders_func : callable + Conversion function + n_params : int + Number of parameters per arm (5 or 6) + direction_column : array + Direction values for each arm + + Returns: + -------- + arm_cylinders : list + List of (endpoint1, endpoint2, cylinder) tuples + """ + # Create cache key from parameter vector + # Using tobytes() is faster than hash for small arrays + key = x_flat.tobytes() + + if key == self._cache_key: + self._hit_count += 1 + return self._arm_cylinders + + # Cache miss - compute geometry + self._miss_count += 1 + n_arms = len(x_flat) // n_params + genome = x_flat.reshape(n_arms, n_params) + + # Add direction column + genome_with_dir = np.column_stack([genome, direction_column]) + + # Get arm cylinders with disc base + self._arm_cylinders = genome_to_arm_cylinders_with_disc_base( + genome_with_dir, config, arms_to_cylinders_func + ) + + self._cache_key = key + return self._arm_cylinders + + def get_stats(self) -> dict: + """Get cache statistics.""" + total = self._hit_count + self._miss_count + hit_rate = self._hit_count / total if total > 0 else 0.0 + return { + 'hits': self._hit_count, + 'misses': self._miss_count, + 'total_requests': total, + 'hit_rate': hit_rate + } + + def reset(self): + """Reset cache and statistics.""" + self._cache_key = None + self._arm_cylinders = None + self._hit_count = 0 + self._miss_count = 0 + + +# ============================================================================ +# CONSTRAINT FUNCTIONS FOR OPTIMIZATION +# ============================================================================ + +def create_cylinder_cylinder_constraint( + i: int, + j: int, + config: OptimizationRepairConfig, + arms_to_cylinders_func: Callable, + geometry_cache: GeometryCache, + n_params: int, + direction_column: npt.NDArray[Any] +) -> Callable: + """ + Create a constraint function for non-collision between two cylinders. + + Parameters: + ----------- + i, j : int + Indices of the two arms + config : OptimizationRepairConfig + Repair configuration + arms_to_cylinders_func : callable + Function to convert genome parameters to cylinders + geometry_cache : GeometryCache + Shared cache for geometry computations + n_params : int + Number of parameters per arm (5 or 6) + direction_column : array + Direction values for each arm + + Returns: + -------- + constraint_func : callable + Function that takes flattened genome and returns signed distance + (positive = no collision, zero/negative = collision) + """ + required_clearance = (2 + config.propeller_tolerance) * config.propeller_radius + + def constraint(x_flat: npt.NDArray[Any]) -> float: + # Get arm cylinders from cache (avoiding redundant computation) + arm_cylinders = geometry_cache.get_arm_cylinders( + x_flat, config, arms_to_cylinders_func, n_params, direction_column + ) + + # Get the two arms + base_i, target_i, _ = arm_cylinders[i] + base_j, target_j, _ = arm_cylinders[j] + + # Compute cylinder-to-cylinder distance + distance = cylinder_to_cylinder_distance( + base_i, target_i, config.propeller_radius, + base_j, target_j, config.propeller_radius + ) + + # Return signed distance (should be >= required_clearance) + return distance - required_clearance + + return constraint + + +def create_cylinder_sphere_constraint( + arm_idx: int, + config: OptimizationRepairConfig, + arms_to_cylinders_func: Callable, + geometry_cache: GeometryCache, + n_params: int, + direction_column: npt.NDArray[Any] +) -> Callable: + """ + Create a constraint function for non-collision between arm cylinder and core sphere. + + Parameters: + ----------- + arm_idx : int + Index of the arm + config : OptimizationRepairConfig + Repair configuration + arms_to_cylinders_func : callable + Function to convert genome parameters to cylinders + geometry_cache : GeometryCache + Shared cache for geometry computations + n_params : int + Number of parameters per arm (5 or 6) + direction_column : array + Direction values for each arm + + Returns: + -------- + constraint_func : callable + Function that takes flattened genome and returns signed distance + """ + sphere_center = np.array([0.0, 0.0, 0.0]) + required_clearance = config.propeller_radius + + def constraint(x_flat: npt.NDArray[Any]) -> float: + # Get arm cylinders from cache (avoiding redundant computation) + arm_cylinders = geometry_cache.get_arm_cylinders( + x_flat, config, arms_to_cylinders_func, n_params, direction_column + ) + + # Get the arm + base_point, target_point, _ = arm_cylinders[arm_idx] + + # Compute line segment to sphere distance + distance = line_segment_to_sphere_distance( + base_point, target_point, sphere_center, config.core_radius + ) + + # Return signed distance (should be >= required_clearance) + return distance - required_clearance + + return constraint + + +def create_xy_projection_constraint( + arm_idx: int, + param_start_idx: int, + min_xy_projection: float +) -> Callable: + """ + Create a constraint to avoid singularity (target directly above disc center). + + This constraint ensures r_xy = sqrt(x^2 + y^2) >= min_xy_projection + for the target position. + """ + def constraint(x_flat: npt.NDArray[Any]) -> float: + # Extract r, theta parameters for this arm + r = x_flat[param_start_idx] + theta = x_flat[param_start_idx + 1] + phi = x_flat[param_start_idx + 2] + + # Convert to Cartesian for xy-projection check + x = r * np.sin(phi) * np.cos(theta) + y = r * np.sin(phi) * np.sin(theta) + r_xy = np.sqrt(x**2 + y**2) + + # Return r_xy - min_xy_projection (should be >= 0) + return r_xy - min_xy_projection + + return constraint + + +# ============================================================================ +# ANGLE NORMALIZATION AND MULTI-START HELPERS +# ============================================================================ + +def normalize_angles(genome: npt.NDArray[Any], angle_indices: List[int] = [1, 2, 3, 4]) -> npt.NDArray[Any]: + """ + Normalize angles to [-π, π] range. + + Parameters: + ----------- + genome : array-like of shape (n_arms, 5) + Genome parameters [r, theta, phi, pitch, yaw] + angle_indices : list of int + Indices of angular parameters (default: [1, 2, 3, 4] for theta, phi, pitch, yaw) + + Returns: + -------- + normalized_genome : array-like of shape (n_arms, 5) + Genome with normalized angles + """ + genome_normalized = genome.copy() + + for idx in angle_indices: + # Wrap angles to [-π, π] + genome_normalized[:, idx] = np.arctan2( + np.sin(genome[:, idx]), + np.cos(genome[:, idx]) + ) + + return genome_normalized + + +def generate_starting_points( + x0: npt.NDArray[Any], + n_starts: int, + perturbation: float, + bounds: Bounds, + rng: Optional[np.random.Generator] = None +) -> List[npt.NDArray[Any]]: + """ + Generate multiple starting points for multi-start optimization. + + Parameters: + ----------- + x0 : array-like + Initial starting point (flattened genome) + n_starts : int + Total number of starting points to generate + perturbation : float + Magnitude of perturbation (as fraction of parameter range) + bounds : Bounds + Parameter bounds + rng : np.random.Generator, optional + Random number generator + + Returns: + -------- + starting_points : list of arrays + List of starting points (first is always x0) + """ + if rng is None: + rng = np.random.default_rng() + + starting_points = [x0.copy()] + + if n_starts <= 1: + return starting_points + + # Generate additional starting points with perturbations + for _ in range(n_starts - 1): + # Compute parameter ranges + param_ranges = np.array(bounds.ub) - np.array(bounds.lb) + + # Generate random perturbation + perturbation_vec = rng.uniform(-1, 1, size=x0.shape) * perturbation * param_ranges + + # Apply perturbation and clip to bounds + x_perturbed = x0 + perturbation_vec + x_perturbed = np.clip(x_perturbed, bounds.lb, bounds.ub) + + starting_points.append(x_perturbed) + + return starting_points + + +def run_optimization( + objective: Callable, + objective_grad: Callable, + x0: npt.NDArray[Any], + bounds: Bounds, + constraints: List[Dict], + config: OptimizationRepairConfig, + verbose: bool = False +) -> Any: + """ + Run single optimization from a starting point. + + Returns: + -------- + result : OptimizeResult + Optimization result from scipy.optimize.minimize + """ + with warnings.catch_warnings(): + warnings.filterwarnings('ignore', category=RuntimeWarning) + + result = minimize( + objective, + x0, + method=config.optimization_method, + jac=objective_grad, + bounds=bounds, + constraints=constraints, + options={ + 'maxiter': config.max_iterations, + 'ftol': config.optimization_tolerance, + 'disp': verbose + } + ) + + return result + + +# ============================================================================ +# MAIN OPTIMIZATION REPAIR FUNCTION +# ============================================================================ + +def optimization_repair_individual( + individual: npt.NDArray[Any], + config: OptimizationRepairConfig, + arms_to_cylinders: Callable = arms_to_cylinders_polar_angular, + cylinders_to_arms: Callable = cylinders_to_arms_polar_angular, + verbose: bool = False +) -> npt.NDArray[Any]: + """ + Repair an individual genome using constrained optimization. + + This function formulates the repair problem as: + + minimize: ||genome_repaired - genome_original||^2 + subject to: + - No cylinder-cylinder collisions + - No cylinder-core sphere intersections + - All parameters within bounds + - xy-projection constraints (avoid singularity) + + Parameters: + ----------- + individual : array-like of shape (n_arms, 6) + Genome representation with [r, theta, phi, pitch, yaw, direction] + config : OptimizationRepairConfig + Configuration parameters + arms_to_cylinders : callable + Function to convert genome to cylinders + cylinders_to_arms : callable + Function to convert cylinders back to genome + verbose : bool + Print optimization progress + + Returns: + -------- + repaired_individual : array-like of shape (n_arms, 6) + Repaired genome + """ + # Filter valid arms + valid_arms = ~np.isnan(individual).any(axis=-1) + n_valid_arms = np.sum(valid_arms) + + if n_valid_arms == 0: + return individual.copy() + + valid_genome = individual[valid_arms].copy() + + # Step 1: Normalize angles if enabled + if config.normalize_angles: + valid_genome_params = valid_genome[:, :-1] # Exclude direction + valid_genome_params_normalized = normalize_angles(valid_genome_params) + valid_genome[:, :-1] = valid_genome_params_normalized + + # Check if repair is needed + arm_cylinders = genome_to_arm_cylinders_with_disc_base( + valid_genome, config, arms_to_cylinders + ) + + if not _check_collisions(arm_cylinders, config): + # No collisions, return original + return individual.copy() + + # Extract parameters (exclude direction column) + x0 = valid_genome[:, :-1].flatten() # Shape: (n_arms * n_params,) + + # Define parameter bounds (pass x0 to support fixed parameters) + bounds = _create_bounds(n_valid_arms, config, arms_to_cylinders, x0) + + # Get bounds for normalization + bounds_lb = np.array(bounds.lb) + bounds_ub = np.array(bounds.ub) + bounds_range = bounds_ub - bounds_lb + + # Avoid division by zero for any fixed parameters + bounds_range = np.where(bounds_range == 0, 1.0, bounds_range) + + # Define objective function: minimize normalized changes for equal weighting + def objective(x): + # Normalize the differences to [0,1] scale for equal weighting + normalized_diff = (x - x0) / bounds_range + return np.sum(normalized_diff**2) + + def objective_grad(x): + # Gradient of normalized objective + normalized_diff = (x - x0) / bounds_range + return 2 * normalized_diff / bounds_range + + # Determine coordinate system + is_cartesian = (arms_to_cylinders == arms_to_cylinders_cartesian_euler) + n_params = 6 if is_cartesian else 5 + + # Create shared geometry cache for all constraints + geometry_cache = GeometryCache() + direction_column = valid_genome[:, -1] # Extract direction column for cache + + # Define constraints + constraints = [] + + # Cylinder-cylinder collision constraints + for i in range(n_valid_arms): + for j in range(i + 1, n_valid_arms): + constraint_func = create_cylinder_cylinder_constraint( + i, j, config, arms_to_cylinders, geometry_cache, n_params, direction_column + ) + constraints.append({ + 'type': 'ineq', + 'fun': constraint_func + }) + + # Cylinder-sphere collision constraints + for i in range(n_valid_arms): + constraint_func = create_cylinder_sphere_constraint( + i, config, arms_to_cylinders, geometry_cache, n_params, direction_column + ) + constraints.append({ + 'type': 'ineq', + 'fun': constraint_func + }) + + # XY-projection constraints (avoid singularity) - only for spherical coordinates + if not is_cartesian: + for i in range(n_valid_arms): + constraint_func = create_xy_projection_constraint( + i, i * n_params, config.min_xy_projection + ) + constraints.append({ + 'type': 'ineq', + 'fun': constraint_func + }) + + # Step 2: Multi-start optimization + if config.use_multi_start and config.n_starts > 1: + # Generate multiple starting points + starting_points = generate_starting_points( + x0, config.n_starts, config.multi_start_perturbation, bounds + ) + + best_result = None + best_objective = float('inf') + best_feasible_result = None + best_feasible_objective = float('inf') + + if verbose: + print(f"\n=== Multi-start optimization with {config.n_starts} starting points ===") + + for i, start_point in enumerate(starting_points): + result = run_optimization( + objective, objective_grad, start_point, + bounds, constraints, config, verbose=False + ) + + # Check if result is feasible (satisfies constraints) + x_test = result.x.reshape(n_valid_arms, n_params) + genome_test = np.column_stack([x_test, valid_genome[:, -1]]) + arm_cylinders_test = genome_to_arm_cylinders_with_disc_base( + genome_test, config, arms_to_cylinders + ) + is_feasible = not _check_collisions(arm_cylinders_test, config) + + if verbose: + feasible_str = "✓ feasible" if is_feasible else "✗ infeasible" + print(f" Start {i+1}/{config.n_starts}: obj={result.fun:.6e} {feasible_str}") + + # Track best overall result + if result.fun < best_objective: + best_objective = result.fun + best_result = result + + # Track best feasible result + if is_feasible and result.fun < best_feasible_objective: + best_feasible_objective = result.fun + best_feasible_result = result + + # Prefer feasible solution if available + if best_feasible_result is not None: + result = best_feasible_result + if verbose: + print(f" → Selected feasible solution with obj={result.fun:.6e}") + else: + result = best_result + if verbose: + print(f" → No feasible solution found, using best infeasible with obj={result.fun:.6e}") + + else: + # Single-start optimization + result = run_optimization( + objective, objective_grad, x0, + bounds, constraints, config, verbose=verbose + ) + + if verbose: + print(f"\nFinal optimization {'succeeded' if result.success else 'failed'}: {result.message}") + print(f"Function value: {result.fun:.6e}") + print(f"Constraint violations: {np.sum(result.constr_violation) if hasattr(result, 'constr_violation') else 'N/A'}") + + # Extract result + is_cartesian = (arms_to_cylinders == arms_to_cylinders_cartesian_euler) + n_params = 6 if is_cartesian else 5 + x_opt = result.x.reshape(n_valid_arms, n_params) + + # Reconstruct genome with direction column + repaired_genome = np.column_stack([x_opt, valid_genome[:, -1]]) + + # Insert back into full genome + result_individual = individual.copy() + result_individual[valid_arms] = repaired_genome + + return result_individual + + +def _create_bounds(n_arms: int, config: OptimizationRepairConfig, arms_to_cylinders_func: Callable, x0: npt.NDArray[Any] = None) -> Bounds: + """Create bounds for optimization variables. + + Parameters: + ----------- + n_arms : int + Number of arms + config : OptimizationRepairConfig + Configuration with parameter bounds + arms_to_cylinders_func : callable + Function to convert genome to cylinders (determines coordinate system) + x0 : array, optional + Initial parameter values (needed if config.fixed_params is set) + + Returns: + -------- + bounds : Bounds + Parameter bounds for optimization + """ + lower = [] + upper = [] + + # Determine coordinate system based on conversion function + is_cartesian = (arms_to_cylinders_func == arms_to_cylinders_cartesian_euler) + + for arm_idx in range(n_arms): + if is_cartesian: + # Cartesian: x, y, z, roll, pitch, yaw + arm_lower = [ + -config.outer_boundary_radius, # x + -config.outer_boundary_radius, # y + -config.outer_boundary_radius, # z + -np.pi, # roll + config.pitch_bounds[0], # pitch + config.yaw_bounds[0] # yaw + ] + arm_upper = [ + config.outer_boundary_radius, # x + config.outer_boundary_radius, # y + config.outer_boundary_radius, # z + np.pi, # roll + config.pitch_bounds[1], # pitch + config.yaw_bounds[1] # yaw + ] + else: + # Spherical: r, theta, phi, pitch, yaw + arm_lower = [ + config.r_bounds[0], # 0: r + config.theta_bounds[0], # 1: theta + config.phi_bounds[0], # 2: phi + config.pitch_bounds[0], # 3: pitch + config.yaw_bounds[0] # 4: yaw + ] + arm_upper = [ + config.r_bounds[1], # 0: r + config.theta_bounds[1], # 1: theta + config.phi_bounds[1], # 2: phi + config.pitch_bounds[1], # 3: pitch + config.yaw_bounds[1] # 4: yaw + ] + + # Fix parameters if specified + if config.fixed_params is not None and x0 is not None: + n_params = 6 if is_cartesian else 5 + param_start_idx = arm_idx * n_params + + for param_idx in config.fixed_params: + if param_idx < len(arm_lower): + # Fix this parameter at its initial value + initial_value = x0[param_start_idx + param_idx] + arm_lower[param_idx] = initial_value + arm_upper[param_idx] = initial_value + + lower.extend(arm_lower) + upper.extend(arm_upper) + + return Bounds(lower, upper) + + +def _check_collisions( + arm_cylinders: List[Tuple[npt.NDArray[Any], npt.NDArray[Any], Cylinder]], + config: OptimizationRepairConfig, + tolerance: float = 1e-5 +) -> bool: + """Check if there are any collisions in the current configuration. + + Parameters: + ----------- + arm_cylinders : list of tuples + List of (endpoint1, endpoint2, cylinder) tuples + config : OptimizationRepairConfig + Configuration parameters + tolerance : float + Numerical tolerance for collision detection (in meters). + Distances within this tolerance are considered valid. + + Returns: + -------- + has_collision : bool + True if there are collisions, False otherwise + """ + n_arms = len(arm_cylinders) + required_clearance = (2 + config.propeller_tolerance) * config.propeller_radius + sphere_center = np.array([0.0, 0.0, 0.0]) + + # Check cylinder-cylinder collisions + for i in range(n_arms): + for j in range(i + 1, n_arms): + ep1_i, ep2_i, _ = arm_cylinders[i] + ep1_j, ep2_j, _ = arm_cylinders[j] + + distance = cylinder_to_cylinder_distance( + ep1_i, ep2_i, config.propeller_radius, + ep1_j, ep2_j, config.propeller_radius + ) + + # Use tolerance to account for numerical precision + if distance < required_clearance - tolerance: + return True + + # Check cylinder-sphere collisions + for i in range(n_arms): + ep1, ep2, _ = arm_cylinders[i] + + distance = line_segment_to_sphere_distance( + ep1, ep2, sphere_center, config.core_radius + ) + + # Use tolerance to account for numerical precision + if distance < config.propeller_radius - tolerance: + return True + + return False + + +# ============================================================================ +# REPAIR OPERATOR CLASS (INTEGRATION WITH BASE) +# ============================================================================ + +class OptimizationBasedRepairOperator(RepairOperator): + """ + Optimization-based repair operator that integrates with the RepairOperator framework. + + This repair operator uses constrained optimization to repair genomes while: + - Minimizing changes to the original genome + - Ensuring no cylinder-cylinder collisions + - Ensuring no cylinder-core sphere intersections + - Respecting disc-based arm attachment geometry + """ + + def __init__( + self, + config: Optional[RepairConfig] = None, + optimization_config: Optional[OptimizationRepairConfig] = None, + coordinate_system: str = 'spherical', # 'spherical' or 'cartesian' + verbose: bool = False + ): + """ + Initialize the optimization-based repair operator. + + Parameters: + ----------- + config : RepairConfig, optional + Standard repair configuration (for compatibility) + optimization_config : OptimizationRepairConfig, optional + Optimization-specific configuration + coordinate_system : str + 'spherical' for polar angular or 'cartesian' for Cartesian Euler + verbose : bool + Print optimization progress + """ + super().__init__(config) + + # Create optimization config, inheriting values from base config if available + if optimization_config is None: + self.optimization_config = OptimizationRepairConfig( + propeller_radius=self.config.propeller_radius, + propeller_tolerance=self.config.propeller_tolerance, + inner_boundary_radius=self.config.inner_boundary_radius, + outer_boundary_radius=self.config.outer_boundary_radius, + ) + else: + self.optimization_config = optimization_config + + self.coordinate_system = coordinate_system + self.verbose = verbose + + # Select appropriate conversion functions + if coordinate_system == 'spherical': + self.arms_to_cylinders = arms_to_cylinders_polar_angular + self.cylinders_to_arms = cylinders_to_arms_polar_angular + self.param_count = 5 # r, theta, phi, pitch, yaw (excluding direction) + elif coordinate_system == 'cartesian': + self.arms_to_cylinders = arms_to_cylinders_cartesian_euler + self.cylinders_to_arms = cylinders_to_arms_cartesian_euler + self.param_count = 6 # x, y, z, roll, pitch, yaw (excluding direction) + else: + raise ValueError(f"Unknown coordinate system: {coordinate_system}") + + def repair(self, genome: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Repair a genome using optimization-based approach. + + Parameters: + ----------- + genome : array-like + Genome to repair + + Returns: + -------- + repaired_genome : array-like + Repaired genome + """ + return optimization_repair_individual( + genome, + self.optimization_config, + self.arms_to_cylinders, + self.cylinders_to_arms, + self.verbose + ) + + def validate(self, genome: npt.NDArray[Any]) -> bool: + """ + Validate a genome (check for collisions and constraint violations). + + Parameters: + ----------- + genome : array-like + Genome to validate + + Returns: + -------- + is_valid : bool + True if genome has no collisions or violations + """ + # Filter valid arms + valid_arms = ~np.isnan(genome).any(axis=-1) + n_valid_arms = np.sum(valid_arms) + + if n_valid_arms == 0: + return True + + valid_genome = genome[valid_arms] + + # Get arm cylinders + arm_cylinders = genome_to_arm_cylinders_with_disc_base( + valid_genome, + self.optimization_config, + self.arms_to_cylinders + ) + + # Check for collisions + return not _check_collisions(arm_cylinders, self.optimization_config) + + def get_bounds(self) -> npt.NDArray[Any]: + """ + Get parameter bounds. + + Returns: + -------- + bounds : array-like of shape (n_params, 2) + Parameter bounds [min, max] + """ + cfg = self.optimization_config + + if self.coordinate_system == 'spherical': + return np.array([ + [cfg.r_bounds[0], cfg.r_bounds[1]], + [cfg.theta_bounds[0], cfg.theta_bounds[1]], + [cfg.phi_bounds[0], cfg.phi_bounds[1]], + [cfg.pitch_bounds[0], cfg.pitch_bounds[1]], + [cfg.yaw_bounds[0], cfg.yaw_bounds[1]], + [0, 1] # direction + ]) + else: # cartesian + return np.array([ + [-cfg.outer_boundary_radius, cfg.outer_boundary_radius], # x + [-cfg.outer_boundary_radius, cfg.outer_boundary_radius], # y + [-cfg.outer_boundary_radius, cfg.outer_boundary_radius], # z + [-np.pi, np.pi], # roll + [cfg.pitch_bounds[0], cfg.pitch_bounds[1]], + [cfg.yaw_bounds[0], cfg.yaw_bounds[1]], + [0, 1] # direction + ]) + + def __repr__(self) -> str: + return (f"OptimizationBasedRepairOperator(" + f"system={self.coordinate_system}, " + f"method={self.optimization_config.optimization_method})") diff --git a/src/ariel/ec/drone/genome_handlers/operators/particle_repair_operator.py b/src/ariel/ec/drone/genome_handlers/operators/particle_repair_operator.py new file mode 100644 index 000000000..a64d887c7 --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/operators/particle_repair_operator.py @@ -0,0 +1,319 @@ + + +import numpy as np +import itertools +from scipy.spatial.transform import Rotation +from typing import Any +import numpy.typing as npt +import fcl +import gc + +from ariel.ec.drone.genome_handlers.conversions.arm_conversions import arms_to_cylinders_polar_angular, cylinders_to_arms_polar_angular + +def particle_repair_individual(individual, propeller_radius, inner_boundary_radius, outer_boundary_radius, + max_iterations=25, step_size=1.0, propeller_tolerance=0.1, repair_along_fixed_axis=None, + arms_to_cylinders=arms_to_cylinders_polar_angular, cylinders_to_arms=cylinders_to_arms_polar_angular): + """Repair collisions between cylindrical arms by iteratively adjusting positions. + + This function performs collision detection and resolution using cylindrical approximations + of drone arms. It supports both free repair (all collision pairs) and symmetric repair + (preserving bilateral symmetry). + + Parameters: + ----------- + individual : array-like + Genome representation of drone arms + propeller_radius : float + Radius of propellers for collision clearance calculation + inner_boundary_radius : float + Minimum distance from origin for arm positions + outer_boundary_radius : float + Maximum distance from origin for arm positions + max_iterations : int, default=25 + Maximum number of repair iterations + step_size : float, default=1.0 + Step size multiplier for collision resolution movements + propeller_tolerance : float, default=0.1 + Additional clearance tolerance for propellers + repair_along_fixed_axis : array-like or None, default=None + Direction vector for symmetric collision resolution. When provided: + - Assumes bilateral symmetry with arms split into two halves + - Only resolves collisions between arms from different halves + - Forces collision resolution along the specified axis direction + - Preserves symmetry during repair process + arms_to_cylinders : callable + Function to convert arm parameters to cylinder representations + cylinders_to_arms : callable + Function to convert cylinder representations back to arm parameters + + Returns: + -------- + array-like + Repaired genome with collision-free arm positions + + Notes: + ------ + For symmetric drones, the recommended repair workflow is: + 1. Apply free repair (repair_along_fixed_axis=None) + 2. Apply symmetry operators to restore bilateral symmetry + 3. Apply constrained repair (repair_along_fixed_axis=[x,y,z]) to maintain symmetry + """ + # Initialize - filter valid arms and convert to cylinders + valid_arms = ~np.isnan(individual.copy()).any(axis=-1) + valid_arm_params = individual.copy()[valid_arms] + cylinders = arms_to_cylinders(valid_arm_params) + constraints_violated = are_distance_constraints_violated(cylinders, inner_boundary_radius, outer_boundary_radius) + if not are_there_cylinder_collisions(cylinders) and not constraints_violated: + return individual # No repair needed if no collisions + num_arms = len(cylinders) + + # Precompute constants + required_clearance = (2 + propeller_tolerance) * propeller_radius + + for iteration in range(max_iterations): + # Apply distance constraints + constraints_violated = are_distance_constraints_violated(cylinders, + inner_boundary_radius=inner_boundary_radius, + outer_boundary_radius=outer_boundary_radius) + if constraints_violated: + cylinders = enforce_distance_constraints(cylinders, inner_boundary_radius, outer_boundary_radius) + + # Check and resolve all collisions + collision_pairs = get_combinations(num_arms, repair_along_fixed_axis) + collisions_found = False + for i, j in collision_pairs: + if are_there_cylinder_collisions([cylinders[i], cylinders[j]]): + collisions_found = True + new_cyl_i, new_cyl_j = resolve_collision(cylinders[i], cylinders[j], required_clearance, + step_size, repair_along_fixed_axis) + + cylinders[i] = new_cyl_i + cylinders[j] = new_cyl_j + + # collisions_found = collisions_found or are_there_cylinder_collisions(cylinders) + + # Check for convergence + if not (collisions_found or constraints_violated): + break + + if iteration == max_iterations - 1: + print(f"Warning: Particle repair reached maximum iterations ({max_iterations}) without convergence.") + + # Convert back and update individual + repaired_arms = cylinders_to_arms(cylinders) + new_individual = individual.copy() + new_individual[valid_arms, :-1] = repaired_arms + + return new_individual + + +def get_combinations(num_arms, repair_along_fixed_axis): + """Generate pairs of arms to check for collisions. + + For symmetric repair (when repair_along_fixed_axis is provided): + - Assumes bilateral symmetry with arms split into two halves + - Only checks collisions between arms from different halves + - This preserves symmetry during collision resolution by ensuring + symmetric arms don't collide with each other within the same half + """ + if repair_along_fixed_axis is None: + return itertools.combinations(range(num_arms), 2) + else: + list1 = range(0, num_arms // 2) + list2 = range(num_arms // 2, num_arms) + return itertools.product(list1, list2) + +def resolve_collision(cyl1, cyl2, required_clearance, step_size, fixed_direction): + """Resolve collision between two cylinders by moving them apart. + + Parameters: + ----------- + cyl1, cyl2 : Cylinder + Cylinder instances with position attributes + required_clearance : float + Minimum distance required between cylinder centers + step_size : float + Multiplier for the collision resolution movement + fixed_direction : array-like or None + If provided, collision resolution follows this direction instead of + the natural separation direction. Used for symmetric repair. + + Returns: + -------- + tuple : (new_cyl1, new_cyl2) + New Cylinder instances with adjusted positions + """ + p1, p2 = cyl1.position, cyl2.position + min_dist = np.linalg.norm(p1 - p2) + + # Calculate separation direction + if fixed_direction is None: + direction = p2 - p1 + else: + direction = np.array(fixed_direction, dtype=float) + + # Handle zero-length direction vectors + direction_norm = np.linalg.norm(direction) + if direction_norm < 1e-6: # Very small or zero vector + # Use a default separation direction (e.g., along x-axis) + direction = np.array([1.0, 0.0, 0.0]) + direction_norm = 1.0 + + direction = direction / direction_norm + + # Calculate required shift + shift_distance = abs(required_clearance - min_dist) * step_size + shift_distance = max(shift_distance, 0.01) # Ensure non-negative shift + # Limit shift to maximum possible + if required_clearance/2 < shift_distance: + shift_distance = required_clearance/2 + + # Apply bidirectional shift and return new cylinders + shift_vector = direction * shift_distance + + if fixed_direction is not None: + axis_to_shift = np.where(np.abs(direction) > 1e-6)[0] + if cyl2.position[axis_to_shift] < cyl1.position[axis_to_shift]: + # cyl1 is closer to origin, move it outward + shift_vector *= -1 + new_pos1 = cyl1.position - shift_vector / 2 + new_pos2 = cyl2.position + shift_vector / 2 + + return cyl1.with_position(new_pos1), cyl2.with_position(new_pos2) + +# Cylinder utilities +# ------------------ + +def are_distance_constraints_violated(cylinders, inner_boundary_radius, outer_boundary_radius): + """ + Check if any cylinder is outside the specified inner or outer boundaries. + + Parameters: + - cylinders: list of dicts, each with keys: + - 'position': numpy array of shape (3,) for cylinder position + - 'radius': float for cylinder radius + - 'height': float for cylinder height + - 'orientation': numpy array of shape (4,) for cylinder orientation as quaternion [w, x, y, z] + - inner_boundary_radius: float, inner boundary radius + - outer_boundary_radius: float, outer boundary radius + + Returns: + - True if any cylinder is outside the boundaries, False otherwise + """ + for cyl in cylinders: + distance_to_origin = np.linalg.norm(cyl.position) + + # Check if cylinder is outside inner boundary + if distance_to_origin < inner_boundary_radius: + return True + + # Check if cylinder is outside outer boundary + if distance_to_origin > outer_boundary_radius: + return True + + return False + +def enforce_distance_constraints(cylinders, inner_boundary_radius, outer_boundary_radius): + """ + Enforce minimum and maximum distance constraints from origin. + + Parameters: + - cylinders: list of Cylinder instances + - inner_boundary_radius: float, minimum distance from origin + - outer_boundary_radius: float, maximum distance from origin + + Returns: + - List of new Cylinder instances with constrained positions + """ + new_cylinders = [] + + for cylinder in cylinders: + position = cylinder.position + distance_to_origin = np.linalg.norm(position) + + if distance_to_origin < inner_boundary_radius: + # Too close to origin, move outward + if np.isclose(distance_to_origin, 0): + # If the cylinder is at the origin, move it to the inner boundary + new_position = np.array([inner_boundary_radius, 0, 0]) + else: + # Move outward along the direction from origin + direction = position / distance_to_origin # Normalize + new_position = direction * inner_boundary_radius + new_cylinders.append(cylinder.with_position(new_position)) + + elif distance_to_origin > outer_boundary_radius: + # Too far from origin, move inward + direction = position / distance_to_origin # Normalize + new_position = direction * outer_boundary_radius + new_cylinders.append(cylinder.with_position(new_position)) + else: + # Position is within bounds, keep original + new_cylinders.append(cylinder) + + return new_cylinders + + +def correct_quaternion_for_trimesh(quat: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Convert a quaternion from X-aligned cylinder (your convention) + to Z-aligned cylinder (Trimesh convention). + + Args: + quat: Quaternion representing orientation (X-aligned) + + Returns: + Adjusted quaternion for Trimesh's Z-aligned cylinder + """ + # Rotation to align X axis to Z axis: -90 degrees around Y + correction = Rotation.from_euler('y', -90, degrees=True) + + # Original orientation + R_orig = Rotation.from_quat(quat) + + # Apply correction + R_corrected = correction * R_orig + return R_corrected.as_quat() + +def are_there_cylinder_collisions(cylinders): + """ + Check if any pair of cylinders in the list is colliding using python-fcl. + + Parameters: + - cylinders: list of dicts, each with keys: + - 'radius': float + - 'height': float + - 'transform': 4x4 numpy array (homogeneous transform) + + Returns: + - True if any pair of cylinders collide, False otherwise + """ + gc.collect() + + # Create FCL collision objects for each cylinder + fcl_objects = [] + for i, cyl in enumerate(cylinders): + radius = cyl.radius + height = cyl.height + tf = cyl.transform + + # Decompose transform into rotation (3x3) and translation (3,) + rotation = tf[:3, :3] + translation = tf[:3, 3] + + # Create FCL transform and object + fcl_tf = fcl.Transform(rotation, translation) + shape = fcl.Cylinder(radius, height) + obj = fcl.CollisionObject(shape, fcl_tf) + + fcl_objects.append(obj) + + # Check for collisions between all pairs + for i in range(len(fcl_objects)): + for j in range(i + 1, len(fcl_objects)): + request = fcl.CollisionRequest() + result = fcl.CollisionResult() + if fcl.collide(fcl_objects[i], fcl_objects[j], request, result) > 0: + return True + + return False diff --git a/src/ariel/ec/drone/genome_handlers/operators/repair_base.py b/src/ariel/ec/drone/genome_handlers/operators/repair_base.py new file mode 100644 index 000000000..4a895e872 --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/operators/repair_base.py @@ -0,0 +1,420 @@ +""" +Base classes and interfaces for repair operators. + +This module provides the abstract base class and common utilities for implementing +repair operations across different genome representations. +""" + +from __future__ import annotations + +from abc import ABC, abstractmethod +from typing import Any, Dict, Optional, Union, List, Tuple +from enum import Enum + +import numpy as np +import numpy.typing as npt + + +class RepairStrategy(Enum): + """Enumeration of repair strategies.""" + CLIP = "clip" # Clip values to bounds + WRAP = "wrap" # Wrap values around bounds + RANDOM = "random" # Replace with random values + +class RepairConfig: + """Configuration for repair operations.""" + + def __init__( + self, + apply_symmetry: bool = True, + enable_collision_repair: bool = True, + propeller_radius: float = 0.0254, # 2-inch propeller radius in meters + inner_boundary_radius: float = 0.09, + outer_boundary_radius: float = 0.4, + max_repair_iterations: int = 50, + repair_step_size: float = 1.0, + propeller_tolerance: float = 0.1, + ): + """ + Initialize repair configuration. + + Args: + apply_symmetry: Whether to apply symmetry after repair + enable_collision_repair: Whether to enable collision detection and repair + propeller_radius: Radius of propellers for collision detection (default: 0.0254m = 2-inch props) + inner_boundary_radius: Minimum distance from origin + outer_boundary_radius: Maximum distance from origin + max_repair_iterations: Maximum iterations for collision repair + repair_step_size: Step size multiplier for collision resolution + propeller_tolerance: Additional clearance tolerance for propellers + reflection_axis: Optional fixed axis direction for symmetric collision resolution + """ + self.apply_symmetry = apply_symmetry + self.enable_collision_repair = enable_collision_repair + self.propeller_radius = propeller_radius + self.inner_boundary_radius = inner_boundary_radius + self.outer_boundary_radius = outer_boundary_radius + self.max_repair_iterations = max_repair_iterations + self.repair_step_size = repair_step_size + self.propeller_tolerance = propeller_tolerance + + assert self.inner_boundary_radius < self.outer_boundary_radius, \ + "Inner boundary radius must be less than outer boundary radius" + assert self.inner_boundary_radius >= 0, \ + "Inner boundary radius must be non-negative" + assert self.outer_boundary_radius > 0, \ + "Outer boundary radius must be positive" + assert self.propeller_radius > 0, \ + "Propeller radius must be positive" + + def __repr__(self) -> str: + collision_str = f", collision={self.enable_collision_repair}" if self.enable_collision_repair else "" + return (f"RepairConfig(symmetry={self.apply_symmetry}{collision_str})") + +class RepairOperator(ABC): + """ + Abstract base class for repair operations on genomes. + + This class defines the interface that all repair operators must implement, + providing a consistent API across different genome representations. + """ + + def __init__(self, config: Optional[RepairConfig] = None): + """ + Initialize the repair operator. + + Args: + config: Repair configuration. If None, creates default config. + """ + self.config = config or RepairConfig() + + @abstractmethod + def repair(self, genome: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Repair a genome to make it valid. + + Args: + genome: Input genome array + + Returns: + Repaired genome + """ + pass + + @abstractmethod + def validate(self, genome: npt.NDArray[Any]) -> bool: + """ + Check if a genome is valid. + + Args: + genome: Genome array to validate + + Returns: + True if genome is valid, False otherwise + """ + pass + + @abstractmethod + def get_bounds(self) -> npt.NDArray[Any]: + """ + Get the parameter bounds for this genome type. + + Returns: + Array of shape (n_params, 2) with [min, max] for each parameter + """ + pass + + def repair_population(self, population: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Repair a population of genomes. + + Args: + population: Population array of shape (pop_size, ...) + + Returns: + Repaired population + """ + result = np.empty_like(population) + for i in range(population.shape[0]): + result[i] = self.repair(population[i]) + return result + + def validate_population(self, population: npt.NDArray[Any]) -> npt.NDArray[bool]: + """ + Validate a population of genomes. + + Args: + population: Population array of shape (pop_size, ...) + + Returns: + Boolean array indicating which individuals are valid + """ + result = np.empty(population.shape[0], dtype=bool) + for i in range(population.shape[0]): + result[i] = self.validate(population[i]) + return result + + def repair_collisions(self, genome: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Repair collisions in a genome (optional, implemented by subclasses). + + This method provides a default implementation that returns the genome unchanged. + Subclasses should override this method to implement collision repair specific + to their coordinate system. + + Args: + genome: Input genome array + + Returns: + Genome with collisions repaired (default: unchanged) + """ + return genome + + def __repr__(self) -> str: + return f"{self.__class__.__name__}({self.config})" + + +class RepairUtilities: + """Common utilities for repair operations.""" + + @staticmethod + def clip_to_bounds( + values: Union[npt.NDArray[Any], float], + bounds: Union[npt.NDArray[Any], Tuple[float, float]] + ) -> Union[npt.NDArray[Any], float]: + """ + Clip values to specified bounds. + + Args: + values: Array of values to clip or single value + bounds: Array of shape (n_params, 2) with [min, max] for each parameter, + or tuple (min, max) for single value + + Returns: + Clipped values + """ + # Handle scalar case + if np.isscalar(values): + if isinstance(bounds, tuple): + return np.clip(values, bounds[0], bounds[1]) + else: + raise ValueError("For scalar values, bounds must be a tuple (min, max)") + + # Handle array case + values = np.asarray(values) + result = values.copy() + + if isinstance(bounds, tuple): + # Single bounds tuple - apply to all values + return np.clip(values, bounds[0], bounds[1]) + else: + # Array of bounds + bounds = np.asarray(bounds) + for i in range(bounds.shape[0]): + if i < values.shape[-1]: # Handle cases where values has fewer parameters + result[..., i] = np.clip(values[..., i], bounds[i, 0], bounds[i, 1]) + return result + + @staticmethod + def wrap_to_bounds( + values: Union[npt.NDArray[Any], float], + bounds: Union[npt.NDArray[Any], Tuple[float, float]] + ) -> Union[npt.NDArray[Any], float]: + """ + Wrap values to specified bounds (useful for angular parameters). + + Args: + values: Array of values to wrap or single value + bounds: Array of shape (n_params, 2) with [min, max] for each parameter, + or tuple (min, max) for single value + + Returns: + Wrapped values + """ + # Handle scalar case + if np.isscalar(values): + if isinstance(bounds, tuple): + min_val, max_val = bounds + range_val = max_val - min_val + return ((values - min_val) % range_val) + min_val + else: + raise ValueError("For scalar values, bounds must be a tuple (min, max)") + + # Handle array case + values = np.asarray(values) + result = values.copy() + + if isinstance(bounds, tuple): + # Single bounds tuple - apply to all values + min_val, max_val = bounds + range_val = max_val - min_val + return ((values - min_val) % range_val) + min_val + else: + # Array of bounds + bounds = np.asarray(bounds) + for i in range(bounds.shape[0]): + if i < values.shape[-1]: + min_val, max_val = bounds[i, 0], bounds[i, 1] + range_val = max_val - min_val + result[..., i] = ((values[..., i] - min_val) % range_val) + min_val + return result + + @staticmethod + def detect_invalid_values(values: npt.NDArray[Any]) -> npt.NDArray[bool]: + """ + Detect NaN or infinite values. + + Args: + values: Array to check + + Returns: + Boolean mask indicating invalid values + """ + return ~np.isfinite(values) + + @staticmethod + def replace_invalid_values( + values: npt.NDArray[Any], + replacement: Union[npt.NDArray[Any], float], + mask: Optional[npt.NDArray[bool]] = None + ) -> npt.NDArray[Any]: + """ + Replace invalid values with replacement values. + + Args: + values: Array with potentially invalid values + replacement: Replacement values (array or scalar) + mask: Optional mask indicating which values to replace + + Returns: + Array with invalid values replaced + """ + if mask is None: + mask = RepairUtilities.detect_invalid_values(values) + + result = values.copy() + if np.isscalar(replacement): + result[mask] = replacement + else: + replacement = np.asarray(replacement) + result[mask] = replacement[mask] + return result + + @staticmethod + def generate_random_replacement( + shape: tuple, + bounds: npt.NDArray[Any], + rng: Optional[np.random.Generator] = None + ) -> npt.NDArray[Any]: + """ + Generate random values within specified bounds. + + Args: + shape: Shape of array to generate + bounds: Array of shape (n_params, 2) with [min, max] for each parameter + rng: Random number generator + + Returns: + Random values within bounds + """ + if rng is None: + rng = np.random.default_rng() + + result = np.empty(shape) + for i in range(bounds.shape[0]): + if i < shape[-1]: + result[..., i] = rng.uniform(bounds[i, 0], bounds[i, 1], size=shape[:-1]) + return result + + @staticmethod + def enforce_discrete_values( + values: npt.NDArray[Any], + discrete_indices: List[int], + discrete_values: List[List[Any]] + ) -> npt.NDArray[Any]: + """ + Enforce discrete values for specified parameters. + + Args: + values: Array of values + discrete_indices: Indices of parameters that should be discrete + discrete_values: List of allowed values for each discrete parameter + + Returns: + Array with discrete values enforced + """ + result = values.copy() + for i, allowed_values in zip(discrete_indices, discrete_values): + if i < values.shape[-1]: + # Find closest allowed value for each element + for j, allowed in enumerate(allowed_values): + if j == 0: + distances = np.abs(values[..., i] - allowed) + closest = np.full_like(values[..., i], allowed) + else: + new_distances = np.abs(values[..., i] - allowed) + closer_mask = new_distances < distances + distances[closer_mask] = new_distances[closer_mask] + closest[closer_mask] = allowed + result[..., i] = closest + return result + + @staticmethod + def enforce_binary_values( + values: npt.NDArray[Any], + binary_indices: List[int], + threshold: float = 0.5 + ) -> npt.NDArray[Any]: + """ + Enforce binary (0/1) values for specified parameters. + + Args: + values: Array of values + binary_indices: Indices of parameters that should be binary + threshold: Threshold for binary conversion + + Returns: + Array with binary values enforced + """ + result = values.copy() + for i in binary_indices: + if i < values.shape[-1]: + result[..., i] = np.where(values[..., i] >= threshold, 1, 0) + return result + + @staticmethod + def validate_bounds( + values: npt.NDArray[Any], + bounds: npt.NDArray[Any], + tolerance: float = 1e-9 + ) -> npt.NDArray[bool]: + """ + Validate that values are within specified bounds. + + Args: + values: Array of values to validate + bounds: Array of shape (n_params, 2) with [min, max] for each parameter + tolerance: Tolerance for bound checking + + Returns: + Boolean array indicating which values are within bounds + """ + valid = np.ones(values.shape, dtype=bool) + for i in range(bounds.shape[0]): + if i < values.shape[-1]: + valid[..., i] &= (values[..., i] >= bounds[i, 0] - tolerance) + valid[..., i] &= (values[..., i] <= bounds[i, 1] + tolerance) + return valid + + @staticmethod + def validate_finite(values: npt.NDArray[Any]) -> npt.NDArray[bool]: + """ + Validate that values are finite (not NaN or infinite). + + Args: + values: Array of values to validate + + Returns: + Boolean array indicating which values are finite + """ + return np.isfinite(values) \ No newline at end of file diff --git a/src/ariel/ec/drone/genome_handlers/operators/repair_cartesian.py b/src/ariel/ec/drone/genome_handlers/operators/repair_cartesian.py new file mode 100644 index 000000000..9384d065b --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/operators/repair_cartesian.py @@ -0,0 +1,408 @@ +""" +Cartesian repair operator for drone genome handlers. + +This module implements repair operations for Cartesian coordinate +representations with Euler angles. +""" + +from __future__ import annotations + +from typing import Any, Optional + +import numpy as np +import numpy.typing as npt + +from .repair_base import RepairOperator, RepairConfig, RepairUtilities +from .symmetry_cartesian import CartesianSymmetryOperator +from ..conversions.arm_conversions import arms_to_cylinders_cartesian_euler, cylinders_to_arms_cartesian_euler +from .particle_repair_operator import particle_repair_individual, are_there_cylinder_collisions +from .symmetry_base import SymmetryPlane + +class CartesianRepairOperator(RepairOperator): + """ + Repair operator for Cartesian coordinate genomes with Euler angles. + + Genome format expected: (max_narms, 7) with columns: + [x, y, z, roll, pitch, yaw, direction] + + Uses NaN masking for variable arm counts. + """ + + def __init__( + self, + config: Optional[RepairConfig] = None, + parameter_limits: Optional[npt.NDArray[Any]] = None, + min_narms: int = 1, + max_narms: int = 8, + symmetry_operator: Optional[CartesianSymmetryOperator] = None, + rng: Optional[np.random.Generator] = None + ): + """ + Initialize the Cartesian repair operator. + + Args: + config: Repair configuration + parameter_limits: Array of shape (7, 2) with [min, max] for each parameter + min_narms: Minimum number of arms + max_narms: Maximum number of arms + symmetry_operator: Optional symmetry operator for symmetry restoration + rng: Random number generator + """ + super().__init__(config) + self.min_narms = min_narms + self.max_narms = max_narms + self.symmetry_operator = symmetry_operator + self.rng = rng if rng is not None else np.random.default_rng() + + # Set default parameter limits if not provided + if parameter_limits is None: + self.parameter_limits = np.array([ + [-1.0, 1.0], # x position + [-1.0, 1.0], # y position + [-1.0, 1.0], # z position + [-np.pi, np.pi], # roll + [-np.pi, np.pi], # pitch + [-np.pi, np.pi], # yaw + [0, 1] # direction (binary) + ]) + else: + if parameter_limits.shape != (7, 2): + raise ValueError("parameter_limits must have shape (7, 2)") + self.parameter_limits = parameter_limits.copy() + + def repair(self, genome: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Repair a Cartesian genome to make it valid. + + Args: + genome: Cartesian genome array of shape (max_narms, 7) + + Returns: + Repaired genome + """ + if genome.shape[1] != 7: + raise ValueError("Cartesian genome must have 7 parameters per arm") + narms = np.sum(~np.isnan(genome[:, 0])) + if narms <= 1: + return genome.copy() + + result = genome.copy() + + # Unapply symmetry if it was applied + if self.config.apply_symmetry and self.symmetry_operator is not None: + result = self.symmetry_operator.unapply_symmetry(result) + if self.symmetry_operator.get_plane() is SymmetryPlane.XY: + axis = [0, 0, 1] + elif self.symmetry_operator.get_plane() is SymmetryPlane.XZ: + axis = [0, 1, 0] + elif self.symmetry_operator.get_plane() is SymmetryPlane.YZ: + axis = [1, 0, 0] + + # Step 2: Clip parameters to bounds + result = self._clip_parameters(result) + + # Step 3: Apply collision repair if enabled + if self.config.enable_collision_repair: + result = self.repair_collisions(result) + + # Check collsions + cylinders = arms_to_cylinders_cartesian_euler(result) + f = are_there_cylinder_collisions(cylinders) + # Step 4: Apply symmetry restoration if enabled + if self.config.apply_symmetry and self.symmetry_operator is not None: + result = self.symmetry_operator.apply_symmetry(result) + # Apply repair again but on reflected axis + result = self.repair_collisions(result, repair_along_fixed_axis=axis) + # Check collsions + cylinders = arms_to_cylinders_cartesian_euler(result) + f = are_there_cylinder_collisions(cylinders) + return result + + def validate(self, genome: npt.NDArray[Any]) -> bool: + """ + Check if a Cartesian genome is valid. + + Args: + genome: Cartesian genome array of shape (max_narms, 7) + + Returns: + True if genome is valid + """ + # Check genome shape first + if len(genome.shape) != 2 or genome.shape[1] != 7: + print("Invalid genome shape, expected (max_narms, 7)") + return False + + # Find valid arms (non-NaN) and check arm count constraints + valid_arms_mask = ~np.isnan(genome[:, 0]) + num_valid_arms = np.sum(valid_arms_mask) + max_narms = genome.shape[0] + + if num_valid_arms < self.min_narms or num_valid_arms > self.max_narms: + print(f"Invalid arm count: {num_valid_arms} (expected between {self.min_narms} and {self.max_narms})") + return False + + if max_narms > self.max_narms: + print(f"Max arms exceeded: {max_narms} (expected <= {self.max_narms})") + return False + + # Check for invalid values only in valid arms + if np.any(valid_arms_mask): + valid_genome = genome[valid_arms_mask] + if not np.isfinite(valid_genome).all(): + print("Genome contains NaN or infinite values in valid arms") + return False + + # Check parameter bounds only for valid arms + if np.any(valid_arms_mask): + valid_genome = genome[valid_arms_mask] + for i in range(7): + param_values = valid_genome[:, i] + if np.any(param_values < self.parameter_limits[i, 0]) or \ + np.any(param_values > self.parameter_limits[i, 1]): + print(f"Parameter {i} out of bounds, values: {param_values}") + return False + + # Check propeller direction values + directions = valid_genome[:, 6] + if not np.all(np.isin(directions, [0, 1])): + print("Direction values must be binary (0 or 1)") + return False + + # Check symmetry constraints if symmetry operator is provided + if self.symmetry_operator is not None: + if not self.symmetry_operator.validate_symmetry(genome): + print("Genome does not satisfy symmetry constraints") + return False + + return True + + def get_bounds(self) -> npt.NDArray[Any]: + """ + Get the parameter bounds for Cartesian genomes. + + Returns: + Array of shape (7, 2) with [min, max] for each parameter + """ + return self.parameter_limits.copy() + + def repair_collisions(self, genome: npt.NDArray[Any], repair_along_fixed_axis=None) -> npt.NDArray[Any]: + """ + Repair collisions in a Cartesian genome using the particle repair operator. + + Args: + genome: Cartesian genome array of shape (max_narms, 7) + + Returns: + Genome with collisions repaired + """ + if genome.shape[1] != 7: + raise ValueError("Cartesian genome must have 7 parameters per arm") + + # Apply collision repair using the particle repair operator + repaired_valid_genome = particle_repair_individual( + genome, + propeller_radius=self.config.propeller_radius, + inner_boundary_radius=self.config.inner_boundary_radius, + outer_boundary_radius=self.config.outer_boundary_radius, + max_iterations=self.config.max_repair_iterations, + step_size=self.config.repair_step_size, + propeller_tolerance=self.config.propeller_tolerance, + repair_along_fixed_axis=repair_along_fixed_axis, + arms_to_cylinders=arms_to_cylinders_cartesian_euler, + cylinders_to_arms=cylinders_to_arms_cartesian_euler + ) + + return repaired_valid_genome + + def _clip_parameters(self, genome: npt.NDArray[Any]) -> npt.NDArray[Any]: + """Clip parameters to their bounds.""" + result = genome.copy() + + # Find valid arms and clip only those parameters + valid_arms_mask = ~np.isnan(genome[:, 0]) + + if np.any(valid_arms_mask): + # Clip all parameters to their bounds for valid arms only + for i in range(7): + valid_values = result[valid_arms_mask, i] + clipped_values = np.clip( + valid_values, + self.parameter_limits[i, 0], + self.parameter_limits[i, 1] + ) + result[valid_arms_mask, i] = clipped_values + + return result + + def _handle_invalid_values(self, genome: npt.NDArray[Any]) -> npt.NDArray[Any]: + """Handle NaN and infinite values.""" + # Detect invalid values + invalid_mask = RepairUtilities.detect_invalid_values(genome) + + if not np.any(invalid_mask): + return genome # No invalid values to repair + + result = genome.copy() + + # Replace invalid values with random valid values + replacement_genome = self._generate_random_genome(genome.shape) + result = RepairUtilities.replace_invalid_values( + result, replacement_genome, invalid_mask + ) + + return result + + def _generate_random_genome(self, shape: tuple) -> npt.NDArray[Any]: + """Generate a random genome for replacement values.""" + return RepairUtilities.generate_random_replacement( + shape, self.parameter_limits, self.rng + ) + + def repair_with_symmetry_plane( + self, + genome: npt.NDArray[Any], + plane: str + ) -> npt.NDArray[Any]: + """ + Repair genome with specific symmetry plane. + + Args: + genome: Genome to repair + plane: Symmetry plane ("xy", "xz", "yz", or None) + + Returns: + Repaired genome with symmetry applied + """ + # Create temporary symmetry operator with specified plane + from .symmetry_base import SymmetryConfig + + temp_config = SymmetryConfig(plane=plane) + temp_symmetry = CartesianSymmetryOperator( + config=temp_config + ) + + # Temporarily set symmetry operator + original_symmetry = self.symmetry_operator + self.symmetry_operator = temp_symmetry + + try: + result = self.repair(genome) + finally: + # Restore original symmetry operator + self.symmetry_operator = original_symmetry + + return result + + def validate_with_tolerance( + self, + genome: npt.NDArray[Any], + tolerance: float = 1e-9 + ) -> bool: + """ + Validate genome with custom tolerance. + + Args: + genome: Genome to validate + tolerance: Tolerance for bound checking + + Returns: + True if genome is valid within tolerance + """ + # Check shape + if genome.shape[1] != 7: + return False + + # Find valid arms + valid_arms_mask = ~np.isnan(genome[:, 0]) + + if np.any(valid_arms_mask): + valid_genome = genome[valid_arms_mask] + + # Check for NaN or infinite values in valid arms + if not np.isfinite(valid_genome).all(): + return False + + # Check bounds with tolerance + bounds_valid = RepairUtilities.validate_bounds(valid_genome, self.parameter_limits, tolerance) + if not np.all(bounds_valid): + return False + + # Check binary direction values + directions = valid_genome[:, 6] + if not np.all(np.isin(directions, [0, 1])): + return False + + return True + + def _count_bounds_violations(self, genome: npt.NDArray[Any]) -> dict: + """Count bounds violations for each parameter.""" + violations = {} + param_names = ['x', 'y', 'z', 'roll', 'pitch', 'yaw', 'direction'] + + # Find valid arms + valid_arms_mask = ~np.isnan(genome[:, 0]) + + if np.any(valid_arms_mask): + valid_genome = genome[valid_arms_mask] + + for i, name in enumerate(param_names): + values = valid_genome[:, i] + min_bound, max_bound = self.parameter_limits[i] + + violations[name] = { + 'below_min': np.sum(values < min_bound), + 'above_max': np.sum(values > max_bound), + 'total': np.sum((values < min_bound) | (values > max_bound)) + } + else: + # No valid arms, so no violations + for name in param_names: + violations[name] = { + 'below_min': 0, + 'above_max': 0, + 'total': 0 + } + + return violations + + def set_parameter_limits(self, parameter_limits: npt.NDArray[Any]) -> None: + """ + Update parameter limits. + + Args: + parameter_limits: New parameter limits array of shape (7, 2) + """ + if parameter_limits.shape != (7, 2): + raise ValueError("parameter_limits must have shape (7, 2)") + self.parameter_limits = parameter_limits.copy() + + def set_arm_count_limits(self, min_narms: int, max_narms: int) -> None: + """ + Update arm count limits. + + Args: + min_narms: New minimum number of arms + max_narms: New maximum number of arms + """ + if min_narms < 1: + raise ValueError("min_narms must be at least 1") + if max_narms < min_narms: + raise ValueError("max_narms must be >= min_narms") + + self.min_narms = min_narms + self.max_narms = max_narms + + def set_symmetry_operator(self, symmetry_operator: CartesianSymmetryOperator) -> None: + """ + Set the symmetry operator. + + Args: + symmetry_operator: New symmetry operator + """ + self.symmetry_operator = symmetry_operator + + def __repr__(self) -> str: + return (f"CartesianRepairOperator(config={self.config}, " + f"arm_limits=({self.min_narms}, {self.max_narms}), " + f"has_symmetry={self.symmetry_operator is not None})") \ No newline at end of file diff --git a/src/ariel/ec/drone/genome_handlers/operators/repair_spherical.py b/src/ariel/ec/drone/genome_handlers/operators/repair_spherical.py new file mode 100644 index 000000000..39ceb8e0f --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/operators/repair_spherical.py @@ -0,0 +1,387 @@ +""" +Spherical repair operator for drone genome handlers. + +This module implements repair operations for spherical coordinate +representations with angular orientations. +""" + +from __future__ import annotations + +from typing import Any, Optional + +import numpy as np +import numpy.typing as npt + +from .repair_base import RepairOperator, RepairConfig, RepairUtilities +from .symmetry_spherical import SphericalSymmetryOperator +from ..conversions.arm_conversions import arms_to_cylinders_polar_angular, cylinders_to_arms_polar_angular +from .particle_repair_operator import particle_repair_individual +from .symmetry_base import SymmetryPlane + +class SphericalRepairOperator(RepairOperator): + """ + Repair operator for spherical coordinate genomes with angular orientations. + + Genome format expected: (max_narms, 6) with columns: + [magnitude, arm_rotation, arm_pitch, motor_rotation, motor_pitch, direction] + + Uses NaN masking for variable arm counts. + """ + + def __init__( + self, + config: Optional[RepairConfig] = None, + parameter_limits: Optional[npt.NDArray[Any]] = None, + min_narms: int = 1, + max_narms: int = 8, + symmetry_operator: Optional[SphericalSymmetryOperator] = None, + rng: Optional[np.random.Generator] = None + ): + """ + Initialize the Spherical repair operator. + + Args: + config: Repair configuration + parameter_limits: Array of shape (6, 2) with [min, max] for each parameter + min_narms: Minimum number of arms + max_narms: Maximum number of arms + symmetry_operator: Optional symmetry operator for symmetry restoration + rng: Random number generator + """ + super().__init__(config) + self.min_narms = min_narms + self.max_narms = max_narms + self.symmetry_operator = symmetry_operator + self.rng = rng if rng is not None else np.random.default_rng() + + # Set default parameter limits if not provided + if parameter_limits is None: + self.parameter_limits = np.array([ + [0.5, 2.0], # magnitude + [-np.pi, np.pi], # arm rotation + [-np.pi, np.pi], # arm pitch + [-np.pi, np.pi], # motor rotation + [-np.pi, np.pi], # motor pitch + [0, 1] # direction (binary) + ]) + else: + if parameter_limits.shape != (6, 2): + raise ValueError("parameter_limits must have shape (6, 2)") + self.parameter_limits = parameter_limits.copy() + + def repair(self, genome: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Repair a spherical genome to make it valid. + + Args: + genome: Spherical genome array of shape (max_narms, 6) + + Returns: + Repaired genome + """ + if genome.shape[1] != 6: + raise ValueError("Spherical genome must have 6 parameters per arm") + narms = np.sum(~np.isnan(genome[:, 0])) + if narms <= 1: + return genome.copy() + + result = genome.copy() + # Unapply symmetry if it was applied + if self.config.apply_symmetry and self.symmetry_operator.get_plane() is not None: + result = self.symmetry_operator.unapply_symmetry(result) + if self.symmetry_operator.get_plane() is SymmetryPlane.XY: + axis = [0, 0, 1] + elif self.symmetry_operator.get_plane() is SymmetryPlane.XZ: + axis = [0, 1, 0] + elif self.symmetry_operator.get_plane() is SymmetryPlane.YZ: + axis = [1, 0, 0] + + # Step 1: Wrap angular parameters to their valid ranges + result = self._wrap_angular_parameters(result) + + # Step 2: Clip parameters to bounds for valid arms + result = self._clip_parameters(result) + + # Step 3: Apply collision repair if enabled + if self.config.enable_collision_repair: + result = self.repair_collisions(result) + + # Step 4: Apply symmetry restoration if enabled + if self.config.apply_symmetry and self.symmetry_operator is not None: + result = self.symmetry_operator.apply_symmetry(result) + # Apply collision repair again but on certain axis + if self.config.enable_collision_repair: + result = self.repair_collisions(result, repair_along_fixed_axis=axis) + + return result + + def validate(self, genome: npt.NDArray[Any]) -> bool: + """ + Check if a spherical genome is valid. + + Args: + genome: Spherical genome array of shape (max_narms, 6) + + Returns: + True if genome is valid + """ + # Check genome shape first + if len(genome.shape) != 2 or genome.shape[1] != 6: + print(f"Invalid genome shape: {genome.shape}, expected (max_narms, 6)") + return False + + # Count valid arms (non-NaN) + valid_arms_mask = ~np.isnan(genome[:, 0]) + num_valid_arms = np.sum(valid_arms_mask) + + # Check arm count constraints + if num_valid_arms < self.min_narms or num_valid_arms > self.max_narms: + print(f"Invalid arm count: {num_valid_arms} (expected between {self.min_narms} and {self.max_narms})") + return False + + # Check parameter bounds for valid arms + if num_valid_arms > 0: + valid_arms = genome[valid_arms_mask] + + for i in range(6): + param_values = valid_arms[:, i] + if np.any(param_values < self.parameter_limits[i, 0]) or \ + np.any(param_values > self.parameter_limits[i, 1]): + print(f"Parameter {i} out of bounds: {param_values}, Genome: \n{genome}. Upper bounds: {self.parameter_limits[i, 1]}, Lower bounds: {self.parameter_limits[i, 0]}") + return False + + # Check that direction values are 0 or 1 + directions = valid_arms[:, 5] + if not np.all(np.isin(directions, [0, 1])): + print(f"Invalid direction values: {directions}") + return False + + # Check symmetry constraints if symmetry operator is provided and enabled + if (self.symmetry_operator is not None and + hasattr(self.symmetry_operator, 'is_enabled') and + self.symmetry_operator.is_enabled()): + if not self.symmetry_operator.validate_symmetry(genome): + print("Genome does not satisfy symmetry constraints") + return False + + return True + + def get_bounds(self) -> npt.NDArray[Any]: + """ + Get the parameter bounds for spherical genomes. + + Returns: + Array of shape (6, 2) with [min, max] for each parameter + """ + return self.parameter_limits.copy() + + def repair_collisions(self, genome: npt.NDArray[Any], repair_along_fixed_axis=None) -> npt.NDArray[Any]: + """ + Repair collisions in a spherical genome using the particle repair operator. + + Args: + genome: Spherical genome array of shape (max_narms, 6) + + Returns: + Genome with collisions repaired + """ + if genome.shape[1] != 6: + raise ValueError("Spherical genome must have 6 parameters per arm") + + # Apply collision repair using the particle repair operator + repaired_valid_genome = particle_repair_individual( + genome, + propeller_radius=self.config.propeller_radius, + inner_boundary_radius=self.config.inner_boundary_radius, + outer_boundary_radius=self.config.outer_boundary_radius, + max_iterations=self.config.max_repair_iterations, + step_size=self.config.repair_step_size, + propeller_tolerance=self.config.propeller_tolerance, + repair_along_fixed_axis=repair_along_fixed_axis, + arms_to_cylinders=arms_to_cylinders_polar_angular, + cylinders_to_arms=cylinders_to_arms_polar_angular + ) + + return repaired_valid_genome + + def _clip_parameters(self, genome: npt.NDArray[Any]) -> npt.NDArray[Any]: + """Clip parameters to bounds for valid arms only.""" + result = genome.copy() + valid_arms_mask = ~np.isnan(result[:, 0]) + + # Clip parameters for valid arms + for i in range(6): + new_params = np.clip( + result[valid_arms_mask, i], + self.parameter_limits[i, 0], + self.parameter_limits[i, 1] + ) + # Special handling for direction parameter (index 5) - must be 0 or 1 + if i == 5: + new_params = np.round(new_params).astype(int) + result[valid_arms_mask, i] = new_params + + return result + + def _wrap_angular_parameters(self, genome: npt.NDArray[Any]) -> npt.NDArray[Any]: + """Wrap angular parameters to their valid ranges.""" + result = genome.copy() + valid_arms_mask = ~np.isnan(result[:, 0]) + + # Wrap angular parameters that should be periodic + angular_params = [1, 2, 3, 4] # arm_rotation, arm_pitch, motor_rotation, motor_pitch + + for param_idx in angular_params: + values = result[valid_arms_mask, param_idx] + # Wrap all angular parameters to [-π, π] range + wrapped = np.mod(values + np.pi, 2*np.pi) - np.pi + result[valid_arms_mask, param_idx] = wrapped + + return result + + def repair_population(self, population: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Repair a population of spherical genomes. + + Args: + population: Population array of shape (pop_size, max_narms, 6) + + Returns: + Repaired population + """ + result = np.empty_like(population) + + for i in range(population.shape[0]): + result[i] = self.repair(population[i]) + + return result + + def validate_population(self, population: npt.NDArray[Any]) -> npt.NDArray[bool]: + """ + Validate a population of spherical genomes. + + Args: + population: Population array of shape (pop_size, max_narms, 6) + + Returns: + Boolean array indicating which individuals are valid + """ + result = np.empty(population.shape[0], dtype=bool) + + for i in range(population.shape[0]): + result[i] = self.validate(population[i]) + + return result + + def get_arm_count(self, genome: npt.NDArray[Any]) -> int: + """ + Get the number of valid arms in a genome. + + Args: + genome: Spherical genome array + + Returns: + Number of valid arms + """ + valid_arms_mask = ~np.isnan(genome[:, 0]) + return np.sum(valid_arms_mask) + + def get_valid_arms(self, genome: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Get only the valid (non-NaN) arms from a genome. + + Args: + genome: Spherical genome array + + Returns: + Array of valid arms + """ + valid_arms_mask = ~np.isnan(genome[:, 0]) + return genome[valid_arms_mask].copy() + + + def remove_random_arm(self, genome: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Remove a random arm (set to NaN). + + Args: + genome: Spherical genome array + + Returns: + Genome with removed arm, or original if min arms reached + """ + result = genome.copy() + valid_arms_mask = ~np.isnan(result[:, 0]) + num_valid_arms = np.sum(valid_arms_mask) + + if num_valid_arms <= self.min_narms: + return result # Can't remove, would go below minimum + + # Select random valid arm + valid_indices = np.where(valid_arms_mask)[0] + selected_index = self.rng.choice(valid_indices) + + # Remove arm + result[selected_index] = np.nan + + return result + + def _count_bounds_violations(self, arms: npt.NDArray[Any]) -> dict: + """Count bounds violations for each parameter.""" + violations = {} + + param_names = ['magnitude', 'arm_rotation', 'arm_pitch', + 'motor_rotation', 'motor_pitch', 'direction'] + + for i, name in enumerate(param_names): + values = arms[:, i] + min_bound, max_bound = self.parameter_limits[i] + + violations[name] = { + 'below_min': np.sum(values < min_bound), + 'above_max': np.sum(values > max_bound), + 'total': np.sum((values < min_bound) | (values > max_bound)) + } + + return violations + + def set_parameter_limits(self, parameter_limits: npt.NDArray[Any]) -> None: + """ + Update parameter limits. + + Args: + parameter_limits: New parameter limits array of shape (6, 2) + """ + if parameter_limits.shape != (6, 2): + raise ValueError("parameter_limits must have shape (6, 2)") + self.parameter_limits = parameter_limits.copy() + + def set_arm_count_limits(self, min_narms: int, max_narms: int) -> None: + """ + Update arm count limits. + + Args: + min_narms: New minimum number of arms + max_narms: New maximum number of arms + """ + if min_narms < 1: + raise ValueError("min_narms must be at least 1") + if max_narms < min_narms: + raise ValueError("max_narms must be >= min_narms") + + self.min_narms = min_narms + self.max_narms = max_narms + + def set_symmetry_operator(self, symmetry_operator: SphericalSymmetryOperator) -> None: + """ + Set the symmetry operator. + + Args: + symmetry_operator: New symmetry operator + """ + self.symmetry_operator = symmetry_operator + + def __repr__(self) -> str: + return (f"SphericalRepairOperator(config={self.config}, " + f"arm_limits=({self.min_narms}, {self.max_narms}), " + f"has_symmetry={self.symmetry_operator is not None})") \ No newline at end of file diff --git a/src/ariel/ec/drone/genome_handlers/operators/symmetry_base.py b/src/ariel/ec/drone/genome_handlers/operators/symmetry_base.py new file mode 100644 index 000000000..a79b8e80f --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/operators/symmetry_base.py @@ -0,0 +1,272 @@ +""" +Base classes and interfaces for symmetry operators. + +This module provides the abstract base class and common utilities for implementing +symmetry operations across different genome representations. +""" + +from __future__ import annotations + +from abc import ABC, abstractmethod +from typing import Any, Dict, Optional, Union, List +from enum import Enum + +import numpy as np +import numpy.typing as npt + + +class SymmetryPlane(Enum): + """Enumeration of supported symmetry planes.""" + XY = "xy" # Mirror across z=0 plane + XZ = "xz" # Mirror across y=0 plane + YZ = "yz" # Mirror across x=0 plane + +class SymmetryConfig: + """Configuration for symmetry operations.""" + + def __init__( + self, + plane: Union[SymmetryPlane, str, None] = None, + enabled: bool = True, + tolerance: float = 1e-6 + ): + """ + Initialize symmetry configuration. + + Args: + plane: Symmetry plane (SymmetryPlane enum, string, or None) + enabled: Whether symmetry is enabled + tolerance: Tolerance for symmetry validation + """ + if isinstance(plane, str): + try: + self.plane = SymmetryPlane(plane) + except ValueError: + raise ValueError(f"Invalid symmetry plane: {plane}") + elif plane is None: + self.plane = None + else: + self.plane = plane + + self.enabled = enabled and (self.plane != None) + self.tolerance = tolerance + + def __repr__(self) -> str: + return f"SymmetryConfig(plane={self.plane}, enabled={self.enabled}, tolerance={self.tolerance})" + + +class SymmetryOperator(ABC): + """ + Abstract base class for symmetry operations on genomes. + + This class defines the interface that all symmetry operators must implement, + providing a consistent API across different genome representations. + """ + + def __init__(self, config: Optional[SymmetryConfig] = None): + """ + Initialize the symmetry operator. + + Args: + config: Symmetry configuration. If None, creates default config. + """ + self.config = config or SymmetryConfig() + + @abstractmethod + def apply_symmetry(self, genome: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Apply symmetry constraints to a genome. + + Args: + genome: Input genome array + + Returns: + Genome with symmetry applied + """ + pass + + @abstractmethod + def validate_symmetry(self, genome: npt.NDArray[Any]) -> bool: + """ + Check if a genome satisfies symmetry constraints. + + Args: + genome: Genome array to validate + + Returns: + True if genome satisfies symmetry constraints, False otherwise + """ + pass + + @abstractmethod + def get_symmetry_pairs(self, genome: npt.NDArray[Any]) -> List[tuple]: + """ + Get pairs of indices that should be symmetric. + + Args: + genome: Genome array + + Returns: + List of (source_index, target_index) tuples + """ + pass + + def apply_symmetry_population(self, population: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Apply symmetry to a population of genomes. + + Args: + population: Population array of shape (pop_size, ...) + + Returns: + Population with symmetry applied + """ + if not self.config.enabled: + return population + + result = np.empty_like(population) + for i in range(population.shape[0]): + result[i] = self.apply_symmetry(population[i]) + return result + + def validate_symmetry_population(self, population: npt.NDArray[Any]) -> npt.NDArray[bool]: + """ + Validate symmetry for a population of genomes. + + Args: + population: Population array of shape (pop_size, ...) + + Returns: + Boolean array indicating which individuals satisfy symmetry + """ + if not self.config.enabled: + return np.ones(population.shape[0], dtype=bool) + + result = np.empty(population.shape[0], dtype=bool) + for i in range(population.shape[0]): + result[i] = self.validate_symmetry(population[i]) + return result + + def is_enabled(self) -> bool: + """Check if symmetry is enabled.""" + return self.config.enabled + + def get_plane(self) -> SymmetryPlane: + """Get the symmetry plane.""" + return self.config.plane + + def get_tolerance(self) -> float: + """Get the symmetry tolerance.""" + return self.config.tolerance + + def __repr__(self) -> str: + return f"{self.__class__.__name__}({self.config})" + + +class SymmetryUtilities: + """Common utilities for symmetry operations.""" + + @staticmethod + def flip_directions(directions: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Flip propeller directions for symmetry. + + Args: + directions: Array of directions (0 or 1) + + Returns: + Flipped directions (1 - original) + """ + return 1 - directions + + @staticmethod + def mirror_coordinate( + coordinate: npt.NDArray[Any], + axis: int + ) -> npt.NDArray[Any]: + """ + Mirror coordinates across a specific axis. + + Args: + coordinate: Coordinate array + axis: Axis to mirror across (0=x, 1=y, 2=z) + + Returns: + Mirrored coordinates + """ + result = coordinate.copy() + result[..., axis] = -result[..., axis] + return result + + @staticmethod + def mirror_angles( + angles: npt.NDArray[Any], + axes: List[int] + ) -> npt.NDArray[Any]: + """ + Mirror angles for symmetry transformation. + + Args: + angles: Array of angles + axes: List of axes to mirror + + Returns: + Mirrored angles + """ + result = angles.copy() + for axis in axes: + result[..., axis] = -result[..., axis] + return result + + @staticmethod + def validate_even_arm_count(narms: int) -> None: + """ + Validate that arm count is even (required for bilateral symmetry). + + Args: + narms: Number of arms + + Raises: + ValueError: If arm count is odd + """ + if narms % 2 != 0: + raise ValueError("Bilateral symmetry requires an even number of arms") + + @staticmethod + def get_symmetric_pairs(narms: int) -> List[tuple]: + """ + Get symmetric pairs for bilateral symmetry. + + Args: + narms: Number of arms (must be even) + + Returns: + List of (source, target) index pairs + """ + SymmetryUtilities.validate_even_arm_count(narms) + half_arms = narms // 2 + return [(i, half_arms + i) for i in range(half_arms)] + + @staticmethod + def check_value_symmetry( + value1: float, + value2: float, + tolerance: float = 1e-6, + should_be_equal: bool = True + ) -> bool: + """ + Check if two values satisfy symmetry constraints. + + Args: + value1: First value + value2: Second value + tolerance: Tolerance for comparison + should_be_equal: If True, values should be equal; if False, they should be negatives + + Returns: + True if values satisfy symmetry constraint + """ + if should_be_equal: + return abs(value1 - value2) <= tolerance + else: + return abs(value1 + value2) <= tolerance \ No newline at end of file diff --git a/src/ariel/ec/drone/genome_handlers/operators/symmetry_cartesian.py b/src/ariel/ec/drone/genome_handlers/operators/symmetry_cartesian.py new file mode 100644 index 000000000..7e302cdc2 --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/operators/symmetry_cartesian.py @@ -0,0 +1,372 @@ +""" +Cartesian symmetry operator for drone genome handlers. + +This module implements bilateral symmetry operations for Cartesian coordinate +representations with Euler angles. +""" + +from __future__ import annotations + +from typing import Any, List, Optional + +import numpy as np +import numpy.typing as npt + +from .symmetry_base import SymmetryOperator, SymmetryConfig, SymmetryPlane, SymmetryUtilities + + +class CartesianSymmetryOperator(SymmetryOperator): + """ + Symmetry operator for Cartesian coordinate genomes with Euler angles. + + Genome format expected: (max_narms, 7) with columns: + [x, y, z, roll, pitch, yaw, direction] + + Uses NaN masking for variable arm counts. + """ + + def __init__( + self, + config: Optional[SymmetryConfig] = None + ): + """ + Initialize the Cartesian symmetry operator. + + Args: + config: Symmetry configuration + """ + super().__init__(config) + + def apply_symmetry(self, genome: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Apply bilateral symmetry to a Cartesian genome. + + Args: + genome: Cartesian genome array of shape (max_narms, 7) + + Returns: + Genome with bilateral symmetry applied + """ + if not self.config.enabled: + return genome.copy() + + # Validate input shape + if genome.ndim != 2 or genome.shape[1] != 7: + raise ValueError(f"Expected genome shape (max_narms, 7), got {genome.shape}") + + # Find valid arms (non-NaN) + valid_arms_mask = ~np.isnan(genome[:, 0]) + if not np.any(valid_arms_mask): + return genome.copy() + max_narms = genome.shape[0] + + + valid_arms = genome[valid_arms_mask] + num_valid_arms = len(valid_arms) + + # Create result genome + result = np.full_like(genome, np.nan) + half_arms = max_narms // 2 + + # Place all valid arms in the result first + result[:num_valid_arms] = valid_arms + # Mirror the first half to the second half + for i in range(half_arms): + source_idx = i + target_idx = half_arms + i + + # Copy all parameters from source to target + result[target_idx] = result[source_idx].copy() + + # Apply symmetry transformations based on the plane + if self.config.plane == SymmetryPlane.XY: + # Mirror across z=0 plane + result[target_idx, 2] = -result[source_idx, 2] # z position + result[target_idx, 3] = -result[source_idx, 3] # (around y-axis) + result[target_idx, 4] = -result[source_idx, 4] # (around z-axis) + # yaw remains the same + + elif self.config.plane == SymmetryPlane.XZ: + # Mirror across y=0 plane + result[target_idx, 1] = -result[source_idx, 1] # y position + result[target_idx, 3] = -result[source_idx, 3] # (around x-axis) + result[target_idx, 5] = -result[source_idx, 5] # (around z-axis) + # pitch remains the same + + elif self.config.plane == SymmetryPlane.YZ: + # Mirror across x=0 plane, 34, 35, 45 + result[target_idx, 0] = -result[source_idx, 0] # x position + result[target_idx, 4] = -result[source_idx, 4] # (around x-axis) + result[target_idx, 5] = -result[source_idx, 5] # (around y-axis) + # roll remains the same + + # For bilateral symmetry, propeller directions should be mirrored + # to maintain rotational balance + result[target_idx, 6] = 1 - result[source_idx, 6] + + return result + + def validate_symmetry(self, genome: npt.NDArray[Any]) -> bool: + """ + Validate that a genome satisfies bilateral symmetry constraints. + + Args: + genome: Cartesian genome array of shape (max_narms, 7) + + Returns: + True if genome satisfies symmetry constraints + """ + if not self.config.enabled: + return True + + # Validate input + if genome.shape[1] != 7: + return False + + # Find valid arms + valid_arms_mask = ~np.isnan(genome[:, 0]) + if not np.any(valid_arms_mask): + return True # Empty genome is trivially symmetric + + valid_arms = genome[valid_arms_mask] + num_valid_arms = len(valid_arms) + + # Check even number of arms + if num_valid_arms % 2 != 0: + return False + + half_arms = num_valid_arms // 2 + tolerance = self.config.tolerance + + for i in range(half_arms): + source_arm = valid_arms[i] + target_arm = valid_arms[half_arms + i] + + # Check symmetry based on the plane + if self.config.plane == SymmetryPlane.XY: + # Check z position mirroring + if not SymmetryUtilities.check_value_symmetry( + target_arm[2], source_arm[2], tolerance, should_be_equal=False + ): + return False + # Check roll and pitch mirroring + if not SymmetryUtilities.check_value_symmetry( + target_arm[3], source_arm[3], tolerance, should_be_equal=False + ): + return False + if not SymmetryUtilities.check_value_symmetry( + target_arm[4], source_arm[4], tolerance, should_be_equal=False + ): + return False + # Check yaw remains same + if not SymmetryUtilities.check_value_symmetry( + target_arm[5], source_arm[5], tolerance, should_be_equal=True + ): + return False + + elif self.config.plane == SymmetryPlane.XZ: + # Check y position mirroring + if not SymmetryUtilities.check_value_symmetry( + target_arm[1], source_arm[1], tolerance, should_be_equal=False + ): + return False + # Check roll and yaw mirroring + if not SymmetryUtilities.check_value_symmetry( + target_arm[3], source_arm[3], tolerance, should_be_equal=False + ): + return False + if not SymmetryUtilities.check_value_symmetry( + target_arm[5], source_arm[5], tolerance, should_be_equal=False + ): + return False + # Check pitch remains same + if not SymmetryUtilities.check_value_symmetry( + target_arm[4], source_arm[4], tolerance, should_be_equal=True + ): + return False + + elif self.config.plane == SymmetryPlane.YZ: + # Check x position mirroring + if not SymmetryUtilities.check_value_symmetry( + target_arm[0], source_arm[0], tolerance, should_be_equal=False + ): + return False + # Check pitch and yaw mirroring + if not SymmetryUtilities.check_value_symmetry( + target_arm[4], source_arm[4], tolerance, should_be_equal=False + ): + return False + if not SymmetryUtilities.check_value_symmetry( + target_arm[5], source_arm[5], tolerance, should_be_equal=False + ): + return False + # Check roll remains same + if not SymmetryUtilities.check_value_symmetry( + target_arm[3], source_arm[3], tolerance, should_be_equal=True + ): + return False + + # Check coordinates that should be same for all planes + for coord_idx in [0, 1, 2]: + if coord_idx == 0 and self.config.plane == SymmetryPlane.YZ: + continue # x is mirrored for yz plane + if coord_idx == 1 and self.config.plane == SymmetryPlane.XZ: + continue # y is mirrored for xz plane + if coord_idx == 2 and self.config.plane == SymmetryPlane.XY: + continue # z is mirrored for xy plane + + if not SymmetryUtilities.check_value_symmetry( + target_arm[coord_idx], source_arm[coord_idx], + tolerance, should_be_equal=True + ): + return False + + # Check propeller direction mirroring + if target_arm[6] != (1 - source_arm[6]): + return False + + return True + + def get_symmetry_pairs(self, genome: npt.NDArray[Any]) -> List[tuple]: + """ + Get pairs of indices that should be symmetric. + + Args: + genome: Cartesian genome array of shape (max_narms, 7) + + Returns: + List of (source_index, target_index) tuples + """ + if not self.config.enabled: + return [] + + # Find valid arms (non-NaN) + valid_arms_mask = ~np.isnan(genome[:, 0]) + if not np.any(valid_arms_mask): + return [] # No valid arms + + valid_indices = np.where(valid_arms_mask)[0] + num_valid_arms = len(valid_indices) + + # Check even number of valid arms + if num_valid_arms % 2 != 0: + return [] # Can't have pairs with odd number of arms + + half_arms = num_valid_arms // 2 + pairs = [] + + for i in range(half_arms): + source_idx = valid_indices[i] + target_idx = valid_indices[half_arms + i] + pairs.append((source_idx, target_idx)) + + return pairs + + def get_mirrored_coordinates(self, genome: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Get coordinates with mirroring applied (without full symmetry). + + Args: + genome: Cartesian genome array of shape (max_narms, 7) + + Returns: + Coordinates with mirroring applied + """ + if not self.config.enabled: + return genome.copy() + + result = genome.copy() + + # Only mirror valid arms (non-NaN) + valid_arms_mask = ~np.isnan(genome[:, 0]) + + if self.config.plane == SymmetryPlane.XY: + result[valid_arms_mask, 2] = -result[valid_arms_mask, 2] # Mirror z + elif self.config.plane == SymmetryPlane.XZ: + result[valid_arms_mask, 1] = -result[valid_arms_mask, 1] # Mirror y + elif self.config.plane == SymmetryPlane.YZ: + result[valid_arms_mask, 0] = -result[valid_arms_mask, 0] # Mirror x + + return result + + def get_mirrored_orientations(self, genome: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Get orientations with mirroring applied (without full symmetry). + + Args: + genome: Cartesian genome array of shape (max_narms, 7) + + Returns: + Orientations with mirroring applied + """ + if not self.config.enabled: + return genome.copy() + + result = genome.copy() + + # Only mirror valid arms (non-NaN) + valid_arms_mask = ~np.isnan(genome[:, 0]) + + if self.config.plane == SymmetryPlane.XY: + result[valid_arms_mask, 3] = -result[valid_arms_mask, 3] # Mirror roll + result[valid_arms_mask, 4] = -result[valid_arms_mask, 4] # Mirror pitch + elif self.config.plane == SymmetryPlane.XZ: + result[valid_arms_mask, 3] = -result[valid_arms_mask, 3] # Mirror roll + result[valid_arms_mask, 5] = -result[valid_arms_mask, 5] # Mirror yaw + elif self.config.plane == SymmetryPlane.YZ: + result[valid_arms_mask, 4] = -result[valid_arms_mask, 4] # Mirror pitch + result[valid_arms_mask, 5] = -result[valid_arms_mask, 5] # Mirror yaw + + return result + + + def unapply_symmetry(self, genome: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Remove symmetry from a genome (keep only first half). + + Args: + genome: Symmetric genome array + + Returns: + Genome with only first half of symmetric arms + """ + if not self.config.enabled: + raise ValueError("Symmetry removal is not enabled in the configuration") + + # Find valid arms + valid_arms_mask = ~np.isnan(genome[:, 0]) + if not np.any(valid_arms_mask): + return genome.copy() + + valid_indices = np.where(valid_arms_mask)[0] + num_valid_arms = len(valid_indices) + + half_arms = num_valid_arms // 2 + + # Create result with only first half + result = genome.copy() + result[half_arms:] = np.nan # Set second half to NaN + + return result + + def unapply_symmetry_population(self, population: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Remove symmetry from a population of genomes. + + Args: + population: Population array of shape (pop_size, max_narms, 7) + + Returns: + Population with symmetry removed + """ + if not self.config.enabled: + return population.copy() + + result = np.empty_like(population) + for i in range(population.shape[0]): + result[i] = self.unapply_symmetry(population[i]) + + return result + + def __repr__(self) -> str: + return f"CartesianSymmetryOperator(config={self.config})" \ No newline at end of file diff --git a/src/ariel/ec/drone/genome_handlers/operators/symmetry_spherical.py b/src/ariel/ec/drone/genome_handlers/operators/symmetry_spherical.py new file mode 100644 index 000000000..a6b7e7c4e --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/operators/symmetry_spherical.py @@ -0,0 +1,350 @@ +""" +Spherical symmetry operator for drone genome handlers. + +This module implements bilateral symmetry operations for spherical coordinate +representations with angular orientations. +""" + +from __future__ import annotations + +from typing import Any, List, Optional + +import numpy as np +import numpy.typing as npt + +from .symmetry_base import SymmetryOperator, SymmetryConfig, SymmetryPlane, SymmetryUtilities +from scipy.spatial.transform import Rotation as R + +class SphericalSymmetryOperator(SymmetryOperator): + """ + Symmetry operator for spherical coordinate genomes with angular orientations. + + Genome format expected: (max_narms, 6) with columns: + [magnitude, arm_rotation, arm_pitch, motor_rotation, motor_pitch, direction] + + Uses NaN masking for variable arm counts. + """ + + def __init__( + self, + config: Optional[SymmetryConfig] = None, + coordinate_conversion_functions: Optional[dict] = None + ): + """ + Initialize the Spherical symmetry operator. + + Args: + config: Symmetry configuration + coordinate_conversion_functions: Optional dict with conversion functions + """ + super().__init__(config) + + # Import coordinate conversion functions + if coordinate_conversion_functions is None: + from ..conversions.arm_conversions import ( + spherical_angular_arms_to_cartesian_positions_and_quaternions, + cartesian_positions_and_quaternions_to_spherical_angular_arms + ) + self.to_cartesian = spherical_angular_arms_to_cartesian_positions_and_quaternions + self.from_cartesian = cartesian_positions_and_quaternions_to_spherical_angular_arms + + else: + self.to_cartesian = coordinate_conversion_functions.get('to_cartesian') + self.from_cartesian = coordinate_conversion_functions.get('from_cartesian') + + def apply_symmetry(self, genome: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Apply bilateral symmetry to a spherical genome. + + Args: + genome: Spherical genome array of shape (max_narms, 6) + + Returns: + Genome with bilateral symmetry applied + """ + if not self.config.enabled: + return genome.copy() + + # Validate input + if genome.shape[1] != 6: + raise ValueError("Spherical genome must have 6 parameters per arm") + + # Find valid arms (non-NaN) + valid_arms_mask = ~np.isnan(genome[:, 0]) + if not np.any(valid_arms_mask): + return genome.copy() + max_narms = genome.shape[0] + narm_valid = np.sum(valid_arms_mask) + if 2*narm_valid > max_narms: + raise ValueError( + f"Genome has {narm_valid} valid arms, but cannot create symmetry with max_narms={max_narms}" + ) + valid_arms = genome[valid_arms_mask] + num_valid_arms = len(valid_arms) + + # Create result genome + result = np.full_like(genome, np.nan) + result[:num_valid_arms] = valid_arms + + # Apply symmetry transformation + if self.config.plane == SymmetryPlane.XY: + # Mirror across z=0 plane + target_arms = self._mirror_across_xy_plane(valid_arms) + elif self.config.plane == SymmetryPlane.XZ: + # Mirror across y=0 plane + target_arms = self._mirror_across_xz_plane(valid_arms) + elif self.config.plane == SymmetryPlane.YZ: + # Mirror across x=0 plane + target_arms = self._mirror_across_yz_plane(valid_arms) + else: + # No specific plane, use general mirroring + raise ValueError(f"Unsupported symmetry plane: {self.config.plane}") + + result[num_valid_arms:2*num_valid_arms] = target_arms + + return result + + def _mirror_across_xy_plane(self, arms: npt.NDArray[Any]) -> npt.NDArray[Any]: + """Mirror arms across the xy plane (z=0).""" + # Convert to Cartesian for easier mirroring + positions, quaternions = self.to_cartesian(arms[:, :5]) + + # Mirror positions across z=0 + positions[:, 2] = -positions[:, 2] + + # Mirror quaternions appropriately for z-axis reflection, #TODO: Visually check this is correct + quaternions[:, 1] = -quaternions[:, 1] # x component + quaternions[:, 2] = -quaternions[:, 2] # y component + + # Convert back to spherical + mirrored_arms = self.from_cartesian(positions, quaternions) + + # Combine with direction (flipped) + result = np.zeros((len(arms), 6)) + result[:, :5] = mirrored_arms + result[:, 5] = 1 - arms[:, 5] # Flip direction + + return result + + + def _mirror_across_xz_plane(self, arms: npt.NDArray[Any]) -> npt.NDArray[Any]: + """Mirror arms across the xz plane (y=0).""" + positions, quaternions = self.to_cartesian(arms[:, :5]) + + # Mirror positions across y=0 + positions[:, 1] = -positions[:, 1] + + # Mirror quaternions appropriately for y-axis reflection, #TODO: Visually check this is correct + quaternions[:, 1] = -quaternions[:, 1] # w component + quaternions[:, 3] = -quaternions[:, 3] # z component + + # Convert back to spherical + mirrored_arms = self.from_cartesian(positions, quaternions) + + # Combine with direction (flipped) + result = np.zeros((len(arms), 6)) + result[:, :5] = mirrored_arms + result[:, 5] = 1 - arms[:, 5] # Flip direction + + return result + + def _mirror_across_yz_plane(self, arms: npt.NDArray[Any]) -> npt.NDArray[Any]: + """Mirror arms across the yz plane (x=0).""" + positions, quaternions = self.to_cartesian(arms[:, :5]) + + # Mirror positions across x=0 + positions[:, 0] = -positions[:, 0] + + # Mirror quaternions appropriately for x-axis reflection, + quaternions[:, 2] = -quaternions[:, 2] # y component + quaternions[:, 3] = -quaternions[:, 3] # z component + + # Convert back to spherical + mirrored_arms = self.from_cartesian(positions, quaternions) + + # Combine with direction (flipped) + result = np.zeros((len(arms), 6)) + result[:, :5] = mirrored_arms + result[:, 5] = 1 - arms[:, 5] # Flip direction + + return result + + def _mirror_arms_direct(self, arms: npt.NDArray[Any], mirror_axis: int) -> npt.NDArray[Any]: + """Direct angular mirroring for spherical coordinates.""" + + if mirror_axis == "xy": + result = self._mirror_across_xy_plane(arms) + elif mirror_axis == "xz": + result = self._mirror_across_xz_plane(arms) + elif mirror_axis == "yz": + result = self._mirror_across_yz_plane(arms) + else: + raise ValueError(f"Unsupported symmetry plane: {mirror_axis}") + + return result + + def validate_symmetry(self, genome: npt.NDArray[Any]) -> bool: + """ + Validate that a genome satisfies bilateral symmetry constraints. + + Args: + genome: Spherical genome array of shape (max_narms, 6) + + Returns: + True if genome satisfies symmetry constraints + """ + if not self.config.enabled: + return True + + # Validate input + if genome.shape[1] != 6: + # print("Invalid genome shape for symmetry validation. Expected (max_narms, 6).") + return False + + # Find valid arms + valid_arms_mask = ~np.isnan(genome[:, 0]) + if not np.any(valid_arms_mask): + return True # Empty genome is trivially symmetric + + valid_arms = genome[valid_arms_mask] + num_valid_arms = len(valid_arms) + + # Check even number of arms + if num_valid_arms % 2 != 0: + # print(f"Invalid genome for symmetry validation: {num_valid_arms} valid arms found, expected even number.") + return False + + half_arms = num_valid_arms // 2 + tolerance = self.config.tolerance + + # Check symmetry by comparing first half with second half + for i in range(half_arms): + source_arm = valid_arms[i] + target_arm = valid_arms[half_arms + i] + + # Check if target arm is the symmetric version of source arm + expected_target = self._mirror_arms_direct(np.array([source_arm]), self.config.plane.value)[0] + + # Compare with tolerance + for j in range(5): # Don't check direction yet + if not SymmetryUtilities.check_value_symmetry( + target_arm[j], expected_target[j], tolerance, should_be_equal=True + ): + # print(f"Validation failed for arm {i}: \n{source_arm} vs \n{target_arm}") + # print(f"Expected: {expected_target}") + return False + + # Check direction flipping + if target_arm[5] != (1 - source_arm[5]): + # print(f"Direction mismatch for arm {i}: {source_arm[5]} vs {target_arm[5]}") + return False + + return True + + + def get_symmetry_pairs(self, genome: npt.NDArray[Any]) -> List[tuple]: + """ + Get pairs of indices that should be symmetric. + + Args: + genome: Spherical genome array of shape (max_narms, 6) + + Returns: + List of (source_index, target_index) tuples + """ + if not self.config.enabled: + return [] + + # Find valid arms + valid_arms_mask = ~np.isnan(genome[:, 0]) + valid_indices = np.where(valid_arms_mask)[0] + num_valid_arms = len(valid_indices) + + if num_valid_arms % 2 != 0: + return [] # Can't have pairs with odd number of arms + + half_arms = num_valid_arms // 2 + pairs = [] + + for i in range(half_arms): + source_idx = valid_indices[i] + target_idx = valid_indices[half_arms + i] + pairs.append((source_idx, target_idx)) + + return pairs + + def apply_symmetry_population(self, population: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Apply symmetry to a population of spherical genomes. + + Args: + population: Population array of shape (pop_size, max_narms, 6) + + Returns: + Population with symmetry applied + """ + if not self.config.enabled: + return population.copy() + + result = np.empty_like(population) + for i in range(population.shape[0]): + result[i] = self.apply_symmetry(population[i]) + return result + + def unapply_symmetry(self, genome: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Remove symmetry from a genome (keep only first half). + + Args: + genome: Symmetric genome array + + Returns: + Genome with only first half of symmetric arms + """ + if not self.config.enabled: + raise ValueError("Symmetry removal is not enabled in the configuration") + + # Find valid arms + valid_arms_mask = ~np.isnan(genome[:, 0]) + if not np.any(valid_arms_mask): + return genome.copy() + + valid_indices = np.where(valid_arms_mask)[0] + num_valid_arms = len(valid_indices) + + if num_valid_arms % 2 != 0: + raise ValueError("Genome must have an even number of valid arms for symmetry removal. Found: ", num_valid_arms) + + half_arms = num_valid_arms // 2 + + # Create result with only first half + result = genome.copy() + result[half_arms:] = np.nan # Set second half to NaN + + return result + + def unapply_symmetry_population(self, population: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Remove symmetry from a population of genomes. + + Args: + population: Population array of shape (pop_size, max_narms, 6) + + Returns: + Population with symmetry removed + """ + if not self.config.enabled: + return population.copy() + + result = np.empty_like(population) + for i in range(population.shape[0]): + result[i] = self.unapply_symmetry(population[i]) + + return result + + def is_enabled(self) -> bool: + """Check if symmetry is enabled.""" + return self.config.enabled + + def __repr__(self) -> str: + return f"SphericalSymmetryOperator(config={self.config})" \ No newline at end of file diff --git a/src/ariel/ec/drone/genome_handlers/repair_workflow.py b/src/ariel/ec/drone/genome_handlers/repair_workflow.py new file mode 100644 index 000000000..1ceb867b3 --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/repair_workflow.py @@ -0,0 +1,700 @@ +""" +Repair workflow module for drone genomes. + +This module implements a three-stage repair process: +1. Optimization repair - Fix collisions using constrained optimization +2. Hover check - Verify the individual can hover +3. Hover repair - Align thrust vectors for optimal hovering + +The workflow always returns a tuple (repaired_individual, status_message). +If repair fails at any stage, returns (NaN_individual, failure_message). +""" + +from __future__ import annotations + +import sys +import os +import numpy as np +import numpy.typing as npt +from typing import Tuple, Optional, List, Dict, Any +import warnings + +# Add drone-hover library to path if DRONE_HOVER_PATH environment variable is set +DRONE_HOVER_PATH = os.environ.get("DRONE_HOVER_PATH", None) +if DRONE_HOVER_PATH and DRONE_HOVER_PATH not in sys.path: + sys.path.insert(0, DRONE_HOVER_PATH) + +# Airevolve imports +from ariel.ec.drone.genome_handlers.operators.optimization_repair_operator import ( + OptimizationBasedRepairOperator, + OptimizationRepairConfig, +) +from ariel.ec.drone.genome_handlers.conversions.arm_conversions import ( + Cylinder, + arms_to_cylinders_polar_angular, + cylinders_to_arms_polar_angular, + arms_to_cylinders_cartesian_euler, + cylinders_to_arms_cartesian_euler, +) +# Note: get_sim is imported lazily in functions that need it due to import issues in hovering_info.py + +# Drone-hover imports +try: + from dronehover.bodies.custom_bodies import Custombody + from dronehover.optimization import Hover + from dronehover.utils import align_vectors + DRONE_HOVER_AVAILABLE = True +except ImportError as e: + DRONE_HOVER_AVAILABLE = False + DRONE_HOVER_IMPORT_ERROR = str(e) + path_msg = f" Set DRONE_HOVER_PATH environment variable if needed." if not DRONE_HOVER_PATH else f" Current path: {DRONE_HOVER_PATH}" + warnings.warn( + f"Failed to import drone-hover library: {e}\n" + f"Hover repair (Stage 3) will not be available.\n" + f"Make sure drone-hover is installed.{path_msg}" + ) + + +# ============================================================================ +# CONVERSION UTILITIES: Genome ↔ Drone-Hover Props +# ============================================================================ + +def genome_to_drone_hover_props( + genome: npt.NDArray[Any], + coordinate_system: str = 'spherical', + propeller_radius: float = 0.0127, # 1-inch radius (2-inch diameter propellers) + cylinder_height: float = None, # Will default to 8 * propeller_radius + default_propsize: int = 2 +) -> List[Dict[str, Any]]: + """ + Convert airevolve genome to drone-hover props format. + + The props format is: + { + "loc": [x, y, z], # Motor position + "dir": [dx, dy, dz, rotation], # Thrust direction + rotation (ccw/cw) + "propsize": int # Propeller size + } + + Parameters: + ----------- + genome : array-like of shape (n_arms, 6) or (n_arms, 7) + Genome in spherical [r, theta, phi, pitch, yaw, direction] + or Cartesian [x, y, z, roll, pitch, yaw, direction] format + coordinate_system : str + 'spherical' or 'cartesian' + propeller_radius : float + Radius of propeller (default: 0.0127m = 1 inch radius, 2-inch diameter propellers) + cylinder_height : float, optional + Height of motor cylinder (default: 8 * propeller_radius = swept area) + default_propsize : int + Default propeller size (default: 2 for 2-inch diameter) + + Returns: + -------- + props : list of dicts + List of propeller configurations in drone-hover format + """ + # Set default cylinder height to 8 * propeller_radius if not provided + if cylinder_height is None: + cylinder_height = 8 * propeller_radius + + # Filter out NaN arms + valid_arms = ~np.isnan(genome).any(axis=-1) + if not np.any(valid_arms): + return [] + + valid_genome = genome[valid_arms] + + # Convert genome to cylinders (which have position and orientation) + if coordinate_system == 'spherical': + cylinders = arms_to_cylinders_polar_angular( + valid_genome, propeller_radius, cylinder_height + ) + elif coordinate_system == 'cartesian': + cylinders = arms_to_cylinders_cartesian_euler( + valid_genome, propeller_radius, cylinder_height + ) + else: + raise ValueError(f"Unknown coordinate system: {coordinate_system}") + + # Extract direction column (last column) + directions = valid_genome[:, -1] + + # Convert cylinders to props + props = [] + for i, cyl in enumerate(cylinders): + # Get motor position (cylinder center) + loc = cyl.position.tolist() + + # Get thrust direction from cylinder orientation + # The cylinder is oriented along its z-axis, so we extract the z-direction + # from the rotation matrix + rotation_matrix = cyl.rotation_matrix + thrust_dir = rotation_matrix[:, 2] # Z-axis direction + + # Determine rotation direction (ccw or cw) + # direction = 0 -> ccw, direction = 1 -> cw + rotation = "ccw" if directions[i] < 0.5 else "cw" + + # Create prop dict + prop = { + "loc": loc, + "dir": thrust_dir.tolist() + [rotation], + "propsize": default_propsize + } + props.append(prop) + + return props + + +def drone_hover_props_to_genome( + props: List[Dict[str, Any]], + coordinate_system: str = 'spherical', + original_genome_shape: Optional[Tuple[int, int]] = None +) -> npt.NDArray[Any]: + """ + Convert drone-hover props back to airevolve genome format. + + Parameters: + ----------- + props : list of dicts + Propeller configurations in drone-hover format + coordinate_system : str + 'spherical' or 'cartesian' + original_genome_shape : tuple, optional + Shape of original genome (n_arms, n_params). If provided and larger + than len(props), will pad with NaN. + + Returns: + -------- + genome : array-like + Genome in airevolve format + """ + if len(props) == 0: + if original_genome_shape is not None: + return np.full(original_genome_shape, np.nan) + else: + return np.array([]) + + # Extract positions and directions (in NED frame from drone-hover) + positions_ned = [] + thrust_dirs_ned = [] + rotations = [] + + for prop in props: + positions_ned.append(prop["loc"]) + thrust_dirs_ned.append(prop["dir"][:3]) # x, y, z components + rotations.append(0.0 if prop["dir"][3] == "ccw" else 1.0) + + positions_ned = np.array(positions_ned) + thrust_dirs_ned = np.array(thrust_dirs_ned) + rotations = np.array(rotations) + + # Convert to genome format based on coordinate system + if coordinate_system == 'spherical': + # Props are in NED frame (from get_sim's ENU_to_NED conversion). + # We must invert the conversions in get_sim/hovering_info.py: + # Position: ENU = convert_to_cartesian(mag, arm_yaw, arm_pitch) + # NED = ENU_to_NED(ENU) = (ENU_y, ENU_x, -ENU_z) + # Direction: NED = orientation_to_unit_vector(0, mot_pitch, mot_yaw) + # = ENU_to_NED @ euler_R(0, pitch, yaw) @ [0, 0, -1] + + # --- Arm positions: NED -> (mag, arm_yaw, arm_pitch) --- + # NED_to_ENU: (ned_x, ned_y, ned_z) -> (ned_y, ned_x, -ned_z) + enu_x = positions_ned[:, 1] + enu_y = positions_ned[:, 0] + enu_z = -positions_ned[:, 2] + + mag = np.sqrt(enu_x**2 + enu_y**2 + enu_z**2) + arm_yaw = np.arctan2(enu_y, enu_x) + # convert_to_cartesian uses: z = mag * sin(pitch), so pitch = arcsin(z/mag) + arm_pitch = np.where(mag > 0, np.arcsin(np.clip(enu_z / mag, -1, 1)), 0.0) + + # --- Motor orientation: NED direction -> (mot_pitch, mot_yaw) --- + # orientation_to_unit_vector(0, p, y) produces NED direction: + # [-sin(p)*sin(y), -sin(p)*cos(y), cos(p)] + # Inversion: mot_pitch = arccos(ned_z), mot_yaw = arctan2(-ned_x, -ned_y) + dirs_norm = np.linalg.norm(thrust_dirs_ned, axis=1, keepdims=True) + dirs_norm = np.where(dirs_norm > 0, dirs_norm, 1.0) + dirs_normalized = thrust_dirs_ned / dirs_norm + mot_pitch = np.arccos(np.clip(dirs_normalized[:, 2], -1, 1)) + mot_yaw = np.arctan2(-dirs_normalized[:, 0], -dirs_normalized[:, 1]) + + # Genome columns: [mag, arm_yaw, arm_pitch, mot_pitch, mot_yaw, direction] + genome = np.column_stack([mag, arm_yaw, arm_pitch, mot_pitch, mot_yaw, rotations]) + + elif coordinate_system == 'cartesian': + from scipy.spatial.transform import Rotation as ScipyRotation + + quaternions = [] + for thrust_dir in thrust_dirs_ned: + thrust_dir = thrust_dir / np.linalg.norm(thrust_dir) + default_z = np.array([0, 0, 1]) + if np.allclose(thrust_dir, default_z): + quat = np.array([1, 0, 0, 0]) + elif np.allclose(thrust_dir, -default_z): + quat = np.array([0, 1, 0, 0]) + else: + rotation_axis = np.cross(default_z, thrust_dir) + rotation_axis = rotation_axis / np.linalg.norm(rotation_axis) + rotation_angle = np.arccos(np.clip(np.dot(default_z, thrust_dir), -1, 1)) + rot = ScipyRotation.from_rotvec(rotation_angle * rotation_axis) + quat = rot.as_quat() + quat = np.array([quat[3], quat[0], quat[1], quat[2]]) + quaternions.append(quat) + quaternions = np.array(quaternions) + + from ariel.ec.drone.genome_handlers.conversions.arm_conversions import ( + cartesian_positions_and_quaternions_to_cartesian_euler_arms + ) + genome_without_dir = cartesian_positions_and_quaternions_to_cartesian_euler_arms( + positions_ned, quaternions + ) + genome = np.column_stack([genome_without_dir, rotations]) + else: + raise ValueError(f"Unknown coordinate system: {coordinate_system}") + + # Pad with NaN if necessary + if original_genome_shape is not None: + n_original_arms = original_genome_shape[0] + n_current_arms = len(genome) + + if n_current_arms < n_original_arms: + # Pad with NaN rows + n_params = genome.shape[1] + padding = np.full((n_original_arms - n_current_arms, n_params), np.nan) + genome = np.vstack([genome, padding]) + + return genome + + +# ============================================================================ +# REPAIR STAGE FUNCTIONS +# ============================================================================ + +def stage1_optimization_repair( + individual: npt.NDArray[Any], + coordinate_system: str = 'spherical', + config: Optional[OptimizationRepairConfig] = None, + verbose: bool = False +) -> Tuple[Optional[npt.NDArray[Any]], str]: + """ + Stage 1: Apply optimization-based repair to fix collisions. + + Parameters: + ----------- + individual : array-like + Genome to repair + coordinate_system : str + 'spherical' or 'cartesian' + config : OptimizationRepairConfig, optional + Configuration for optimization repair + verbose : bool + Print progress messages + + Returns: + -------- + (repaired_individual, message) : tuple + - repaired_individual: Repaired genome or None if failed + - message: Status message + """ + try: + if verbose: + print(" Stage 1: Optimization Repair...") + + # Create repair operator + repair_operator = OptimizationBasedRepairOperator( + optimization_config=config, + coordinate_system=coordinate_system, + verbose=verbose + ) + + # Apply repair + repaired = repair_operator.repair(individual) + + # Validate repair + if repair_operator.validate(repaired): + if verbose: + print(" ✓ Stage 1: Passed") + return repaired, "Stage 1: Success" + else: + if verbose: + print(" ✗ Stage 1: Failed (validation failed)") + return None, "Failed at Stage 1: Optimization Repair (validation failed)" + + except Exception as e: + if verbose: + print(f" ✗ Stage 1: Failed with exception: {e}") + return None, f"Failed at Stage 1: Optimization Repair (exception: {e})" + + +def stage2_hover_check( + individual: npt.NDArray[Any], + verbose: bool = False, + allow_spinning: bool = False +) -> Tuple[bool, str]: + """ + Stage 2: Check if the individual can hover. + + Uses the same logic as gate_train.py:311-318 + + Parameters: + ----------- + individual : array-like + Genome to check + verbose : bool + Print progress messages + allow_spinning : bool + Whether to allow spinning hover (default: False) + + Returns: + -------- + (can_hover, message) : tuple + - can_hover: True if can hover, False otherwise + - message: Status message + """ + try: + if verbose: + print(" Stage 2: Hover Check...") + # Debug: Print individual info + print(f" Individual shape: {individual.shape}") + print(f" Valid arms: {(~np.isnan(individual).any(axis=-1)).sum()}") + + # Lazy import to avoid module-level import issues + from ariel.ec.drone.inspection.morphological_descriptors.hovering_info import get_sim + + # Get simulator + sim = get_sim(individual) + + # Compute hover + sim.compute_hover(verbose=False) + + # Check success + if sim.static_success == False: + spinning_success = sim.spinning_success if allow_spinning else False + else: + spinning_success = False + + success = sim.static_success or spinning_success + + # Determine hover type + if sim.static_success: + hover_type = "static" + elif spinning_success: + hover_type = "spinning" + else: + hover_type = "none" + + if success: + if verbose: + print(f" ✓ Stage 2: Passed ({hover_type} hover)") + return True, f"Stage 2: Success ({hover_type} hover)" + else: + if verbose: + print(" ✗ Stage 2: Failed (cannot hover)") + # Debug: Print why it failed + print(f" static_success: {sim.static_success}") + print(f" spinning_success: {sim.spinning_success}") + print(f" allow_spinning: {allow_spinning}") + # Check if hover solution exists + if hasattr(sim, 'eta') and sim.eta is not None: + print(f" eta (motor thrusts): {sim.eta}") + print(f" eta min/max: {sim.eta.min():.4f} / {sim.eta.max():.4f}") + if hasattr(sim, 'residual'): + print(f" residual: {sim.residual}") + return False, "Failed at Stage 2: Hover Check (cannot hover)" + + except Exception as e: + if verbose: + print(f" ✗ Stage 2: Failed with exception: {e}") + import traceback + traceback.print_exc() + return False, f"Failed at Stage 2: Hover Check (exception: {e})" + + +def stage3_hover_repair( + individual: npt.NDArray[Any], + coordinate_system: str = 'spherical', + verbose: bool = False +) -> Tuple[Optional[npt.NDArray[Any]], str]: + """ + Stage 3: Apply hover repair to align thrust vectors. + + Uses hover_repair() from drone-hover library. + + Parameters: + ----------- + individual : array-like + Genome to repair + coordinate_system : str + 'spherical' or 'cartesian' + verbose : bool + Print progress messages + + Returns: + -------- + (repaired_individual, message) : tuple + - repaired_individual: Repaired genome or None if failed + - message: Status message + """ + if not DRONE_HOVER_AVAILABLE: + return None, f"Failed at Stage 3: Hover Repair (drone-hover not available: {DRONE_HOVER_IMPORT_ERROR})" + + try: + if verbose: + print(" Stage 3: Hover Repair...") + + # Use the same get_sim() function as Stage 2 to ensure consistency + from ariel.ec.drone.inspection.morphological_descriptors.hovering_info import get_sim + + sim = get_sim(individual) + + if sim is None: + if verbose: + print(" ✗ Stage 3: Failed (could not create simulator)") + return None, "Failed at Stage 3: Hover Repair (could not create simulator)" + + # Apply hover repair + # Reimplementation of hover_repair() from drone-hover/examples/hover_repair.py + sim.compute_hover(verbose=False) + + if not sim.static_success: + if verbose: + print(" ✗ Stage 3: Failed (hover repair requires hoverable drone)") + return None, "Failed at Stage 3: Hover Repair (drone cannot hover)" + + # Get the drone from sim + drone = sim.drone + + # Get thrust direction + f = sim.Bf @ sim.eta + f = f / np.linalg.norm(f) + + # Align vectors to point downward ([0, 0, -1]) + R2 = align_vectors(f, [0, 0, -1]) + + # Apply rotation to all props + repaired_props = [] + for prop in drone.props: + new_prop = prop.copy() + + new_pos = R2 @ np.array(prop["loc"]) + new_dir = R2 @ np.array(prop["dir"][0:3]) + + new_prop["loc"] = new_pos.tolist() + new_prop["dir"] = new_dir.tolist() + [prop["dir"][3]] + + repaired_props.append(new_prop) + + # Convert back to genome + repaired_individual = drone_hover_props_to_genome( + repaired_props, + coordinate_system, + original_genome_shape=individual.shape + ) + + if verbose: + print(" ✓ Stage 3: Passed") + + return repaired_individual, "Stage 3: Success" + + except Exception as e: + if verbose: + print(f" ✗ Stage 3: Failed with exception: {e}") + return None, f"Failed at Stage 3: Hover Repair (exception: {e})" + + +# ============================================================================ +# MAIN REPAIR WORKFLOW +# ============================================================================ + +def repair_operation_process( + individual: npt.NDArray[Any], + coordinate_system: str = 'spherical', + optimization_config: Optional[OptimizationRepairConfig] = None, + allow_spinning_hover: bool = False, + verbose: bool = False +) -> Tuple[npt.NDArray[Any], str]: + """ + Execute the complete three-stage repair workflow. + + Workflow: + 1. Optimization Repair - Fix collisions + 2. Hover Check - Verify can hover + 3. Hover Repair - Align thrust vectors + + If any stage fails, returns NaN individual with failure message. + + Parameters: + ----------- + individual : array-like + Genome to repair + coordinate_system : str + 'spherical' or 'cartesian' + optimization_config : OptimizationRepairConfig, optional + Configuration for optimization repair + allow_spinning_hover : bool + Whether to allow spinning hover in Stage 2 + verbose : bool + Print detailed progress messages + + Returns: + -------- + (repaired_individual, status_message) : tuple + - repaired_individual: Repaired genome or NaN genome if failed + - status_message: Detailed status message indicating success or failure stage + """ + if verbose: + print("\n=== Repair Operation Process ===") + + # Default config: always fix motor orientation params (pitch=3, yaw=4) + if optimization_config is None: + optimization_config = OptimizationRepairConfig(fixed_params=[3, 4]) + + # Stage 1: Optimization Repair (fix collisions, preserve motor orientation) + repaired, msg = stage1_optimization_repair( + individual, coordinate_system, optimization_config, verbose + ) + + if repaired is None: + # Stage 1 failed - return NaN individual + nan_individual = np.full_like(individual, np.nan) + if verbose: + print(f"✗ Repair failed: {msg}\n") + return nan_individual, msg + + # If Stage 1 didn't change the genome (no collisions), the individual is + # already valid — skip Stages 2+3 to avoid breaking already-repaired genomes + # whose geometry may not survive the Stage 3 round-trip. + if np.array_equal(repaired, individual): + if verbose: + print(" No collisions found — skipping Stages 2+3\n") + return individual.copy(), "No repair needed: collision-free" + + if verbose: + print(f" Post-Stage 1 genome:\n{repaired}") + + # Stage 2: Hover Check (only after Stage 1 modified the genome) + can_hover, msg = stage2_hover_check(repaired, verbose, allow_spinning_hover) + + if not can_hover: + # Stage 2 failed - return NaN individual + nan_individual = np.full_like(individual, np.nan) + if verbose: + print(f"✗ Repair failed: {msg}\n") + return nan_individual, msg + + # Stage 3: Hover Repair + final_repaired, msg = stage3_hover_repair(repaired, coordinate_system, verbose) + + if final_repaired is None: + # Stage 3 failed - return NaN individual + nan_individual = np.full_like(individual, np.nan) + if verbose: + print(f"✗ Repair failed: {msg}\n") + return nan_individual, msg + + # All stages passed! + if verbose: + print("✓ Repair completed successfully\n") + + return final_repaired, "All stages passed: Success" + + +# ============================================================================ +# UTILITY FUNCTIONS +# ============================================================================ + +def create_nan_individual(shape: Tuple[int, ...]) -> npt.NDArray[Any]: + """ + Create a NaN individual with the given shape. + + Parameters: + ----------- + shape : tuple + Shape of the individual array + + Returns: + -------- + nan_individual : array-like + Array filled with NaN values + """ + return np.full(shape, np.nan) + + +def is_nan_individual(individual: npt.NDArray[Any]) -> bool: + """ + Check if an individual is all NaN. + + Parameters: + ----------- + individual : array-like + Individual to check + + Returns: + -------- + is_nan : bool + True if all values are NaN + """ + return np.all(np.isnan(individual)) + + +# ============================================================================ +# EXAMPLE USAGE +# ============================================================================ + +if __name__ == "__main__": + print("=== Repair Workflow Module Test ===\n") + + # Create a test genome (spherical coordinates) + # Format: [r, theta, phi, pitch, yaw, direction] + test_genome = np.array([ + [0.15, 0.0, np.pi/4, 0.1, 0.0, 0.0], + [0.15, np.pi/2, np.pi/4, 0.1, 0.0, 1.0], + [0.15, np.pi, np.pi/4, 0.1, 0.0, 0.0], + [0.15, -np.pi/2, np.pi/4, 0.1, 0.0, 1.0], + ], dtype=float) + + print("Test genome shape:", test_genome.shape) + print("Test genome:\n", test_genome) + + # Test conversion to props + print("\n--- Testing genome_to_drone_hover_props ---") + props = genome_to_drone_hover_props(test_genome, coordinate_system='spherical') + print(f"Converted {len(props)} props:") + for i, prop in enumerate(props): + print(f" Prop {i+1}:") + print(f" loc: {prop['loc']}") + print(f" dir: {prop['dir']}") + print(f" propsize: {prop['propsize']}") + + # Test conversion back to genome + print("\n--- Testing drone_hover_props_to_genome ---") + reconstructed = drone_hover_props_to_genome( + props, coordinate_system='spherical', original_genome_shape=test_genome.shape + ) + print("Reconstructed genome shape:", reconstructed.shape) + print("Reconstructed genome:\n", reconstructed) + + # Check roundtrip error (excluding direction column which may have precision issues) + print("\n--- Roundtrip Conversion Test ---") + error = np.abs(test_genome - reconstructed) + print(f"Max error: {np.max(error):.6e}") + print(f"Mean error: {np.mean(error):.6e}") + + # Test full repair workflow + print("\n--- Testing Full Repair Workflow ---") + repaired, status = repair_operation_process( + test_genome, + coordinate_system='spherical', + verbose=True + ) + + print(f"\nFinal status: {status}") + print(f"Repaired individual is NaN: {is_nan_individual(repaired)}") + + if not is_nan_individual(repaired): + print("Repaired genome:\n", repaired) + + print("\n=== Test Complete ===") diff --git a/src/ariel/ec/drone/genome_handlers/spherical_angular_genome_handler.py b/src/ariel/ec/drone/genome_handlers/spherical_angular_genome_handler.py new file mode 100644 index 000000000..066429f6e --- /dev/null +++ b/src/ariel/ec/drone/genome_handlers/spherical_angular_genome_handler.py @@ -0,0 +1,1318 @@ +from __future__ import annotations + +from dataclasses import dataclass +from typing import Any, List, Tuple, Optional + +import numpy as np +import numpy.typing as npt + +from .base import GenomeHandler +from .cppn.innovation import InnovationCounter +from .operators import ( + SphericalSymmetryOperator, + SphericalRepairOperator, + SymmetryConfig, + RepairConfig +) + + +@dataclass +class SphericalNeatGenome: + """Wraps a spherical arm array with NEAT-style innovation IDs. + + Attributes: + arms: (max_narms, 6) array with NaN padding for empty slots. + innovation_ids: (max_narms,) int array; -1 marks empty slots. + """ + + arms: npt.NDArray[Any] + innovation_ids: npt.NDArray[Any] + + def copy(self) -> SphericalNeatGenome: + return SphericalNeatGenome( + arms=self.arms.copy(), + innovation_ids=self.innovation_ids.copy(), + ) + + +class SphericalAngularDroneGenomeHandler(GenomeHandler): + """ + Genome handler for drone designs using spherical coordinates and angular orientations. + + Genome format: (narms, 6) array with columns: + [magnitude, arm_rotation, arm_pitch, motor_rotation, motor_pitch, direction] + + Features: + - Dynamic arm addition/removal during mutation + - Optional symmetry enforcement + - Vectorized operations for efficiency + - Collision repair capabilities + - Variable population sizes with NaN masking + """ + + _innovation_counter: InnovationCounter = InnovationCounter() + + def __init__( + self, + genome: npt.NDArray[Any] | SphericalNeatGenome | None = None, + min_max_narms: Tuple[int, int] | None = None, + parameter_limits: npt.NDArray[Any] | None = None, + append_arm_chance: float = 0.1, + mutation_probs: Optional[List[float] | npt.NDArray[Any]] = None, + mutation_scales_percentage: Optional[npt.NDArray[Any]] = None, + bilateral_plane_for_symmetry: str | None = None, + repair: bool = False, + enable_collision_repair: bool = False, + propeller_radius: float = 0.0508/2, # 2-inch propeller radius in meters + inner_boundary_radius: float = 0.0055, + outer_boundary_radius: float = 0.11, + max_repair_iterations: int = 100, + repair_step_size: float = 1.0, + propeller_tolerance: float = 0.1, + rnd: np.random.Generator | None = None, + ) -> None: + """ + Initialize the Spherical Angular genome handler. + + Args: + genome: Pre-existing genome array of shape (max_narms, 6) + min_max_narms: Tuple of (min_arms, max_arms). If None, defaults to (3, 8) + parameter_limits: Array of shape (6, 2) with [min, max] for each parameter. If None, uses defaults + append_arm_chance: Probability of adding/removing arms during mutation + mutation_probs: Custom mutation probabilities for each parameter + mutation_scales_percentage: Mutation scales as percentage of parameter ranges + bilateral_plane_for_symmetry: Plane for bilateral symmetry ("xy", "xz", "yz", or None) + repair: Whether to apply repair operations + enable_collision_repair: Whether to enable collision detection and repair + propeller_radius: Radius of propellers for collision detection + inner_boundary_radius: Minimum distance from origin + outer_boundary_radius: Maximum distance from origin + max_repair_iterations: Maximum iterations for collision repair + repair_step_size: Step size multiplier for collision resolution + propeller_tolerance: Additional clearance tolerance for propellers + rnd: Random number generator + """ + self.rnd = rnd if rnd is not None else np.random.default_rng() + + # Set basic attributes from standardized parameters + if min_max_narms is None: + self.min_narms, self.max_narms = 3, 8 # Default range for spherical + else: + self.min_narms, self.max_narms = min_max_narms + + # Setup parameter limits + if parameter_limits is None: + # Default limits: [magnitude, arm_rotation, arm_pitch, motor_rotation, motor_pitch, direction] + # arm_pitch uses elevation convention: 0 = horizontal, + # +π/2 = straight up, −π/2 = straight down. + self.parameter_limits = np.array([ + [0.055, 0.17], # magnitude + [-np.pi, np.pi], # arm rotation (azimuth) + [-np.pi/2, np.pi/2], # arm pitch (elevation) + [-np.pi, np.pi], # motor rotation (azimuth) + [-np.pi, np.pi], # motor pitch + [0, 1] # direction + ]) + else: + self.parameter_limits = np.asarray(parameter_limits) + if self.parameter_limits.shape != (6, 2): + raise ValueError("parameter_limits must have shape (6, 2)") + + # Validate inputs + self._validate_initialization_parameters( + (self.min_narms, self.max_narms), self.parameter_limits, append_arm_chance, + mutation_probs, mutation_scales_percentage + ) + + self.append_arm_chance = append_arm_chance + + # Handle bilateral symmetry parameter + valid_planes = {"xy", "xz", "yz", None} + if bilateral_plane_for_symmetry not in valid_planes: + raise ValueError(f"bilateral_plane_for_symmetry must be one of {valid_planes}") + self.bilateral_plane_for_symmetry = bilateral_plane_for_symmetry + self.symmetry = bilateral_plane_for_symmetry is not None + + self.repair_enabled = repair + + # Store collision repair parameters + self.enable_collision_repair = enable_collision_repair + self.propeller_radius = propeller_radius + self.inner_boundary_radius = inner_boundary_radius + self.outer_boundary_radius = outer_boundary_radius + self.max_repair_iterations = max_repair_iterations + self.repair_step_size = repair_step_size + self.propeller_tolerance = propeller_tolerance + + # Setup mutation parameters + self._setup_mutation_parameters(mutation_probs, mutation_scales_percentage) + + # Initialize operators + self._setup_operators() + + # Initialize genome — handle SphericalNeatGenome, ndarray, or None + self.fitness: float | None = None + if isinstance(genome, SphericalNeatGenome): + self.genome = genome.copy() + elif genome is not None: + # Raw ndarray — wrap with sequential innovation IDs for + # backward compatibility with CMA-ES / mu+lambda strategies. + arms = genome.copy() + valid_mask = ~np.isnan(arms[:, 0]) + inno = np.full(arms.shape[0], -1, dtype=int) + inno[valid_mask] = np.arange(int(valid_mask.sum())) + self.genome = SphericalNeatGenome(arms=arms, innovation_ids=inno) + else: + self.genome = self._generate_random_genome() + + def _validate_initialization_parameters( + self, + min_max_narms: Tuple[int, int], + parameter_limits: npt.NDArray[Any], + append_arm_chance: float, + mutation_probs: Optional[List[float] | npt.NDArray[Any]], + mutation_scales_percentage: Optional[npt.NDArray[Any]] + ) -> None: + """Validate initialization parameters.""" + min_narms, max_narms = min_max_narms + + if min_narms < 1: + raise ValueError("min_narms must be at least 1") + if max_narms < min_narms: + raise ValueError("max_narms must be >= min_narms") + if not (0 <= append_arm_chance <= 0.5): + raise ValueError("append_arm_chance must be between 0 and 0.5") + + parameter_limits = np.asarray(parameter_limits) + if parameter_limits.shape != (6, 2): + raise ValueError("parameter_limits must have shape (6, 2)") + if np.any(parameter_limits[:, 0] >= parameter_limits[:, 1]): + raise ValueError("parameter_limits: min values must be < max values") + + if mutation_probs is not None: + mutation_probs = np.asarray(mutation_probs) + if len(mutation_probs) != 6: + raise ValueError("mutation_probs must have length 6") + if np.any(mutation_probs < 0): + raise ValueError("mutation_probs must be non-negative") + + if mutation_scales_percentage is not None: + mutation_scales_percentage = np.asarray(mutation_scales_percentage) + if len(mutation_scales_percentage) != 6: + raise ValueError("mutation_scales_percentage must have length 6") + if np.any(mutation_scales_percentage < 0): + raise ValueError("mutation_scales_percentage must be non-negative") + + def _setup_mutation_parameters( + self, + mutation_probs: Optional[List[float] | npt.NDArray[Any]], + mutation_scales_percentage: Optional[npt.NDArray[Any]] + ) -> None: + """Setup mutation probabilities and scales.""" + nparms = 6 + mutation_window = 1 - 2 * self.append_arm_chance + + # Setup mutation probabilities + if mutation_probs is None: + # Uniform distribution across parameters + param_prob = mutation_window / nparms + mutation_probs = np.repeat(param_prob, nparms) + else: + mutation_probs = np.asarray(mutation_probs) + # Normalize to fit in mutation window + total_prob = np.sum(mutation_probs) + if total_prob > 0: + mutation_probs = mutation_probs * (mutation_window / total_prob) + + # Combine with add/remove probabilities + self.mutation_probabilities = np.array([ + self.append_arm_chance, # Add arm probability + self.append_arm_chance, # Remove arm probability + *mutation_probs # Parameter mutation probabilities + ]) + + # Validate probabilities sum to 1 + prob_sum = np.sum(self.mutation_probabilities) + if not np.isclose(prob_sum, 1.0, rtol=1e-6): + raise ValueError(f"Mutation probabilities must sum to 1, got {prob_sum}") + + # Setup mutation scales + if mutation_scales_percentage is None: + mutation_scales_percentage = np.array([0.05, 0.05, 0.05, 0.05, 0.05, 0.0]) + + # Convert percentages to absolute scales + parameter_ranges = self.parameter_limits[:, 1] - self.parameter_limits[:, 0] + self.mutation_scales = parameter_ranges * mutation_scales_percentage + + def _setup_operators(self) -> None: + """Initialize the symmetry and repair operators.""" + # Setup symmetry operator + from .operators.symmetry_base import SymmetryPlane + + # Map bilateral plane string to SymmetryPlane enum + plane_mapping = { + "xy": SymmetryPlane.XY, + "xz": SymmetryPlane.XZ, + "yz": SymmetryPlane.YZ, + None: None + } + + symmetry_config = SymmetryConfig( + plane=plane_mapping.get(self.bilateral_plane_for_symmetry), + enabled=self.symmetry + ) + self.symmetry_operator = SphericalSymmetryOperator( + config=symmetry_config, + ) + + # Setup repair operator + repair_config = RepairConfig( + apply_symmetry=self.symmetry, + enable_collision_repair=self.enable_collision_repair, + propeller_radius=self.propeller_radius, + inner_boundary_radius=self.inner_boundary_radius, + outer_boundary_radius=self.outer_boundary_radius, + max_repair_iterations=self.max_repair_iterations, + repair_step_size=self.repair_step_size, + propeller_tolerance=self.propeller_tolerance + ) + self.repair_operator = SphericalRepairOperator( + config=repair_config, + min_narms=self.min_narms, + max_narms=self.max_narms, + parameter_limits=self.parameter_limits, + symmetry_operator=self.symmetry_operator, + rng=self.rnd + ) + + def _generate_random_genome(self, innovation_ids: npt.NDArray[Any] | None = None) -> SphericalNeatGenome: + """Generate a single random genome. + + Parameters + ---------- + innovation_ids : array, optional + Pre-assigned innovation IDs for the initial arms. When + generating the initial population all individuals share the + same IDs so that NEAT crossover alignment works from gen 0. + If *None*, new IDs are drawn from the class-level counter. + """ + arms = np.full((self.max_narms, 6), np.nan) + inno = np.full(self.max_narms, -1, dtype=int) + + # Determine number of arms for this individual + num_arms = self.rnd.integers(self.min_narms, self.max_narms + 1) + + # Generate random parameters for the arms (excluding phi) + for i in [0, 1, 3, 4]: # r, theta, pitch, yaw + arms[:num_arms, i] = self.rnd.uniform( + low=self.parameter_limits[i, 0], + high=self.parameter_limits[i, 1], + size=num_arms + ) + + # For phi (index 2), sample to achieve uniform spatial distribution on sphere. + # phi is an elevation angle (0 = horizontal, π/2 = up, −π/2 = down). + # Uniform sphere coverage requires sampling sin(phi) uniformly and inverting + # with arcsin. This is valid for any elevation range including negatives. + phi_min, phi_max = self.parameter_limits[2, 0], self.parameter_limits[2, 1] + sin_phi = self.rnd.uniform(low=np.sin(phi_min), high=np.sin(phi_max), size=num_arms) + arms[:num_arms, 2] = np.arcsin(sin_phi) + + arms[:num_arms, 5] = self.rnd.integers(0, 2, size=num_arms) + + # Assign innovation IDs + if innovation_ids is not None: + inno[:num_arms] = innovation_ids[:num_arms] + else: + for j in range(num_arms): + inno[j] = self._innovation_counter.next_innovation() + + # If symmetry is enabled, apply symmetry to the genome + if self.symmetry: + # Reduce to half if symmetry is enabled + arms[self.max_narms // 2:] = np.nan + inno[self.max_narms // 2:] = -1 + + if self.symmetry: + arms = self.symmetry_operator.apply_symmetry(arms) + + if self.repair_enabled: + arms = self.repair_operator.repair(arms) + + return SphericalNeatGenome(arms=arms, innovation_ids=inno) + + def generate_random_population(self, population_size: int, as_nparray : bool = False) -> List[SphericalAngularDroneGenomeHandler]: + """ + Generate a population of random genome handlers. + + All individuals share the same innovation IDs for their starting + arms so that NEAT crossover alignment works from generation 0. + + Args: + population_size: Number of individuals to generate + + Returns: + List of random genome handler instances + """ + # Pre-allocate shared innovation IDs for the starting topology + shared_innos = np.array( + [self._innovation_counter.next_innovation() for _ in range(self.max_narms)], + dtype=int, + ) + + population = [] + for _ in range(population_size): + individual = SphericalAngularDroneGenomeHandler( + genome=None, + min_max_narms=(self.min_narms, self.max_narms), + parameter_limits=self.parameter_limits, + append_arm_chance=self.append_arm_chance, + mutation_probs=None, # Will use default + mutation_scales_percentage=None, # Will use default + bilateral_plane_for_symmetry=self.bilateral_plane_for_symmetry, + repair=self.repair_enabled, + enable_collision_repair=self.enable_collision_repair, + propeller_radius=self.propeller_radius, + inner_boundary_radius=self.inner_boundary_radius, + outer_boundary_radius=self.outer_boundary_radius, + max_repair_iterations=self.max_repair_iterations, + repair_step_size=self.repair_step_size, + propeller_tolerance=self.propeller_tolerance, + rnd=self.rnd, + ) + individual.genome = individual._generate_random_genome( + innovation_ids=shared_innos, + ) + population.append(individual) + + return population + + def random_population(self, pop_size: int) -> npt.NDArray[Any]: + """ + Generate a random population as a numpy array (vectorized version). + + Args: + pop_size: Size of the population to generate + + Returns: + Population array of shape (pop_size, max_narms, 6) + """ + array_shape = (pop_size, self.max_narms, 6) + population = np.empty(array_shape) + + # Generate random arms for all individuals + # For parameters other than phi (index 2), sample uniformly + for i in [0, 1, 3, 4]: # r, theta, pitch, yaw + population[:, :, i] = self.rnd.uniform( + low=self.parameter_limits[i, 0], + high=self.parameter_limits[i, 1], + size=(pop_size, self.max_narms) + ) + + # For phi (index 2), sample to achieve uniform spatial distribution on sphere. + # phi is an elevation angle (0 = horizontal, π/2 = up, −π/2 = down). + # Uniform sphere coverage requires sampling sin(phi) uniformly and inverting + # with arcsin. This is valid for any elevation range including negatives. + phi_min, phi_max = self.parameter_limits[2, 0], self.parameter_limits[2, 1] + sin_phi = self.rnd.uniform( + low=np.sin(phi_min), + high=np.sin(phi_max), + size=(pop_size, self.max_narms) + ) + population[:, :, 2] = np.arcsin(sin_phi) + + population[:, :, 5] = self.rnd.integers(0, 2, size=(pop_size, self.max_narms)) + + if self.symmetry: + # If symmetry is enabled, only keep half of the genome + population[:, self.max_narms // 2:, :] = np.nan + else: + # Remove random arms from each drone to create variable arm counts + num_arms_to_remove = self.rnd.integers( + 0, self.max_narms + 1 - self.min_narms, + size=pop_size + ) + + # Create mask for arms to remove + arms_to_remove_mask = np.zeros(array_shape, dtype=bool) + for i in range(pop_size): + if num_arms_to_remove[i] > 0: + indices_to_remove = self.rnd.choice( + self.max_narms, + num_arms_to_remove[i], + replace=False + ) + arms_to_remove_mask[i, indices_to_remove, :] = True + + # Apply mask (set removed arms to NaN) + population[arms_to_remove_mask] = np.nan + + if self.symmetry: + # Apply symmetry to the population + population = self.symmetry_operator.apply_symmetry_population(population) + # Apply post-processing + if self.repair_enabled: + population = self.repair_population(population) + return population + + def crossover(self, other: SphericalAngularDroneGenomeHandler) -> SphericalAngularDroneGenomeHandler: + """NEAT-style crossover using innovation-number gene alignment. + + Matching genes (same innovation ID in both parents) are inherited + randomly. Disjoint / excess genes are inherited from the fitter + parent; when fitness is equal each disjoint gene has a 50 % + chance of inclusion. + """ + if not isinstance(other, SphericalAngularDroneGenomeHandler): + raise TypeError("Other parent must be SphericalAngularDroneGenomeHandler") + + # Determine fitter parent (self.fitness / other.fitness set by NEAT loop) + f1 = self.fitness if self.fitness is not None else 0.0 + f2 = other.fitness if other.fitness is not None else 0.0 + equal_fitness = np.isclose(f1, f2) + self_is_fitter = f1 > f2 + + # Build {innovation_id: arm_params} dicts for each parent + g1_arms, g1_inno = self.genome.arms, self.genome.innovation_ids + g2_arms, g2_inno = other.genome.arms, other.genome.innovation_ids + + d1 = {int(inno): g1_arms[i] for i, inno in enumerate(g1_inno) if inno >= 0} + d2 = {int(inno): g2_arms[i] for i, inno in enumerate(g2_inno) if inno >= 0} + + all_innos = sorted(set(d1.keys()) | set(d2.keys())) + + child_arms_list: list[tuple[int, npt.NDArray[Any]]] = [] + for inno in all_innos: + in1, in2 = inno in d1, inno in d2 + if in1 and in2: + # Matching gene — inherit randomly + child_arms_list.append( + (inno, d1[inno].copy() if self.rnd.random() < 0.5 else d2[inno].copy()) + ) + elif in1 and not in2: + # Only in self + if self_is_fitter or (equal_fitness and self.rnd.random() < 0.5): + child_arms_list.append((inno, d1[inno].copy())) + else: + # Only in other + if not self_is_fitter or (equal_fitness and self.rnd.random() < 0.5): + child_arms_list.append((inno, d2[inno].copy())) + + # Enforce min/max arm constraints + if len(child_arms_list) > self.max_narms: + child_arms_list = child_arms_list[:self.max_narms] + while len(child_arms_list) < self.min_narms: + # Fill from fitter parent's genes not yet included + source = d1 if self_is_fitter or equal_fitness else d2 + for k, v in source.items(): + if k not in {x[0] for x in child_arms_list}: + child_arms_list.append((k, v.copy())) + break + else: + break + + # Pack into (max_narms, 6) array + child_arr = np.full((self.max_narms, 6), np.nan) + child_inno = np.full(self.max_narms, -1, dtype=int) + for idx, (inno, params) in enumerate(child_arms_list[:self.max_narms]): + child_arr[idx] = params + child_inno[idx] = inno + + # Symmetry / repair + if self.symmetry: + child_arr = self._apply_symmetry_single(child_arr) + if self.repair_enabled: + child_arr = self.repair_operator.repair(child_arr) + + child_genome = SphericalNeatGenome(arms=child_arr, innovation_ids=child_inno) + + child = SphericalAngularDroneGenomeHandler( + genome=child_genome, + min_max_narms=(self.min_narms, self.max_narms), + parameter_limits=self.parameter_limits, + append_arm_chance=self.append_arm_chance, + bilateral_plane_for_symmetry=self.bilateral_plane_for_symmetry, + repair=self.repair_enabled, + enable_collision_repair=self.enable_collision_repair, + propeller_radius=self.propeller_radius, + inner_boundary_radius=self.inner_boundary_radius, + outer_boundary_radius=self.outer_boundary_radius, + max_repair_iterations=self.max_repair_iterations, + repair_step_size=self.repair_step_size, + propeller_tolerance=self.propeller_tolerance, + rnd=self.rnd, + ) + + return child + + def crossover_vectorized( + self, + population: npt.NDArray[Any], + mating_pool1: npt.NDArray[Any], + mating_pool2: npt.NDArray[Any] + ) -> npt.NDArray[Any]: + """ + Vectorized crossover operation for efficiency. + + Args: + population: Population array of shape (pop_size, max_narms, 6) + mating_pool1: Indices of first parents + mating_pool2: Indices of second parents + + Returns: + Children population array + """ + pop_size, max_narms, nparms = population.shape + + # Shuffle arms of each individual for genetic diversity + shuffle_indices = np.array([ + self.rnd.permutation(max_narms) for _ in range(pop_size) + ]) + population_shuffled = population[np.arange(pop_size)[:, None], shuffle_indices] + + # Select parents + parent1s = population_shuffled[mating_pool1] + parent2s = population_shuffled[mating_pool2] + + if parent1s.shape != parent2s.shape: + raise ValueError("Parent populations must have the same shape") + + # Generate random choices for arm selection + random_choices = self.rnd.choice([0, 1], size=parent1s.shape[:-1]) + + # Perform crossover + children = np.where( + random_choices[..., np.newaxis] == 0, + parent1s, + parent2s + ) + + if self.symmetry: + # If symmetry is enabled, apply symmetry to the children + children = self.apply_symmetry_pop(children) + # Apply repair if needed + if self.repair_enabled: + children = self.repair_population(children) + + return children + + def mutate(self, genome=None) -> None: + """Mutate this genome in place.""" + if genome is not None: + if isinstance(genome, SphericalNeatGenome): + self.genome = genome + else: + # Raw ndarray passed in — wrap it + arms = genome + valid_mask = ~np.isnan(arms[:, 0]) + inno = np.full(arms.shape[0], -1, dtype=int) + inno[valid_mask] = np.arange(int(valid_mask.sum())) + self.genome = SphericalNeatGenome(arms=arms, innovation_ids=inno) + + arms = self.genome.arms + inno = self.genome.innovation_ids + + if self.symmetry: + # Temporarily remove symmetry for mutation + arms = self._unapply_symmetry_single(arms) + else: + arms = arms.copy() + + # Choose mutation type + mutation_type = self.rnd.choice( + len(self.mutation_probabilities), + p=self.mutation_probabilities + ) + + if mutation_type == 0: + # Add arm mutation — assign new innovation ID + empty_mask = np.isnan(arms[:, 0]) + arms = self._mutate_add_arm(arms) + # Find newly filled slot + new_filled = np.isnan(self.genome.arms[:, 0]) if not self.symmetry else empty_mask + for i in range(len(arms)): + if empty_mask[i] and not np.isnan(arms[i, 0]): + inno[i] = self._innovation_counter.next_innovation() + break + elif mutation_type == 1: + # Remove arm mutation — set innovation ID to -1 + non_empty_before = ~np.isnan(arms[:, 0]) + arms = self._mutate_remove_arm(arms) + for i in range(len(arms)): + if non_empty_before[i] and np.isnan(arms[i, 0]): + inno[i] = -1 + break + else: + # Parameter mutation + param_index = mutation_type - 2 + arms = self._mutate_parameter(arms, param_index) + + # Ensure genome is valid has the correct number of arms for symmetry + if self.symmetry: + arms = self._apply_symmetry_single(arms) + + self.genome = SphericalNeatGenome(arms=arms, innovation_ids=inno) + + if self.repair_enabled: + self.repair() + + return self.genome + + def mutation_vectorized(self, population: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Vectorized mutation operation for efficiency. + + Args: + population: Population array to mutate + + Returns: + Mutated population array + """ + if self.symmetry: + population = self.unapply_symmetry_pop(population) + + pop_size, max_narms, nparms = population.shape + pop = population.copy() + + # Choose mutation type for each individual + mutation_choices = np.nonzero(self.mutation_probabilities)[0] + mutations = self.rnd.choice( + mutation_choices, + size=pop_size, + p=self.mutation_probabilities[self.mutation_probabilities != 0] + ) + + # Apply different mutation types + self._apply_add_mutations(pop, mutations) + self._apply_remove_mutations(pop, mutations) + self._apply_parameter_mutations(pop, mutations) + + if self.symmetry: + pop = self.apply_symmetry_pop(pop) + # Apply post-processing + if self.repair_enabled: + pop = self.repair_population(pop) + + return pop + + def _mutate_add_arm(self, genome: npt.NDArray[Any]) -> None: + """Add a random arm to the genome.""" + # Find empty slots (NaN values) + empty_mask = np.isnan(genome[:, 0]) + + if not np.any(empty_mask) or (self.symmetry and not np.any(empty_mask[:self.max_narms // 2])): + return genome # No empty slots available + + # Select random empty slot + empty_indices = np.where(empty_mask)[0] + selected_index = self.rnd.choice(empty_indices) + + # Generate new arm parameters + new_arm = np.zeros(6) + new_arm[:5] = self.rnd.uniform( + low=self.parameter_limits[:5, 0], + high=self.parameter_limits[:5, 1] + ) + new_arm[5] = self.rnd.integers(0, 2) + + genome[selected_index] = new_arm + + return genome + + def _mutate_remove_arm(self, genome: npt.NDArray[Any]) -> None: + """Remove a random arm from the genome.""" + # Find non-empty slots + non_empty_mask = ~np.isnan(genome[:, 0]) + if not np.any(non_empty_mask): + return genome # No arms to remove + + # Select random non-empty slot + non_empty_indices = np.where(non_empty_mask)[0] + selected_index = self.rnd.choice(non_empty_indices) + + genome[selected_index] = np.nan + + return genome + + def _mutate_parameter(self, genome: npt.NDArray[Any], param_index: int) -> None: + """Mutate a specific parameter of a random arm.""" + # Find non-empty arms + non_empty_mask = ~np.isnan(genome[:, 0]) + if not np.any(non_empty_mask): + return genome # No arms to mutate + + # Select random arm + non_empty_indices = np.where(non_empty_mask)[0] + selected_arm = self.rnd.choice(non_empty_indices) + + if param_index == 5: + # Flip direction parameter + genome[selected_arm, param_index] = 1 - genome[selected_arm, param_index] + else: + # Add Gaussian perturbation + perturbation = self.rnd.normal(0, self.mutation_scales[param_index]) + genome[selected_arm, param_index] += perturbation + + # Handle angular parameters (wrap around) + if param_index in [1, 2, 3, 4]: # Angular parameters + genome[selected_arm, param_index] = self._wrap_angle( + genome[selected_arm, param_index], + self.parameter_limits[param_index, 0], + self.parameter_limits[param_index, 1], + ) + else: + # Clip non-angular parameters to limits + genome[selected_arm, param_index] = np.clip( + genome[selected_arm, param_index], + self.parameter_limits[param_index, 0], + self.parameter_limits[param_index, 1] + ) + + return genome + + def _apply_add_mutations( + self, + population: npt.NDArray[Any], + mutations: npt.NDArray[Any] + ) -> None: + """Apply add arm mutations to population.""" + add_mask = (mutations == 0) + if not np.any(add_mask): + return + + # Find individuals with empty slots + empty_indices = np.isnan(population[:, :, 0]) + valid_add_mask = np.any(empty_indices, axis=1) + add_mask &= valid_add_mask + + if not np.any(add_mask): + return + + # Get available indices for adding + available_indices = np.argwhere(empty_indices[add_mask]) + if len(available_indices) == 0: + return + + # Select random indices + selected_indices = self.rnd.choice( + len(available_indices), + size=np.sum(add_mask), + replace=True + ) + + # Generate new arms + num_new_arms = np.sum(add_mask) + new_arms = np.zeros((num_new_arms, 6)) + new_arms[:, :5] = self.rnd.uniform( + low=self.parameter_limits[:5, 0], + high=self.parameter_limits[:5, 1], + size=(num_new_arms, 5) + ) + new_arms[:, 5] = self.rnd.integers(0, 2, size=num_new_arms) + + # Apply new arms + for i, idx in enumerate(selected_indices): + pop_idx, arm_idx = available_indices[idx] + actual_pop_idx = np.where(add_mask)[0][pop_idx] + population[actual_pop_idx, arm_idx] = new_arms[i] + + def _apply_remove_mutations( + self, + population: npt.NDArray[Any], + mutations: npt.NDArray[Any] + ) -> None: + """Apply remove arm mutations to population.""" + remove_mask = (mutations == 1) + if not np.any(remove_mask): + return + + # Find individuals with non-empty arms + non_empty_indices = ~np.isnan(population[:, :, 0]) + valid_remove_mask = np.any(non_empty_indices, axis=1) + remove_mask &= valid_remove_mask + + if not np.any(remove_mask): + return + + # Get available indices for removal + available_indices = np.argwhere(non_empty_indices[remove_mask]) + if len(available_indices) == 0: + return + + # Select random indices + selected_indices = self.rnd.choice( + len(available_indices), + size=np.sum(remove_mask), + replace=True + ) + + # Remove arms + for idx in selected_indices: + pop_idx, arm_idx = available_indices[idx] + actual_pop_idx = np.where(remove_mask)[0][pop_idx] + population[actual_pop_idx, arm_idx] = np.nan + + def _apply_parameter_mutations( + self, + population: npt.NDArray[Any], + mutations: npt.NDArray[Any] + ) -> None: + """Apply parameter mutations to population.""" + perturb_mask = (mutations >= 2) + if not np.any(perturb_mask): + return + + drone_indices = np.where(perturb_mask)[0] + + # Find non-empty motors for each drone + non_empty_mask = ~np.isnan(population[drone_indices, :, 0]) + num_non_empty = non_empty_mask.sum(axis=1) + + # Filter out drones with no motors + valid_drones = num_non_empty > 0 + if not np.any(valid_drones): + return + + valid_drone_indices = drone_indices[valid_drones] + valid_non_empty_mask = non_empty_mask[valid_drones] + valid_num_non_empty = num_non_empty[valid_drones] + + # Select random motor for each valid drone + random_indices = self.rnd.integers(0, valid_num_non_empty) + cumsum_non_empty = np.cumsum(valid_non_empty_mask, axis=1) + selected_motors = np.argmax( + cumsum_non_empty == (random_indices[:, None] + 1), + axis=1 + ) + + # Get parameter indices + selected_params = mutations[perturb_mask][valid_drones] - 2 + + # Apply mutations + for i, (drone_idx, motor_idx, param_idx) in enumerate( + zip(valid_drone_indices, selected_motors, selected_params) + ): + if param_idx == 5: + # Flip direction + population[drone_idx, motor_idx, param_idx] = \ + 1 - population[drone_idx, motor_idx, param_idx] + else: + # Add perturbation + perturbation = self.rnd.normal(0, self.mutation_scales[param_idx]) + population[drone_idx, motor_idx, param_idx] += perturbation + + # Handle angular parameters + if param_idx in [1, 2, 3, 4]: + population[drone_idx, motor_idx, param_idx] = self._wrap_angle( + population[drone_idx, motor_idx, param_idx], + self.parameter_limits[param_idx, 0], + self.parameter_limits[param_idx, 1], + ) + else: + # Clip non-angular parameters to limits + population[drone_idx, motor_idx, param_idx] = np.clip( + population[drone_idx, motor_idx, param_idx], + self.parameter_limits[param_idx, 0], + self.parameter_limits[param_idx, 1] + ) + + def _wrap_angle(self, angle: float, low: float, high: float) -> float: + """Wrap angle to [low, high) range.""" + span = high - low + return low + (angle - low) % span + + def copy(self) -> SphericalAngularDroneGenomeHandler: + """ + Create a deep copy of this genome handler. + + Returns: + Copy of this genome handler + """ + return SphericalAngularDroneGenomeHandler( + genome=self.genome.copy(), + min_max_narms=(self.min_narms, self.max_narms), + parameter_limits=self.parameter_limits.copy(), + append_arm_chance=self.append_arm_chance, + bilateral_plane_for_symmetry=self.bilateral_plane_for_symmetry, + repair=self.repair_enabled, + enable_collision_repair=self.enable_collision_repair, + propeller_radius=self.propeller_radius, + inner_boundary_radius=self.inner_boundary_radius, + outer_boundary_radius=self.outer_boundary_radius, + max_repair_iterations=self.max_repair_iterations, + repair_step_size=self.repair_step_size, + propeller_tolerance=self.propeller_tolerance, + rnd=self.rnd, + ) + + def is_valid(self) -> bool: + """ + Check if the genome represents a valid drone configuration. + + Returns: + True if valid, False otherwise + """ + # Use the repair operator to validate the genome + return self.repair_operator.validate(self.genome.arms) + + def compatibility_distance(self, other: SphericalAngularDroneGenomeHandler) -> float: + """Phenotypic compatibility distance using edit distance. + + Uses Hungarian-algorithm optimal arm matching on normalised + parameters plus an arm-count penalty. This is permutation- + invariant and produces meaningful distances even when all + genomes share the same innovation IDs (fixed arm count). + """ + from ariel.ec.drone.evaluators.edit_distance import ( + compute_edit_distance, + ) + + return float( + compute_edit_distance( + self.genome.arms, + other.genome.arms, + min_vals=self.parameter_limits[:, 0], + max_vals=self.parameter_limits[:, 1], + ) + ) + + def repair(self) -> None: + """ + Repair the genome to make it valid by clipping out-of-bounds values. + """ + # Use the repair operator on the arms array, preserving innovation IDs + self.genome.arms = self.repair_operator.repair(self.genome.arms) + + def repair_population(self, population: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Repair a population array. + + Args: + population: Population array to repair + + Returns: + Repaired population array + """ + # This is a placeholder - implement based on your specific repair logic + # For now, just clip parameters to bounds + pop = population.copy() + + repaired_pop = self.repair_operator.repair_population(pop) + + return repaired_pop + + def apply_symmetry_pop(self, population: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Apply symmetry to a population. + + Args: + population: Population array to make symmetric + + Returns: + Symmetric population array + """ + if not self.symmetry: + return population + + # Use the symmetry operator to apply symmetry to population + return self.symmetry_operator.apply_symmetry_population(population) + + def unapply_symmetry_pop(self, population: npt.NDArray[Any]) -> npt.NDArray[Any]: + """ + Remove symmetry from a population. + + Args: + population: Symmetric population array + + Returns: + Population array with symmetry removed + """ + if not self.symmetry: + return population + + # Use the symmetry operator to remove symmetry from population + return self.symmetry_operator.unapply_symmetry_population(population) + + def _apply_symmetry_single(self, genome: npt.NDArray[Any]) -> npt.NDArray[Any]: + """Apply symmetry to a single genome.""" + if not self.symmetry: + return genome + + # Use the symmetry operator to apply symmetry + return self.symmetry_operator.apply_symmetry(genome) + + def _unapply_symmetry_single(self, genome: npt.NDArray[Any]) -> npt.NDArray[Any]: + """Remove symmetry from a single genome.""" + if not self.symmetry: + return genome + + # Use the symmetry operator to remove symmetry + return self.symmetry_operator.unapply_symmetry(genome) + + def validate_symmetry(self) -> bool: + """ + Check if the genome satisfies symmetry constraints. + + Returns: + True if genome satisfies symmetry constraints + """ + if not self.symmetry: + return True + return self.symmetry_operator.validate_symmetry(self.genome.arms) + + def get_symmetry_pairs(self) -> List[tuple]: + """ + Get pairs of indices that should be symmetric. + + Returns: + List of (source_index, target_index) tuples + """ + return self.symmetry_operator.get_symmetry_pairs(self.genome.arms) + + def apply_symmetry(self) -> None: + """ + Apply symmetry to the current genome. + """ + if self.symmetry: + self.genome.arms = self.symmetry_operator.apply_symmetry(self.genome.arms) + + def unapply_symmetry(self) -> None: + """ + Remove symmetry from the current genome (keep only first half). + """ + if self.symmetry: + self.genome.arms = self.symmetry_operator.unapply_symmetry(self.genome.arms) + + def get_valid_arms(self) -> npt.NDArray[Any]: + """ + Get only the valid (non-NaN) arms from the genome. + + Returns: + Array of valid arms with shape (num_valid_arms, 6) + """ + valid_mask = ~np.isnan(self.genome.arms[:, 0]) + return self.genome.arms[valid_mask].copy() + + def get_arm_count(self) -> int: + """ + Get the number of valid arms in the genome. + + Returns: + Number of valid arms + """ + valid_mask = ~np.isnan(self.genome.arms[:, 0]) + return int(np.sum(valid_mask)) + + def get_spherical_coordinates(self) -> npt.NDArray[Any]: + """ + Get spherical coordinates of valid arms. + + Returns: + Array of shape (num_valid_arms, 3) with [magnitude, arm_rotation, arm_pitch] + """ + valid_arms = self.get_valid_arms() + return valid_arms[:, :3].copy() + + def get_motor_orientations(self) -> npt.NDArray[Any]: + """ + Get motor orientations of valid arms. + + Returns: + Array of shape (num_valid_arms, 2) with [motor_rotation, motor_pitch] + """ + valid_arms = self.get_valid_arms() + return valid_arms[:, 3:5].copy() + + def get_propeller_directions(self) -> npt.NDArray[Any]: + """ + Get propeller directions of valid arms. + + Returns: + Array of shape (num_valid_arms,) with direction values + """ + valid_arms = self.get_valid_arms() + return valid_arms[:, 5].copy() + + def set_arm(self, arm_index: int, arm_data: npt.NDArray[Any]) -> None: + """ + Set data for a specific arm. + + Args: + arm_index: Index of the arm to set + arm_data: Array of 6 parameters for the arm + """ + if not (0 <= arm_index < self.max_narms): + raise ValueError(f"arm_index must be between 0 and {self.max_narms-1}") + + if len(arm_data) != 6: + raise ValueError("arm_data must have exactly 6 elements") + + self.genome.arms[arm_index] = arm_data + + def remove_arm(self, arm_index: int) -> None: + """ + Remove an arm by setting it to NaN. + + Args: + arm_index: Index of the arm to remove + """ + if not (0 <= arm_index < self.max_narms): + raise ValueError(f"arm_index must be between 0 and {self.max_narms-1}") + + self.genome.arms[arm_index] = np.nan + self.genome.innovation_ids[arm_index] = -1 + + def add_random_arm(self) -> bool: + """ + Add a random arm to an empty slot. + + Returns: + True if arm was added, False if no empty slots available + """ + empty_mask = np.isnan(self.genome.arms[:, 0]) + if not np.any(empty_mask): + return False + + empty_indices = np.where(empty_mask)[0] + selected_index = self.rnd.choice(empty_indices) + + new_arm = np.zeros(6) + new_arm[:5] = self.rnd.uniform( + low=self.parameter_limits[:5, 0], + high=self.parameter_limits[:5, 1] + ) + new_arm[5] = self.rnd.integers(0, 2) + + self.genome.arms[selected_index] = new_arm + self.genome.innovation_ids[selected_index] = self._innovation_counter.next_innovation() + return True + + def compact_genome(self) -> npt.NDArray[Any]: + """ + Get a compact representation with only valid arms. + + Returns: + Array containing only non-NaN arms + """ + return self.get_valid_arms() + + def __str__(self) -> str: + """String representation of the genome handler.""" + num_arms = self.get_arm_count() + return (f"SphericalAngularDroneGenomeHandler(" + f"arms={num_arms}/{self.max_narms}, " + f"bilateral_plane_for_symmetry={self.bilateral_plane_for_symmetry}, " + f"repair={self.repair_enabled})") + + def __repr__(self) -> str: + """Detailed string representation of the genome handler.""" + return (f"SphericalAngularDroneGenomeHandler(" + f"min_max_narms=({self.min_narms}, {self.max_narms}), " + f"append_arm_chance={self.append_arm_chance}, " + f"bilateral_plane_for_symmetry={self.bilateral_plane_for_symmetry}, " + f"repair={self.repair_enabled}, " + f"current_arms={self.get_arm_count()})") + + +# Utility functions for backward compatibility +def create_spherical_angular_handler( + min_narms: int = 3, + max_narms: int = 8, + magnitude_range: Tuple[float, float] = (0.5, 2.0), + angle_range: Tuple[float, float] = (0.0, 2*np.pi), + **kwargs +) -> SphericalAngularDroneGenomeHandler: + """ + Convenience function to create a SphericalAngularDroneGenomeHandler with common parameters. + + Args: + min_narms: Minimum number of arms + max_narms: Maximum number of arms + magnitude_range: Range for magnitude parameter + angle_range: Range for angular parameters + **kwargs: Additional arguments passed to the constructor + + Returns: + Configured SphericalAngularDroneGenomeHandler instance + """ + # Default parameter limits: [magnitude, arm_rot, arm_pitch, motor_rot, motor_pitch, direction] + parameter_limits = np.array([ + [magnitude_range[0], magnitude_range[1]], # magnitude + [angle_range[0], angle_range[1]], # arm rotation + [angle_range[0], angle_range[1]], # arm pitch + [angle_range[0], angle_range[1]], # motor rotation + [angle_range[0], angle_range[1]], # motor pitch + [0, 1] # direction (discrete) + ]) + + return SphericalAngularDroneGenomeHandler( + genome=None, + min_max_narms=(min_narms, max_narms), + parameter_limits=parameter_limits, + **kwargs + ) + + +# Example usage and testing +if __name__ == "__main__": + print("=== SphericalAngularDroneGenomeHandler Testing ===") + + # Create parameter limits + parameter_limits = np.array([ + [0.5, 2.0], # magnitude + [0.0, 2*np.pi], # arm rotation + [0.0, np.pi], # arm pitch + [0.0, 2*np.pi], # motor rotation + [0.0, np.pi], # motor pitch + [0, 1] # direction + ]) + + # Create genome handler + handler = SphericalAngularDroneGenomeHandler( + genome=None, + min_max_narms=(3, 6), + parameter_limits=parameter_limits, + append_arm_chance=0.1, + bilateral_plane_for_symmetry=None, + repair=True + ) + + print(f"Created handler: {handler}") + + # Generate random individual + individual = handler.copy() + individual.genome = individual._generate_random_genome() + + print(f"Generated individual with {individual.get_arm_count()} arms") + print(f"Valid: {individual.is_valid()}") + + # Test mutations + print("\n--- Testing Mutations ---") + original_arms = individual.get_arm_count() + + for i in range(5): + individual.mutate() + new_arms = individual.get_arm_count() + print(f"Mutation {i+1}: {original_arms} -> {new_arms} arms") + original_arms = new_arms + + # Test population operations + print("\n--- Testing Population Operations ---") + population = handler.random_population(10) + print(f"Generated population shape: {population.shape}") + + arm_counts = [np.sum(~np.isnan(pop[:, 0])) for pop in population] + print(f"Arm counts: {arm_counts}") + + # Test crossover + print("\n--- Testing Crossover ---") + parent1 = handler.copy() + parent1.genome = handler._generate_random_genome() + parent2 = handler.copy() + parent2.genome = handler._generate_random_genome() + + child = parent1.crossover(parent2) + print(f"Parent 1: {parent1.get_arm_count()} arms") + print(f"Parent 2: {parent2.get_arm_count()} arms") + print(f"Child: {child.get_arm_count()} arms") + \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/__init__.py b/src/ariel/ec/drone/inspection/__init__.py new file mode 100644 index 000000000..11e1e1825 --- /dev/null +++ b/src/ariel/ec/drone/inspection/__init__.py @@ -0,0 +1 @@ +# Visualization and analysis tools \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/animation_utils.py b/src/ariel/ec/drone/inspection/animation_utils.py new file mode 100644 index 000000000..c6a3e11f3 --- /dev/null +++ b/src/ariel/ec/drone/inspection/animation_utils.py @@ -0,0 +1,578 @@ +""" +Animation utilities for creating videos and GIFs from evolution visualizations. + +This module handles the creation of animations from sequences of matplotlib figures, +including temporary file management and format conversion. + +# TODO: [LOW] Add progress bars for long animation rendering processes +# TODO: [LOW] Add support for additional output formats (WebM, APNG) +# TODO: [LOW] Implement memory-efficient rendering for very large datasets +""" + +import os +import tempfile +from typing import List, Callable, Optional, Union +import matplotlib.pyplot as plt +import matplotlib.animation as animation +from PIL import Image + +from ariel.ec.drone.inspection.create_subplot import create_subplot + + +def animate_grids( + grids: List[List[List[Callable]]], + interval: int = 100, + dpi: int = 300, + gif_format: bool = False, + frame_skip: int = 1, + output_path: Optional[str] = None, + cleanup: bool = True +) -> animation.ArtistAnimation: + """ + Create an animation from a sequence of grid layouts. + + Args: + grids: List of grid layouts (each grid is a 2D array of plotting functions) + interval: Time between frames in milliseconds + dpi: Resolution for saved frames + gif_format: If True, save as GIF; if False, save as MP4 + frame_skip: Skip every N frames for faster animation + output_path: Custom output path (if None, uses default naming) + cleanup: If True, remove temporary files after animation creation + + Returns: + matplotlib ArtistAnimation object + """ + # Apply frame skipping + grids = grids[::frame_skip] + + if len(grids) == 0: + raise ValueError("No grids provided after frame skipping") + + # Create temporary directory for frame images + temp_dir = tempfile.mkdtemp() + + try: + # Generate and save frame images + img_paths = _generate_frame_images(grids, temp_dir, dpi) + + # Create animation from images + ani = _create_animation_from_images(img_paths, interval) + + # Save animation + if output_path is None: + output_path = "./animated_evolution.gif" if gif_format else "./animated_evolution.mp4" + + _save_animation(ani, output_path, gif_format) + + return ani + + finally: + if cleanup: + _cleanup_temp_files(temp_dir, img_paths if 'img_paths' in locals() else []) + + +def _generate_frame_images( + grids: List[List[List[Callable]]], + temp_dir: str, + dpi: int +) -> List[str]: + """Generate image files for each frame.""" + img_paths = [] + + for i, grid in enumerate(grids): + print(f"Generating frame {i+1}/{len(grids)}") + + # Create subplot from grid + fig, axs, img_plots, texts = create_subplot(grid) + + # Save frame image + img_path = os.path.join(temp_dir, f"frame_{i:04d}.png") + fig.savefig(img_path, dpi=dpi, bbox_inches='tight') + img_paths.append(img_path) + + # Close figure to free memory + plt.close(fig) + + return img_paths + + +def _create_animation_from_images( + img_paths: List[str], + interval: int +) -> animation.ArtistAnimation: + """Create matplotlib animation from image files.""" + print("Loading images for animation...") + + # Load all images + images = [Image.open(img_path) for img_path in img_paths] + + # Create figure for animation + fig, ax = plt.subplots(figsize=(12, 8)) + fig.subplots_adjust(left=0, bottom=0, right=1, top=1) + ax.axis('off') + + # Create animation frames + animation_frames = [] + for img in images: + im = ax.imshow(img, animated=True) + animation_frames.append([im]) + + # Create animation + ani = animation.ArtistAnimation( + fig, + animation_frames, + interval=interval, + blit=True, + repeat=True + ) + + return ani + + +def _save_animation( + ani: animation.ArtistAnimation, + output_path: str, + gif_format: bool +) -> None: + """Save animation to file.""" + print(f"Saving animation to {output_path}") + + if gif_format: + # Save as GIF + ani.save(output_path, writer='pillow', fps=10) + else: + # Save as MP4 + try: + ani.save(output_path, writer='ffmpeg', fps=10, bitrate=1800) + except Exception as e: + print(f"FFmpeg not available, trying alternative: {e}") + # Fallback to other writers + try: + ani.save(output_path, writer='imagemagick', fps=10) + except Exception as e2: + print(f"ImageMagick also not available: {e2}") + print("Saving as GIF instead...") + gif_path = output_path.replace('.mp4', '.gif') + ani.save(gif_path, writer='pillow', fps=10) + + +def _cleanup_temp_files(temp_dir: str, img_paths: List[str]) -> None: + """Clean up temporary files and directory.""" + print("Cleaning up temporary files...") + + # Remove image files + for img_path in img_paths: + try: + if os.path.exists(img_path): + os.remove(img_path) + except OSError: + pass + + # Remove temporary directory + try: + os.rmdir(temp_dir) + except OSError: + pass + + +def create_animation_from_functions( + plot_functions: List[Callable], + interval: int = 200, + figsize: tuple = (12, 8), + output_path: Optional[str] = None, + gif_format: bool = False +) -> animation.FuncAnimation: + """ + Create an animation where each frame is generated by a plotting function. + + Args: + plot_functions: List of functions that create plots (each should take ax as argument) + interval: Time between frames in milliseconds + figsize: Figure size for animation + output_path: Path to save animation (if None, just returns animation object) + gif_format: If True, save as GIF; if False, save as MP4 + + Returns: + matplotlib FuncAnimation object + """ + fig, ax = plt.subplots(figsize=figsize) + + def animate_frame(frame_num): + ax.clear() + plot_functions[frame_num](ax) + ax.set_title(f"Frame {frame_num + 1}/{len(plot_functions)}") + + ani = animation.FuncAnimation( + fig, + animate_frame, + frames=len(plot_functions), + interval=interval, + repeat=True + ) + + if output_path: + _save_animation(ani, output_path, gif_format) + + return ani + + +def create_slideshow_animation( + figures: List[plt.Figure], + interval: int = 1000, + output_path: Optional[str] = None, + gif_format: bool = True +) -> animation.ArtistAnimation: + """ + Create a slideshow animation from a list of matplotlib figures. + + Args: + figures: List of matplotlib Figure objects + interval: Time between slides in milliseconds + output_path: Path to save animation + gif_format: If True, save as GIF; if False, save as MP4 + + Returns: + matplotlib ArtistAnimation object + """ + if len(figures) == 0: + raise ValueError("No figures provided") + + # Create a new figure for the animation + ani_fig, ani_ax = plt.subplots(figsize=figures[0].get_size_inches()) + ani_ax.axis('off') + + # Convert figures to images and create animation frames + temp_dir = tempfile.mkdtemp() + animation_frames = [] + + try: + for i, fig in enumerate(figures): + # Save figure to temporary file + temp_path = os.path.join(temp_dir, f"slide_{i}.png") + fig.savefig(temp_path, bbox_inches='tight') + + # Load as image and add to animation + img = Image.open(temp_path) + im = ani_ax.imshow(img) + animation_frames.append([im]) + + # Clean up + os.remove(temp_path) + + # Create animation + ani = animation.ArtistAnimation( + ani_fig, + animation_frames, + interval=interval, + blit=True, + repeat=True + ) + + if output_path: + _save_animation(ani, output_path, gif_format) + + return ani + + finally: + try: + os.rmdir(temp_dir) + except OSError: + pass + + +def save_frames_as_images( + grids: List[List[List[Callable]]], + output_dir: str, + dpi: int = 300, + prefix: str = "frame" +) -> List[str]: + """ + Save each frame as a separate image file. + + Args: + grids: List of grid layouts + output_dir: Directory to save images + dpi: Resolution for saved images + prefix: Prefix for image filenames + + Returns: + List of saved image file paths + """ + os.makedirs(output_dir, exist_ok=True) + saved_paths = [] + + for i, grid in enumerate(grids): + # Create subplot from grid + fig, axs, img_plots, texts = create_subplot(grid) + + # Save image + filename = f"{prefix}_{i:04d}.png" + filepath = os.path.join(output_dir, filename) + fig.savefig(filepath, dpi=dpi, bbox_inches='tight') + saved_paths.append(filepath) + + # Close figure + plt.close(fig) + + print(f"Saved frame {i+1}/{len(grids)}: {filename}") + + return saved_paths + + +def create_comparison_animation( + grids_list: List[List[List[List[Callable]]]], + labels: List[str], + interval: int = 500, + output_path: Optional[str] = None, + gif_format: bool = False +) -> animation.ArtistAnimation: + """ + Create an animation comparing multiple evolution runs side by side. + + Args: + grids_list: List of grid sequences, one for each evolution run + labels: Labels for each evolution run + interval: Time between frames in milliseconds + output_path: Path to save animation + gif_format: If True, save as GIF; if False, save as MP4 + + Returns: + matplotlib ArtistAnimation object + """ + if len(grids_list) != len(labels): + raise ValueError("Number of grid sequences must match number of labels") + + # Ensure all sequences have the same length + min_length = min(len(grids) for grids in grids_list) + grids_list = [grids[:min_length] for grids in grids_list] + + # Create combined grids for each frame + combined_grids = [] + for frame_idx in range(min_length): + # Combine grids horizontally for this frame + frame_grids = [grids_list[run_idx][frame_idx] for run_idx in range(len(grids_list))] + + # Create a combined grid with labels + combined_grid = [] + max_rows = max(len(grid) for grid in frame_grids) + + for row_idx in range(max_rows): + combined_row = [] + for run_idx, grid in enumerate(frame_grids): + if row_idx == 0: + # Add label for first row + label_func = lambda ax, label=labels[run_idx]: ax.text( + 0.5, 0.5, label, ha='center', va='center', + fontsize=14, fontweight='bold' + ) + combined_row.append(label_func) + + if row_idx < len(grid): + combined_row.extend(grid[row_idx]) + else: + # Add empty plots if grid is shorter + for _ in range(len(frame_grids[0][0]) if frame_grids[0] else 1): + combined_row.append(lambda ax: ax.axis('off')) + + combined_grid.append(combined_row) + + combined_grids.append(combined_grid) + + # Create animation from combined grids + return animate_grids( + combined_grids, + interval=interval, + output_path=output_path, + gif_format=gif_format + ) + + +class AnimationBuilder: + """ + Builder class for creating complex animations with various configuration options. + """ + + def __init__(self): + self.grids = [] + self.interval = 200 + self.dpi = 300 + self.figsize = (12, 8) + self.gif_format = False + self.frame_skip = 1 + self.output_path = None + self.cleanup = True + + def add_grid(self, grid: List[List[Callable]]) -> 'AnimationBuilder': + """Add a grid layout to the animation sequence.""" + self.grids.append(grid) + return self + + def set_interval(self, interval: int) -> 'AnimationBuilder': + """Set the time between frames in milliseconds.""" + self.interval = interval + return self + + def set_dpi(self, dpi: int) -> 'AnimationBuilder': + """Set the resolution for rendered frames.""" + self.dpi = dpi + return self + + def set_figsize(self, figsize: tuple) -> 'AnimationBuilder': + """Set the figure size for the animation.""" + self.figsize = figsize + return self + + def set_output_format(self, gif_format: bool) -> 'AnimationBuilder': + """Set whether to output as GIF (True) or MP4 (False).""" + self.gif_format = gif_format + return self + + def set_frame_skip(self, frame_skip: int) -> 'AnimationBuilder': + """Set frame skipping (1 = no skip, 2 = every other frame, etc.).""" + self.frame_skip = frame_skip + return self + + def set_output_path(self, output_path: str) -> 'AnimationBuilder': + """Set the output file path.""" + self.output_path = output_path + return self + + def set_cleanup(self, cleanup: bool) -> 'AnimationBuilder': + """Set whether to clean up temporary files.""" + self.cleanup = cleanup + return self + + def build(self) -> animation.ArtistAnimation: + """Build and return the animation.""" + if not self.grids: + raise ValueError("No grids added to animation") + + return animate_grids( + self.grids, + interval=self.interval, + dpi=self.dpi, + gif_format=self.gif_format, + frame_skip=self.frame_skip, + output_path=self.output_path, + cleanup=self.cleanup + ) + + +def check_animation_requirements() -> dict: + """ + Check if required libraries and tools are available for animation creation. + + Returns: + Dictionary with availability status of different animation backends + """ + requirements = { + 'matplotlib': False, + 'PIL': False, + 'ffmpeg': False, + 'imagemagick': False + } + + # Check matplotlib + try: + import matplotlib.animation + requirements['matplotlib'] = True + except ImportError: + pass + + # Check PIL + try: + from PIL import Image + requirements['PIL'] = True + except ImportError: + pass + + # Check ffmpeg + try: + import subprocess + result = subprocess.run(['ffmpeg', '-version'], + capture_output=True, text=True, timeout=5) + requirements['ffmpeg'] = result.returncode == 0 + except (subprocess.SubprocessError, FileNotFoundError, subprocess.TimeoutExpired): + pass + + # Check imagemagick + try: + import subprocess + result = subprocess.run(['convert', '-version'], + capture_output=True, text=True, timeout=5) + requirements['imagemagick'] = result.returncode == 0 + except (subprocess.SubprocessError, FileNotFoundError, subprocess.TimeoutExpired): + pass + + return requirements + + +def get_recommended_settings(num_frames: int, file_size_limit_mb: float = 50) -> dict: + """ + Get recommended animation settings based on number of frames and file size constraints. + + Args: + num_frames: Number of frames in the animation + file_size_limit_mb: Target maximum file size in MB + + Returns: + Dictionary with recommended settings + """ + settings = { + 'interval': 200, + 'dpi': 150, + 'frame_skip': 1, + 'gif_format': False + } + + # Adjust settings based on number of frames + if num_frames > 100: + settings['frame_skip'] = max(1, num_frames // 50) # Limit to ~50 frames + settings['interval'] = 150 + elif num_frames > 50: + settings['interval'] = 300 + + # Adjust for file size + estimated_size_mb = num_frames * settings['dpi'] / 1000 # Rough estimate + if estimated_size_mb > file_size_limit_mb: + # Reduce DPI to meet file size constraint + settings['dpi'] = max(75, int(settings['dpi'] * file_size_limit_mb / estimated_size_mb)) + + # If still too large, prefer GIF format + if estimated_size_mb > file_size_limit_mb * 1.5: + settings['gif_format'] = True + + return settings + + +# Utility functions for backward compatibility +def animate_grids_legacy(grids, interval=100, dpi=300, gif_format=False, frame_skip=1): + """Legacy function for backward compatibility.""" + return animate_grids( + grids=grids, + interval=interval, + dpi=dpi, + gif_format=gif_format, + frame_skip=frame_skip + ) + + +if __name__ == "__main__": + # Example usage and testing + print("=== Animation Utils Testing ===") + + # Check requirements + requirements = check_animation_requirements() + print("Animation requirements:") + for requirement, available in requirements.items(): + status = "✓" if available else "✗" + print(f" {status} {requirement}") + + # Test recommended settings + settings = get_recommended_settings(100, 25) + print(f"\nRecommended settings for 100 frames, 25MB limit:") + for key, value in settings.items(): + print(f" {key}: {value}") + + print("\n=== Testing Complete ===") \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/behavioural_analysis/__init__.py b/src/ariel/ec/drone/inspection/behavioural_analysis/__init__.py new file mode 100644 index 000000000..03d47fc65 --- /dev/null +++ b/src/ariel/ec/drone/inspection/behavioural_analysis/__init__.py @@ -0,0 +1 @@ +# Package init diff --git a/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/__init__.py b/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/__init__.py new file mode 100644 index 000000000..03d47fc65 --- /dev/null +++ b/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/__init__.py @@ -0,0 +1 @@ +# Package init diff --git a/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/animate_individual_with_gates.py b/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/animate_individual_with_gates.py new file mode 100644 index 000000000..e0718ecaf --- /dev/null +++ b/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/animate_individual_with_gates.py @@ -0,0 +1,144 @@ +from ariel.visualisation.drone.animation import view, animate +from ariel.simulation.tasks.drone_gate_env import DroneGateEnv +from ariel.ec.drone.evaluators.gate_train import backandforth, circle, slalom, figure8, animate_policy +from ariel.ec.drone.inspection.morphological_descriptors.hovering_info import get_sim + +import os +from stable_baselines3 import PPO +import torch +import numpy as np + + +def animate_individual( + gate_cfg, + individual_dir, + save_dir, + file_name, + device=None, + view_type='top', # Options: 'top', 'iso' + follow=False, + draw_forces=False, + draw_path=False, + auto_play=True, + record=False, + motor_colors=['red', 'blue', 'green', 'orange', 'purple', 'brown'] +): + if device is None: + device = "cuda:0" if torch.cuda.is_available() else "cpu" + + if not os.path.exists(save_dir): + os.makedirs(save_dir) + + ind_policy_file = individual_dir + "/policy.zip" + individual_body = individual_dir + "/individual.npy" + if not os.path.exists(individual_body): + individual_body = individual_dir + "/genome.npy" + individual = np.load(individual_body, allow_pickle=True) + if hasattr(individual, "arms"): + individual = individual.arms + elif isinstance(individual, np.ndarray) and individual.dtype == object: + individual = individual.item().arms + + # Define the environment + if gate_cfg == "backandforth": + gate_pos = backandforth.gate_pos + gate_yaw = backandforth.gate_yaw + start_pos = backandforth.starting_pos + x_bounds = backandforth.x_bounds + y_bounds = backandforth.y_bounds + z_bounds = backandforth.z_bounds + elif gate_cfg == "figure8": + gate_pos = figure8.gate_pos + gate_yaw = figure8.gate_yaw + start_pos = figure8.starting_pos + x_bounds = figure8.x_bounds + y_bounds = figure8.y_bounds + z_bounds = figure8.z_bounds + elif gate_cfg == "circle": + gate_pos = circle.gate_pos + gate_yaw = circle.gate_yaw + start_pos = circle.starting_pos + x_bounds = circle.x_bounds + y_bounds = circle.y_bounds + z_bounds = circle.z_bounds + elif gate_cfg == "slalom": + gate_pos = slalom.gate_pos + gate_yaw = slalom.gate_yaw + start_pos = slalom.starting_pos + x_bounds = slalom.x_bounds + y_bounds = slalom.y_bounds + z_bounds = slalom.z_bounds + else: + raise ValueError("Invalid gate configuration") + + env = DroneGateEnv( + num_envs=1, + individual=individual, + gates_pos=gate_pos, + gate_yaw=gate_yaw, + start_pos=start_pos, + x_bounds=x_bounds, + y_bounds=y_bounds, + z_bounds=z_bounds, + initialize_at_random_gates=False, + gates_ahead=1, + num_state_history=0, + num_action_history=0, + history_step_size=1, + render_mode=None, + ) + + # Load the policy + policy_kwargs = dict( + activation_fn=torch.nn.ReLU, + net_arch=dict(pi=[64, 64, 64], vf=[64, 64, 64]), + log_std_init=0, + ) + model = PPO( + "MlpPolicy", + env, + policy_kwargs=policy_kwargs, + verbose=0, + n_steps=1000, + batch_size=1000, + n_epochs=10, + gamma=0.999, + device=device, + ) + model = PPO.load(ind_policy_file) + + animate_policy( + individual, + model, + env, + deterministic=True, + log_times=False, + print_vel=False, + log=None, + record_steps=1200, + record_file=save_dir + file_name, + show_window=False, + follow=follow, + draw_forces=draw_forces, + draw_path=draw_path, + auto_play=auto_play, + record=record, + motor_colors=motor_colors, + ) + +# Example usage +if __name__ == "__main__": + gate_cfg="slalom" + individual_dir="/home/jed/workspaces/airevolve/data_backup/asym_slalom/asym_slalom4evo_logs_20250320_095329/gen40/ind964/" + save_dir="./plots/example_comparison/" + animate_individual(gate_cfg, individual_dir, save_dir, + file_name="top_view.mp4", + device=None, view_type='top', follow=True, + draw_forces=False, draw_path=False, + auto_play=True, record=False) + + animate_individual(gate_cfg, individual_dir, save_dir, + file_name="iso_view.mp4", + device=None, view_type='iso', follow=True, + draw_forces=False, draw_path=False, + auto_play=True, record=False) \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/animate_lee_individual.py b/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/animate_lee_individual.py new file mode 100644 index 000000000..89cd55c9f --- /dev/null +++ b/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/animate_lee_individual.py @@ -0,0 +1,189 @@ +import json +import os +import numpy as np + +from ariel.visualisation.drone.animation import view +from ariel.simulation.drone.controllers.utils.gate_configs import GATE_CONFIGS +from ariel.ec.drone.evaluators.lee_tune_evaluator import simulate_with_gains +from ariel.ec.drone.inspection.utils import convert_to_cartesian, ENU_to_NED +from ariel.ec.drone.inspection.morphological_descriptors.hovering_info import orientation_to_unit_vector + + +def _genome_to_propellers(genome): + """Convert a genome array to propeller dicts for the view() function.""" + propellers = [] + for arm in genome: + r, theta, phi, motor_pitch, motor_yaw, direction = arm + ex, ey, ez = convert_to_cartesian(r, theta, phi) + x, y, z = ENU_to_NED(ex, ey, ez) + rot = "ccw" if direction < 0.5 else "cw" + motor_dir = orientation_to_unit_vector(0.0, motor_pitch, motor_yaw) + propellers.append({ + "loc": [float(x), float(y), float(z)], + "dir": [float(motor_dir[0]), float(motor_dir[1]), float(motor_dir[2]), rot], + "propsize": 2, + }) + return propellers + + +def animate_lee_individual(genome, tuning_results_path, gate_cfg, + save_dir, file_name, + sim_time=20.0, dt=0.005, + view_type='top', follow=True, + draw_forces=False, draw_path=True, + auto_play=True, record=True, + motor_colors=None, fps=100, + overlay_text_position='lower right', + overlay_text_scale=0.7): + """ + Pre-record a Lee-controller flight and replay it via view(). + + Args: + genome: Drone morphology array (N_arms, 6). + tuning_results_path: Path to tuning_results.json. + gate_cfg: Gate configuration name. + save_dir: Directory to save the output video. + file_name: Video filename (e.g. '/top_view.mp4'). + sim_time: Simulation duration in seconds. + dt: Simulation timestep (default 0.005 s = 200 Hz). + view_type: Camera view ('top' or 'iso'). + follow: Whether camera follows the drone. + draw_forces: Whether to draw thrust vectors. + draw_path: Whether to draw flight path. + auto_play: Whether animation auto-plays. + record: Whether to record video. + motor_colors: List of colour names for motors. + fps: Playback frames per second. + """ + if motor_colors is None: + motor_colors = ['red', 'blue', 'green', 'orange', 'purple', 'brown'] + + os.makedirs(save_dir, exist_ok=True) + + # Load tuning results + with open(tuning_results_path, 'r') as f: + tuning = json.load(f) + + gains = tuning['gains'] + bspline_timing = tuning.get('bspline_timing', None) + gate_offsets = tuning.get('gate_offsets', None) + + # Legacy tuning_results.json files saved Stage-1 winners with + # gate_offsets=[0.0]*N, but Stage 1 actually ran against the B-spline's + # tension-based defaults (it passed gate_offsets=None). Remap all-zeros + # to None so the trajectory reproduces what CMA-ES evaluated. + if gate_offsets is not None and not np.any(np.asarray(gate_offsets)): + gate_offsets = None + + gate_config = GATE_CONFIGS[gate_cfg] + + # Run simulation once with trajectory recording + result = simulate_with_gains( + individual=genome, + pos_gain=gains['pos_P'], + vel_gain=gains['vel_P'], + att_gain=gains['att_P'], + rate_gain=gains['rate_P'], + gate_config=gate_config, + sim_time=sim_time, + dt=dt, + bspline_timing=bspline_timing, + gate_offsets=gate_offsets, + record_trajectory=True, + ) + + traj = result['trajectory'] + positions = traj['positions'] + euler_angles = traj['euler_angles'] + motor_commands = traj['motor_commands'] + gate_passes = traj['gate_passes'] + + # Subsample from simulation rate (200 Hz) to playback rate (100 Hz) + sim_hz = int(round(1.0 / dt)) + subsample = max(1, sim_hz // fps) + positions = positions[::subsample] + euler_angles = euler_angles[::subsample] + motor_commands = motor_commands[::subsample] + # Build the playback gate counter by taking the cumulative sum at the full + # simulation rate and subsampling the cumulative array. This preserves + # every pass (a prior implementation collapsed multiple passes within one + # playback window via np.any, which silently lost one when two crossings + # landed in the same window). + gates_cumulative = np.cumsum(gate_passes.astype(int))[::subsample] + gates_total = len(gate_config.gate_pos) + + print(f"[animate_lee_individual] sim gates_passed={result['gates_passed']} " + f"sum(gate_passes)={int(gate_passes.sum())} " + f"cumulative_final={int(gates_cumulative[-1])}") + pass_steps = np.where(gate_passes)[0] + if len(pass_steps) > 0: + print(f"[animate_lee_individual] pass sim_steps={pass_steps.tolist()[:20]}" + f"{'...' if len(pass_steps) > 20 else ''} " + f"times_s={[round(s * dt, 3) for s in pass_steps[:20].tolist()]}") + + # Normalise motor commands for visualisation + w_max = motor_commands.max() + if w_max > 0: + motor_commands = motor_commands / w_max + + # Low-pass the motor commands so the thrust arrows don't jitter frame-to-frame. + # Window is in playback frames; ~0.1s of smoothing. + smooth_window = max(3, int(0.1 * fps)) + if motor_commands.shape[0] >= smooth_window: + kernel = np.ones(smooth_window) / smooth_window + padded = np.pad(motor_commands, ((smooth_window - 1, 0), (0, 0)), mode='edge') + motor_commands = np.stack([ + np.convolve(padded[:, m], kernel, mode='valid') + for m in range(motor_commands.shape[1]) + ], axis=1) + + num_motors = genome.shape[0] + num_frames = len(positions) + + # Build propellers config for view() + propellers = _genome_to_propellers(genome) + + # Index-based callback for view() + frame_idx = [0] + + def get_drone_state(): + idx = min(frame_idx[0], num_frames - 1) + frame_idx[0] += 1 + + state = { + 'x': positions[idx, 0], + 'y': positions[idx, 1], + 'z': positions[idx, 2], + 'phi': euler_angles[idx, 0], + 'theta': euler_angles[idx, 1], + 'psi': euler_angles[idx, 2], + } + for m in range(num_motors): + state[f'u{m+1}'] = motor_commands[idx, m] + + if overlay_text_position is not None: + state['gates_passed'] = int(gates_cumulative[idx]) + state['gates_total'] = gates_total + + return state + + view( + propellers, + get_drone_state=get_drone_state, + fps=fps, + gate_pos=gate_config.gate_pos, + gate_yaw=gate_config.gate_yaw, + gate_size=gate_config.gate_size, + record_steps=num_frames, + record_file=save_dir + file_name, + show_window=False, + view_type=view_type, + follow=follow, + draw_forces=draw_forces, + draw_path=draw_path, + auto_play=auto_play, + record=record, + motor_colors=motor_colors, + overlay_text_position=overlay_text_position, + overlay_text_scale=overlay_text_scale, + ) diff --git a/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/calculate_stats.py b/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/calculate_stats.py new file mode 100644 index 000000000..4c7693150 --- /dev/null +++ b/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/calculate_stats.py @@ -0,0 +1,33 @@ +import numpy as np + +def calculate_stats(gate_times_sec, n_gates): + """Calculate lap times, segment times, and their statistics.""" + segment_durations = np.diff(gate_times_sec) + segment_indices = np.arange(len(segment_durations)) % n_gates + + avg_times = [] + std_times = [] + + for i in range(n_gates): + segment_times = segment_durations[segment_indices == i] + avg_times.append(np.mean(segment_times)) + std_times.append(np.std(segment_times)) + + n_laps = len(gate_times_sec) // n_gates + lap_times = [] + for lap in range(n_laps): + start_idx = lap * n_gates + end_idx = start_idx + n_gates - 1 + lap_time = gate_times_sec[end_idx] - gate_times_sec[start_idx] + lap_times.append(lap_time) + + lap_times = np.array(lap_times) + + return { + "avg_segment_times": avg_times, + "std_segment_times": std_times, + "lap_times": lap_times, + "avg_lap_time": np.mean(lap_times), + "std_lap_time": np.std(lap_times), + "total_laps": n_laps, + } \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/combine_videos.py b/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/combine_videos.py new file mode 100644 index 000000000..52930ebd9 --- /dev/null +++ b/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/combine_videos.py @@ -0,0 +1,51 @@ +import os +from moviepy import VideoFileClip, clips_array + +def combine_videos_from_directory(directory, output_file="combined_output.mp4"): + """ + Combines specific videos from a directory into a single video and saves it. + + Args: + directory (str): Path to the directory containing video files. + output_file (str): Name of the output video file. + """ + # Define the filenames to look for + filenames = { + "vid1": "iso_view.mp4", + "vid2": "top_view.mp4", + "vid3": "speed_plot.mp4", + "vid4": "angular_speed_plot.mp4", + "long_vid": "actions_plot.mp4" + } + + # Resolve full paths for the required videos + video_paths = {key: os.path.join(directory, value) for key, value in filenames.items()} + + # Load the video files + try: + vid1 = VideoFileClip(video_paths["vid1"]) + vid2 = VideoFileClip(video_paths["vid2"]) + vid3 = VideoFileClip(video_paths["vid3"]) + vid4 = VideoFileClip(video_paths["vid4"]) + long_vid = VideoFileClip(video_paths["long_vid"]) + except FileNotFoundError as e: + print(f"Error: {e}") + return + + # Arrange square videos in 2x2 grid + grid = clips_array([[vid1, vid3], + [vid2, vid4]]) + + # Combine the grid and long video side by side + final_video = clips_array([[grid, long_vid]]) + + # Write the result to the output file + final_video.write_videofile(directory+"/"+output_file, codec='libx264', audio_codec='aac') + +# Example usage +if __name__ == "__main__": + # Specify the directory containing the videos + # directory = "/path/to/your/videos" + # For demonstration, using a hardcoded path + # You should replace this with your actual path + combine_videos_from_directory("/home/jed/workspaces/airevolve/plots/example_comparison") \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/extract_lee_simulation_data.py b/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/extract_lee_simulation_data.py new file mode 100644 index 000000000..9e995f497 --- /dev/null +++ b/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/extract_lee_simulation_data.py @@ -0,0 +1,82 @@ +import json +import numpy as np + +from ariel.simulation.drone.controllers.utils.gate_configs import GATE_CONFIGS +from ariel.ec.drone.evaluators.lee_tune_evaluator import simulate_with_gains + + +def extract_lee_simulation_data(genome, tuning_results_path, gate_cfg, + sim_time=20.0, dt=0.005): + """ + Extract simulation data for a Lee-controller-tuned individual. + + Loads tuning results (gains, bspline_timing, gate_offsets), runs the + simulation with trajectory recording, and returns data in the same + format as extract_simulation_data (for RL individuals). + + Args: + genome: Drone morphology array (N_arms, 6). + tuning_results_path: Path to tuning_results.json. + gate_cfg: Gate configuration name ('circle', 'figure8', 'slalom', 'backandforth'). + sim_time: Simulation time in seconds. + dt: Simulation timestep in seconds. + + Returns: + dict with keys: + positions: (N, 3) array + velocities: (N, 3) array + angular_velocities: (N, 3) array + gate_passes: (N,) boolean array + actions: (N, num_motors) array normalised to [0, 1] + """ + # Load tuning results + with open(tuning_results_path, 'r') as f: + tuning = json.load(f) + + gains = tuning['gains'] + bspline_timing = tuning.get('bspline_timing', None) + gate_offsets = tuning.get('gate_offsets', None) + + # Legacy tuning_results.json files saved Stage-1 winners with + # gate_offsets=[0.0]*N, but Stage 1 actually ran against the B-spline's + # tension-based defaults (it passed gate_offsets=None). Remap all-zeros + # to None so the trajectory reproduces what CMA-ES evaluated. + if gate_offsets is not None and not np.any(np.asarray(gate_offsets)): + gate_offsets = None + + gate_config = GATE_CONFIGS[gate_cfg] + + # Run simulation with trajectory recording + result = simulate_with_gains( + individual=genome, + pos_gain=gains['pos_P'], + vel_gain=gains['vel_P'], + att_gain=gains['att_P'], + rate_gain=gains['rate_P'], + gate_config=gate_config, + sim_time=sim_time, + dt=dt, + bspline_timing=bspline_timing, + gate_offsets=gate_offsets, + record_trajectory=True, + ) + + traj = result['trajectory'] + + # Normalise motor commands to [0, 1] range + # w_cmd values are angular velocities (rad/s); normalise per-motor by + # mapping [0, max_observed] -> [0, 1] for visualisation consistency + motor_cmds = traj['motor_commands'] + w_max = motor_cmds.max() + if w_max > 0: + actions = motor_cmds / w_max + else: + actions = np.zeros_like(motor_cmds) + + return { + 'positions': traj['positions'], + 'velocities': traj['velocities'], + 'angular_velocities': traj['angular_velocities'], + 'gate_passes': traj['gate_passes'], + 'actions': actions, + } diff --git a/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/extract_simulation_data.py b/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/extract_simulation_data.py new file mode 100644 index 000000000..a4cde3b5c --- /dev/null +++ b/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/extract_simulation_data.py @@ -0,0 +1,101 @@ +from stable_baselines3 import PPO +from ariel.ec.drone.inspection.morphological_descriptors.hovering_info import get_sim +from ariel.simulation.tasks.drone_gate_env import DroneGateEnv +from ariel.ec.drone.evaluators.gate_train import backandforth, circle, slalom, figure8 +import torch +import numpy as np + +def extract_simulation_data(individual, policy_file, gate_cfg, device): + """ + Extract simulation data for a given individual and policy file. + + Args: + individual (np.ndarray): The individual configuration. + policy_file (str): Path to the policy file. + gate_cfg (str): Gate configuration (e.g., "circle", "slalom"). + device (str): Device to run the simulation on (e.g., "cuda:0" or "cpu"). + + Returns: + dict: A dictionary containing positions, velocities, angular velocities, gate passes, and actions. + """ + # Unwrap genome objects (e.g. SphericalNeatGenome) to the raw arms array + if hasattr(individual, "arms"): + individual = individual.arms + elif isinstance(individual, np.ndarray) and individual.dtype == object: + individual = individual.item().arms + + # Define the environment based on the gate configuration + gate_configs = { + "backandforth": backandforth, + "circle": circle, + "slalom": slalom, + "figure8": figure8 + } + if gate_cfg not in gate_configs: + raise ValueError("Invalid gate configuration") + + gate_config = gate_configs[gate_cfg] + + env = DroneGateEnv( + num_envs=1, + individual=individual, + gates_pos=gate_config.gate_pos, + gate_yaw=gate_config.gate_yaw, + start_pos=gate_config.starting_pos, + x_bounds=gate_config.x_bounds, + y_bounds=gate_config.y_bounds, + z_bounds=gate_config.z_bounds, + initialize_at_random_gates=False, + gates_ahead=1, + num_state_history=0, + num_action_history=0, + history_step_size=1, + render_mode=None, + ) + + # Load the policy + policy_kwargs = dict(activation_fn=torch.nn.ReLU, net_arch=dict(pi=[64, 64, 64], vf=[64, 64, 64]), log_std_init=0) + model = PPO("MlpPolicy", env, + policy_kwargs=policy_kwargs, + verbose=0, + n_steps=1000, + batch_size=1000, + n_epochs=10, + gamma=0.999, + device=device) + + try: + model = PPO.load(policy_file) + except: + model = PPO.load(policy_file[:-4]) + + # Run the simulation + env.reset() + positions, velocities, angular_velocities, gate_passes, actions = [], [], [], [], [] + + for _ in range(1200): + action, _ = model.predict(env.states, deterministic=True) + states, rewards, dones, infos = env.step(action) + + positions.append(env.world_states[0, 0:3]) + velocities.append(env.world_states[0, 3:6]) + angular_velocities.append(env.world_states[0, 9:12]) + gate_passes.append(infos[0]["gate_passed"]) + # Normalize actions to be between 0 and 1 + a = action[0] * 0.5 + 0.5 + actions.append(a) + + # Convert lists to numpy arrays + positions = np.array(positions[:-1]) + velocities = np.array(velocities[:-1]) + angular_velocities = np.array(angular_velocities[:-1]) + gate_passes = np.array(gate_passes[:-1]) + actions = np.array(actions[:-1]) + + return { + "positions": positions, + "velocities": velocities, + "angular_velocities": angular_velocities, + "gate_passes": gate_passes, + "actions": actions + } diff --git a/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/plot_racing_line.py b/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/plot_racing_line.py new file mode 100644 index 000000000..2f1bc5841 --- /dev/null +++ b/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/plot_racing_line.py @@ -0,0 +1,175 @@ +import numpy as np +from matplotlib.collections import LineCollection +from matplotlib.colors import PowerNorm +import matplotlib.pyplot as plt +import torch + +from ariel.ec.drone.inspection.behavioural_analysis.extract_simulation_data import extract_simulation_data + + +def plot_racing_line_speed(ind_speed, ind_positions_2d, save_dir, save_name=None, + vmin=None, vmax=None, colormap='viridis', + cbar_label="Speed", title="Best Individual", + suptitle="Drone Racing Line (Colored by Speed)", + width=864, height=700, dpi=200, min_timestep=0, max_timestep=None): + """ + Plots the racing line for speed for a single individual. + + Parameters: + ind_speed (numpy.ndarray): Array of speeds for the individual. + ind_positions_2d (numpy.ndarray): 2D positions of the individual. + save_dir (str): Directory to save the plot. + """ + # Trim the data to the specified time range + if max_timestep is None: + max_timestep = ind_positions_2d.shape[0]-1 + ind_positions_2d = ind_positions_2d[min_timestep:max_timestep] + ind_speed = ind_speed[min_timestep:max_timestep] + ind_speed = ind_speed[min_timestep:max_timestep] # Speed is one less than positions + ind_positions_2d = ind_positions_2d[min_timestep:max_timestep] # Positions are one less than speed + + points = ind_positions_2d.reshape(-1, 1, 2) + ind_segments = np.concatenate([points[:-1], points[1:]], axis=1) + + # Normalize speed + if vmin is None: + vmin = ind_speed.min() + if vmax is None: + vmax = ind_speed.max() + norm_speed = PowerNorm(gamma=3.0, vmin=vmin, vmax=vmax) + + # Create LineCollection for speed + ind_lc_speed = LineCollection(ind_segments, cmap=colormap, norm=norm_speed) + ind_lc_speed.set_array(ind_speed[:-1]) + ind_lc_speed.set_linewidth(2) + + # Create figure and axis + fig, ax = plt.subplots(figsize=(width / dpi, height / dpi)) + + # Add LineCollection to the plot + ax.add_collection(ind_lc_speed) + ax.set_xlim(ind_positions_2d[:, 0].min(), ind_positions_2d[:, 0].max()) + ax.set_ylim(ind_positions_2d[:, 1].min(), ind_positions_2d[:, 1].max()) + ax.set_aspect('equal') + ax.grid(True) + ax.set_xlabel("x") + ax.set_ylabel("y") + + # Add colorbar + cbar = fig.colorbar(ind_lc_speed, ax=ax, orientation='horizontal', fraction=0.02, pad=0.1) + cbar.set_label(cbar_label) + + # Add title + ax.text(0.5, -0.2, title, ha='center', va='center', transform=ax.transAxes) + fig.suptitle(suptitle) + + # Adjust layout and save the figure + fig.tight_layout() + if save_name is None: + save_name = "racing_line_speed.png" + fig.savefig(f"{save_dir}{save_name}", dpi=dpi) + plt.close(fig) + +import numpy as np +import matplotlib.pyplot as plt +from matplotlib.collections import LineCollection +from matplotlib.colors import PowerNorm + +def plot_racing_line_speed_segments(ind_speed, ind_positions_2d, save_dir, save_name=None, + vmin=None, vmax=None, colormap='viridis', + cbar_label="Speed", suptitle="Drone Racing Line Segments (Colored by Speed)", + width=864, height=700, dpi=200, min_timestep=0, max_timestep=None): + """ + Plots the racing line for speed, splitting the track into 4 segments and displaying them in a column. + + Parameters: + ind_speed (numpy.ndarray): Array of speeds for the individual. + ind_positions_2d (numpy.ndarray): 2D positions of the individual. + save_dir (str): Directory to save the plot. + """ + # Trim the data to the specified time range + if max_timestep is None: + max_timestep = ind_positions_2d.shape[0]-12 + ind_positions_2d = ind_positions_2d[min_timestep:max_timestep] + ind_speed = ind_speed[min_timestep:max_timestep] + + # Split data into 4 segments + num_points = ind_positions_2d.shape[0] + segment_size = num_points // 4 + segments_positions = [ind_positions_2d[i * segment_size:(i + 1) * segment_size] for i in range(4)] + segments_speed = [ind_speed[i * segment_size:(i + 1) * segment_size] for i in range(4)] + + # Normalize speed + if vmin is None: + vmin = ind_speed.min() + if vmax is None: + vmax = ind_speed.max() + norm_speed = PowerNorm(gamma=3.0, vmin=vmin, vmax=vmax) + + # Create figure and subplots + fig, axes = plt.subplots(4, 1, figsize=(width / dpi, height / dpi), dpi=dpi) + fig.subplots_adjust(hspace=0.5) + + for i, (positions, speeds, ax) in enumerate(zip(segments_positions, segments_speed, axes)): + # Create segments for LineCollection + points = positions.reshape(-1, 1, 2) + ind_segments = np.concatenate([points[:-1], points[1:]], axis=1) + + # Create LineCollection for speed + ind_lc_speed = LineCollection(ind_segments, cmap=colormap, norm=norm_speed) + ind_lc_speed.set_array(speeds[:-1]) + ind_lc_speed.set_linewidth(2) + + # Add LineCollection to the plot + ax.add_collection(ind_lc_speed) + ax.set_xlim(positions[:, 0].min(), positions[:, 0].max()) + ax.set_ylim(positions[:, 1].min(), positions[:, 1].max()) + ax.set_aspect('equal') + ax.grid(True) + # ax.set_xlabel("x") + # ax.set_ylabel("y") + # ax.set_title(f"Segment {i + 1}") + + # Add colorbar + # cbar = fig.colorbar(ind_lc_speed, ax=ax, orientation='horizontal', fraction=0.02, pad=0.1) + # cbar.set_label(cbar_label) + + # Add overall title + fig.suptitle(suptitle) + + # Adjust layout and save the figure + fig.tight_layout(rect=[0, 0, 1, 0.96]) + if save_name is None: + save_name = "racing_line_speed_segments.png" + fig.savefig(f"{save_dir}{save_name}", dpi=dpi) + plt.close(fig) + +if __name__ == "__main__": + # Example usage + save_dir = "./plots/example_comparison/" + ind_dir = "/home/jed/workspaces/airevolve/data_backup/asym_slalom/asym_slalom4evo_logs_20250320_095329/gen40/ind964/" + policy_file = ind_dir + "/policy.zip" + body = ind_dir + "/individual.npy" + individual = np.load(body) + gate_cfg = "slalom" + device = "cuda:0" if torch.cuda.is_available() else "cpu" + + data = extract_simulation_data(individual, policy_file, gate_cfg, device) + speed = np.linalg.norm(data["velocities"], axis=1) + angular_speed = np.linalg.norm(data["angular_velocities"], axis=1) + positions_2d = data["positions"][:, :2] + + plot_racing_line_speed_segments( + ind_speed=speed, + ind_positions_2d=positions_2d, + save_dir=save_dir, + save_name="racing_line_speed.png", + vmin=0, # Minimum speed for normalization + vmax=13, # Maximum speed for normalization + colormap="plasma", # Colormap for the plot + cbar_label="Speed (m/s)", # Label for the colorbar + # title="Example Racing Line", # Title of the plot + suptitle="Drone Racing Line Example", + min_timestep=0, + max_timestep=None, # Maximum timestep for the plot +) \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/plot_speed_actions.py b/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/plot_speed_actions.py new file mode 100644 index 000000000..f1fa7a6e0 --- /dev/null +++ b/src/ariel/ec/drone/inspection/behavioural_analysis/gate_based/plot_speed_actions.py @@ -0,0 +1,480 @@ +import numpy as np +import matplotlib.pyplot as plt +from matplotlib.animation import FuncAnimation, FFMpegWriter + +import os +import torch + +from ariel.ec.drone.inspection.behavioural_analysis.gate_based.calculate_stats import calculate_stats + +import numpy as np +import matplotlib.pyplot as plt +from scipy.interpolate import interp1d + +import numpy as np +import matplotlib.pyplot as plt +from scipy.interpolate import interp1d + +import numpy as np +import matplotlib.pyplot as plt + +import numpy as np +import matplotlib.pyplot as plt + +import numpy as np +import matplotlib.pyplot as plt + +def plot_normalized_speeds(speeds, gate_passes, gate_start, gate_end, + title="Normalized Speeds", xlabel="Time (Normalized Between Gates)", ylabel="Speed", + fontsize=12, font_size_x_label=12, font_size_y_label=12, + font_size_ticks=10, color_palette=None, alphas=None, save_as="normalized_speeds.png", + show_grid=True, grid_linestyle='--', grid_linewidth=0.5, grid_alpha=0.7, + show_legend=True, legend_labels=None, legend_fontsize=12, legend_loc='lower right'): + """ + Plots normalized speeds for each drone, considering gate passes. + + Parameters: + - speeds: numpy array of shape (num_drones, num_timesteps), speeds of drones + - gate_passes: numpy array of shape (num_drones, num_timesteps), gate pass information for drones + - gate_start: starting gate index + - gate_end: ending gate index + - title: title of the plot + - xlabel: label for the x-axis + - ylabel: label for the y-axis + - fontsize: font size for the title + - font_size_x_label: font size for the x-axis label + - font_size_y_label: font size for the y-axis label + - font_size_ticks: font size for the x and y ticks + - color_palette: list of colors for each drone's speed plot + - save_as: file name to save the plot + - show_grid: whether to show grid lines on the plot + - grid_linestyle: linestyle for grid + - grid_linewidth: linewidth for grid + - grid_alpha: transparency for grid + - show_legend: whether to display a legend + - legend_labels: list of labels for the legend + """ + + # Default color palette if none is provided + if color_palette is None: + color_palette = ["red", "green", "blue", "orange", "yellow"] + if alphas is None: + alphas = [1.0] * len(color_palette) + num_drones = speeds.shape[0] + + max_num_gate_passes = np.min(np.sum(gate_passes, axis=1)) + print(f"Max number of gate passes: {max_num_gate_passes}") + + # Reduce all speeds to the same number of gate passes + new_speeds = [] + new_gate_passes = [] + for drone_num in range(num_drones): + cs = np.cumsum(gate_passes[drone_num]) + when_max_gate_passes = np.where(cs == max_num_gate_passes)[0][0] + drone_speeds = speeds[drone_num][:when_max_gate_passes] + drone_gate_passes = gate_passes[drone_num][:when_max_gate_passes] + + new_speeds.append(drone_speeds) + new_gate_passes.append(drone_gate_passes) + + drone_timesteps_per_segment = [] + drone_speeds_per_segment = [] + for drone_num in range(num_drones): + drone_speeds = new_speeds[drone_num] + drone_gate_passes = new_gate_passes[drone_num] + + segments_ends = np.where(drone_gate_passes)[0] + segments_starts = np.concatenate(([0], segments_ends[:-1] + 1)) + speed_in_segments = [drone_speeds[segments_starts[i]:segments_ends[i]] for i in range(len(segments_starts))] + drone_speeds_per_segment.append(speed_in_segments) + + timestep_per_segment = [] + for i, segment in enumerate(speed_in_segments): + timestep_per_segment.append(len(segment)) + drone_timesteps_per_segment.append(timestep_per_segment) + + drone_timesteps_per_segment = np.array(drone_timesteps_per_segment) + max_length_per_segment = np.max(drone_timesteps_per_segment, axis=0) + + fig, ax = plt.subplots(1) + viable_gates = np.arange(gate_start, gate_end) + seg_prev_ends = [] + + if gate_start != 0: + ax.axvline(x=gate_start, linestyle='dotted', color='purple', alpha=0.75) + for segment_num in viable_gates: + drone_prev_ends = [] + for drone_num in range(num_drones): + drone_speeds_in_segment = drone_speeds_per_segment[drone_num][segment_num] + mx_ts = drone_timesteps_per_segment[drone_num][segment_num] + drone_ts_in_segment = np.arange(mx_ts) + + timestep_norm = segment_num + (drone_ts_in_segment / mx_ts) + + # Handle previous segment ends + if segment_num != viable_gates[0]: + timestep_norm = np.insert(timestep_norm, 0, seg_prev_ends[segment_num - viable_gates[0] - 1][drone_num][0]) + drone_speeds_in_segment = np.insert(drone_speeds_in_segment, 0, seg_prev_ends[segment_num - viable_gates[0] - 1][drone_num][1]) + + ax.plot(timestep_norm, drone_speeds_in_segment, color=color_palette[drone_num], alpha=alphas[drone_num]) + + drone_prev_ends.append([timestep_norm[-1], drone_speeds_in_segment[-1]]) + + seg_prev_ends.append(drone_prev_ends) + ax.axvline(x=segment_num + 1, linestyle='dotted', color='purple', alpha=0.75) + + # Set plot labels and title + ax.set_title(title, fontsize=fontsize) + ax.set_xlabel(xlabel, fontsize=font_size_x_label) + ax.set_ylabel(ylabel, fontsize=font_size_y_label) + + # Customize grid + if show_grid: + ax.grid(True, which='both', linestyle=grid_linestyle, linewidth=grid_linewidth, alpha=grid_alpha) + + # Set tick label font size + ax.tick_params(axis='x', labelsize=font_size_ticks) + ax.tick_params(axis='y', labelsize=font_size_ticks) + + # Show legend if requested + legend_labels.append("Gate Passage") + if show_legend: + ax.legend(legend_labels, fontsize=legend_fontsize, loc=legend_loc) + + # Save the plot + fig.savefig(save_as, bbox_inches="tight") + + + +def plot_speed(timesteps, speed, gate_passes, title, save_path, + animate=False, ax=None, fps=100, width=864, + height=700, dpi=200, gate_lines=False, + gate_labels=False, gate_label_ylevel=12.0, + fontsize=7, pad=0.05, offset_val=0.5, + gate_line_alpha=0.5, alpha=1.0, color='orange'): + """Plot speed over time with optional animation and support for overlapping plots.""" + if ax is None: + fig, ax = plt.subplots(figsize=(width / dpi, height / dpi)) + new_fig = True + else: + new_fig = False + + ax.plot(timesteps, speed, label='Speed', color=color, alpha=alpha) + gate_indices = np.where(gate_passes)[0] + + if gate_lines: + for i, idx in enumerate(gate_indices): + ax.axvline(x=idx, color=color, linestyle='--', label='Gate Passage' if i == 0 else "", alpha=gate_line_alpha) + if gate_labels: + offset = offset_val if i % 2 == 0 else -offset_val + yi = speed[idx] + ax.plot([idx, idx], [yi, gate_label_ylevel+offset], linestyle='dotted', color='gray', linewidth=1) + ax.text(idx, gate_label_ylevel+offset, str(i), fontsize=fontsize, ha='center', va='center', color='black', + bbox=dict(boxstyle=f'circle,pad={pad}', fc=color, alpha=0.5)) + + ax.set_xlabel("Time Step") + ax.set_ylabel("Speed") + ax.set_title(title) + ax.legend() + ax.grid(True) + + if animate and new_fig: + fig.subplots_adjust(bottom=0.2) + vline = ax.axvline(timesteps[0], color='red', linestyle='--', linewidth=2) + + def update(frame): + vline.set_xdata([timesteps[frame]]) + return vline, + + ani = FuncAnimation(fig, update, frames=len(timesteps), interval=1000 / fps, blit=True) + writer = FFMpegWriter(fps=fps) + ani.save(save_path.replace(".png", ".mp4"), writer=writer, dpi=dpi) + plt.close() + elif new_fig: + fig.savefig(save_path, dpi=dpi, bbox_inches='tight') + print(f"Plot saved to {save_path}") + +def plot_angular_speed(timesteps, angular_speed, gate_passes, title, save_path, + animate=False, fig=None, ax=None, fps=100, width=864, height=700, + dpi=200, gate_lines=False, gate_labels=False, + gate_label_ylevel=11.0, fontsize=7, pad=0.05, + offset_val=0.5, gate_line_alpha=0.5, alpha=1.0, color='blue'): + """Plot angular speed over time with optional animation and support for overlapping plots.""" + if ax is None: + fig, ax = plt.subplots(figsize=(width / dpi, height / dpi)) + new_fig = True + else: + new_fig = False + + ax.plot(timesteps, angular_speed, label='Angular Speed', color=color, alpha=alpha) + gate_indices = np.where(gate_passes)[0] + + if gate_lines: + for i, idx in enumerate(gate_indices): + ax.axvline(x=idx, color=color, linestyle='--', label='Gate Passage' if i == 0 else "", alpha=gate_line_alpha) + if gate_labels: + offset = offset_val if i % 2 == 0 else -offset_val + yi = angular_speed[idx] + ax.plot([idx, idx], [yi, gate_label_ylevel+offset], linestyle='dotted', color='gray', linewidth=1) + ax.text(idx, gate_label_ylevel+offset, str(i), fontsize=fontsize, ha='center', va='center', color='black', + bbox=dict(boxstyle=f'circle,pad={pad}', fc=color, alpha=0.5)) + + ax.set_xlabel("Time Step") + ax.set_ylabel("Angular Speed") + ax.set_title(title) + ax.legend() + ax.grid(True) + + if animate and new_fig: + fig.subplots_adjust(bottom=0.2) + vline = ax.axvline(timesteps[0], color='red', linestyle='--', linewidth=2) + + def update(frame): + vline.set_xdata([timesteps[frame]]) + return vline, + + ani = FuncAnimation(fig, update, frames=len(timesteps), interval=1000 / fps, blit=True) + writer = FFMpegWriter(fps=fps) + ani.save(save_path.replace(".png", ".mp4"), writer=writer, dpi=dpi) + plt.close() + elif new_fig: + fig.savefig(save_path, dpi=dpi, bbox_inches='tight') + print(f"Plot saved to {save_path}") + +def plot_actions(timesteps, actions, gate_passes, motor_colors, save_path, animate=False, fps=100, width=864, height=1400, dpi=200): + """Plot motor actions over time with optional animation.""" + nactions = actions.shape[1] + fig, axs = plt.subplots(nactions, 1, figsize=(width / dpi, height / dpi), sharex=True) + + for i in range(nactions): + axs[i].plot(timesteps, actions[:, i], label=f'Motor {i+1}', color=motor_colors[i]) + gate_indices = np.where(gate_passes)[0] + for idx in gate_indices: + axs[i].axvline(x=idx, color='red', linestyle='--', label='Gate Passage' if idx == gate_indices[0] else "", alpha=0.5) + axs[i].set_ylabel(f'Motor {i+1}') + axs[i].set_ylim(-0.1, 1.1) + axs[i].grid(True) + + axs[-1].set_xlabel("Time Step") + fig.suptitle("Motor Actions Over Time with Gate Passages") + fig.tight_layout() + + if animate: + vlines = [axs[i].axvline(timesteps[0], color='red', linestyle='--', linewidth=2) for i in range(nactions)] + + def update(frame): + for vline in vlines: + vline.set_xdata([timesteps[frame]]) + return vlines + + ani = FuncAnimation(fig, update, frames=len(timesteps), interval=1000 / fps, blit=True) + writer = FFMpegWriter(fps=fps) + ani.save(save_path.replace(".png", ".mp4"), writer=writer, dpi=dpi) + plt.close() + else: + fig.savefig(save_path, dpi=dpi, bbox_inches='tight') + print(f"Plot saved to {save_path}") + +# Example usage: +# stats = calculate_stats(ind_gate_times_sec, n_gates) +# plot_speed(ind_timesteps, ind_speed, gps[0], "Individual Speed Over Time", "./plots/speed_individual.png", animate=True) +# plot_angular_speed(ind_timesteps, ind_angular_speed, gps[0], "Individual Angular Speed Over Time", "./plots/angspeed_individual.png", animate=True) +# plot_actions(ind_timesteps, ass[0], gps[0], motor_colors, "./plots/actions_individual.png", animate=True) + +# Example usage + # 1) speed plot with gate lines and labels + # 2) angspeed plot with gate lines and labels + # 3) action plot + # 6) speed plot animated, gate lines no, labels + # 7) angspeed plot animated, gate lines no, labels + # 8) action plot animated +def plot_speed_angspeed_actions(timesteps, speed, angular_speed, actions, gate_passes, save_dir, + motor_colors=['red', 'blue', 'green', 'orange', 'purple', 'brown'], + fps=100, width=864, height=700, dpi=200, gate_lines=False, gate_labels=False, + gate_label_ylevel=11.0, fontsize=7, pad=0.05, offset_val=0.5, gate_line_alpha=0.5, + alpha=1.0, color='blue', animate=False): + """ + Plots speed, angular speed, and motor actions with gate lines and labels. + + Args: + timesteps (np.ndarray): Array of timesteps. + speed (np.ndarray): Array of speed values. + angular_speed (np.ndarray): Array of angular speed values. + actions (np.ndarray): Array of motor actions. + gate_passes (np.ndarray): Array indicating gate passes. + motor_colors (list): List of colors for motor actions. + save_dir (str): Directory to save the plots. + """ + if not os.path.exists(save_dir): + os.makedirs(save_dir) + + # 1) Speed plot with gate lines and labels + plot_speed( + timesteps=timesteps, + speed=speed, + gate_passes=gate_passes, + title="Speed Over Time with Gate Passages", + save_path=os.path.join(save_dir, "speed_plot.png"), + fps=fps, width=width, height=height, dpi=dpi, + gate_lines=gate_lines, gate_labels=gate_labels, + gate_label_ylevel=gate_label_ylevel, fontsize=fontsize, pad=pad, + offset_val=offset_val, gate_line_alpha=gate_line_alpha, alpha=alpha, + color=color, animate=animate + ) + + # 2) Angular speed plot with gate lines and labels + plot_angular_speed( + timesteps=timesteps, + angular_speed=angular_speed, + gate_passes=gate_passes, + title="Angular Speed Over Time with Gate Passages", + save_path=os.path.join(save_dir, "angular_speed_plot.png"), + fps=fps, width=width, height=height, dpi=dpi, + gate_lines=gate_lines, gate_labels=gate_labels, + gate_label_ylevel=gate_label_ylevel, fontsize=fontsize, pad=pad, + offset_val=offset_val, gate_line_alpha=gate_line_alpha, alpha=alpha, + color=color, animate=animate + ) + + # 3) Action plot + plot_actions( + timesteps=timesteps, + actions=actions, + gate_passes=gate_passes, + motor_colors=motor_colors, + save_path=os.path.join(save_dir, "actions_plot.png"), + fps=fps, width=width, height=height*2, dpi=dpi, animate=animate + ) + + # 4) speed plot compared to hexacopter + # 5) angspeed compared to hexacopter +def plot_comparison( + ind1_timesteps, ind1_data, ind1_gate_passes, + ind2_timesteps, ind2_data, ind2_gate_passes, + plot_function, + save_dir, filename, + gate_lines=False, gate_labels=False, + title="Comparison Between Two Individuals", legend_labels=["Individual 1", "Individual 2"], + ind1_color="orange", ind1_alpha=1.0, ind1_gate_line_alpha=0.5, ind1_gate_label_ylevel=12.0, + ind2_color="green", ind2_alpha=1.0, ind2_gate_line_alpha=0.5, ind2_gate_label_ylevel=0.0, + width=864, height=700, dpi=200 +): + """ + Plots a comparison between two individuals using the specified plot function. + + Args: + ind1_timesteps: Timesteps for individual 1. + ind1_data: Data for individual 1 (e.g., speed or angular speed). + ind1_gate_passes: Gate passes for individual 1. + ind2_timesteps: Timesteps for individual 2. + ind2_data: Data for individual 2 (e.g., speed or angular speed). + ind2_gate_passes: Gate passes for individual 2. + plot_function: Function to use for plotting (e.g., plot_speed or plot_angular_speed). + title: Title of the plot. + save_dir: Directory to save the plot. + filename: Filename for the saved plot. + ind1_color: Color for individual 1 (default: "orange"). + ind1_alpha: Alpha for individual 1 (default: 1.0). + ind1_gate_line_alpha: Gate line alpha for individual 1 (default: 0.5). + ind1_gate_label_ylevel: Gate label y-level for individual 1 (default: 12.0). + ind2_color: Color for individual 2 (default: "green"). + ind2_alpha: Alpha for individual 2 (default: 1.0). + ind2_gate_line_alpha: Gate line alpha for individual 2 (default: 0.5). + ind2_gate_label_ylevel: Gate label y-level for individual 2 (default: 0.0). + width: Width of the plot (default: 864). + height: Height of the plot (default: 700). + dpi: DPI for the plot (default: 200). + """ + fig, ax = plt.subplots(figsize=(width / dpi, height / dpi)) + plot_function( + ind1_timesteps, ind1_data, ind1_gate_passes, + title, save_path=None, ax=ax, color=ind1_color, alpha=ind1_alpha, gate_lines=gate_lines, gate_labels=gate_labels, + gate_line_alpha=ind1_gate_line_alpha, gate_label_ylevel=ind1_gate_label_ylevel + ) + plot_function( + ind2_timesteps, ind2_data, ind2_gate_passes, + title, save_path=None, ax=ax, color=ind2_color, alpha=ind2_alpha, gate_lines=gate_lines, gate_labels=gate_labels, + gate_line_alpha=ind2_gate_line_alpha, gate_label_ylevel=ind2_gate_label_ylevel + ) + ax.legend(legend_labels) + fig.savefig(os.path.join(save_dir, filename), dpi=dpi, bbox_inches='tight') + print(f"Plot saved to {os.path.join(save_dir, filename)}") + + + +if __name__ == "__main__": + + # Define directories and configurations + save_dir = "./plots/example_comparison/" + if not os.path.exists(save_dir): + os.makedirs(save_dir) + + # Load data for two individuals + individual1_dir = "/home/jed/workspaces/airevolve/data_backup/asym_slalom/asym_slalom4evo_logs_20250320_095329/gen40/ind964/" + individual2_dir = "/home/jed/workspaces/airevolve/logs/hex_slalom/rep1/" + ind1_policy_file = individual1_dir + "/policy.zip" + ind2_policy_file = individual2_dir + "/policy.zip" + individual1_body = individual1_dir + "/individual.npy" + individual2_body = individual2_dir + "/individual.npy" + individual1 = np.load(individual1_body) + # individual2 = np.load(individual2_body) + individual2 = np.array([[0.24, np.pi/3, 0.0, 0.0, 0.0, 1.0], + [0.24, 2*np.pi/3, 0.0, 0.0, 0.0, 0.0], + [0.24, np.pi, 0.0, 0.0, 0.0, 1.0], + [0.24, 4*np.pi/3, 0.0, 0.0, 0.0, 0.0], + [0.24, 5*np.pi/3, 0.0, 0.0, 0.0, 1.0], + [0.24, 0.0, 0.0, 0.0, 0.0, 0.0]]) + + gate_cfg = "slalom" + device = "cuda:0" if torch.cuda.is_available() else "cpu" + + # Extract simulation data for both individuals + ind1_data = extract_simulation_data(individual1, ind1_policy_file, gate_cfg, device) + ind2_data = extract_simulation_data(individual2, ind2_policy_file, gate_cfg, device) + + # Access extracted data + ind1_speed = np.linalg.norm(ind1_data["velocities"], axis=1) + ind1_angular_speed = np.linalg.norm(ind1_data["angular_velocities"], axis=1) + ind1_timesteps = np.arange(len(ind1_speed)) + ind1_gate_passes = ind1_data["gate_passes"] + ind1_actions = ind1_data["actions"] + + ind2_speed = np.linalg.norm(ind2_data["velocities"], axis=1) + ind2_angular_speed = np.linalg.norm(ind2_data["angular_velocities"], axis=1) + ind2_timesteps = np.arange(len(ind2_speed)) + ind2_gate_passes = ind2_data["gate_passes"] + + fps, width, height, dpi = 100, 864, 700, 200 + gate_label_ylevel = 11.0 + fontsize = 7 + pad = 0.05 + offset_val = 0.5 + gate_line_alpha = 0.5 + alpha = 1.0 + motor_colors = ['red', 'blue', 'green', 'orange', 'purple', 'brown'] + color = 'blue' + # Plot speed, angular speed, and actions for individual 1 + plot_speed_angspeed_actions(ind1_timesteps, ind1_speed, ind1_angular_speed, ind1_actions, ind1_gate_passes, save_dir=save_dir, + fps=fps, width=width, height=height, dpi=dpi, gate_lines=True, gate_labels=True, + gate_label_ylevel=gate_label_ylevel, fontsize=fontsize, pad=pad, offset_val=offset_val, gate_line_alpha=gate_line_alpha, + alpha=alpha, color=color, animate=False) + # Plot speed comparison + plot_comparison( + ind1_timesteps, ind1_speed, ind1_gate_passes, + ind2_timesteps, ind2_speed, ind2_gate_passes, + plot_speed, save_dir, "speed_comparison.png", + "Speed Comparison Between Two Individuals" + ) + + # Example usage for angular speed comparison + plot_comparison( + ind1_timesteps, ind1_angular_speed, ind1_gate_passes, + ind2_timesteps, ind2_angular_speed, ind2_gate_passes, + plot_angular_speed, save_dir, "angular_speed_comparison.png", + "Angular Speed Comparison Between Two Individuals" + ) + + plot_speed_angspeed_actions(ind1_timesteps, ind1_speed, ind1_angular_speed, ind1_actions, ind1_gate_passes, save_dir=save_dir, + fps=fps, width=width, height=height, dpi=dpi, gate_lines=True, gate_labels=False, + gate_label_ylevel=gate_label_ylevel, fontsize=fontsize, pad=pad, offset_val=offset_val, gate_line_alpha=gate_line_alpha, + alpha=alpha, color=color, animate=True) \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/cppn_visualizer.py b/src/ariel/ec/drone/inspection/cppn_visualizer.py new file mode 100644 index 000000000..bb716254e --- /dev/null +++ b/src/ariel/ec/drone/inspection/cppn_visualizer.py @@ -0,0 +1,393 @@ +"""Visualization of CPPN network graphs. + +Follows the DroneVisualizer / VisualizationConfig pattern from drone_visualizer.py. +Renders the CPPN as a layered directed graph with node-type coloring, weight-scaled +connections, and optional activation/weight/bias labels. +""" + +from __future__ import annotations + +import copy +from collections import defaultdict, deque +from dataclasses import dataclass, field +from typing import Any, Dict, List, Optional, Tuple + +import matplotlib.patches as mpatches +import matplotlib.pyplot as plt +from matplotlib.patches import FancyArrowPatch + +from ariel.ec.drone.genome_handlers.cppn.network import ( + CPPNNetwork, + NodeType, +) +from ariel.ec.drone.genome_handlers.cppn.evaluation import topological_sort + + +# Short display names for activation functions +_ACTIVATION_SHORT = { + "identity": "id", + "sigmoid": "sig", + "tanh": "tanh", + "sin": "sin", + "cos": "cos", + "gaussian": "gauss", + "abs": "abs", + "relu": "relu", + "step": "step", +} + + +@dataclass +class CPPNVisualizationConfig: + """Configuration for CPPN network graph visualization.""" + + # Node colors by type + input_node_color: str = "#66bb6a" # green + hidden_node_color: str = "#ffa726" # orange + output_node_color: str = "#42a5f5" # blue + + # Connection colors by weight sign + positive_weight_color: str = "#1565c0" # dark blue + negative_weight_color: str = "#c62828" # dark red + disabled_connection_color: str = "#9e9e9e" # gray + + # Connection line width scaled by |weight| + min_line_width: float = 0.5 + max_line_width: float = 4.0 + + # Disabled connections + disabled_alpha: float = 0.3 + disabled_linestyle: str = "--" + + # Layout params + layer_spacing: float = 2.0 + node_vertical_spacing: float = 1.2 + node_radius: float = 0.35 + + # Label toggles + show_activation_labels: bool = True + show_weight_labels: bool = False + show_bias_values: bool = False + + # Legend + show_legend: bool = True + + # Figure + figsize: Tuple[float, float] = (12, 8) + title_fontsize: int = 14 + label_fontsize: int = 9 + weight_fontsize: int = 7 + + +class CPPNVisualizer: + """Renders a CPPN network as a layered directed graph.""" + + def __init__(self, config: Optional[CPPNVisualizationConfig] = None) -> None: + self.config = config if config is not None else CPPNVisualizationConfig() + + # ------------------------------------------------------------------ + # Public API + # ------------------------------------------------------------------ + + def plot_network( + self, + network_or_handler: Any, + ax: Optional[plt.Axes] = None, + title: Optional[str] = None, + show_disabled: bool = True, + **kwargs, + ) -> Tuple[plt.Figure, plt.Axes]: + """Plot the CPPN network graph. + + Args: + network_or_handler: A ``CPPNNetwork`` instance, or any object with + a ``.genome`` attribute that is a ``CPPNNetwork`` (duck-typed). + ax: Existing matplotlib axes. Creates a new figure if *None*. + title: Optional title. + show_disabled: Whether to draw disabled connections. + **kwargs: Override any ``CPPNVisualizationConfig`` field. + + Returns: + ``(fig, ax)`` tuple. + """ + network = self._extract_network(network_or_handler) + config = self._apply_config_overrides(**kwargs) + + if ax is None: + fig, ax = plt.subplots(figsize=config.figsize) + else: + fig = ax.figure + + # Compute layout + positions, layers = self._compute_positions(network, config) + + # Draw connections first (behind nodes) + self._draw_connections(ax, network, positions, config, show_disabled) + + # Draw nodes on top + self._draw_nodes(ax, network, positions, config) + + # Legend + if config.show_legend: + self._draw_legend(ax, config) + + # Title + if title: + ax.set_title(title, fontsize=config.title_fontsize) + + ax.set_aspect("equal") + ax.axis("off") + ax.autoscale_view() + fig.tight_layout() + return fig, ax + + # ------------------------------------------------------------------ + # Internals + # ------------------------------------------------------------------ + + @staticmethod + def _extract_network(obj: Any) -> CPPNNetwork: + if isinstance(obj, CPPNNetwork): + return obj + if hasattr(obj, "genome"): + return obj.genome + raise TypeError( + f"Expected CPPNNetwork or an object with a .genome attribute, got {type(obj)}" + ) + + def _apply_config_overrides(self, **kwargs) -> CPPNVisualizationConfig: + config = copy.deepcopy(self.config) + for key, value in kwargs.items(): + if hasattr(config, key): + setattr(config, key, value) + return config + + # ---- layer assignment ---- + + @staticmethod + def _compute_layers(network: CPPNNetwork) -> Dict[int, int]: + """Assign each node to a layer using longest-path depth from inputs.""" + input_ids = {n.node_id for n in network.get_input_nodes()} + output_ids = {n.node_id for n in network.get_output_nodes()} + + # Build adjacency from enabled connections + children: Dict[int, List[int]] = defaultdict(list) + for conn in network.get_enabled_connections(): + children[conn.source_id].append(conn.target_id) + + # BFS / longest-path depth from inputs + depth: Dict[int, int] = {nid: 0 for nid in input_ids} + queue = deque(input_ids) + while queue: + nid = queue.popleft() + for child in children[nid]: + new_depth = depth[nid] + 1 + if child not in depth or new_depth > depth[child]: + depth[child] = new_depth + queue.append(child) + + # Assign any unreachable nodes (isolated hidden/output) a depth + for nid in network.nodes: + if nid not in depth: + depth[nid] = 1 + + # Force output nodes to max(hidden_depths) + 1 + hidden_depths = [ + depth[nid] for nid in depth if nid not in input_ids and nid not in output_ids + ] + output_layer = (max(hidden_depths) + 1) if hidden_depths else 1 + for nid in output_ids: + depth[nid] = output_layer + + # Force input nodes to layer 0 + for nid in input_ids: + depth[nid] = 0 + + return depth + + def _compute_positions( + self, network: CPPNNetwork, config: CPPNVisualizationConfig + ) -> Tuple[Dict[int, Tuple[float, float]], Dict[int, int]]: + """Return ``{node_id: (x, y)}`` and ``{node_id: layer}``.""" + layers = self._compute_layers(network) + + # Group nodes by layer + layer_nodes: Dict[int, List[int]] = defaultdict(list) + for nid, layer in layers.items(): + layer_nodes[layer].append(nid) + + # Sort within each layer + input_nodes = {n.node_id for n in network.get_input_nodes()} + output_nodes = {n.node_id: n.output_index for n in network.get_output_nodes()} + + for layer_idx in layer_nodes: + nids = layer_nodes[layer_idx] + if all(nid in output_nodes for nid in nids): + nids.sort(key=lambda n: output_nodes.get(n, 0)) + else: + nids.sort() + + # Compute positions + positions: Dict[int, Tuple[float, float]] = {} + for layer_idx, nids in layer_nodes.items(): + x = layer_idx * config.layer_spacing + n = len(nids) + y_start = -(n - 1) / 2.0 * config.node_vertical_spacing + for i, nid in enumerate(nids): + positions[nid] = (x, y_start + i * config.node_vertical_spacing) + + return positions, layers + + # ---- drawing helpers ---- + + def _draw_connections( + self, + ax: plt.Axes, + network: CPPNNetwork, + positions: Dict[int, Tuple[float, float]], + config: CPPNVisualizationConfig, + show_disabled: bool, + ) -> None: + # Count parallel edges between the same pair to offset curvature + pair_count: Dict[Tuple[int, int], int] = defaultdict(int) + pair_index: Dict[Tuple[int, int], int] = defaultdict(int) + for conn in network.connections.values(): + pair = (min(conn.source_id, conn.target_id), max(conn.source_id, conn.target_id)) + pair_count[pair] += 1 + + for conn in network.connections.values(): + if not conn.enabled and not show_disabled: + continue + if conn.source_id not in positions or conn.target_id not in positions: + continue + + src = positions[conn.source_id] + dst = positions[conn.target_id] + + # Curvature for parallel edges + pair = (min(conn.source_id, conn.target_id), max(conn.source_id, conn.target_id)) + idx = pair_index[pair] + pair_index[pair] += 1 + total = pair_count[pair] + if total > 1: + rad = 0.15 * (idx - (total - 1) / 2.0) + else: + rad = 0.0 + + # Color and style + if not conn.enabled: + color = config.disabled_connection_color + alpha = config.disabled_alpha + linestyle = config.disabled_linestyle + elif conn.weight >= 0: + color = config.positive_weight_color + alpha = 0.8 + linestyle = "-" + else: + color = config.negative_weight_color + alpha = 0.8 + linestyle = "-" + + # Line width scaled by |weight| + weight_abs = abs(conn.weight) + lw = config.min_line_width + (config.max_line_width - config.min_line_width) * min( + weight_abs / 3.0, 1.0 + ) + + arrow = FancyArrowPatch( + posA=src, + posB=dst, + arrowstyle="-|>", + connectionstyle=f"arc3,rad={rad}", + color=color, + alpha=alpha, + linewidth=lw, + linestyle=linestyle, + mutation_scale=12, + zorder=1, + ) + ax.add_patch(arrow) + + # Weight labels + if config.show_weight_labels and conn.enabled: + mx = (src[0] + dst[0]) / 2.0 + my = (src[1] + dst[1]) / 2.0 + rad * 0.5 + ax.text( + mx, my, f"{conn.weight:.2f}", + fontsize=config.weight_fontsize, + ha="center", va="center", + bbox=dict(boxstyle="round,pad=0.1", fc="white", ec="none", alpha=0.7), + zorder=3, + ) + + def _draw_nodes( + self, + ax: plt.Axes, + network: CPPNNetwork, + positions: Dict[int, Tuple[float, float]], + config: CPPNVisualizationConfig, + ) -> None: + for node in network.nodes.values(): + if node.node_id not in positions: + continue + x, y = positions[node.node_id] + + # Color by type + if node.node_type == NodeType.INPUT: + color = config.input_node_color + elif node.node_type == NodeType.OUTPUT: + color = config.output_node_color + else: + color = config.hidden_node_color + + circle = plt.Circle( + (x, y), config.node_radius, + facecolor=color, edgecolor="black", linewidth=1.2, zorder=4, + ) + ax.add_patch(circle) + + # Label + label = self._node_label(node, config) + ax.text( + x, y, label, + fontsize=config.label_fontsize, + ha="center", va="center", + fontweight="bold", zorder=5, + ) + + # Bias annotation + if config.show_bias_values and node.node_type != NodeType.INPUT: + ax.text( + x, y - config.node_radius - 0.15, + f"b={node.bias:.2f}", + fontsize=config.weight_fontsize, + ha="center", va="top", color="gray", + zorder=5, + ) + + @staticmethod + def _node_label(node, config: CPPNVisualizationConfig) -> str: + if node.node_type == NodeType.INPUT: + return node.input_label or f"in{node.node_id}" + if node.node_type == NodeType.OUTPUT: + # The handler stores output labels in _OUTPUT_LABELS but we don't import it; + # fall back to output_index + return f"out{node.output_index}" if node.output_index is not None else f"o{node.node_id}" + # Hidden: show activation short name + if config.show_activation_labels: + return _ACTIVATION_SHORT.get(node.activation.value, node.activation.value) + return str(node.node_id) + + def _draw_legend(self, ax: plt.Axes, config: CPPNVisualizationConfig) -> None: + handles = [ + mpatches.Patch(facecolor=config.input_node_color, edgecolor="black", label="Input"), + mpatches.Patch(facecolor=config.hidden_node_color, edgecolor="black", label="Hidden"), + mpatches.Patch(facecolor=config.output_node_color, edgecolor="black", label="Output"), + plt.Line2D([0], [0], color=config.positive_weight_color, lw=2, label="+weight"), + plt.Line2D([0], [0], color=config.negative_weight_color, lw=2, label="-weight"), + plt.Line2D( + [0], [0], color=config.disabled_connection_color, + lw=1, linestyle="--", label="Disabled", + ), + ] + ax.legend(handles=handles, loc="upper left", fontsize=config.label_fontsize, framealpha=0.8) diff --git a/src/ariel/ec/drone/inspection/create_subplot.py b/src/ariel/ec/drone/inspection/create_subplot.py new file mode 100644 index 000000000..84d256c88 --- /dev/null +++ b/src/ariel/ec/drone/inspection/create_subplot.py @@ -0,0 +1,223 @@ +""" +Subplot creation utilities for grid-based visualizations. + +This module creates subplot layouts from 2D grids of plotting functions, +providing the foundation for evolutionary population visualizations. + +# TODO: [HIGH] Add comprehensive error handling and input validation +# TODO: [HIGH] Improve function documentation and add type hints +# TODO: [MEDIUM] Refactor create_subplot function - it's overly complex +# TODO: [MEDIUM] Standardize parameter naming and conventions +# TODO: [MEDIUM] Add proper logging for debugging subplot creation issues +# TODO: [LOW] Consider splitting large functions into smaller utilities +# TODO: [LOW] Add more flexible subplot configuration options +""" + +import matplotlib.pyplot as plt +import numpy as np +from typing import Optional, List, Tuple, Callable, Union, Any +import numpy.typing as npt + +def create_subplot( + grid: List[List[Callable]], + axs: Optional[Any] = None, + fig: Optional[plt.Figure] = None, + twod: bool = True, + adjust: bool = True, + figaspect: float = 0.5, + title: Optional[str] = None, + color: str = 'blue' # color parameter appears unused +) -> Tuple[plt.Figure, Any, List, List]: + """ + Create a subplot using a 2D grid of functions. + + Each function in the grid should take a single argument: the axes object to plot on. + + Args: + grid: 2D list of plotting functions + axs: Optional existing axes objects to use + fig: Optional existing figure to use + twod: Whether to create 2D or 3D subplots + adjust: Whether to adjust subplot spacing + figaspect: Aspect ratio for 3D plots + title: Optional title for the entire figure + color: Color parameter (currently unused) + + Returns: + Tuple of (figure, axes, images_list, texts_list) + + Raises: + ValueError: If grid is empty, not rectangular, or contains invalid functions + TypeError: If grid contains non-callable elements + """ + # Input validation + if not grid: + raise ValueError("Grid cannot be empty") + + # Validate grid structure + rows = len(grid) + if rows == 0: + raise ValueError("Grid must have at least one row") + + if not grid[0]: + raise ValueError("Grid rows cannot be empty") + + cols = len(grid[0]) + + # Check that all rows have the same length (rectangular grid) + for i, row in enumerate(grid): + if len(row) != cols: + raise ValueError(f"Grid must be rectangular. Row {i} has {len(row)} columns, expected {cols}") + + # Check that all elements are callable + for j, func in enumerate(row): + if not callable(func): + raise TypeError(f"Grid element at [{i}][{j}] is not callable: {type(func)}") + + # Validate parameters + if figaspect <= 0: + raise ValueError("figaspect must be positive") + + # Get the dimensions of the grid + rows = len(grid) + cols = len(grid[0]) + + # Create figure and axes objects if not provided + # TODO: [MEDIUM] The axes handling logic is overly complex and error-prone + if twod and axs is None: + fig, axs = plt.subplots(rows, cols, figsize=(16,12)) # TODO: [MEDIUM] Make figsize configurable + + # TODO: [HIGH] This axes reshaping logic is confusing and fragile + if type(axs) == np.ndarray: # TODO: [LOW] Use isinstance() instead of type() + if len(axs.shape) == 1: + axs = np.array([axs]) + elif not twod and axs is None: + fig = plt.figure(figsize=plt.figaspect(figaspect)) + + + # Adjust subplot spacing if requested + if adjust and twod: + plt.subplots_adjust(wspace=0, hspace=0) # TODO: [MEDIUM] Make spacing configurable + elif adjust and not twod: + fig.subplots_adjust(wspace=0, hspace=0) + + # TODO: [MEDIUM] These lists are never populated - should either remove or implement + imgs = [] + txts = [] + + # Iterate over the grid and call each plotting function + for i in range(rows): + for j in range(cols): + try: + if twod: + if isinstance(axs, np.ndarray): + if len(axs.shape) == 1: + if j >= len(axs): + raise IndexError(f"Column index {j} out of range for axes array of length {len(axs)}") + grid[i][j](axs[j]) + else: + if i >= axs.shape[0] or j >= axs.shape[1]: + raise IndexError(f"Grid position [{i}][{j}] out of range for axes shape {axs.shape}") + grid[i][j](axs[i, j]) + else: + grid[i][j](axs) # Single axes case + else: + # Create 3D subplot for each grid position + axs = fig.add_subplot(rows, cols, i*cols+j+1, projection='3d') + grid[i][j](axs) + except Exception as e: + print(f"Warning: Failed to execute plotting function at grid position [{i}][{j}]: {e}") + # Continue with next function rather than failing entirely + + # TODO: [MEDIUM] Handle case where title is None more gracefully + fig.suptitle(title) + + # TODO: [HIGH] The imgs and txts lists are always empty - fix or document why + return fig, axs, imgs, txts + +def plot_img( + ax: plt.Axes, + img: npt.NDArray, + fitness: Optional[float] = None, + generation: Optional[int] = None +) -> Tuple[Any, Any]: + """ + Plot an image with optional fitness and generation text overlay. + + Args: + ax: The axes object to plot on + img: The image array to plot + fitness: Optional fitness value to display + generation: Optional generation number to display + + Returns: + Tuple of (image_object, text_object) + + Raises: + ValueError: If img is not a valid image array + TypeError: If ax is not a matplotlib Axes object + """ + # Input validation + if ax is None: + raise TypeError("Axes object cannot be None") + + if img is None: + raise ValueError("Image array cannot be None") + + if not isinstance(img, np.ndarray): + raise TypeError(f"Image must be numpy array, got {type(img)}") + + if img.size == 0: + raise ValueError("Image array cannot be empty") + + # Validate image dimensions (should be 2D or 3D) + if img.ndim not in [2, 3]: + raise ValueError(f"Image must be 2D or 3D array, got {img.ndim}D") + + try: + im = ax.imshow(img, interpolation='nearest', animated=True) + ax.set_xticks([]) + ax.set_yticks([]) + + # Create text overlay with improved logic + txt = None + if generation is not None and fitness is not None: + txt = ax.text(0.5, 0.1, f"Gen: {generation}, f: {fitness:.3f}", + horizontalalignment='center', verticalalignment='center', + transform=ax.transAxes, color='white') + elif generation is not None: + txt = ax.text(0.5, 0.1, f"Gen: {generation}", horizontalalignment='center', + verticalalignment='center', transform=ax.transAxes, color='white') + elif fitness is not None: + txt = ax.text(0.5, 0.1, f"Fitness: {fitness:.3f}", horizontalalignment='center', + verticalalignment='center', transform=ax.transAxes, color='white') + + return im, txt + except Exception as e: + raise RuntimeError(f"Failed to plot image: {e}") from e + +def remove_ticks(ax: plt.Axes) -> Tuple[None, None]: + """ + Remove ticks and spines from an axes object for clean visualization. + + Args: + ax: The axes object to clean up + + Returns: + Tuple of (None, None) for compatibility with other plotting functions + + # TODO: [LOW] Consider if return value is needed - seems like compatibility hack + # TODO: [MEDIUM] Add option to selectively remove only certain spines/ticks + """ + # Remove all spines (borders) + ax.spines['top'].set_visible(False) + ax.spines['right'].set_visible(False) + ax.spines['bottom'].set_visible(False) + ax.spines['left'].set_visible(False) + + # Remove tick marks and labels + ax.set_xticks([]) + ax.set_yticks([]) + + # TODO: [LOW] This return value seems arbitrary - document or remove + return None, None \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/drone_visualizer.py b/src/ariel/ec/drone/inspection/drone_visualizer.py new file mode 100644 index 000000000..6595e82ce --- /dev/null +++ b/src/ariel/ec/drone/inspection/drone_visualizer.py @@ -0,0 +1,877 @@ +""" +Modern, clean interface for drone genome visualization. + +This module provides a high-level, object-oriented interface for visualizing +drone genomes with support for multiple coordinate systems, cylinder visualization, +and clean APIs. +""" + +from __future__ import annotations +from typing import Optional, Union, Dict, Any, Tuple, List +from dataclasses import dataclass +import numpy as np +import numpy.typing as npt +import matplotlib.pyplot as plt +import matplotlib.patches +from mpl_toolkits.mplot3d import Axes3D +from scipy.spatial.transform import Rotation +import gc + +from . import utils as u + +try: + import trimesh + import multiprocessing + TRIMESH_AVAILABLE = True +except ImportError: + TRIMESH_AVAILABLE = False + +from ariel.ec.drone.genome_handlers.conversions.arm_conversions import Cylinder + +# Launch in separate process to avoid blocking +def show_scene(scene_obj): + scene_obj.show(viewer='gl') + +@dataclass +class VisualizationConfig: + """Configuration for drone visualization styling and display options.""" + + # Basic display options + circle_radius: float = 0.0254 # 2-inch propeller radius in meters + scale_factor: float = 1.2 + + # 3D view options + elevation: float = 30 + azimuth: float = 30 + include_motor_orientation: bool = True + + # Axis and labeling options + show_axis: bool = True + show_axis_ticks: bool = True + axis_labels: bool = True + fontsize: int = 10 + + # 2D specific options + show_limits: bool = True + include_motor_orientation_2d: int = 0 # 0=none, 1=arrows, 2=arrows+labels + + # Colors + arm_color: str = 'k' + motor_color: str = 'm' + orientation_color: str = 'r' + limit_circle_color: str = 'black' + cylinder_color: str = 'b' + constraint_min_color: str = 'r' + constraint_max_color: str = 'g' + + # Line styles + arm_linestyle: str = '--' + limit_linestyle: str = ':' + + # Cylinder visualization options + cylinder_alpha: float = 0.6 + cylinder_num_lines: int = 6 + show_constraints: bool = True + constraint_alpha: float = 0.1 + + +class DroneVisualizer: + """ + High-level interface for visualizing drone genomes and cylinder arrangements. + + Supports both Cartesian and polar coordinate genome formats with automatic + detection and conversion. Provides clean APIs for 2D, 3D, blueprint, and + cylinder visualizations. + """ + + def __init__(self, config: Optional[VisualizationConfig] = None): + """ + Initialize the drone visualizer. + + Args: + config: Visualization configuration. Uses defaults if None. + """ + self.config = config if config is not None else VisualizationConfig() + + def plot_3d( + self, + genome_data: Any, + ax: Optional[Axes3D] = None, + title: Optional[str] = None, + fitness: Optional[float] = None, + generation: Optional[int] = None, + **kwargs + ) -> Tuple[plt.Figure, Axes3D]: + """ + Create a 3D visualization of a drone genome. + + Args: + genome_data: Genome handler object or numpy array + ax: Existing 3D axes to plot on. Creates new if None. + title: Custom title for the plot + fitness: Fitness value to display in title + generation: Generation number to display in title + **kwargs: Additional config overrides + + Returns: + Tuple of (figure, axes) + """ + # Extract standardized data + data = u.auto_extract_genome_data(genome_data) + + # Create figure/axes if needed + if ax is None: + fig = plt.figure(figsize=(8, 6)) + ax = fig.add_subplot(111, projection='3d') + else: + fig = ax.figure + + # Apply config overrides + config = self._apply_config_overrides(**kwargs) + + # Plot each motor/arm + for i, (pos, orient, direction) in enumerate(zip( + data['positions'], + data['orientations'], + data['directions'] + )): + x, y, z = pos + + # Draw arm to origin + ax.plot([0, x], [0, y], [0, z], + color=config.arm_color, + linestyle=config.arm_linestyle) + + # Draw motor orientation if enabled + if config.include_motor_orientation: + self._draw_motor_orientation_3d(ax, pos, orient, config) + + # Draw propeller circle and direction + self._draw_propeller_3d(ax, pos, orient, direction, config) + + # Set up axes and limits + self._setup_3d_axes(ax, data['positions'], config) + + # Set title + self._set_title(ax, title, fitness, generation, config) + + # Set view angle + ax.view_init(elev=config.elevation, azim=config.azimuth) + + return fig, ax + + def plot_2d( + self, + genome_data: Any, + ax: Optional[plt.Axes] = None, + title: Optional[str] = None, + fitness: Optional[float] = None, + generation: Optional[int] = None, + xlim: Optional[Tuple[float, float]] = None, + ylim: Optional[Tuple[float, float]] = None, + **kwargs + ) -> Tuple[plt.Figure, plt.Axes]: + """ + Create a 2D top-down visualization of a drone genome. + + Args: + genome_data: Genome handler object or numpy array + ax: Existing 2D axes to plot on. Creates new if None. + title: Custom title for the plot + fitness: Fitness value to display in title + generation: Generation number to display in title + xlim: X-axis limits (auto-computed if None) + ylim: Y-axis limits (auto-computed if None) + **kwargs: Additional config overrides + + Returns: + Tuple of (figure, axes) + """ + # Extract standardized data + data = u.auto_extract_genome_data(genome_data) + + # Create figure/axes if needed + if ax is None: + fig, ax = plt.subplots(figsize=(8, 8)) + else: + fig = ax.figure + + # Apply config overrides + config = self._apply_config_overrides(**kwargs) + + # Plot each motor/arm + for i, (pos, orient, direction) in enumerate(zip( + data['positions'], + data['orientations'], + data['directions'] + )): + x, y, z = pos + + # Draw arm to origin (2D projection) + ax.plot([0, x], [0, y], + color=config.arm_color, + linestyle=config.arm_linestyle) + + # Draw motor circle + circle = plt.Circle((x, y), config.circle_radius, + edgecolor=config.motor_color, + facecolor='none') + ax.add_patch(circle) + + # Draw propeller direction arrow + self._draw_propeller_direction_2d(ax, (x, y), direction, config) + + # Draw motor orientation if enabled + if config.include_motor_orientation_2d > 0: + self._draw_motor_orientation_2d(ax, pos, orient, config) + + # Draw limit circles if enabled + if config.show_limits: + self._draw_limit_circles(ax, config) + + # Set up axes and limits + self._setup_2d_axes(ax, data['positions'], xlim, ylim, config) + + # Set title + self._set_title(ax, title, fitness, generation, config) + + return fig, ax + + def plot_blueprint( + self, + genome_data: Any, + title: Optional[str] = None, + figsize: Tuple[float, float] = (12, 12), + **kwargs + ) -> Tuple[plt.Figure, List[Axes3D]]: + """ + Create a blueprint-style visualization with 4 different views. + + Args: + genome_data: Genome handler object or numpy array + title: Title for the entire figure + figsize: Figure size + **kwargs: Additional config overrides + + Returns: + Tuple of (figure, list of axes) + """ + # Define views: (elevation, azimuth, label) + views = [ + (0, 90, "Front View"), # Front + (0, 0, "Side View"), # Side + (90, 0, "Top View"), # Top + (30, 45, "Isometric") # Isometric + ] + + fig = plt.figure(figsize=figsize) + fig.subplots_adjust(wspace=0.1, hspace=0.1) + + axes = [] + for i, (elev, azim, view_label) in enumerate(views): + ax = fig.add_subplot(2, 2, i+1, projection='3d') + + # Plot with specific view angle + config_override = {**kwargs, 'elevation': elev, 'azimuth': azim} + self.plot_3d(genome_data, ax=ax, title=view_label, **config_override) + + axes.append(ax) + + if title: + fig.suptitle(title, fontsize=16) + + return fig, axes + + + def plot_cylinders_3d( + self, + cylinders: List[Cylinder], + ax: Optional[Axes3D] = None, + title: Optional[str] = None, + d_min: Optional[float] = None, + d_max: Optional[float] = None, + color_map: Optional[str] = 'jet', + **kwargs + ) -> Tuple[plt.Figure, Axes3D]: + """ + Create a 3D visualization of cylinder arrangements. + + Args: + cylinders: List of Cylinder objects to visualize + ax: Existing 3D axes to plot on. Creates new if None. + title: Custom title for the plot + d_min: Minimum distance constraint (for visualization) + d_max: Maximum distance constraint (for visualization) + color_map: Colormap name for cylinder colors + **kwargs: Additional config overrides + + Returns: + Tuple of (figure, axes) + """ + # Create figure/axes if needed + if ax is None: + fig = plt.figure(figsize=(10, 8)) + ax = fig.add_subplot(111, projection='3d') + else: + fig = ax.figure + + # Apply config overrides + config = self._apply_config_overrides(**kwargs) + + # Create colormap for cylinders + if len(cylinders) > 1: + colors = plt.cm.get_cmap(color_map)(np.linspace(0, 1, len(cylinders))) + else: + colors = [config.cylinder_color] + + # Draw constraint spheres if provided + if config.show_constraints and (d_min is not None or d_max is not None): + self._draw_constraint_spheres(ax, d_min, d_max, config) + + # Draw cylinders + max_extent = 0 + for i, cylinder in enumerate(cylinders): + color = colors[i] if len(cylinders) > 1 else config.cylinder_color + self._draw_cylinder_3d(ax, cylinder, color, config) + + # Track extent for bounds + p1, p2 = cylinder.get_endpoints() + max_extent = max(max_extent, + np.linalg.norm(p1), + np.linalg.norm(p2)) + + # Set up axes + if d_max is not None: + extent = d_max * 1.1 + else: + extent = max_extent * config.scale_factor + + ax.set_xlim(-extent, extent) + ax.set_ylim(-extent, extent) + ax.set_zlim(-extent, extent) + + if config.axis_labels: + ax.set_xlabel('X') + ax.set_ylabel('Y') + ax.set_zlabel('Z') + + # Add legend for constraints + if config.show_constraints and (d_min is not None or d_max is not None): + self._add_constraint_legend(ax, d_min, d_max) + + # Set title + if title: + ax.set_title(title, fontsize=config.fontsize) + + # Set view angle + ax.view_init(elev=config.elevation, azim=config.azimuth) + + return fig, ax + + def plot_cylinders_trimesh(self, cylinders: List[Cylinder]) -> None: + """ + Visualize cylinders using Trimesh interactive viewer. + + Args: + cylinders: List of Cylinder objects to visualize + + Raises: + ImportError: If trimesh is not available + """ + if not TRIMESH_AVAILABLE: + raise ImportError("Trimesh is required for interactive 3D visualization. " + "Install with: pip install trimesh[easy]") + + cylinder_meshes = [] + + for cyl in cylinders: + # Create cylinder mesh along X-axis (trimesh default) + mesh = trimesh.creation.cylinder( + radius=cyl.radius, + height=cyl.height, + sections=32, + segment=None, + transform=np.eye(4) + ) + + # Apply the cylinder's transformation matrix + mesh.apply_transform(cyl.transform) + cylinder_meshes.append(mesh) + + # Create scene and show + scene = trimesh.Scene(cylinder_meshes) + + p = multiprocessing.Process(target=show_scene, args=(scene,)) + p.start() + + return p # Return process handle in case user wants to manage it + + def _apply_config_overrides(self, **kwargs) -> VisualizationConfig: + """Apply configuration overrides to current config.""" + import copy + config = copy.deepcopy(self.config) + + # Apply overrides + for key, value in kwargs.items(): + if hasattr(config, key): + setattr(config, key, value) + + return config + + def _draw_motor_orientation_3d( + self, + ax: Axes3D, + position: npt.NDArray, + orientation: npt.NDArray, + config: VisualizationConfig + ) -> None: + """Draw motor orientation vector in 3D.""" + x, y, z = position + roll, pitch, yaw = orientation + + # Create rotation matrix using drone's coordinate system + R = u.create_rotation_matrix_euler(roll, pitch, yaw) + + # Create unit z-axis vector and rotate it + z_axis = np.array([0, 0, config.circle_radius * 2]) + rotated_z = R @ z_axis + + # Draw orientation vector + ax.plot([x, x + rotated_z[0]], + [y, y + rotated_z[1]], + [z, z + rotated_z[2]], + color=config.orientation_color) + + def _draw_propeller_3d( + self, + ax: Axes3D, + position: npt.NDArray, + orientation: npt.NDArray, + direction: int, + config: VisualizationConfig + ) -> None: + """Draw propeller circle and direction arrow in 3D.""" + x, y, z = position + roll, pitch, yaw = orientation + + # Create rotation matrix using drone's coordinate system + R = u.create_rotation_matrix_euler(roll, pitch, yaw) + + # Create circle points in local XY plane (perpendicular to motor axis) + num_points = 100 + theta = np.linspace(0, 2 * np.pi, num_points) + circle_local = np.array([ + config.circle_radius * np.cos(theta), + config.circle_radius * np.sin(theta), + np.zeros_like(theta) + ]).T + + # Rotate and translate circle + circle_world = (R @ circle_local.T).T + position + + ax.plot(circle_world[:, 0], circle_world[:, 1], circle_world[:, 2], + color=config.motor_color) + + # Draw direction arrow + if direction == 1: # Clockwise + arrow_start_idx = 75 + arrow_end_idx = 85 + else: # Counter-clockwise + arrow_start_idx = 25 + arrow_end_idx = 15 + + arrow_start = circle_world[arrow_start_idx] + arrow_end = circle_world[arrow_end_idx] + arrow_vec = arrow_end - arrow_start + + ax.quiver(arrow_start[0], arrow_start[1], arrow_start[2], + arrow_vec[0], arrow_vec[1], arrow_vec[2], + color=config.motor_color, arrow_length_ratio=0.3) + + def _draw_propeller_direction_2d( + self, + ax: plt.Axes, + position: Tuple[float, float], + direction: int, + config: VisualizationConfig + ) -> None: + """Draw propeller direction arrow in 2D.""" + x, y = position + + # Create arrow points on circle + if direction == 1: # Clockwise + start_angle = 3 * np.pi / 4 + end_angle = np.pi / 2 + else: # Counter-clockwise + start_angle = np.pi / 4 + end_angle = np.pi / 2 + + arrow_start = np.array([ + x + config.circle_radius * np.cos(start_angle), + y + config.circle_radius * np.sin(start_angle) + ]) + arrow_end = np.array([ + x + config.circle_radius * np.cos(end_angle), + y + config.circle_radius * np.sin(end_angle) + ]) + + # Draw arrow + arrowstyle = matplotlib.patches.ArrowStyle( + "Fancy", head_length=0.4, head_width=0.4, tail_width=0.1 + ) + ax.annotate('', xy=arrow_end, xytext=arrow_start, + arrowprops=dict(facecolor=config.motor_color, + edgecolor=config.motor_color, + arrowstyle=arrowstyle)) + + def _draw_motor_orientation_2d( + self, + ax: plt.Axes, + position: npt.NDArray, + orientation: npt.NDArray, + config: VisualizationConfig + ) -> None: + """Draw motor orientation in 2D.""" + x, y, z = position + roll, pitch, yaw = orientation + + # Project 3D orientation to 2D + scale = config.circle_radius * 1.25 + x_proj = scale * np.sin(pitch) * np.cos(yaw) + y_proj = scale * np.sin(pitch) * np.sin(yaw) + + # Draw orientation vector + ax.quiver(x, y, x_proj, y_proj, + angles='xy', scale_units='xy', scale=1, + color='b') + + # Add angle labels if requested + if config.include_motor_orientation_2d == 2: + label = f"Y:{np.round(np.degrees(yaw),0)}°, P:{np.round(np.degrees(pitch),0)}°" + ax.text(x - config.circle_radius * 1.05, y, label, + fontsize=6, ha='right') + + def _draw_limit_circles(self, ax: plt.Axes, config: VisualizationConfig) -> None: + """Draw constraint limit circles in 2D.""" + # Inner limit circle + inner_circle = plt.Circle((0, 0), 0.09, + linestyle=config.limit_linestyle, + edgecolor=config.limit_circle_color, + facecolor='none') + ax.add_patch(inner_circle) + + # Outer limit circle + outer_circle = plt.Circle((0, 0), 0.4, + linestyle=config.limit_linestyle, + edgecolor=config.limit_circle_color, + facecolor='none') + ax.add_patch(outer_circle) + + def _draw_cylinder_3d( + self, + ax: Axes3D, + cylinder: Cylinder, + color: str, + config: VisualizationConfig + ) -> None: + """Draw a single cylinder in 3D using the correct drone orientation system.""" + # Get cylinder endpoints + p1, p2 = cylinder.get_endpoints() + + # Generate circle points using drone's coordinate system + # The cylinder orientation should match the drone motor orientation + top_circle_points = self._generate_oriented_circle_points( + cylinder.radius, cylinder.orientation, p1 + ) + bottom_circle_points = self._generate_oriented_circle_points( + cylinder.radius, cylinder.orientation, p2 + ) + + # Draw top and bottom circles + ax.plot(top_circle_points[:, 0], top_circle_points[:, 1], + top_circle_points[:, 2], color=color) + ax.plot(bottom_circle_points[:, 0], bottom_circle_points[:, 1], + bottom_circle_points[:, 2], color=color) + + # Draw connecting lines + indices = np.arange(0, len(top_circle_points), + len(top_circle_points) // config.cylinder_num_lines) + for i in indices: + ax.plot([top_circle_points[i, 0], bottom_circle_points[i, 0]], + [top_circle_points[i, 1], bottom_circle_points[i, 1]], + [top_circle_points[i, 2], bottom_circle_points[i, 2]], + color=color) + + def _generate_oriented_circle_points( + self, + radius: float, + orientation: npt.NDArray, + center: npt.NDArray, + num_points: int = 100 + ) -> npt.NDArray: + """Generate circle points with proper orientation matching drone system.""" + # Convert quaternion to rotation matrix if needed + # Quaternion [qx, qy, qz, qw] + R = u.create_rotation_matrix_quaternion(orientation) + + # Create circle points in local XY plane (consistent with drone motors) + theta = np.linspace(0, 2 * np.pi, num_points) + circle_local = np.array([ + radius * np.cos(theta), + radius * np.sin(theta), + np.zeros_like(theta) + ]).T + + # Apply rotation and translation + circle_world = (R @ circle_local.T).T + center + + return circle_world + + def _draw_constraint_spheres( + self, + ax: Axes3D, + d_min: Optional[float], + d_max: Optional[float], + config: VisualizationConfig + ) -> None: + """Draw constraint spheres for distance limits.""" + u = np.linspace(0, 2 * np.pi, 20) + v = np.linspace(0, np.pi, 20) + + if d_min is not None: + x = d_min * np.outer(np.cos(u), np.sin(v)) + y = d_min * np.outer(np.sin(u), np.sin(v)) + z = d_min * np.outer(np.ones(np.size(u)), np.cos(v)) + ax.plot_surface(x, y, z, color=config.constraint_min_color, + alpha=config.constraint_alpha) + + if d_max is not None: + x = d_max * np.outer(np.cos(u), np.sin(v)) + y = d_max * np.outer(np.sin(u), np.sin(v)) + z = d_max * np.outer(np.ones(np.size(u)), np.cos(v)) + ax.plot_surface(x, y, z, color=config.constraint_max_color, + alpha=config.constraint_alpha) + + def _add_constraint_legend( + self, + ax: Axes3D, + d_min: Optional[float], + d_max: Optional[float] + ) -> None: + """Add legend for constraint visualization.""" + from matplotlib.lines import Line2D + + legend_elements = [] + if d_min is not None: + legend_elements.append( + Line2D([0], [0], color=self.config.constraint_min_color, lw=2, + label=f'Min Distance ({d_min:.3f})') + ) + if d_max is not None: + legend_elements.append( + Line2D([0], [0], color=self.config.constraint_max_color, lw=2, + label=f'Max Distance ({d_max:.3f})') + ) + + if legend_elements: + ax.legend(handles=legend_elements, loc='upper right') + + def _setup_3d_axes( + self, + ax: Axes3D, + positions: npt.NDArray, + config: VisualizationConfig + ) -> None: + """Set up 3D axes properties and limits.""" + bounds = u.compute_visualization_bounds(positions, config.scale_factor) + + ax.set_xlim(bounds['xlim']) + ax.set_ylim(bounds['ylim']) + ax.set_zlim(bounds['zlim']) + + if config.axis_labels: + ax.set_xlabel('X') + ax.set_ylabel('Y') + ax.set_zlabel('Z') + + if not config.show_axis: + ax.set_axis_off() + + if not config.show_axis_ticks: + ax.tick_params(labelbottom=False, labeltop=False, + labelleft=False, labelright=False) + + def _setup_2d_axes( + self, + ax: plt.Axes, + positions: npt.NDArray, + xlim: Optional[Tuple[float, float]], + ylim: Optional[Tuple[float, float]], + config: VisualizationConfig + ) -> None: + """Set up 2D axes properties and limits.""" + if xlim is None or ylim is None: + bounds = u.compute_visualization_bounds(positions, config.scale_factor) + xlim = xlim or bounds['xlim'] + ylim = ylim or bounds['ylim'] + + ax.set_xlim(xlim) + ax.set_ylim(ylim) + ax.set_aspect('equal') + ax.grid(True) + + ax.tick_params(labelbottom=config.show_axis_ticks, + labelleft=config.show_axis_ticks) + + def _set_title( + self, + ax: Union[Axes3D, plt.Axes], + title: Optional[str], + fitness: Optional[float], + generation: Optional[int], + config: VisualizationConfig + ) -> None: + """Set plot title with fitness and generation info.""" + if title: + ax.set_title(title, fontsize=config.fontsize) + elif fitness is not None or generation is not None: + title_parts = [] + if generation is not None: + title_parts.append(f'G: {generation}') + if fitness is not None: + title_parts.append(f'F: {np.round(fitness, 2)}') + + if title_parts: + ax.set_title(', '.join(title_parts), fontsize=config.fontsize) + + +# Convenience functions for backward compatibility and ease of use +def visualize_cylinders( + cylinders: List[Cylinder], + title: Optional[str] = None, + d_min: Optional[float] = None, + d_max: Optional[float] = None, + use_trimesh: bool = False, + config: Optional[VisualizationConfig] = None +) -> Union[Tuple[plt.Figure, Axes3D], multiprocessing.Process]: + """ + Convenience function to visualize a single set of cylinders. + + Args: + cylinders: List of Cylinder objects + title: Plot title + d_min: Minimum distance constraint + d_max: Maximum distance constraint + use_trimesh: Whether to use interactive Trimesh viewer + config: Visualization configuration + + Returns: + Either (figure, axes) tuple for matplotlib or Process handle for trimesh + """ + gc.collect() # Clean up memory before visualization + + visualizer = DroneVisualizer(config) + + if use_trimesh: + return visualizer.plot_cylinders_trimesh(cylinders) + else: + return visualizer.plot_cylinders_3d( + cylinders, title=title, d_min=d_min, d_max=d_max + ) + + +def compare_cylinder_arrangements( + arrangements: List[List[Cylinder]], + labels: Optional[List[str]] = None, + d_min: Optional[float] = None, + d_max: Optional[float] = None, + figsize: Tuple[float, float] = (15, 7), + config: Optional[VisualizationConfig] = None +) -> Tuple[plt.Figure, List[Axes3D]]: + """ + Compare multiple cylinder arrangements side by side. + + Args: + arrangements: List of cylinder arrangements to compare + labels: Labels for each arrangement + d_min: Minimum distance constraint + d_max: Maximum distance constraint + figsize: Figure size + config: Visualization configuration + + Returns: + Tuple of (figure, list of axes) + """ + visualizer = DroneVisualizer(config) + + n_arrangements = len(arrangements) + cols = min(n_arrangements, 3) # Max 3 columns + rows = (n_arrangements + cols - 1) // cols # Ceiling division + + fig = plt.figure(figsize=figsize) + fig.subplots_adjust(wspace=0.1, hspace=0.2) + + axes = [] + for i, cylinders in enumerate(arrangements): + ax = fig.add_subplot(rows, cols, i+1, projection='3d') + + # Generate title + if labels and i < len(labels): + title = labels[i] + else: + title = f"Arrangement {i+1}" + + # Plot the arrangement + visualizer.plot_cylinders_3d( + cylinders, ax=ax, title=title, d_min=d_min, d_max=d_max + ) + + axes.append(ax) + + return fig, axes + + +def create_drone_cylinder_combo( + genome_data: Any, + cylinders: List[Cylinder], + title: Optional[str] = None, + d_min: Optional[float] = None, + d_max: Optional[float] = None, + figsize: Tuple[float, float] = (15, 7), + config: Optional[VisualizationConfig] = None +) -> Tuple[plt.Figure, Tuple[Axes3D, Axes3D]]: + """ + Create side-by-side visualization of drone genome and cylinder arrangement. + + Args: + genome_data: Drone genome data + cylinders: List of Cylinder objects + title: Overall figure title + d_min: Minimum distance constraint + d_max: Maximum distance constraint + figsize: Figure size + config: Visualization configuration + + Returns: + Tuple of (figure, (drone_axes, cylinder_axes)) + """ + visualizer = DroneVisualizer(config) + + fig = plt.figure(figsize=figsize) + fig.subplots_adjust(wspace=0.1) + + # Plot drone genome + ax1 = fig.add_subplot(121, projection='3d') + visualizer.plot_3d(genome_data, ax=ax1, title="Drone Configuration") + + # Plot cylinders + ax2 = fig.add_subplot(122, projection='3d') + visualizer.plot_cylinders_3d( + cylinders, ax=ax2, title="Cylinder Arrangement", + d_min=d_min, d_max=d_max + ) + + if title: + fig.suptitle(title, fontsize=16) + + return fig, (ax1, ax2) \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/evolution_analyzer.py b/src/ariel/ec/drone/inspection/evolution_analyzer.py new file mode 100644 index 000000000..9a29fb05e --- /dev/null +++ b/src/ariel/ec/drone/inspection/evolution_analyzer.py @@ -0,0 +1,679 @@ +""" +Main interface for evolutionary analysis and visualization. + +This module provides high-level classes and functions that orchestrate +the various components for comprehensive evolutionary analysis. +""" + +from typing import List, Optional, Tuple, Union, Dict, Any +import numpy as np +import numpy.typing as npt +import matplotlib.pyplot as plt +from pathlib import Path + +from .population_filtering import ( + get_top_k_individuals, + get_generation_fitness_statistics, + flatten_population_across_generations, + filter_by_unique_individuals +) +from .grid_generators import ( + generate_best_individuals_fitness_grid, + calculate_optimal_grid_size +) +from .evolution_plotters import ( + plot_best_individuals_ever, + plot_best_individuals_per_generation, + plot_population, + create_evolution_summary_plot, + save_evolution_plots +) +from .animation_utils import ( + animate_grids, + AnimationBuilder, + get_recommended_settings +) + + +class EvolutionAnalyzer: + """ + Main class for analyzing evolutionary runs and creating visualizations. + + This class provides a high-level interface for all evolutionary analysis + tasks, from basic statistics to complex visualizations and animations. + """ + + def __init__( + self, + population_data: npt.NDArray, + fitness_data: npt.NDArray, + parameter_limits: Optional[npt.NDArray] = None, + generation_labels: Optional[List[str]] = None + ): + """ + Initialize the evolution analyzer. + + Args: + population_data: Array of shape (n_generations, pop_size, n_arms, n_params) + fitness_data: Array of shape (n_generations, pop_size) + parameter_limits: Optional parameter bounds for similarity calculations + generation_labels: Optional labels for generations + """ + self.population_data = np.asarray(population_data) + self.fitness_data = np.asarray(fitness_data) + self.parameter_limits = parameter_limits + self.generation_labels = generation_labels + + # Validate input shapes + if self.population_data.ndim != 4: + raise ValueError("population_data must be 4D: (generations, pop_size, n_arms, n_params)") + if self.fitness_data.ndim != 2: + raise ValueError("fitness_data must be 2D: (generations, pop_size)") + + n_gens_pop, pop_size_pop = self.population_data.shape[:2] + n_gens_fit, pop_size_fit = self.fitness_data.shape + + if n_gens_pop != n_gens_fit or pop_size_pop != pop_size_fit: + raise ValueError("Population and fitness data shapes don't match") + + self.n_generations = n_gens_pop + self.pop_size = pop_size_pop + self.n_arms = self.population_data.shape[2] + self.n_params = self.population_data.shape[3] + + # Cache for computed statistics + self._fitness_stats = None + self._best_individuals = None + self._best_fitnesses = None + + @property + def fitness_statistics(self) -> Dict[str, Any]: + """Get fitness statistics across all generations.""" + if self._fitness_stats is None: + self._fitness_stats = get_generation_fitness_statistics(self.fitness_data) + return self._fitness_stats + + @property + def best_individuals_per_generation(self) -> Tuple[npt.NDArray, npt.NDArray]: + """Get the best individual from each generation.""" + if self._best_individuals is None: + from .population_filtering import select_best_per_generation + self._best_individuals, self._best_fitnesses = select_best_per_generation( + self.population_data, self.fitness_data + ) + return self._best_individuals, self._best_fitnesses + + def get_top_individuals_overall( + self, + k: int = 10, + similarity_threshold: Optional[float] = None + ) -> Tuple[npt.NDArray, npt.NDArray]: + """ + Get the top k individuals across all generations. + + Args: + k: Number of individuals to return + similarity_threshold: If provided, ensure diversity + + Returns: + Tuple of (top_individuals, top_fitnesses) + """ + flat_pop, flat_fit = flatten_population_across_generations( + self.population_data, self.fitness_data, remove_nan=True + ) + + top_individuals, top_fitnesses, _ = get_top_k_individuals( + flat_pop, flat_fit, k, reverse=False, + similarity_threshold=similarity_threshold, + parameter_limits=self.parameter_limits + ) + + return np.array(top_individuals), np.array(top_fitnesses) + + def analyze_diversity(self, generation: Optional[int] = None) -> Dict[str, float]: + """ + Analyze population diversity for a specific generation or overall. + + Args: + generation: Specific generation to analyze (if None, analyzes all) + + Returns: + Dictionary with diversity metrics + """ + if self.parameter_limits is None: + raise ValueError("parameter_limits required for diversity analysis") + + # Import edit distance functions + from ariel.ec.drone.evaluators.edit_distance import compute_edit_distance + + if generation is not None: + # Analyze specific generation + population = self.population_data[generation] + fitness = self.fitness_data[generation] + + # Remove NaN individuals + valid_mask = ~np.isnan(fitness) + population = population[valid_mask] + fitness = fitness[valid_mask] + else: + # Analyze across all generations + population, fitness = flatten_population_across_generations( + self.population_data, self.fitness_data, remove_nan=True + ) + + if len(population) == 0: + return {'mean_distance': 0.0, 'std_distance': 0.0, 'diversity_index': 0.0} + + # Extract min/max values from parameter_limits + # Assuming parameter_limits is (min_vals, max_vals) tuple + if isinstance(self.parameter_limits, tuple) and len(self.parameter_limits) == 2: + min_vals, max_vals = self.parameter_limits + else: + # Fallback: use data bounds + min_vals = np.nanmin(population, axis=(0, 1)) + max_vals = np.nanmax(population, axis=(0, 1)) + + # Calculate pairwise distances + distances = [] + for i in range(len(population)): + for j in range(i + 1, len(population)): + dist = compute_edit_distance(population[i], population[j], min_vals, max_vals) + distances.append(dist) + + distances = np.array(distances) + + return { + 'mean_distance': np.mean(distances), + 'std_distance': np.std(distances), + 'diversity_index': np.mean(distances) / self.n_arms, # Normalized + 'num_individuals': len(population) + } + + def create_summary_report(self) -> Dict[str, Any]: + """ + Create a comprehensive summary report of the evolutionary run. + + Returns: + Dictionary with summary statistics and analysis + """ + # Basic statistics + fitness_stats = self.fitness_statistics + best_inds, best_fits = self.best_individuals_per_generation + + # Overall best + best_overall_idx = np.argmax(best_fits) + best_overall_fitness = best_fits[best_overall_idx] + best_overall_generation = best_overall_idx + + # Convergence analysis + final_gen_mean = fitness_stats['mean'][-1] + initial_gen_mean = fitness_stats['mean'][0] + improvement = final_gen_mean - initial_gen_mean + + # Diversity analysis + try: + initial_diversity = self.analyze_diversity(0) + final_diversity = self.analyze_diversity(-1) + overall_diversity = self.analyze_diversity() + except (ValueError, ImportError): + initial_diversity = final_diversity = overall_diversity = {} + + report = { + 'run_statistics': { + 'n_generations': self.n_generations, + 'population_size': self.pop_size, + 'n_arms': self.n_arms, + 'n_parameters': self.n_params + }, + 'fitness_summary': { + 'best_overall': float(best_overall_fitness), + 'best_generation': int(best_overall_generation), + 'final_mean': float(final_gen_mean), + 'initial_mean': float(initial_gen_mean), + 'improvement': float(improvement), + 'final_max': float(fitness_stats['max'][-1]), + 'final_min': float(fitness_stats['min'][-1]), + 'final_std': float(fitness_stats['std'][-1]) + }, + 'diversity_analysis': { + 'initial': initial_diversity, + 'final': final_diversity, + 'overall': overall_diversity + }, + 'convergence_metrics': { + 'fitness_range_final': float(fitness_stats['max'][-1] - fitness_stats['min'][-1]), + 'fitness_range_initial': float(fitness_stats['max'][0] - fitness_stats['min'][0]), + 'generations_to_best': int(best_overall_generation), + 'improvement_rate': float(improvement / self.n_generations) + } + } + + return report + + def plot_fitness_evolution( + self, + figsize: Tuple[float, float] = (12, 8), + show_stats: bool = True + ) -> plt.Figure: + """ + Create a comprehensive fitness evolution plot. + + Args: + figsize: Figure size + show_stats: Whether to show statistical bands + + Returns: + matplotlib Figure + """ + fig, ax = plt.subplots(figsize=figsize) + + stats = self.fitness_statistics + generations = np.arange(self.n_generations) + + # Plot mean fitness + ax.plot(generations, stats['mean'], label='Mean', linewidth=2, color='blue') + + if show_stats: + # Add standard deviation bands + ax.fill_between( + generations, + stats['mean'] - stats['std'], + stats['mean'] + stats['std'], + alpha=0.3, color='blue', label='±1 Std' + ) + + # Plot max and min + ax.plot(generations, stats['max'], label='Best', linestyle='--', color='green') + ax.plot(generations, stats['min'], label='Worst', linestyle='--', color='red') + + # Highlight best overall + best_inds, best_fits = self.best_individuals_per_generation + best_gen = np.argmax(best_fits) + ax.scatter([best_gen], [best_fits[best_gen]], + color='gold', s=100, zorder=5, label='Best Overall') + + ax.set_xlabel('Generation') + ax.set_ylabel('Fitness') + ax.set_title('Fitness Evolution Over Generations') + ax.legend() + ax.grid(True, alpha=0.3) + + return fig + + def create_animation( + self, + animation_type: str = 'best_with_fitness', + output_path: Optional[str] = None, + **kwargs + ) -> 'animation.ArtistAnimation': + """ + Create an animation of the evolutionary process. + + Args: + animation_type: Type of animation ('best_with_fitness', 'top_individuals', 'population') + output_path: Path to save animation + **kwargs: Additional arguments for animation creation + + Returns: + matplotlib ArtistAnimation object + """ + if animation_type == 'best_with_fitness': + grids = generate_best_individuals_fitness_grid( + list(self.population_data), + list(self.fitness_data), + **kwargs + ) + elif animation_type == 'top_individuals': + # Create grids showing top individuals from each generation + grids = [] + for gen in range(self.n_generations): + pop = self.population_data[gen] + fit = self.fitness_data[gen] + + # Get top individuals + top_inds, top_fits, _ = get_top_k_individuals(pop, fit, 9) + + # Create grid (this would need to be implemented) + grid = self._create_simple_grid(top_inds, top_fits, (3, 3), **kwargs) + grids.append(grid) + else: + raise ValueError(f"Unknown animation type: {animation_type}") + + # Get recommended settings + settings = get_recommended_settings(len(grids)) + settings.update(kwargs) + + return animate_grids(grids, output_path=output_path, **settings) + + def _create_simple_grid(self, individuals, fitnesses, grid_size, twod=True, **kwargs): + """Helper method to create a simple visualization grid.""" + import functools + from ariel.ec.drone.inspection.drone_visualizer import DroneVisualizer + + visualizer = DroneVisualizer() + rows, cols = grid_size + grid = [] + + for i, (ind, fit) in enumerate(zip(individuals, fitnesses)): + if i >= rows * cols: + break + + if twod: + viz_func = functools.partial( + visualizer.plot_2d, + genome_data=ind, + title=f"Fitness: {np.round(fit, 2)}", + **kwargs + ) + else: + viz_func = functools.partial( + visualizer.plot_3d, + genome_data=ind, + title=f"Fitness: {np.round(fit, 2)}", + **kwargs + ) + + grid.append(viz_func) + + # Fill remaining slots + while len(grid) < rows * cols: + from ariel.ec.drone.inspection.create_subplot import remove_ticks + grid.append(remove_ticks) + + return np.array(grid).reshape(grid_size) + + def save_all_plots( + self, + output_dir: Union[str, Path], + prefix: str = "evolution", + formats: List[str] = ['png', 'pdf'] + ) -> List[str]: + """ + Save all standard plots for this evolutionary run. + + Args: + output_dir: Directory to save plots + prefix: Prefix for filenames + formats: List of file formats + + Returns: + List of saved file paths + """ + return save_evolution_plots( + self.population_data, + self.fitness_data, + str(output_dir), + prefix, + formats + ) + + def export_data(self, output_path: Union[str, Path]) -> None: + """ + Export evolution data to a file. + + Args: + output_path: Path to save data file + """ + import pickle + + data = { + 'population_data': self.population_data, + 'fitness_data': self.fitness_data, + 'parameter_limits': self.parameter_limits, + 'generation_labels': self.generation_labels, + 'summary_report': self.create_summary_report() + } + + with open(output_path, 'wb') as f: + pickle.dump(data, f) + + @classmethod + def load_from_file(cls, file_path: Union[str, Path]) -> 'EvolutionAnalyzer': + """ + Load evolution data from a file. + + Args: + file_path: Path to data file + + Returns: + EvolutionAnalyzer instance + """ + import pickle + + with open(file_path, 'rb') as f: + data = pickle.load(f) + + return cls( + population_data=data['population_data'], + fitness_data=data['fitness_data'], + parameter_limits=data.get('parameter_limits'), + generation_labels=data.get('generation_labels') + ) + + +class MultiRunAnalyzer: + """ + Analyzer for comparing multiple evolutionary runs. + """ + + def __init__(self, analyzers: List[EvolutionAnalyzer], labels: List[str]): + """ + Initialize multi-run analyzer. + + Args: + analyzers: List of EvolutionAnalyzer instances + labels: Labels for each run + """ + if len(analyzers) != len(labels): + raise ValueError("Number of analyzers must match number of labels") + + self.analyzers = analyzers + self.labels = labels + self.n_runs = len(analyzers) + + def compare_fitness_evolution(self, figsize: Tuple[float, float] = (14, 8)) -> plt.Figure: + """ + Create a comparison plot of fitness evolution across runs. + + Args: + figsize: Figure size + + Returns: + matplotlib Figure + """ + fig, (ax1, ax2) = plt.subplots(1, 2, figsize=figsize) + + # Plot 1: Mean fitness evolution + for analyzer, label in zip(self.analyzers, self.labels): + stats = analyzer.fitness_statistics + generations = np.arange(analyzer.n_generations) + ax1.plot(generations, stats['mean'], label=label, linewidth=2) + + ax1.set_xlabel('Generation') + ax1.set_ylabel('Mean Fitness') + ax1.set_title('Mean Fitness Evolution Comparison') + ax1.legend() + ax1.grid(True, alpha=0.3) + + # Plot 2: Best fitness evolution + for analyzer, label in zip(self.analyzers, self.labels): + stats = analyzer.fitness_statistics + generations = np.arange(analyzer.n_generations) + ax2.plot(generations, stats['max'], label=label, linewidth=2) + + ax2.set_xlabel('Generation') + ax2.set_ylabel('Best Fitness') + ax2.set_title('Best Fitness Evolution Comparison') + ax2.legend() + ax2.grid(True, alpha=0.3) + + plt.tight_layout() + return fig + + def create_comparison_summary(self) -> Dict[str, Any]: + """ + Create a summary comparing all runs. + + Returns: + Dictionary with comparison statistics + """ + summaries = [analyzer.create_summary_report() for analyzer in self.analyzers] + + comparison = { + 'run_labels': self.labels, + 'best_fitness_per_run': [s['fitness_summary']['best_overall'] for s in summaries], + 'final_mean_per_run': [s['fitness_summary']['final_mean'] for s in summaries], + 'improvement_per_run': [s['fitness_summary']['improvement'] for s in summaries], + 'generations_to_best_per_run': [s['fitness_summary']['generations_to_best'] for s in summaries] + } + + # Overall statistics + best_fitnesses = comparison['best_fitness_per_run'] + comparison['overall_best_run'] = self.labels[np.argmax(best_fitnesses)] + comparison['overall_best_fitness'] = np.max(best_fitnesses) + comparison['mean_best_fitness'] = np.mean(best_fitnesses) + comparison['std_best_fitness'] = np.std(best_fitnesses) + + return comparison + + def plot_comparison_grid(self, **kwargs) -> plt.Figure: + """ + Create a grid comparing best individuals from each run. + + Returns: + matplotlib Figure + """ + from evolution_plotters import plot_evolution_comparison + + population_lists = [list(analyzer.population_data) for analyzer in self.analyzers] + fitness_lists = [list(analyzer.fitness_data) for analyzer in self.analyzers] + + fig, axs = plot_evolution_comparison( + population_lists, fitness_lists, self.labels, **kwargs + ) + + return fig + + +# Convenience functions for quick analysis +def quick_analysis( + population_data: npt.NDArray, + fitness_data: npt.NDArray, + output_dir: Optional[Union[str, Path]] = None, + create_animation: bool = False +) -> EvolutionAnalyzer: + """ + Perform a quick analysis of evolutionary data with standard outputs. + + Args: + population_data: Population evolution data + fitness_data: Fitness evolution data + output_dir: Directory to save outputs (if None, just returns analyzer) + create_animation: Whether to create an animation + + Returns: + EvolutionAnalyzer instance + """ + analyzer = EvolutionAnalyzer(population_data, fitness_data) + + if output_dir is not None: + output_path = Path(output_dir) + output_path.mkdir(exist_ok=True) + + # Save summary report + report = analyzer.create_summary_report() + import json + with open(output_path / "summary_report.json", 'w') as f: + json.dump(report, f, indent=2) + + # Save plots + analyzer.save_all_plots(output_path) + + # Save fitness evolution plot + fig = analyzer.plot_fitness_evolution() + fig.savefig(output_path / "fitness_evolution.png", dpi=300, bbox_inches='tight') + plt.close(fig) + + # Create animation if requested + if create_animation: + try: + analyzer.create_animation(output_path=str(output_path / "evolution_animation.gif")) + except Exception as e: + print(f"Animation creation failed: {e}") + + # Export data + analyzer.export_data(output_path / "evolution_data.pkl") + + print(f"Analysis complete. Results saved to {output_path}") + + return analyzer + + +def compare_runs( + analyzers: List[EvolutionAnalyzer], + labels: List[str], + output_dir: Optional[Union[str, Path]] = None +) -> MultiRunAnalyzer: + """ + Compare multiple evolutionary runs. + + Args: + analyzers: List of EvolutionAnalyzer instances + labels: Labels for each run + output_dir: Directory to save comparison outputs + + Returns: + MultiRunAnalyzer instance + """ + multi_analyzer = MultiRunAnalyzer(analyzers, labels) + + if output_dir is not None: + output_path = Path(output_dir) + output_path.mkdir(exist_ok=True) + + # Save comparison summary + comparison = multi_analyzer.create_comparison_summary() + import json + with open(output_path / "comparison_summary.json", 'w') as f: + json.dump(comparison, f, indent=2) + + # Save comparison plots + fig1 = multi_analyzer.compare_fitness_evolution() + fig1.savefig(output_path / "fitness_comparison.png", dpi=300, bbox_inches='tight') + plt.close(fig1) + + fig2 = multi_analyzer.plot_comparison_grid() + fig2.savefig(output_path / "morphology_comparison.png", dpi=300, bbox_inches='tight') + plt.close(fig2) + + print(f"Comparison complete. Results saved to {output_path}") + + return multi_analyzer + + +# Example usage +if __name__ == "__main__": + print("=== Evolution Analyzer Example ===") + + # Generate sample data for demonstration + n_gens, pop_size, n_arms, n_params = 50, 20, 4, 6 + + # Simulated evolution with improving fitness + population_data = np.random.rand(n_gens, pop_size, n_arms, n_params) + fitness_data = np.random.rand(n_gens, pop_size) + + # Add fitness improvement trend + for gen in range(n_gens): + fitness_data[gen] += gen * 0.01 # Gradual improvement + + # Quick analysis + analyzer = quick_analysis(population_data, fitness_data) + + # Print summary + report = analyzer.create_summary_report() + print("\nEvolution Summary:") + print(f"Best fitness: {report['fitness_summary']['best_overall']:.3f}") + print(f"Improvement: {report['fitness_summary']['improvement']:.3f}") + print(f"Best found at generation: {report['fitness_summary']['best_generation']}") + + print("\n=== Example Complete ===") \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/evolution_plotters.py b/src/ariel/ec/drone/inspection/evolution_plotters.py new file mode 100644 index 000000000..d7d8868fb --- /dev/null +++ b/src/ariel/ec/drone/inspection/evolution_plotters.py @@ -0,0 +1,532 @@ +""" +High-level plotting functions for evolutionary visualization. + +This module provides the main plotting interfaces for visualizing evolutionary +populations, combining grid generation with subplot creation and display. +""" + +from typing import List, Tuple, Optional, Union +import numpy as np +import numpy.typing as npt +import matplotlib.pyplot as plt +import functools +from ariel.ec.drone.inspection.drone_visualizer import DroneVisualizer + +from .grid_generators import ( + generate_best_individuals_fitness_grid, + generate_population_grid, + generate_top_individuals_across_generations_grid, + generate_best_per_generation_grid, + generate_best_ever_grid, + generate_comparison_grid +) +from .create_subplot import create_subplot + + +def plot_top_individuals_across_generations( + population_data: List[npt.NDArray], + fitness_data: List[npt.NDArray], + grid_size: Tuple[int, int] = (4, 4), + twod: bool = True, + include_motor_orientation: Union[bool, int] = 0, + worst: bool = False, + title: Optional[str] = None, + show_ticks: bool = True +) -> Tuple[plt.Figure, npt.NDArray, List, List]: + """ + Plot top individuals from selected generations across evolution. + + Args: + population_data: List of population arrays for each generation + fitness_data: List of fitness arrays for each generation + grid_size: Tuple of (rows, cols) for grid layout + twod: If True, use 2D visualization; if False, use 3D + include_motor_orientation: Whether to show motor orientations + worst: If True, show worst individuals instead of best + title: Title for the plot + show_ticks: Whether to show axis ticks and labels + + Returns: + Tuple of (figure, axes, top_individuals_per_generation, selected_generation_indices) + """ + # Generate grid layout + grid = generate_top_individuals_across_generations_grid( + population_data=population_data, + fitness_data=fitness_data, + grid_size=grid_size, + twod=twod, + include_motor_orientation=include_motor_orientation, + worst=worst, + show_ticks=show_ticks + ) + + # Create subplot from grid + fig, axs, img_plots, texts = create_subplot(grid, twod=twod, title=title) + + # Return additional data for analysis + from .population_filtering import get_generation_indices_for_limit, get_top_k_individuals + + num_gens = len(population_data) + gen_indices = get_generation_indices_for_limit(num_gens, grid_size[1]) + + top_individuals_per_gen = [] + for idx in gen_indices: + if worst: + top_inds, top_fits, _ = get_top_k_individuals( + population_data[idx], fitness_data[idx], grid_size[0], reverse=True + ) + else: + top_inds, top_fits, _ = get_top_k_individuals( + population_data[idx], fitness_data[idx], grid_size[0], reverse=False + ) + top_individuals_per_gen.append((top_inds, top_fits)) + + return fig, axs, top_individuals_per_gen, gen_indices + + +def plot_best_individuals_per_generation( + population_data: npt.NDArray, + fitness_data: npt.NDArray, + grid_size: Tuple[int, int] = (4, 4), + twod: bool = True, + include_motor_orientation: Union[bool, int] = 0, + worst: bool = False, + title: Optional[str] = None +) -> Tuple[plt.Figure, npt.NDArray, npt.NDArray, npt.NDArray]: + """ + Plot the best individual from selected generations. + + Args: + population_data: Array of shape (n_generations, pop_size, n_arms, n_params) + fitness_data: Array of shape (n_generations, pop_size) + grid_size: Tuple of (rows, cols) for grid layout + twod: If True, use 2D visualization + include_motor_orientation: Whether to show motor orientations + worst: If True, show worst individuals + title: Title for the plot + + Returns: + Tuple of (figure, axes, best_individuals, best_fitnesses) + """ + # Generate grid layout + grid = generate_best_per_generation_grid( + population_data=population_data, + fitness_data=fitness_data, + grid_size=grid_size, + twod=twod, + include_motor_orientation=include_motor_orientation, + worst=worst, + title=title + ) + + # Create subplot from grid + fig, axs, img_plots, texts = create_subplot(grid, twod=twod, title=title) + + # Get the actual best individuals data + from .population_filtering import select_best_per_generation + best_individuals, best_fitnesses = select_best_per_generation( + population_data, fitness_data, worst=worst + ) + + return fig, axs, best_individuals, best_fitnesses + + +def plot_best_individuals_ever( + population_data: npt.NDArray, + fitness_data: npt.NDArray, + grid_size: Tuple[int, int] = (4, 4), + twod: bool = True, + include_motor_orientation: Union[bool, int] = 0, + worst: bool = False, + title: Optional[str] = None, + similarity_threshold: Optional[float] = None, + round_to: int = 2 +) -> Tuple[plt.Figure, npt.NDArray, npt.NDArray, npt.NDArray]: + """ + Plot the best individuals across all generations. + + Args: + population_data: Array of shape (n_generations, pop_size, n_arms, n_params) + fitness_data: Array of shape (n_generations, pop_size) + grid_size: Tuple of (rows, cols) for grid layout + twod: If True, use 2D visualization + include_motor_orientation: Whether to show motor orientations + worst: If True, show worst individuals + title: Title for the plot + similarity_threshold: If provided, ensure diversity in selection + round_to: Number of decimal places for fitness display + + Returns: + Tuple of (figure, axes, top_individuals, top_fitnesses) + """ + # Generate grid layout + grid, top_individuals, top_fitnesses = generate_best_ever_grid( + population_data=population_data, + fitness_data=fitness_data, + grid_size=grid_size, + twod=twod, + include_motor_orientation=include_motor_orientation, + worst=worst, + title=title, + similarity_threshold=similarity_threshold, + round_to=round_to + ) + + # Create subplot from grid + fig, axs, img_plots, texts = create_subplot(grid, twod=twod, title=title) + + return fig, axs, top_individuals, top_fitnesses + + +def plot_population( + population: npt.NDArray, + fitnesses: Optional[npt.NDArray] = None, + twod: bool = True, + title: Optional[str] = None, + include_motor_orientation: Union[bool, int] = 0, + figsize: Optional[Tuple[float, float]] = None +) -> Tuple[plt.Figure, npt.NDArray]: + """ + Plot an entire population in a grid layout. + + Args: + population: Array of individuals + fitnesses: Optional array of fitness values + twod: If True, use 2D visualization + title: Title for the plot + include_motor_orientation: Whether to show motor orientations + figsize: Optional figure size + + Returns: + Tuple of (figure, axes) + """ + # Generate grid layout + grid = generate_population_grid( + population=population, + fitnesses=fitnesses, + twod=twod, + include_motor_orientation=include_motor_orientation + ) + + # Create subplot from grid + adjust = twod + fig, axs, img_plots, texts = create_subplot(grid, twod=twod, adjust=adjust) + + if title: + fig.suptitle(title) + + if figsize: + fig.set_size_inches(figsize) + + return fig, axs + + +def plot_evolution_comparison( + population_lists: List[List[npt.NDArray]], + fitness_lists: List[List[npt.NDArray]], + labels: List[str], + grid_size: Tuple[int, int] = (2, 4), + twod: bool = True, + include_motor_orientation: Union[bool, int] = 0, + title: Optional[str] = None +) -> Tuple[plt.Figure, npt.NDArray]: + """ + Plot a comparison of best individuals from multiple evolution runs. + + Args: + population_lists: List of population data lists (one per run) + fitness_lists: List of fitness data lists (one per run) + labels: Labels for each evolution run + grid_size: Tuple of (rows, cols) for grid layout + twod: If True, use 2D visualization + include_motor_orientation: Whether to show motor orientations + title: Title for the plot + + Returns: + Tuple of (figure, axes) + """ + # Generate grid layout + grid = generate_comparison_grid( + population_lists=population_lists, + fitness_lists=fitness_lists, + labels=labels, + grid_size=grid_size, + twod=twod, + include_motor_orientation=include_motor_orientation + ) + + # Create subplot from grid + fig, axs, img_plots, texts = create_subplot(grid, twod=twod, title=title) + + return fig, axs + + +def plot_fitness_progression_with_individuals( + population_data: List[npt.NDArray], + fitness_data: List[npt.NDArray], + num_individuals: int = 5, + twod: bool = True, + include_motor_orientation: Union[bool, int] = 0, + title: Optional[str] = None +) -> Tuple[plt.Figure, npt.NDArray]: + """ + Plot fitness progression alongside visualizations of top individuals. + + Args: + population_data: List of population arrays for each generation + fitness_data: List of fitness arrays for each generation + num_individuals: Number of top individuals to show + twod: If True, use 2D visualization + include_motor_orientation: Whether to show motor orientations + title: Title for the plot + + Returns: + Tuple of (figure, axes) + """ + from ariel.ec.drone.inspection.plot_fitness import plot_fitness + import functools + + # Get the overall best individuals + from .population_filtering import flatten_population_across_generations, get_top_k_individuals + + flat_pop, flat_fit = flatten_population_across_generations( + np.array(population_data), np.array(fitness_data), remove_nan=True + ) + + top_individuals, top_fitnesses, _ = get_top_k_individuals( + flat_pop, flat_fit, num_individuals, reverse=False + ) + + # Create a custom grid: fitness plot on left, individuals on right + grid = [] + + # First row: fitness plot spanning multiple cells + fitness_func = functools.partial( + plot_fitness, + population_data=population_data, + fitness_data=fitness_data + ) + + # Create layout: fitness plot + individual visualizations + if num_individuals <= 4: + # Single row layout + grid_layout = [[fitness_func]] + + for i, (individual, fitness) in enumerate(zip(top_individuals, top_fitnesses)): + visualizer = DroneVisualizer() + if twod: + viz_func = functools.partial( + lambda ax, ind=individual, fit=fitness: + visualizer.plot_2d( + genome_data=ind, title=f"Fitness: {np.round(fit, 2)}" + ) + ) + else: + viz_func = functools.partial( + lambda ax, ind=individual, fit=fitness: + visualizer.plot_3d( + genome_data=ind, title=f"Fitness: {np.round(fit, 2)}" + ) + ) + grid_layout[0].append(viz_func) + + grid = grid_layout + else: + # Multi-row layout + grid.append([fitness_func]) + + # Add individuals in subsequent rows + individuals_per_row = min(4, num_individuals) + for i in range(0, num_individuals, individuals_per_row): + row = [] + for j in range(individuals_per_row): + idx = i + j + if idx < len(top_individuals): + individual = top_individuals[idx] + fitness = top_fitnesses[idx] + + visualizer = DroneVisualizer() + if twod: + viz_func = functools.partial( + visualizer.plot_2d, + genome_data=individual, + title=f"Fitness: {np.round(fitness, 2)}" + ) + else: + viz_func = functools.partial( + visualizer.plot_3d, + genome_data=individual, + title=f"Fitness: {np.round(fitness, 2)}" + ) + + row.append(viz_func) + + if row: # Only add non-empty rows + grid.append(row) + + # Create subplot from grid + fig, axs, img_plots, texts = create_subplot(grid, twod=twod, title=title) + + return fig, axs + + +def create_evolution_summary_plot( + population_data: npt.NDArray, + fitness_data: npt.NDArray, + title: Optional[str] = None, + figsize: Tuple[float, float] = (16, 12), + parameter_limits: Optional[Tuple[npt.NDArray, npt.NDArray]] = None +) -> plt.Figure: + """ + Create a comprehensive summary plot of the evolutionary run. + + Args: + population_data: Array of shape (n_generations, pop_size, n_arms, n_params) + fitness_data: Array of shape (n_generations, pop_size) + title: Title for the overall plot + figsize: Figure size + parameter_limits: Optional tuple of (min_vals, max_vals) for diversity calculation + + Returns: + matplotlib Figure object + """ + fig = plt.figure(figsize=figsize) + + # Create a custom layout with multiple subplots + gs = fig.add_gridspec(3, 4, hspace=0.3, wspace=0.3) + + # 1. Fitness progression plot + ax_fitness = fig.add_subplot(gs[0, :2]) + from ariel.ec.drone.inspection.plot_fitness import plot_fitness + plot_fitness(ax_fitness, population_data, fitness_data) + ax_fitness.set_title("Fitness Progression") + + # 2. Diversity plot + ax_diversity = fig.add_subplot(gs[0, 2:]) + from .plot_diversity import plot_diversity_from_amalgamated + + # Convert population data to format expected by diversity function + population_list = [population_data[gen] for gen in range(len(population_data))] + + # Set default parameter limits if not provided + if parameter_limits is None: + min_vals = np.array([0.09, 0, 0, 0, 0, 0]) + max_vals = np.array([0.4, 2*np.pi, 2*np.pi, 2*np.pi, 2*np.pi, 1]) + param_bounds = np.column_stack([min_vals, max_vals]) + else: + min_vals, max_vals = parameter_limits + param_bounds = np.column_stack([min_vals, max_vals]) + + # Plot diversity for single run (wrapped as list for consistency) + plot_diversity_from_amalgamated(ax_diversity, [population_list], + title='Population Diversity', + min_max_params=param_bounds) + + # 3. Top individuals ever + ax_top = fig.add_subplot(gs[1:, :2]) + top_grid, top_inds, top_fits = generate_best_ever_grid( + population_data, fitness_data, grid_size=(3, 2), twod=True + ) + ax_top.set_title("Top Individuals Overall") + ax_top.axis('off') + + # 4. Fitness statistics + ax_stats = fig.add_subplot(gs[1:, 2:]) + from .population_filtering import get_generation_fitness_statistics + stats = get_generation_fitness_statistics(fitness_data) + + generations = np.arange(len(fitness_data)) + ax_stats.plot(generations, stats['mean'], label='Mean', linewidth=2) + ax_stats.fill_between( + generations, + stats['mean'] - stats['std'], + stats['mean'] + stats['std'], + alpha=0.3, label='±1 Std' + ) + ax_stats.plot(generations, stats['max'], label='Max', linestyle='--') + ax_stats.plot(generations, stats['min'], label='Min', linestyle='--') + + ax_stats.set_xlabel("Generation") + ax_stats.set_ylabel("Fitness") + ax_stats.set_title("Fitness Statistics") + ax_stats.legend() + ax_stats.grid(True, alpha=0.3) + + if title: + fig.suptitle(title, fontsize=16, fontweight='bold') + + return fig + + +def save_evolution_plots( + population_data: npt.NDArray, + fitness_data: npt.NDArray, + output_dir: str, + prefix: str = "evolution", + formats: List[str] = ['png', 'pdf'], + dpi: int = 300 +) -> List[str]: + """ + Save multiple evolution visualization plots to files. + + Args: + population_data: Array of shape (n_generations, pop_size, n_arms, n_params) + fitness_data: Array of shape (n_generations, pop_size) + output_dir: Directory to save plots + prefix: Prefix for filenames + formats: List of file formats to save + dpi: Resolution for raster formats + + Returns: + List of saved file paths + """ + import os + os.makedirs(output_dir, exist_ok=True) + + saved_files = [] + + # 1. Best individuals ever + fig1, _, top_inds, top_fits = plot_best_individuals_ever( + population_data, fitness_data, title="Best Individuals Ever" + ) + + for fmt in formats: + filename = f"{prefix}_best_ever.{fmt}" + filepath = os.path.join(output_dir, filename) + fig1.savefig(filepath, dpi=dpi, bbox_inches='tight') + saved_files.append(filepath) + + plt.close(fig1) + + # 2. Best per generation + fig2, _, best_inds, best_fits = plot_best_individuals_per_generation( + population_data, fitness_data, title="Best Per Generation" + ) + + for fmt in formats: + filename = f"{prefix}_best_per_gen.{fmt}" + filepath = os.path.join(output_dir, filename) + fig2.savefig(filepath, dpi=dpi, bbox_inches='tight') + saved_files.append(filepath) + + plt.close(fig2) + + # 3. Evolution summary + fig3 = create_evolution_summary_plot( + population_data, fitness_data, title="Evolution Summary" + ) + + for fmt in formats: + filename = f"{prefix}_summary.{fmt}" + filepath = os.path.join(output_dir, filename) + fig3.savefig(filepath, dpi=dpi, bbox_inches='tight') + saved_files.append(filepath) + + plt.close(fig3) + + return saved_files + + +# Backward compatibility aliases +plot_top_individuals = plot_top_individuals_across_generations +plot_best_individuals = plot_best_individuals_per_generation \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/grid_generators.py b/src/ariel/ec/drone/inspection/grid_generators.py new file mode 100644 index 000000000..eba2485cf --- /dev/null +++ b/src/ariel/ec/drone/inspection/grid_generators.py @@ -0,0 +1,573 @@ +""" +Grid generation utilities for creating visualization layouts. + +This module provides functions for generating different types of grid layouts +for visualizing evolutionary populations, including fitness grids, comparison grids, +and population overview grids. + +# TODO: [MEDIUM] Add comprehensive input validation to all grid generation functions +# TODO: [MEDIUM] Standardize parameter naming across functions (e.g., twod vs use_2d) +# TODO: [LOW] Add more grid layout options (circular, hierarchical, etc.) +# TODO: [LOW] Consider adding caching for expensive grid computations +""" + +import functools +import numpy as np +from typing import List, Callable, Tuple, Optional, Union +import numpy.typing as npt + +from .population_filtering import ( + get_top_k_individuals, + get_generation_indices_for_limit, + select_best_per_generation, + flatten_population_across_generations +) + +# Import visualization components +from ariel.ec.drone.inspection.drone_visualizer import DroneVisualizer +from ariel.ec.drone.inspection.create_subplot import remove_ticks +from ariel.ec.drone.inspection.plot_fitness import plot_fitness + + +def generate_best_individuals_fitness_grid( + population_data: List[npt.NDArray], + fitness_data: List[npt.NDArray], + twod: bool = True, + small_grid: bool = False, + include_motor_orientation: Union[bool, int] = True, + worst: bool = False, + title: Optional[str] = None +) -> List[npt.NDArray]: + """ + Generate grids showing best individuals from each generation with fitness plot. + + Args: + population_data: List of population arrays for each generation + fitness_data: List of fitness arrays for each generation + twod: If True, use 2D visualization; if False, use 3D + small_grid: If True, use 3x3 grid; if False, use 4x4 grid + include_motor_orientation: Whether to show motor orientations + worst: If True, show worst individuals instead of best + title: Title for the grid + + Returns: + List of grid arrays, one for each generation + """ + grids = [] + k = 8 if small_grid else 15 # Number of individuals to show + grid_size = 3 if small_grid else 4 + + for gen, (population, fitness) in enumerate(zip(population_data, fitness_data)): + # Get top individuals for this generation + if worst: + top_individuals, top_fitnesses, _ = get_top_k_individuals( + population, fitness, k, reverse=True + ) + else: + top_individuals, top_fitnesses, _ = get_top_k_individuals( + population, fitness, k, reverse=False + ) + + # Create grid of visualization functions + grid = [] + for i, (individual, fit_score) in enumerate(zip(top_individuals, top_fitnesses)): + # Determine label positioning + labelleft = (i % grid_size == 0) + labelbottom = ((grid_size * (grid_size - 1)) <= i < (grid_size * grid_size)) + + visualizer = DroneVisualizer() + if twod: + viz_func = functools.partial( + visualizer.plot_2d, + genome_data=individual, + title=f"Fitness: {np.round(fit_score, 2)}" + ) + else: + viz_func = functools.partial( + visualizer.plot_3d, + genome_data=individual, + title=f"Fitness: {np.round(fit_score, 2)}" + ) + + grid.append(viz_func) + + # Add fitness plot in the corner + fitness_func = functools.partial( + plot_fitness, + population_data=population_data, + fitness_data=fitness_data, + gen_line=gen + ) + grid.append(fitness_func) + + # Reshape to square grid + grid = np.array(grid).reshape(grid_size, grid_size) + grids.append(grid) + + return grids + + +def generate_population_grid( + population: npt.NDArray, + fitnesses: Optional[npt.NDArray] = None, + twod: bool = True, + include_motor_orientation: Union[bool, int] = 0 +) -> List[List[Callable]]: + """ + Generate a grid layout for visualizing an entire population. + + Args: + population: Array of individuals + fitnesses: Optional array of fitness values + twod: If True, use 2D visualization + include_motor_orientation: Whether to show motor orientations + + Returns: + 2D list of visualization functions arranged in a grid + """ + pop_size = len(population) + + # Calculate grid dimensions + rows = int(np.ceil(np.sqrt(pop_size))) + cols = int(np.ceil(pop_size / rows)) + + grid = [] + for r in range(rows): + row = [] + for c in range(cols): + idx = r * cols + c + + # Determine label positioning + labelleft = (c == 0) + labelbottom = (r == rows - 1) + + if idx < pop_size: + individual = population[idx] + fitness = fitnesses[idx] if fitnesses is not None else None + + visualizer = DroneVisualizer() + fitness_title = f"Fitness: {np.round(fitness, 2)}" if fitness is not None else "No fitness" + if twod: + viz_func = functools.partial( + visualizer.plot_2d, + genome_data=individual, + title=fitness_title + ) + else: + viz_func = functools.partial( + visualizer.plot_3d, + genome_data=individual, + title=fitness_title + ) + row.append(viz_func) + else: + # Empty cell + row.append(remove_ticks) + + grid.append(row) + + return grid + + +def generate_top_individuals_across_generations_grid( + population_data: List[npt.NDArray], + fitness_data: List[npt.NDArray], + grid_size: Tuple[int, int] = (4, 4), + twod: bool = True, + include_motor_orientation: Union[bool, int] = 0, + worst: bool = False, + show_ticks: bool = True +) -> List[List[Callable]]: + """ + Generate a grid showing top individuals across selected generations. + + Args: + population_data: List of population arrays + fitness_data: List of fitness arrays + grid_size: Tuple of (rows, cols) for grid layout + twod: If True, use 2D visualization + include_motor_orientation: Whether to show motor orientations + worst: If True, show worst individuals + show_ticks: Whether to show axis ticks and labels + + Returns: + 2D list of visualization functions + """ + rows, cols = grid_size + num_gens = len(population_data) + + # Get evenly spaced generation indices + gen_indices = get_generation_indices_for_limit(num_gens, cols) + + # Get top individuals from selected generations + top_individuals_per_gen = [] + for idx in gen_indices: + if worst: + top_inds, top_fits, _ = get_top_k_individuals( + population_data[idx], fitness_data[idx], rows, reverse=True + ) + else: + top_inds, top_fits, _ = get_top_k_individuals( + population_data[idx], fitness_data[idx], rows, reverse=False + ) + top_individuals_per_gen.append((top_inds, top_fits)) + + # Create grid + grid = [] + for row in range(rows): + grid_row = [] + for col in range(cols): + if col < len(top_individuals_per_gen): + individuals, fitnesses = top_individuals_per_gen[col] + + if row < len(individuals): + individual = individuals[row] + fitness = fitnesses[row] + generation = gen_indices[col] + + visualizer = DroneVisualizer() + if twod: + viz_func = functools.partial( + visualizer.plot_2d, + genome_data=individual, + title=f"Gen {generation}: {np.round(fitness, 2)}" + ) + else: + viz_func = functools.partial( + visualizer.plot_3d, + genome_data=individual, + title=f"Gen {generation}: {np.round(fitness, 2)}" + ) + + grid_row.append(viz_func) + else: + grid_row.append(remove_ticks) + else: + grid_row.append(remove_ticks) + + grid.append(grid_row) + + return grid + + +def generate_best_per_generation_grid( + population_data: npt.NDArray, + fitness_data: npt.NDArray, + grid_size: Tuple[int, int] = (4, 4), + twod: bool = True, + include_motor_orientation: Union[bool, int] = 0, + worst: bool = False, + title: Optional[str] = None +) -> List[List[Callable]]: + """ + Generate a grid showing the best individual from selected generations. + + Args: + population_data: Array of shape (n_generations, pop_size, n_arms, n_params) + fitness_data: Array of shape (n_generations, pop_size) + grid_size: Tuple of (rows, cols) for grid layout + twod: If True, use 2D visualization + include_motor_orientation: Whether to show motor orientations + worst: If True, show worst individuals + title: Title for the grid + + Returns: + 2D list of visualization functions + """ + rows, cols = grid_size + num_gens = len(population_data) + num_slots = rows * cols + + # Get evenly spaced generation indices + gen_indices = get_generation_indices_for_limit(num_gens, num_slots) + + # Get best individual from each selected generation + best_individuals, best_fitnesses = select_best_per_generation( + population_data, fitness_data, worst=worst + ) + + # Create visualization functions + viz_functions = [] + for i, gen_idx in enumerate(gen_indices): + individual = best_individuals[gen_idx] + fitness = best_fitnesses[gen_idx] + + visualizer = DroneVisualizer() + if twod: + viz_func = functools.partial( + visualizer.plot_2d, + genome_data=individual, + title=f"Gen {gen_idx}: {np.round(fitness, 2)}" + ) + else: + viz_func = functools.partial( + visualizer.plot_3d, + genome_data=individual, + title=f"Gen {gen_idx}: {np.round(fitness, 2)}" + ) + + viz_functions.append(viz_func) + + # Arrange in grid + grid = np.array(viz_functions).reshape(grid_size) + return grid.tolist() + + +def generate_best_ever_grid( + population_data: npt.NDArray, + fitness_data: npt.NDArray, + grid_size: Tuple[int, int] = (4, 4), + twod: bool = True, + include_motor_orientation: Union[bool, int] = 0, + worst: bool = False, + title: Optional[str] = None, + similarity_threshold: Optional[float] = None, + round_to: int = 2 +) -> Tuple[List[List[Callable]], npt.NDArray, npt.NDArray]: + """ + Generate a grid showing the best individuals across all generations. + + Args: + population_data: Array of shape (n_generations, pop_size, n_arms, n_params) + fitness_data: Array of shape (n_generations, pop_size) + grid_size: Tuple of (rows, cols) for grid layout + twod: If True, use 2D visualization + include_motor_orientation: Whether to show motor orientations + worst: If True, show worst individuals + title: Title for the grid + similarity_threshold: If provided, ensure diversity in selection + round_to: Number of decimal places for fitness display + + Returns: + Tuple of (grid, top_individuals, top_fitnesses) + """ + rows, cols = grid_size + k = rows * cols + + # Flatten across all generations + flat_population, flat_fitnesses = flatten_population_across_generations( + population_data, fitness_data, remove_nan=True + ) + + # Get top individuals + if worst: + top_individuals, top_fitnesses, _ = get_top_k_individuals( + flat_population, flat_fitnesses, k, reverse=True, + similarity_threshold=similarity_threshold + ) + else: + top_individuals, top_fitnesses, _ = get_top_k_individuals( + flat_population, flat_fitnesses, k, reverse=False, + similarity_threshold=similarity_threshold + ) + + # Create grid + grid = [] + for i, (individual, fitness) in enumerate(zip(top_individuals, top_fitnesses)): + # Determine label positioning + labelleft = (i % cols == 0) + labelbottom = ((cols * (rows - 1)) <= i < (cols * rows)) + + visualizer = DroneVisualizer() + if twod: + viz_func = functools.partial( + visualizer.plot_2d, + genome_data=individual, + title=f"Fitness: {np.round(fitness, round_to)}" + ) + else: + viz_func = functools.partial( + visualizer.plot_3d, + genome_data=individual, + title=f"Fitness: {np.round(fitness, round_to)}" + ) + + grid.append(viz_func) + + # Arrange in grid + grid_2d = np.array(grid).reshape(grid_size) + + return grid_2d.tolist(), np.array(top_individuals), np.array(top_fitnesses) + + +def generate_comparison_grid( + population_lists: List[List[npt.NDArray]], + fitness_lists: List[List[npt.NDArray]], + labels: List[str], + grid_size: Tuple[int, int] = (4, 4), + twod: bool = True, + include_motor_orientation: Union[bool, int] = 0 +) -> List[List[Callable]]: + """ + Generate a grid comparing best individuals from multiple evolution runs. + + Args: + population_lists: List of population data lists (one per run) + fitness_lists: List of fitness data lists (one per run) + labels: Labels for each evolution run + grid_size: Tuple of (rows, cols) for grid layout + twod: If True, use 2D visualization + include_motor_orientation: Whether to show motor orientations + + Returns: + 2D list of visualization functions + """ + rows, cols = grid_size + num_runs = len(population_lists) + + if len(fitness_lists) != num_runs or len(labels) != num_runs: + raise ValueError("Number of runs must match across all inputs") + + # Get best individuals from each run + best_individuals = [] + best_fitnesses = [] + + for pop_data, fit_data in zip(population_lists, fitness_lists): + # Flatten across generations for this run + flat_pop, flat_fit = flatten_population_across_generations( + np.array(pop_data), np.array(fit_data), remove_nan=True + ) + + # Get single best individual + best_idx = np.argmax(flat_fit) + best_individuals.append(flat_pop[best_idx]) + best_fitnesses.append(flat_fit[best_idx]) + + # Create grid with run comparisons + grid = [] + items_per_row = cols // num_runs if cols >= num_runs else 1 + + for row in range(rows): + grid_row = [] + for col in range(cols): + run_idx = col // items_per_row + + if run_idx < num_runs: + individual = best_individuals[run_idx] + fitness = best_fitnesses[run_idx] + label = labels[run_idx] + + visualizer = DroneVisualizer() + if twod: + viz_func = functools.partial( + visualizer.plot_2d, + genome_data=individual, + title=f"{label}: {np.round(fitness, 2)}" + ) + else: + viz_func = functools.partial( + visualizer.plot_3d, + genome_data=individual, + title=f"{label}: {np.round(fitness, 2)}" + ) + + grid_row.append(viz_func) + else: + grid_row.append(remove_ticks) + + grid.append(grid_row) + + return grid + + +def calculate_optimal_grid_size(num_items: int, max_cols: int = 8) -> Tuple[int, int]: + """ + Calculate optimal grid dimensions for a given number of items. + + Args: + num_items: Number of items to arrange + max_cols: Maximum number of columns allowed + + Returns: + Tuple of (rows, cols) for optimal layout + + Raises: + ValueError: If num_items or max_cols are invalid + """ + if not isinstance(num_items, int): + raise TypeError(f"num_items must be an integer, got {type(num_items)}") + if not isinstance(max_cols, int): + raise TypeError(f"max_cols must be an integer, got {type(max_cols)}") + + if num_items < 0: + raise ValueError(f"num_items must be non-negative, got {num_items}") + if max_cols <= 0: + raise ValueError(f"max_cols must be positive, got {max_cols}") + + if num_items == 0: + return (1, 1) + + # Try to make it as square as possible + sqrt_items = int(np.ceil(np.sqrt(num_items))) + + if sqrt_items <= max_cols: + cols = sqrt_items + rows = int(np.ceil(num_items / cols)) + else: + cols = max_cols + rows = int(np.ceil(num_items / cols)) + + return (rows, cols) + + +def add_grid_labels( + grid: List[List[Callable]], + row_labels: Optional[List[str]] = None, + col_labels: Optional[List[str]] = None +) -> List[List[Callable]]: + """ + Add row and column labels to a grid layout. + + Args: + grid: 2D list of visualization functions + row_labels: Optional labels for rows + col_labels: Optional labels for columns + + Returns: + Modified grid with label functions added + """ + rows = len(grid) + cols = len(grid[0]) if rows > 0 else 0 + + # Create new grid with space for labels + new_grid = [] + + # Add column labels if provided + if col_labels: + label_row = [] + if row_labels: + label_row.append(remove_ticks) # Empty corner + + for col, label in enumerate(col_labels[:cols]): + label_func = functools.partial( + lambda ax, text=label: ax.text( + 0.5, 0.5, text, ha='center', va='center', + fontsize=12, fontweight='bold' + ) + ) + label_row.append(label_func) + + new_grid.append(label_row) + + # Add rows with optional row labels + for row_idx, row in enumerate(grid): + new_row = [] + + if row_labels and row_idx < len(row_labels): + label_func = functools.partial( + lambda ax, text=row_labels[row_idx]: ax.text( + 0.5, 0.5, text, ha='center', va='center', + fontsize=12, fontweight='bold', rotation=90 + ) + ) + new_row.append(label_func) + + new_row.extend(row) + new_grid.append(new_row) + + return new_grid + + +# Backward compatibility functions +get_best_individuals_fitness_grid = generate_best_individuals_fitness_grid +get_grid_for_population = generate_population_grid \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/learning_analysis/__init__.py b/src/ariel/ec/drone/inspection/learning_analysis/__init__.py new file mode 100644 index 000000000..03d47fc65 --- /dev/null +++ b/src/ariel/ec/drone/inspection/learning_analysis/__init__.py @@ -0,0 +1 @@ +# Package init diff --git a/src/ariel/ec/drone/inspection/learning_analysis/learning_descriptors.py b/src/ariel/ec/drone/inspection/learning_analysis/learning_descriptors.py new file mode 100644 index 000000000..6707454eb --- /dev/null +++ b/src/ariel/ec/drone/inspection/learning_analysis/learning_descriptors.py @@ -0,0 +1,569 @@ +import pandas as pd +import numpy as np +import matplotlib.pyplot as plt +import time +import os +from multiprocessing import Pool, cpu_count +from functools import partial +import argparse + +def read_file(monitor_file): + data = pd.read_csv(monitor_file, skiprows=1) # Skip the first row (comments) + episode_rewards = data["r"] # Rewards per episode + time_steps = data["t"] # Timesteps at each episode + + # remove the last episode if it is not finished + if type(episode_rewards[len(episode_rewards)-1]) == str: + episode_rewards = episode_rewards[:-1] + time_steps = time_steps[:-1] + + episode_rewards = np.array(episode_rewards, dtype=float) + time_steps = np.array(time_steps, dtype=int) + + return episode_rewards, time_steps + +def sliding_window_performance(episode_rewards, window_size=50, type_of='mean'): + performances = [] + for i in range(window_size, len(episode_rewards)+window_size): + window = episode_rewards[i-window_size:i] + # set dtype to float to avoid overflow errors + try: + window = np.array(window, dtype=float) + except: + print("Error in window") + print(window) + print(episode_rewards) + window = np.array(window, dtype=float) + if type_of == 'mean': + value = np.mean(window) + elif type_of == 'max': + value = np.max(window) + elif type_of == 'min': + value = np.min(window) + elif type_of == 'median': + try: + value = np.nanmedian(window) + except: + print("Error in window, median") + print(window) + print(episode_rewards) + exit() + elif type_of == 'std': + value = np.std(window) + elif type_of == 'var': + value = np.var(window) + + performances.append(value) + + return performances + +def asymptotic_performance(episode_rewards): + return np.max(episode_rewards) + +def stability_of_learning(episode_rewards): # Mean of the differences between consecutive episode rewards + diffs = np.abs(np.diff(episode_rewards)) + return np.mean(diffs) + +def calculate_burnin_phase_start_time(smoothed_rewards, time_steps): + return 0 + +def calculate_burnin_phase_end_time(smoothed_rewards, time_steps): + last_reward = smoothed_rewards[-1] + diffs = np.diff(smoothed_rewards) + idx = np.argmax(diffs) + return time_steps[idx+1] + +def calculate_burnin_phase_start_performance(smoothed_rewards, window_size=50): + return smoothed_rewards[0] + +def calculate_burnin_phase_end_performance(smoothed_rewards, window_size=50): + last_reward = smoothed_rewards[-1] + diffs = np.diff(smoothed_rewards) + idx = np.argmax(diffs) + + if idx >= len(smoothed_rewards): + return smoothed_rewards[-1] + + return smoothed_rewards[idx] + +def calculate_convergence_phase_start_time(smoothed_rewards_median, time_steps, tol=0.05): + last_reward = smoothed_rewards_median[-1] + + # Find the first index where the rolling std remains below threshold + if last_reward < 0: + lower_bound_maintained = smoothed_rewards_median > last_reward*(1+tol) + upper_bound_maintained = smoothed_rewards_median < last_reward*(1-tol) + else: + lower_bound_maintained = smoothed_rewards_median < last_reward*(1+tol) + upper_bound_maintained = smoothed_rewards_median > last_reward*(1-tol) + + bounds_maintained = np.logical_and(lower_bound_maintained, upper_bound_maintained) + reversed_bounds_maintained = np.flip(bounds_maintained) + + idx_reversed = np.where(np.logical_not(reversed_bounds_maintained)) + + if len(idx_reversed[0]) == 0: + return time_steps[0] + + idx = len(time_steps) - idx_reversed[0][0] + + return time_steps[idx] + +def calculate_convergence_phase_end_time(smoothed_rewards_median, time_steps, tol=0.05): + return time_steps[-1] + +def calculate_convergence_phase_start_performance(smoothed_rewards_median, convergence_phase_start_time, time_steps): + idx = np.where(time_steps == convergence_phase_start_time)[0][0] + return smoothed_rewards_median[idx] + +def calculate_convergence_phase_end_performance(smoothed_rewards_median, time_steps, tol=0.05): + return smoothed_rewards_median[-1] + +def calculate_burnin_phase_speed(burnin_performance, burnin_time): + if burnin_time == 0: + return burnin_performance + return burnin_performance / burnin_time + +def calculate_convergence_phase_speed(convergence_time, convergence_performance): + if convergence_time == 0: + return convergence_performance + return convergence_performance / convergence_time + +def calculate_intermediate_phase_time_performance(convergence_time, convergence_performance, burnin_time, burnin_performance): + if burnin_time > convergence_time: + return np.nan, np.nan + + return convergence_time - burnin_time, convergence_performance - burnin_performance + +def calculate_intermediate_speed(int_time, int_performance): + if int_time == 0: + return np.nan + return int_performance / int_time + +def process_individual(args): + """Process a single individual's data - designed for parallel execution""" + directory, experiment, g, local_idx, ind_num, window_size = args + + monitor_file_path = os.path.join(directory, experiment, f'gen{g}', f'ind{ind_num}', 'monitor.csv') + + if os.path.exists(monitor_file_path): + try: + episode_rewards, time_steps = read_file(monitor_file_path) + smoothed_rewards_median = sliding_window_performance(episode_rewards, window_size=window_size, type_of='median') + + burnin_start_time = calculate_burnin_phase_start_time(smoothed_rewards_median, time_steps) + burnin_end_time = calculate_burnin_phase_end_time(smoothed_rewards_median, time_steps) + burnin_start_performance = calculate_burnin_phase_start_performance(smoothed_rewards_median, window_size=window_size) + burnin_end_performance = calculate_burnin_phase_end_performance(smoothed_rewards_median, window_size=window_size) + convergence_start_time = calculate_convergence_phase_start_time(smoothed_rewards_median, time_steps, tol=0.15) + convergence_end_time = calculate_convergence_phase_end_time(smoothed_rewards_median, time_steps, tol=0.15) + convergence_start_performance = calculate_convergence_phase_start_performance(smoothed_rewards_median, convergence_start_time, time_steps) + convergence_end_performance = calculate_convergence_phase_end_performance(smoothed_rewards_median, time_steps, tol=0.15) + + burnin_speed = calculate_burnin_phase_speed(burnin_end_performance-burnin_start_performance, burnin_end_time) + convergence_speed = calculate_convergence_phase_speed(convergence_end_time-convergence_start_time, convergence_end_performance-convergence_start_performance) + intermediate_time, intermediate_performance = calculate_intermediate_phase_time_performance(convergence_start_time, convergence_start_performance, burnin_end_time, burnin_end_performance) + intermediate_speed = calculate_intermediate_speed(intermediate_time, intermediate_performance) + + mxr = np.max(episode_rewards) + volatility = stability_of_learning(episode_rewards) + + return (g, local_idx, [burnin_start_time, burnin_end_time, burnin_start_performance, burnin_end_performance, burnin_speed, + convergence_start_time, convergence_end_time, convergence_start_performance, convergence_end_performance, convergence_speed, + intermediate_time, intermediate_performance, intermediate_speed, + mxr, volatility]) + except Exception as e: + print(f'Error processing {monitor_file_path}: {e}') + return (g, local_idx, [np.nan, np.nan, np.nan, np.nan, np.nan, + np.nan, np.nan, np.nan, np.nan, np.nan, + np.nan, np.nan, np.nan, + np.nan, np.nan]) + else: + print(f'File {monitor_file_path} does not exist') + return (g, local_idx, [np.nan, np.nan, np.nan, np.nan, np.nan, + np.nan, np.nan, np.nan, np.nan, np.nan, + np.nan, np.nan, np.nan, + np.nan, np.nan]) + +def get_learning_data(directory, num_generations=40, window_size=1000, type_of='median', + multiple_experiments=True, n_processes=None): + """ + Extract learning data from experiment directories with optional parallelization. + Automatically detects the number of individuals per generation from folder structure. + + Parameters: + ----------- + directory : str + Path to the data directory + num_generations : int, default=40 + Number of generations to process + window_size : int, default=1000 + Window size for sliding window performance calculation + type_of : str, default='median' + Type of sliding window calculation + multiple_experiments : bool, default=True + Whether to process multiple experiment folders or treat directory as single experiment + n_processes : int, optional + Number of processes for parallelization. If None, uses all available CPU cores + + Returns: + -------- + total_data : list + Learning data with shape (num_experiments, num_generations, max_individuals_found, 15) + """ + + if n_processes is None: + n_processes = cpu_count() + + start_time = time.time() + + if multiple_experiments: + # List all folders in the directory as experiment folders + experiment_folders = [f for f in os.listdir(directory) if os.path.isdir(os.path.join(directory, f))] + else: + # Treat the directory itself as the single experiment + experiment_folders = ['.'] + directory = os.path.dirname(directory) + if directory == '': + directory = '.' + + total_data = [] + + print(os.listdir(directory)) + for experiment in experiment_folders: + print(f'Processing experiment: {experiment}') + exp_start_time = time.time() + + # Discover the actual structure by scanning directories + experiment_path = os.path.join(directory, experiment) + generation_structure = {} + max_individuals = 0 + + # Scan each generation to find individual folders + for g in range(num_generations): + gen_path = os.path.join(experiment_path, f'gen{g}') + if os.path.exists(gen_path): + # Find all individual folders (ind*) + individual_folders = [f for f in os.listdir(gen_path) + if os.path.isdir(os.path.join(gen_path, f)) and f.startswith('ind')] + + # Extract individual numbers and sort them + individual_numbers = [] + for ind_folder in individual_folders: + try: + ind_num = int(ind_folder.replace('ind', '')) + individual_numbers.append(ind_num) + except ValueError: + print(f"Warning: Could not parse individual folder name: {ind_folder}") + continue + + individual_numbers.sort() + generation_structure[g] = individual_numbers + max_individuals = max(max_individuals, len(individual_numbers)) + + print(f" Generation {g}: Found {len(individual_numbers)} individuals (ind{min(individual_numbers)} to ind{max(individual_numbers)})") + else: + print(f" Generation {g}: Directory not found - {gen_path}") + generation_structure[g] = [] + + print(f"Maximum individuals in any generation: {max_individuals}") + + # Initialize data structure for this experiment + exp_data = [] + + # Prepare arguments for parallel processing + parallel_args = [] + + for g in range(num_generations): + individual_numbers = generation_structure.get(g, []) + for local_idx, ind_num in enumerate(individual_numbers): + parallel_args.append((directory, experiment, g, local_idx, ind_num, window_size)) + + # Process individuals in parallel + print(f'Processing {len(parallel_args)} individuals using {n_processes} processes...') + + with Pool(processes=n_processes) as pool: + results = pool.map(process_individual, parallel_args) + + # Organize results back into the expected structure + for g in range(num_generations): + individual_numbers = generation_structure.get(g, []) + gen_data = [None] * max_individuals # Initialize with max size + + # Fill in the actual data + for local_idx, ind_num in enumerate(individual_numbers): + # Find the result for this generation and local index + for gen_idx, loc_idx, data in results: + if gen_idx == g and loc_idx == local_idx: + gen_data[local_idx] = data + break + else: + # If no data found, fill with NaN + gen_data[local_idx] = [np.nan] * 15 + + exp_data.append(gen_data) + + total_data.append(exp_data) + print(f'Experiment {experiment} completed in {time.time() - exp_start_time:.2f} seconds') + + print(f"Total processing time: {time.time() - start_time:.2f} seconds") + return total_data + +def plot_learning_data(learning_data): + num_experiments, num_generations, pop_size, nparams = learning_data.shape + fig1, axs1 = plt.subplots(3, 2, figsize=(15, 10)) + axs1 = axs1.flatten() + fig2, axs2 = plt.subplots(3, 2, figsize=(15, 10)) + axs2 = axs2.flatten() + labels = ['Time of burnin phase', 'Peak after burnin phase', 'Asymptotic performance', 'Stability of learning', 'Point of convergence', 'Learnability'] + + avr_data_across_gens = np.nanmean(learning_data, axis=2) + + avr_data = np.nanmean(avr_data_across_gens, axis=0) + std_data = np.nanstd(avr_data_across_gens, axis=0) + + for i in range(nparams): + ax = axs1[i] + ax.set_title(labels[i]) + for j in range(num_experiments): + ax.plot(avr_data_across_gens[j, :, i].T, alpha=0.3, label=f'Experiment {j}') + + ax.grid(True) + + fig1.suptitle('Learning descriptors across different experiments') + + for i in range(nparams): + ax = axs2[i] + ax.set_title(labels[i]) + ax.plot(avr_data[:, i], label='Mean') + ax.fill_between(np.arange(num_generations), avr_data[:, i] - std_data[:, i], avr_data[:, i] + std_data[:, i], alpha=0.3, label='Std') + ax.grid(True) + + fig2.suptitle('Learning descriptors across different generations') + + return fig1, axs1, fig2, axs2 + +def save_learning_data_as_csv(learning_data, output_path): + """ + Save learning data as a CSV file with proper column headers. + + Parameters: + ----------- + learning_data : list + Learning data from get_learning_data function + output_path : str + Path where to save the CSV file + """ + # Column headers for the learning data + columns = [ + 'experiment_id', 'generation', 'individual', + 'burnin_start_time', 'burnin_end_time', 'burnin_start_performance', + 'burnin_end_performance', 'burnin_speed', + 'convergence_start_time', 'convergence_end_time', 'convergence_start_performance', + 'convergence_end_performance', 'convergence_speed', + 'intermediate_time', 'intermediate_performance', 'intermediate_speed', + 'max_reward', 'volatility' + ] + + # Flatten the data and create DataFrame + rows = [] + for exp_id, experiment in enumerate(learning_data): + for gen_id, generation in enumerate(experiment): + for ind_id, individual_data in enumerate(generation): + if individual_data is not None and not all(np.isnan(individual_data) if isinstance(individual_data, (list, np.ndarray)) else [False]): + row = [exp_id, gen_id, ind_id] + individual_data + rows.append(row) + + df = pd.DataFrame(rows, columns=columns) + df.to_csv(output_path, index=False) + print(f"Learning data saved to: {output_path}") + print(f"Total records saved: {len(df)}") + + # Print summary of individuals per generation + if len(df) > 0: + gen_counts = df.groupby('generation')['individual'].count() + print("Individuals per generation:") + for gen, count in gen_counts.items(): + print(f" Generation {gen}: {count} individuals") + + +if __name__ == '__main__': + parser = argparse.ArgumentParser(description="Process learning data and optionally plot results.") + + # Add arguments + parser.add_argument('--mode', type=str, choices=['single', 'collect'], required=True, + help='Mode: "single" for single file analysis, "collect" for full data collection') + parser.add_argument('--data_path', type=str, nargs='*', action='append', required=True, + help='Path(s) to data directory/directories (for collect mode) or monitor.csv file (for single mode). Can be specified multiple times or as space-separated list.') + parser.add_argument('--num_generations', type=int, default=40, + help='Number of generations to process (collect mode only)') + parser.add_argument('--window_size', type=int, default=1000, + help='Window size for sliding window performance calculation') + parser.add_argument('--multiple_experiments', action='store_true', default=True, + help='Whether to process multiple experiment folders (collect mode only)') + parser.add_argument('--n_processes', type=int, default=None, + help='Number of processes for parallelization (collect mode only)') + + args = parser.parse_args() + + # Flatten the data_path list (in case of nested lists from action='append') + data_paths = [] + for path_group in args.data_path: + if isinstance(path_group, list): + data_paths.extend(path_group) + else: + data_paths.append(path_group) + + # Remove any empty strings + data_paths = [path for path in data_paths if path] + + if not data_paths: + print("Error: No data paths provided") + exit(1) + + start_time = time.time() + + if args.mode == 'single': + # Single file analysis mode + print(f"Performing single analysis on: {args.data_path[0][0]}") + + if not os.path.exists(args.data_path[0][0]): + print(f"Error: File {args.data_path[0][0]} does not exist") + exit(1) + + episode_rewards, time_steps = read_file(args.data_path[0][0]) + last_reward = episode_rewards[-1] + smoothed_rewards_median = sliding_window_performance(episode_rewards, window_size=args.window_size, type_of='median') + minxr = np.min(smoothed_rewards_median) + + burnin_start_time = calculate_burnin_phase_start_time(smoothed_rewards_median, time_steps) + burnin_end_time = calculate_burnin_phase_end_time(smoothed_rewards_median, time_steps) + burnin_start_performance = calculate_burnin_phase_start_performance(smoothed_rewards_median, window_size=args.window_size) + burnin_end_performance = calculate_burnin_phase_end_performance(smoothed_rewards_median, window_size=args.window_size) + convergence_start_time = calculate_convergence_phase_start_time(smoothed_rewards_median, time_steps, tol=0.1) + convergence_end_time = calculate_convergence_phase_end_time(smoothed_rewards_median, time_steps, tol=0.1) + convergence_start_performance = calculate_convergence_phase_start_performance(smoothed_rewards_median, convergence_start_time, time_steps) + convergence_end_performance = calculate_convergence_phase_end_performance(smoothed_rewards_median, time_steps, tol=0.1) + burnin_speed = calculate_burnin_phase_speed(burnin_end_performance-burnin_start_performance, burnin_end_time) + convergence_speed = calculate_convergence_phase_speed(convergence_end_time-convergence_start_time, convergence_end_performance-convergence_start_performance) + intermediate_time, intermediate_performance = calculate_intermediate_phase_time_performance(convergence_start_time, convergence_start_performance, burnin_end_time, burnin_end_performance) + intermediate_speed = calculate_intermediate_speed(intermediate_time, intermediate_performance) + + ap = asymptotic_performance(episode_rewards) + sl = stability_of_learning(episode_rewards) + + print(f"Burnin phase start time: {burnin_start_time}") + print(f"Burnin phase end time: {burnin_end_time}") + print(f"Burnin phase start performance: {burnin_start_performance}") + print(f"Burnin phase end performance: {burnin_end_performance}") + print(f"Convergence phase start time: {convergence_start_time}") + print(f"Convergence phase end time: {convergence_end_time}") + print(f"Convergence phase start performance: {convergence_start_performance}") + print(f"Convergence phase end performance: {convergence_end_performance}") + print(f"Burnin phase speed: {burnin_speed}") + print(f"Convergence phase speed: {convergence_speed}") + print(f"Intermediate phase time: {intermediate_time}") + print(f"Intermediate phase performance: {intermediate_performance}") + print(f"Intermediate phase speed: {intermediate_speed}") + print("Asymptotic performance: ", ap) + print("Stability of learning: ", sl) + + # Create plot /home/jed/workspaces/airevolve/data_backup/asym_circle/asym_circle4evo_logs_20250320_095305/gen15/ind364/figure.png + plt.figure(figsize=(12, 8)) + plt.plot(time_steps, episode_rewards, label='Episode rewards', color='gray', alpha=0.5) + plt.plot(time_steps, smoothed_rewards_median, label='Smoothed rewards median', linewidth=5) + plt.plot(burnin_end_time, burnin_end_performance, color='red', label='Point of Fastest Learning Progress', marker='o', markersize=20) + plt.plot([burnin_end_time, burnin_end_time], [minxr, burnin_end_performance], color='red', linestyle='--', linewidth=5) + plt.plot([0, burnin_end_time], [burnin_end_performance, burnin_end_performance], color='red', linestyle='--', linewidth=5) + plt.plot([0, time_steps[-1]], [last_reward*(1+0.1), last_reward*(1+0.1)], color='purple', linestyle='--', linewidth=5) + plt.plot([0, time_steps[-1]], [last_reward, last_reward], color='purple', linestyle='-', label='Last reward', linewidth=5) + plt.plot([0, time_steps[-1]], [last_reward*(1-0.1), last_reward*(1-0.1)], color='purple', linestyle='--', label='Convergence bounds', linewidth=5) + plt.plot(convergence_start_time, convergence_start_performance, color='purple', label='Point of convergence', marker='o', markersize=20) + plt.legend(fontsize=21, loc='lower right') + plt.xlabel('Time Steps', fontsize=28) + plt.ylabel('Reward', fontsize=28) + # Set ticksize + plt.xticks(fontsize=28) + plt.yticks(fontsize=28) + # plt.title('Learning Analysis') + plt.grid(True) + + # Save plot in the same directory as the data file + plot_path = os.path.join(os.path.dirname(args.data_path[0][0]), 'learning_analysis.png') + plt.savefig(plot_path) + print(f"Plot saved to: {plot_path}") + + elif args.mode == 'collect': + # Full data collection mode + + + # Check if multiple paths are provided + if len(data_paths) > 1: + print(f"Processing multiple directories: {data_paths}") + for path in data_paths: + if not os.path.exists(path): + print(f"Error: Directory {path} does not exist") + exit(1) + + learning_data = get_learning_data( + directory=path, + num_generations=args.num_generations, + window_size=args.window_size, + multiple_experiments=args.multiple_experiments, + n_processes=args.n_processes + ) + + # Save the data as CSV + output_path = os.path.join(path, 'learning_data.csv') + save_learning_data_as_csv(learning_data, output_path) + else: + print(f"Performing full data collection on: {args.data_path}") + if not os.path.exists(data_paths[0]): + print(f"Error: Directory {data_paths[0]} does not exist") + exit(1) + + learning_data = get_learning_data( + directory=data_paths[0], + num_generations=args.num_generations, + window_size=args.window_size, + multiple_experiments=args.multiple_experiments, + n_processes=args.n_processes + ) + + # Save the data as CSV + output_path = os.path.join(data_paths[0], 'learning_data.csv') + save_learning_data_as_csv(learning_data, output_path) + # Optionally create plots + try: + learning_data_array = np.array(learning_data) + fig1, axs1, fig2, axs2 = plot_learning_data(learning_data_array) + + # Save plots + plot1_path = os.path.join(args.data_path, 'learning_descriptors_experiments.png') + plot2_path = os.path.join(args.data_path, 'learning_descriptors_generations.png') + fig1.savefig(plot1_path) + fig2.savefig(plot2_path) + print(f"Plots saved to: {plot1_path} and {plot2_path}") + + except Exception as e: + print(f"Warning: Could not create plots - {e}") + + print(f"Total execution time: {time.time() - start_time:.2f} seconds") + + # Example usage: + # + # Single analysis: + # python script.py --mode single --data_path /path/to/monitor.csv + # + # Multiple directories data collection (auto-detects population sizes): + # python airevolve/inspection_tools/learning_descriptors.py --mode collect --data_path /path/to/data1 /path/to/data2 --multiple_experiments + # python airevolve/inspection_tools/learning_descriptors.py --mode collect --data_path /media/jed/My\ Passport/asym_figure8/ /media/jed/My\ Passport/asym_slalom/ --multiple_experiments + # + # Using wildcards (bash will expand): + # python script.py --mode collect --data_path /path/to/exp_* --num_generations 50 + # + # From file list: + # python script.py --mode collect --data_path $(cat directory_list.txt) + +# def did_catastrophic_forgetting_occur(): +# pass \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/morphological_descriptors/__init__.py b/src/ariel/ec/drone/inspection/morphological_descriptors/__init__.py new file mode 100644 index 000000000..03d47fc65 --- /dev/null +++ b/src/ariel/ec/drone/inspection/morphological_descriptors/__init__.py @@ -0,0 +1 @@ +# Package init diff --git a/src/ariel/ec/drone/inspection/morphological_descriptors/area.py b/src/ariel/ec/drone/inspection/morphological_descriptors/area.py new file mode 100644 index 000000000..2f7fc39b5 --- /dev/null +++ b/src/ariel/ec/drone/inspection/morphological_descriptors/area.py @@ -0,0 +1,53 @@ +import numpy as np +import scipy + +import ariel.ec.drone.inspection.utils as u + +def compute_area_for_individual(individual, perimeter=False): + + points = u.get_points(individual) + points = points[:,:2] + + try: + convex_hull = scipy.spatial.ConvexHull(points) + except: # Then points are coplanar + return 0 + + if perimeter: + area = convex_hull.area + else: + area = convex_hull.volume + + return area + +def compute_area_for_population(population, perimeter=False): + areas = np.empty(len(population)) + for i, individual in enumerate(population): + areas[i] = compute_area_for_individual(individual, perimeter=perimeter) + + return areas + +def compute_area(individual_or_population, perimeter=False): + num_dims = len(individual_or_population.shape) + if num_dims == 2: + narms, nparams = individual_or_population.shape + individual_or_population = np.append(individual_or_population, np.zeros((1,nparams)), axis=0) + + area = compute_area_for_individual(individual_or_population, perimeter=perimeter) + elif num_dims == 3: + pop_size, narms, nparams = individual_or_population.shape + individual_or_population = np.append(individual_or_population, np.zeros((pop_size,1,nparams)), axis=1) + + area = compute_area_for_population(individual_or_population, perimeter=perimeter) + elif num_dims == 4: + ngens, pop_size, narms, nparams = individual_or_population.shape + individual_or_population = np.append(individual_or_population, np.zeros((ngens, pop_size,1,nparams)), axis=2) + + ngens, pop_size, narms, nparms = individual_or_population.shape + area = np.empty((ngens, pop_size)) + for gen in range(ngens): + area[gen] = compute_area_for_population(individual_or_population[gen], perimeter=perimeter) + else: + raise Exception(f"Error area, shape did not match: {individual_or_population.shape}") + + return area \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/morphological_descriptors/avr_arm_length.py b/src/ariel/ec/drone/inspection/morphological_descriptors/avr_arm_length.py new file mode 100644 index 000000000..921d8bde9 --- /dev/null +++ b/src/ariel/ec/drone/inspection/morphological_descriptors/avr_arm_length.py @@ -0,0 +1,8 @@ + +import numpy as np + +def compute_avr_arm_length(individual_or_population): + num_dims = len(individual_or_population.shape) + var = np.nanmean(individual_or_population[...,0], axis=num_dims-2) + var = np.nan_to_num(var) # if any arms are empty + return var \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/morphological_descriptors/biradial_symmetry.py b/src/ariel/ec/drone/inspection/morphological_descriptors/biradial_symmetry.py new file mode 100644 index 000000000..be25b6b53 --- /dev/null +++ b/src/ariel/ec/drone/inspection/morphological_descriptors/biradial_symmetry.py @@ -0,0 +1,125 @@ +import numpy as np + +import ariel.ec.drone.inspection.utils as u + +def reflect_points(points, plane): + # Unpack the plane coefficients + a, b, c, d = plane + + # Convert points to a NumPy array if not already + points = np.array(points) + + # Calculate the numerator for the scale factor for all points at once + scale_numerator = 2 * (a * points[:, 0] + b * points[:, 1] + c * points[:, 2] + d) + + # Calculate the denominator for the scale factor (it's a constant) + scale_denominator = a**2 + b**2 + c**2 + + # Compute the scale factor for all points + scale = scale_numerator / scale_denominator + + # Calculate the reflected points using broadcasting + reflected_points = points - scale[:, np.newaxis] * np.array([a, b, c]) + + # Round the result to 15 decimal places and return + return reflected_points.round(8) + +def sum_closest_distance(list1, list2): + # Convert lists to numpy arrays + array1 = np.array(list1) + array2 = np.array(list2) + + # Calculate the squared differences and sum them along the last axis + distances = np.sqrt(((array1[:, np.newaxis, :] - array2[np.newaxis, :, :]) ** 2).sum(axis=2)) + + # Find the minimum distance for each point in array1 + min_distances = np.min(distances, axis=1) + + # Calculate the mean of these minimum distances + mean_distance = np.sum(min_distances) + + return mean_distance + +def find_best_reflection_plane(points, coarse_step=20, fine_step=5, fixed_plane=None): + best_score = float('inf') + best_plane = None + centroid = np.mean(points, axis=0) + if fixed_plane is not None: + # Use the fixed plane directly + reflected_points = reflect_points(points, fixed_plane) + best_score = sum_closest_distance(points, reflected_points) + return fixed_plane, best_score + + def search_planes(theta_range, phi_range): + nonlocal best_score, best_plane + for theta in theta_range: + for phi in phi_range: + a = np.sin(theta) * np.cos(phi) + b = np.sin(theta) * np.sin(phi) + c = np.cos(theta) + d = -(a * centroid[0] + b * centroid[1] + c * centroid[2]) + plane = np.array((a, b, c, d)).round(15) + reflected_points = reflect_points(points, plane) + if (reflected_points == points.astype(np.float64)).all(): + break + score = sum_closest_distance(points, reflected_points) + + if score < best_score: + best_score = score + best_plane = plane + if score < 1e-15: # perfect symmetry, don't continue + return + + # Coarse search + coarse_theta_range = np.linspace(0, np.pi, coarse_step) + coarse_phi_range = np.linspace(0, 2 * np.pi, coarse_step) + search_planes(coarse_theta_range, coarse_phi_range) + + # Fine search around the best coarse result + if not isinstance(best_plane, np.ndarray): + print(f"Warning, symmetry not found for shape: {points}, coarse_step={coarse_step}, fine_step={fine_step}") + + best_theta = np.arccos(best_plane[2]) + best_phi = np.arctan2(best_plane[1], best_plane[0]) + fine_theta_range = np.linspace(best_theta - np.pi / coarse_step, best_theta + np.pi / coarse_step, fine_step) + fine_phi_range = np.linspace(best_phi - 2 * np.pi / coarse_step, best_phi + 2 * np.pi / coarse_step, fine_step) + search_planes(fine_theta_range, fine_phi_range) + + return best_plane, best_score + +def compute_symmetry_for_individual(individual, fixed_plane=None): + num_dims = len(individual.shape) + num_arms = np.sum(~np.isnan(individual).all(axis=num_dims-1), axis=num_dims-2) + if num_arms == 0: + return 0 + points = u.get_points(individual) + points = np.append(points, [[0,0,0]], axis=0) + _, best_score = find_best_reflection_plane(points, coarse_step=20, fine_step=5, fixed_plane=fixed_plane) + if best_score < 1e-6: + return 0 + return best_score + +def compute_symmetry_for_population(population, fixed_plane=None): + best_score = np.empty(len(population)) + + for ind, individual in enumerate(population): + best_score[ind] = compute_symmetry_for_individual(individual, fixed_plane=fixed_plane) + + return best_score + +def compute_symmetry(individual_or_population, max_workers=4, fixed_plane=None): + num_dims = len(individual_or_population.shape) + + if num_dims == 2: + best_score = compute_symmetry_for_individual(individual_or_population, fixed_plane=fixed_plane) + elif num_dims == 3: + best_score = compute_symmetry_for_population(individual_or_population, fixed_plane=fixed_plane) + elif num_dims == 4: + ngens, pop_size, narms, nparms = individual_or_population.shape + best_score = np.empty((ngens, pop_size)) + for gen in range(ngens): + best_score[gen] = compute_symmetry_for_population(individual_or_population[gen], fixed_plane=fixed_plane) + else: + raise Exception(f"Error symmetry, shape did not match: {individual_or_population.shape}") + + return best_score \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/morphological_descriptors/central_symmetry.py b/src/ariel/ec/drone/inspection/morphological_descriptors/central_symmetry.py new file mode 100644 index 000000000..dfebced10 --- /dev/null +++ b/src/ariel/ec/drone/inspection/morphological_descriptors/central_symmetry.py @@ -0,0 +1,90 @@ +import numpy as np + +def compute_symmetry(data): + """ + Calculate the symmetry score for each individual in the given data. + + Parameters: + data (numpy.ndarray): Input array of shape (generations, population_size, max_arms, 6), + (population_size, max_arms, 6), or (max_arms, 6) + + Returns: + numpy.ndarray: Symmetry scores for each individual + """ + # Determine the shape of the input data + if data.ndim == 4: + generations, population_size, max_arms, _ = data.shape + has_generations = True + elif data.ndim == 3: + population_size, max_arms, _ = data.shape + generations = 1 + has_generations = False + elif data.ndim == 2: + max_arms, _ = data.shape + population_size = 1 + generations = 1 + has_generations = False + else: + raise ValueError("Input data must have shape (generations, population_size, max_arms, 6), (population_size, max_arms, 6), or (max_arms, 6)") + + # Extract the relevant parameters (arm length, arm yaw, arm pitch) + arm_lengths = data[..., 0] + arm_yaws = data[..., 1] + arm_pitches = data[..., 2] + + # Convert arms to 3D points + x = arm_lengths * np.cos(arm_yaws) * np.cos(arm_pitches) + y = arm_lengths * np.sin(arm_yaws) * np.cos(arm_pitches) + z = arm_lengths * np.sin(arm_pitches) + points = np.stack((x, y, z), axis=-1) + + # Mirror the arms by negating the 3D coordinates + mirrored_points = -points + + # Calculate the symmetry score for each individual + symmetry_scores = np.zeros((generations, population_size)) + + for gen in range(generations): + for ind in range(population_size): + if has_generations: + individual_points = points[gen, ind] + mirrored_individual_points = mirrored_points[gen, ind] + else: + individual_points = points[ind] if population_size > 1 else points + mirrored_individual_points = mirrored_points[ind] if population_size > 1 else mirrored_points + + # Filter out NaN arms + valid_arms = ~np.isnan(individual_points).any(axis=1) + valid_mirrored_arms = ~np.isnan(mirrored_individual_points).any(axis=1) + individual_points = individual_points[valid_arms] + mirrored_individual_points = mirrored_individual_points[valid_mirrored_arms] + + if individual_points.size == 0 or mirrored_individual_points.size == 0: + symmetry_scores[gen, ind] = np.nan + continue + + # Calculate the distance between each mirrored point and all actual points + distances = np.linalg.norm(individual_points[:, np.newaxis, :] - mirrored_individual_points[np.newaxis, :, :], axis=2) + + # Find the minimum distance for each mirrored point + min_distances = np.min(distances, axis=1) + + # Average the minimum distances to get the symmetry score + symmetry_scores[gen, ind] = np.mean(min_distances) + + # If there were no generations, return a 1D array + if not has_generations: + return symmetry_scores[0] if population_size > 1 else symmetry_scores[0, 0] + + return symmetry_scores + +# # Example usage: +# data_with_generations = np.random.rand(10, 5, 4, 6) # Example data with shape (generations, population_size, max_arms, 6) +# data_without_generations = np.random.rand(5, 4, 6) # Example data with shape (population_size, max_arms, 6) +# data_single_individual = np.random.rand(4, 6) # Example data with shape (max_arms, 6) +# scores_with_generations = calculate_symmetry_score(data_with_generations) +# scores_without_generations = calculate_symmetry_score(data_without_generations) +# score_single_individual = calculate_symmetry_score(data_single_individual) +# print(scores_with_generations) +# print(scores_without_generations) +# print(score_single_individual) \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/morphological_descriptors/centre_of_gravity.py b/src/ariel/ec/drone/inspection/morphological_descriptors/centre_of_gravity.py new file mode 100644 index 000000000..855e81fe4 --- /dev/null +++ b/src/ariel/ec/drone/inspection/morphological_descriptors/centre_of_gravity.py @@ -0,0 +1,2 @@ +def centre_of_gravity(individual): + return [0,0,0] \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/morphological_descriptors/hovering_info.py b/src/ariel/ec/drone/inspection/morphological_descriptors/hovering_info.py new file mode 100644 index 000000000..669c88efa --- /dev/null +++ b/src/ariel/ec/drone/inspection/morphological_descriptors/hovering_info.py @@ -0,0 +1,235 @@ +import numpy as np +import copy + +from dronehover.bodies.custom_bodies import Custombody +from dronehover.optimization import Hover +from ariel.ec.drone.genome_handlers.mounting_points import ( + generate_disc_mounting_points, + assign_nearest_mounting_point +) + +import ariel.ec.drone.inspection.utils as u +from ariel.ec.drone.inspection.morphological_descriptors.mass import compute_total_mass +from ariel.ec.drone.inspection.morphological_descriptors.centre_of_gravity import centre_of_gravity +from ariel.ec.drone.inspection.morphological_descriptors.inertia import inertia + +def euler_to_rotation_matrix(roll, pitch, yaw): + """ + Converts Euler angles (roll, pitch, yaw) to a rotation matrix. + The rotation matrix follows the z-y-x convention (yaw-pitch-roll). + """ + # Compute individual rotation matrices + R_z = np.array([ + [np.cos(yaw), -np.sin(yaw), 0], + [np.sin(yaw), np.cos(yaw), 0], + [0, 0, 1] + ]) + + R_y = np.array([ + [np.cos(pitch), 0, np.sin(pitch)], + [0, 1, 0 ], + [-np.sin(pitch), 0, np.cos(pitch)] + ]) + + R_x = np.array([ + [1, 0, 0 ], + [0, np.cos(roll), -np.sin(roll)], + [0, np.sin(roll), np.cos(roll)] + ]) + + # Combined rotation matrix + R = np.dot(R_z, np.dot(R_y, R_x)) + return R + +def orientation_to_unit_vector(roll, pitch, yaw): + """ + Converts roll, pitch, and yaw to a unit vector where the negative z-axis is pointing up. + """ + # Define the negative z-axis vector + default_rotation = np.array([0, 0, -1]) + + # Get the rotation matrix from Euler angles + R = euler_to_rotation_matrix(roll, pitch, yaw) + transform_from_ENU_to_NED = np.array([[0, 1, 0], [1, 0, 0], [0, 0, -1]]) + R = transform_from_ENU_to_NED @ R + # Transform the negative z-axis using the rotation matrix + transformed_vector = np.dot(R, default_rotation) + + # Normalize the resulting vector + unit_vector = transformed_vector / np.linalg.norm(transformed_vector) + + return unit_vector + +def get_sim(individual, motor_template = {"propsize": 2}): + # remove rows with nan values + individual = individual[~np.isnan(individual).any(axis=1)] + + mass = compute_total_mass(individual) + cg = centre_of_gravity(individual) + Ix, Iy, Iz, Ixy, Ixz, Iyz = inertia(individual) + + + props = [] + propeller_positions = [] + mypypd = individual[:,:6] # [mag, arm_yaw, arm_pitch, mot_pitch, mot_yaw, dir] + for mag, arm_yaw, arm_pitch, mot_pitch, mot_yaw, dir in mypypd: + global_x,global_y,global_z = u.convert_to_cartesian(mag, arm_yaw, arm_pitch) + x,y,z = u.ENU_to_NED(global_x,global_y,global_z) + + propeller_positions.append([float(x), float(y), float(z)]) + + tmp = copy.deepcopy(motor_template) + tmp.update({"loc": [float(x),float(y),float(z)]}) + if dir == 0: + d = "ccw" + else: + d = "cw" + + ENU_unit_vector = orientation_to_unit_vector(0,mot_pitch,mot_yaw) + unit_vector = ENU_unit_vector + tmp.update({"dir": [float(unit_vector[0]),float(unit_vector[1]),float(unit_vector[2]), d]}) + + props.append(tmp) + + # Generate 8 mounting points on 60mm diameter disc + disc_mounting_points = generate_disc_mounting_points(num_points=8, diameter=0.060) + + # Assign each propeller to nearest mounting point + mounting_points = assign_nearest_mounting_point(propeller_positions, disc_mounting_points) + + # Create drone with mounting points + # Note: We override mass/inertia calculations since we use our own descriptors + drone = Custombody(props, mountpoints=mounting_points, mass=mass, cg=cg, Ix=Ix, Iy=Iy, Iz=Iz, Ixy=Ixy, Ixz=Ixz, Iyz=Iyz) + + # Define hovering optimizer for drone + try: + sim = Hover(drone) + except: + sim = None + + return sim + +def drone_info(individual): + + sim = get_sim(individual) + if sim is None: + return 0, np.nan, np.nan, np.nan, np.nan + sim.compute_hover(verbose=False) + sim.static(verbose=False,tol=1e-5) + spinning_success = False + + if sim.static_success == False: + sim.spinning(verbose=False,tol=1e-5) + spinning_success = sim.spinning_success + + success = sim.static_success or spinning_success + if sim.static_success: + hover_type = 2 + elif spinning_success: + hover_type = 1 + else: + hover_type = 0 + + if not(success): + max_thrust_to_weight = np.nan + input_cost = np.nan + rank_controlability = np.nan + controlability = np.nan + else: + max_thrust_to_weight = np.linalg.norm(sim.f_max)/9.81 + input_cost = sim.input_cost + rank_controlability = np.linalg.matrix_rank(sim.Bm) + #controlability = np.linalg.eig(sim.Bm @ sim.Bm.T).eigenvalues[-1] + eigenvalues, eigenvectors = np.linalg.eig(sim.Bm @ sim.Bm.T) + controlability = min(eigenvalues) + + return hover_type, max_thrust_to_weight, input_cost, rank_controlability, controlability + +def max_thrust_to_weight(individual_or_population): + if len(individual_or_population.shape) == 4: + ngens, pop_size, max_num_arms, nparams = individual_or_population.shape + result = np.zeros((ngens, pop_size)) + for g in range(ngens): + for i in range(pop_size): + hover_type, result[g,i], input_cost, rank_controlability, controlability = drone_info(individual_or_population[g,i]) + return result + if len(individual_or_population.shape) == 3: + hover_type, result, input_cost, rank_controlability, controlability = drone_info(individual_or_population) + return result + if len(individual_or_population.shape) == 2: + hover_type, result, input_cost, rank_controlability, controlability = drone_info(individual_or_population) + return result + return np.nan + +def input_cost(individual_or_population): + if len(individual_or_population.shape) == 4: + ngens, pop_size, max_num_arms, nparams = individual_or_population.shape + input_cost = np.zeros((ngens, pop_size)) + for g in range(ngens): + for i in range(pop_size): + hover_type, max_thrust_to_weight, input_cost[g,i], rank_controlability, controlability = drone_info(individual_or_population[g,i]) + elif len(individual_or_population.shape) == 3: + input_cost = np.zeros((individual_or_population.shape[0])) + for i in range(individual_or_population.shape[0]): + hover_type, max_thrust_to_weight, input_cost[i], rank_controlability, controlability = drone_info(individual_or_population[i]) + else: + hover_type, max_thrust_to_weight, input_cost, rank_controlability, controlability = drone_info(individual_or_population) + + return input_cost + +def rank_controlability(individual_or_population): + if len(individual_or_population.shape) == 4: + ngens, pop_size, max_num_arms, nparams = individual_or_population.shape + rank_controlability = np.zeros((ngens, pop_size)) + for g in range(ngens): + for i in range(pop_size): + hover_type, max_thrust_to_weight, input_cost, rank_controlability[g,i], controlability = drone_info(individual_or_population[g,i]) + elif len(individual_or_population.shape) == 3: + rank_controlability = np.zeros((individual_or_population.shape[0])) + for i in range(individual_or_population.shape[0]): + hover_type, max_thrust_to_weight, input_cost, rank_controlability[i], controlability = drone_info(individual_or_population[i]) + + elif len(individual_or_population.shape) == 2: + hover_type, max_thrust_to_weight, input_cost, rank_controlability, controlability = drone_info(individual_or_population) + + return rank_controlability + +def controlability(individual_or_population): + if len(individual_or_population.shape) == 4: + ngens, pop_size, max_num_arms, nparams = individual_or_population.shape + result = np.zeros((ngens, pop_size)) + for g in range(ngens): + for i in range(pop_size): + hover_type, mtw, ic, rc, result[g,i] = drone_info(individual_or_population[g,i]) + return result + if len(individual_or_population.shape) == 3: + result = np.zeros((individual_or_population.shape[0])) + for i in range(individual_or_population.shape[0]): + hover_type, mtw, ic, rc, result[i] = drone_info(individual_or_population[i]) + return result + if len(individual_or_population.shape) == 2: + hover_type, mtw, ic, rc, result = drone_info(individual_or_population) + return result + return np.nan + +def compute_hovering_info(individual_or_population): + + if len(individual_or_population.shape) == 4: + ngens, pop_size, max_num_arms, nparams = individual_or_population.shape + hovering_info = np.zeros((ngens, pop_size, 5)) + for g in range(ngens): + for i in range(pop_size): + success, max_thrust_to_weight, input_cost, rank_controlability, controlability = drone_info(individual_or_population[g,i]) + hovering_info[g,i] = [success, max_thrust_to_weight, input_cost, rank_controlability, controlability] + + if len(individual_or_population.shape) == 3: + pop_size, max_num_arms, nparams = individual_or_population.shape + hovering_info = np.zeros((pop_size, 5)) + for i in range(pop_size): + success, max_thrust_to_weight, input_cost, rank_controlability, controlability = drone_info(individual_or_population[i]) + hovering_info[i] = [success, max_thrust_to_weight, input_cost, rank_controlability, controlability] + else: + hovering_info = np.zeros((5)) + success, max_thrust_to_weight, input_cost, rank_controlability, controlability = drone_info(individual_or_population) + hovering_info = [success, max_thrust_to_weight, input_cost, rank_controlability, controlability] + return hovering_info diff --git a/src/ariel/ec/drone/inspection/morphological_descriptors/inertia.py b/src/ariel/ec/drone/inspection/morphological_descriptors/inertia.py new file mode 100644 index 000000000..80a529511 --- /dev/null +++ b/src/ariel/ec/drone/inspection/morphological_descriptors/inertia.py @@ -0,0 +1,79 @@ +""" +Inertia Calculation using Drone-Hover Physics + +Computes realistic inertia matrix components using parallel axis theorem +and beam contributions. Integrates with drone-hover package for physics-based +inertia calculation with automatic mounting point assignment. +""" + +import numpy as np +from numpy.linalg import norm +from dronehover.bodies.custom_bodies import Custombody +from ariel.ec.drone.genome_handlers.mounting_points import ( + generate_disc_mounting_points, + assign_nearest_mounting_point +) +import ariel.ec.drone.inspection.utils as u + + +def inertia(individual): + """ + Compute inertia matrix components for an individual drone. + + Uses drone-hover's physics-based inertia calculation with automatic + mounting point assignment from an 8-point disc (60mm diameter). + + Args: + individual (np.ndarray): Genome array with shape (n_arms, 6) + Columns: [magnitude, arm_yaw, arm_pitch, mot_pitch, mot_yaw, direction] + + Returns: + tuple: (Ix, Iy, Iz, Ixy, Ixz, Iyz) inertia components in kg*m^2 + """ + # Remove rows with NaN values + individual = individual[~np.isnan(individual).any(axis=1)] + + if len(individual) == 0: + # No valid arms, return default minimal inertia + return [0.01, 0.01, 0.01, 0, 0, 0] + + # Convert genome to propeller locations + props = [] + propeller_positions = [] + + for mag, arm_yaw, arm_pitch, mot_pitch, mot_yaw, direction in individual: + # Convert spherical to Cartesian (ENU frame) + global_x, global_y, global_z = u.convert_to_cartesian(mag, arm_yaw, arm_pitch) + + # Convert to NED frame (required by drone-hover) + x, y, z = u.ENU_to_NED(global_x, global_y, global_z) + + propeller_positions.append([float(x), float(y), float(z)]) + + # Determine rotation direction + rotation = "cw" if direction > 0.5 else "ccw" + + # Motor thrust direction (simplified - mostly downward) + # In NED frame, motors typically point downward (positive Z) + props.append({ + "loc": [float(x), float(y), float(z)], + "dir": [0, 0, -1, rotation], # Downward thrust in NED + "propsize": 2 # Default 2-inch propeller + }) + + # Generate 8 mounting points on 60mm diameter disc + disc_mounting_points = generate_disc_mounting_points(num_points=8, diameter=0.060) + + # Assign each propeller to nearest mounting point + mounting_points = assign_nearest_mounting_point(propeller_positions, disc_mounting_points) + + try: + # Use drone-hover's Custombody with mounting points for physics-based calculation + drone = Custombody(props, mountpoints=mounting_points) + + return [drone.Ix, drone.Iy, drone.Iz, drone.Ixy, drone.Ixz, drone.Iyz] + + except Exception as e: + # Fallback to minimal inertia if calculation fails + print(f"Warning: Inertia calculation failed: {e}. Using default values.") + return [0.01, 0.01, 0.01, 0, 0, 0] \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/morphological_descriptors/mass.py b/src/ariel/ec/drone/inspection/morphological_descriptors/mass.py new file mode 100644 index 000000000..b0481c2df --- /dev/null +++ b/src/ariel/ec/drone/inspection/morphological_descriptors/mass.py @@ -0,0 +1,10 @@ +import numpy as np + +def compute_total_mass(individual_or_population, core_mass=0.25, motor_mass=0.05, arm_mass_coeff=0.01): + num_dims = len(individual_or_population.shape) + + num_arms = np.sum(~np.isnan(individual_or_population).all(axis=num_dims-1), axis=num_dims-2) + arm_lengths = individual_or_population[...,0] + mass = core_mass + num_arms*motor_mass + arm_mass_coeff*np.nansum(arm_lengths, axis=num_dims-2) + + return mass \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/morphological_descriptors/num_arms.py b/src/ariel/ec/drone/inspection/morphological_descriptors/num_arms.py new file mode 100644 index 000000000..badc9cd93 --- /dev/null +++ b/src/ariel/ec/drone/inspection/morphological_descriptors/num_arms.py @@ -0,0 +1,7 @@ +import numpy as np + +def compute_num_arms(individual_or_population): + num_dims = len(individual_or_population.shape) + num_arms = np.sum(~np.isnan(individual_or_population).all(axis=num_dims-1), axis=num_dims-2) + + return num_arms \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/morphological_descriptors/proportion.py b/src/ariel/ec/drone/inspection/morphological_descriptors/proportion.py new file mode 100644 index 000000000..0d15d894b --- /dev/null +++ b/src/ariel/ec/drone/inspection/morphological_descriptors/proportion.py @@ -0,0 +1,62 @@ +import numpy as np +import ariel.ec.drone.inspection.utils as u + +def calculate_proportionality(individual): + # Remove rows with all NaNs + valid_points = individual[~np.isnan(individual).all(axis=1)] + + if valid_points.shape[0] == 0: + return np.nan # No valid points, return NaN + + # Calculate the ranges in each dimension + x_range = np.ptp(valid_points[:, 0]) # Range in x dimension + y_range = np.ptp(valid_points[:, 1]) # Range in y dimension + z_range = np.ptp(valid_points[:, 2]) # Range in z dimension + + # Determine the dimensionality + unique_x = (valid_points[:, 0] == 0.0).all() + unique_y = (valid_points[:, 1] == 0.0).all() + unique_z = (valid_points[:, 2] == 0.0).all() + if (unique_x and unique_y) or (unique_x and unique_z) or (unique_y and unique_z) : + # 1D shape + return 1.0 + elif not(unique_x) and not(unique_y) and unique_z: + # 2D shape in XY plane + aspect_ratios = [x_range / y_range, y_range / x_range] + return min(aspect_ratios) + elif not(unique_x) and not(unique_z) and unique_y: + # 2D shape in XZ plane + aspect_ratios = [x_range / z_range, z_range / x_range] + return min(aspect_ratios) + elif not(unique_y) and not(unique_z) and unique_x: + # 2D shape in YZ plane + aspect_ratios = [y_range / z_range, z_range / y_range] + return min(aspect_ratios) + else: + # 3D shape + aspect_ratios = [ + min(x_range / y_range, y_range / x_range), + min(x_range / z_range, z_range / x_range), + min(y_range / z_range, z_range / y_range) + ] + return np.mean(aspect_ratios) + +def compute_proportion(individual_or_population): + # Handle cases where population could be (8, 3), (n, 8, 3), or (m, n, 8, 3) + if individual_or_population.ndim == 2: + narms, nparams = individual_or_population.shape + individual_or_population = np.append(individual_or_population, np.zeros((1,nparams)), axis=0) # Add core as point + points = np.nan_to_num(u.get_points(individual_or_population)) + return calculate_proportionality(points) + + elif individual_or_population.ndim == 3: + pop_size, narms, nparams = individual_or_population.shape + individual_or_population = np.append(individual_or_population, np.zeros((pop_size,1,nparams)), axis=1) # Add core as point + points = np.nan_to_num(u.get_points(individual_or_population)) + return np.array([calculate_proportionality(individual) for individual in points]) + + elif individual_or_population.ndim == 4: + ngens, pop_size, narms, nparams = individual_or_population.shape + individual_or_population = np.append(individual_or_population, np.zeros((ngens, pop_size,1,nparams)), axis=2) # Add core as point + points = np.nan_to_num(u.get_points(individual_or_population)) + return np.array([[calculate_proportionality(individual) for individual in gen] for gen in points]) \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/morphological_descriptors/thrust_alignment.py b/src/ariel/ec/drone/inspection/morphological_descriptors/thrust_alignment.py new file mode 100644 index 000000000..f4c56587e --- /dev/null +++ b/src/ariel/ec/drone/inspection/morphological_descriptors/thrust_alignment.py @@ -0,0 +1,95 @@ +import numpy as np +from ariel.ec.drone.inspection.morphological_descriptors.hovering_info import orientation_to_unit_vector +""" +Computes how the thrust vectors of multirotor aligns (is parallel to) each other. +If the output is equal to the number of the number of thrust vectors, then they are all parallel to each other. +""" +def unit_vector_to_yaw_pitch(unit_vector): + """ + Converts a unit vector to yaw (rotation around z-axis) and pitch (rotation around y-axis). + + Args: + unit_vector (np.ndarray): A 3D unit vector [x, y, z]. + + Returns: + tuple: (yaw, pitch) in radians. + """ + x, y, z = unit_vector + yaw = np.arctan2(y, x) # Yaw: angle in the x-y plane + pitch = np.arcsin(z) # Pitch: angle from the x-y plane + + return yaw, pitch + +def thrust_alignment(individual_or_population, normalize=False): + if len(individual_or_population.shape) == 4: + alignment_list = [] + for gen in individual_or_population: + gen_list = [] + for individual in gen: + alignment = thrust_alignment(individual, normalize) + gen_list.append(alignment) + alignment_list.append(gen_list) + return np.array(alignment_list) + elif len(individual_or_population.shape) == 3: + alignment_list = [] + for individual in individual_or_population: + alignment = thrust_alignment(individual, normalize) + alignment_list.append(alignment) + return np.array(alignment_list) + else: + thrust_vectors = [orientation_to_unit_vector(0., arm[4], arm[3]) for arm in individual_or_population] + thrust_vector_sum = np.sum(thrust_vectors, axis=0) + alignment = np.linalg.norm(thrust_vector_sum) + if normalize: + num_arm = len(individual_or_population) + alignment = alignment / num_arm + return alignment + +def thrust_unitvector_yaw(individual_or_population): + if len(individual_or_population.shape) == 4: + yaw_list = [] + for gen in individual_or_population: + gen_list = [] + for individual in gen: + yaw = thrust_unitvector_yaw(individual) + gen_list.append(yaw) + yaw_list.append(gen_list) + + return np.array(yaw_list) + elif len(individual_or_population.shape) == 3: + yaw_list = [] + for individual in individual_or_population: + yaw = thrust_unitvector_yaw(individual) + yaw_list.append(yaw) + return np.array(yaw_list) + else: + thrust_vectors = [orientation_to_unit_vector(0., arm[4], arm[3]) for arm in individual_or_population] + thrust_vector_norm = np.sum(thrust_vectors, axis=0) / len(thrust_vectors) + + yaw, pitch = unit_vector_to_yaw_pitch(thrust_vector_norm) + return yaw + +def thrust_unitvector_pitch(individual_or_population): + + if len(individual_or_population.shape) == 4: + pitch_list = [] + for gen in individual_or_population: + gen_list = [] + for individual in gen: + pitch = thrust_unitvector_pitch(individual) + gen_list.append(pitch) + pitch_list.append(gen_list) + return np.array(pitch_list) + elif len(individual_or_population.shape) == 3: + pitch_list = [] + for individual in individual_or_population: + pitch = thrust_unitvector_pitch(individual) + pitch_list.append(pitch) + return np.array(pitch_list) + else: + thrust_vectors = [orientation_to_unit_vector(0., arm[4], arm[3]) for arm in individual_or_population] + thrust_vector_norm = np.sum(thrust_vectors, axis=0) / len(thrust_vectors) + + yaw, pitch = unit_vector_to_yaw_pitch(thrust_vector_norm) + + return pitch \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/morphological_descriptors/var_arm_length.py b/src/ariel/ec/drone/inspection/morphological_descriptors/var_arm_length.py new file mode 100644 index 000000000..6b225e64e --- /dev/null +++ b/src/ariel/ec/drone/inspection/morphological_descriptors/var_arm_length.py @@ -0,0 +1,7 @@ +import numpy as np + +def compute_var_arm_length(individual_or_population): + num_dims = len(individual_or_population.shape) + var = np.nanvar(individual_or_population[...,0], axis=num_dims-2) + var = np.nan_to_num(var) # if any arms are empty + return var \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/morphological_descriptors/volume.py b/src/ariel/ec/drone/inspection/morphological_descriptors/volume.py new file mode 100644 index 000000000..3efc12fa6 --- /dev/null +++ b/src/ariel/ec/drone/inspection/morphological_descriptors/volume.py @@ -0,0 +1,52 @@ +import numpy as np +import scipy + +import ariel.ec.drone.inspection.utils as u + +def compute_volume_for_individual(individual): + max_narms, _ = individual.shape + points = u.get_points(individual) + if max_narms+1 - np.sum((points[:,:] == 0.0).all(axis=1)) < 3: + return 0 + elif (points[:,2] == 0.0).all(): + points = points[:,:2] + + try: + convex_hull = scipy.spatial.ConvexHull(points) + except: + return 0 + coverage = convex_hull.volume + + return coverage + +def compute_volume_for_population(population, max_workers=4): + coverage = np.empty(len(population)) + for i, individual in enumerate(population): + coverage[i] = compute_volume_for_individual(individual) + + return coverage + +def compute_volume(individual_or_population, max_workers=4): + num_dims = len(individual_or_population.shape) + + if num_dims == 2: + narms, nparams = individual_or_population.shape + individual_or_population = np.append(individual_or_population, np.zeros((1,nparams)), axis=0) # Add core as point + + coverage = compute_volume_for_individual(individual_or_population) + elif num_dims == 3: + pop_size, narms, nparams = individual_or_population.shape + individual_or_population = np.append(individual_or_population, np.zeros((pop_size,1,nparams)), axis=1) # Add core as point + + coverage = compute_volume_for_population(individual_or_population, max_workers=max_workers) + elif num_dims == 4: + ngens, pop_size, narms, nparams = individual_or_population.shape + individual_or_population = np.append(individual_or_population, np.zeros((ngens, pop_size,1,nparams)), axis=2) # Add core as point + + coverage = np.empty((ngens, pop_size)) + for gen in range(ngens): + coverage[gen] = compute_volume_for_population(individual_or_population[gen], max_workers=max_workers) + else: + raise Exception(f"Error compute_volume, shape did not match: {individual_or_population.shape}") + + return coverage \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/morphological_descriptors/xyz.py b/src/ariel/ec/drone/inspection/morphological_descriptors/xyz.py new file mode 100644 index 000000000..67dfadd70 --- /dev/null +++ b/src/ariel/ec/drone/inspection/morphological_descriptors/xyz.py @@ -0,0 +1,235 @@ +import numpy as np + +from ariel.ec.drone.inspection.morphological_descriptors.hovering_info import euler_to_rotation_matrix + + +def get_xyzs(individual): + default_rotation = np.array([0, 0, -1])# Define the negative z-axis vector + + xs = np.zeros(len(individual)) + ys = np.zeros(len(individual)) + zs = np.zeros(len(individual)) + + for i, (arm_length, arm_yaw, arm_pitch, motor_pitch, motor_yaw, direction) in enumerate(individual): + # Get the rotation matrix from Euler angles + R = euler_to_rotation_matrix(0, motor_pitch, motor_yaw) + transform_from_ENU_to_NED = np.array([[0, 1, 0], [1, 0, 0], [0, 0, -1]]) + R = transform_from_ENU_to_NED @ R + # Transform the negative z-axis using the rotation matrix + transformed_vector = np.dot(R, default_rotation) + # Normalize the resulting vector + transformed_vector = transformed_vector / np.linalg.norm(transformed_vector) + transformed_vector = arm_length * transformed_vector + + xs[i] = transformed_vector[0] + ys[i] = transformed_vector[1] + zs[i] = transformed_vector[2] + + return xs, ys, zs + +def avr_x(individual_or_population): + if len(individual_or_population.shape) == 4: + xs_list = [] + for gen in individual_or_population: + gen_list = [] + for individual in gen: + xs = avr_x(individual) + gen_list.append(xs) + xs_list.append(gen_list) + return np.array(xs_list) + elif len(individual_or_population.shape) == 3: + xs_list = [] + for individual in individual_or_population: + xs = avr_x(individual) + xs_list.append(xs) + return np.array(xs_list) + else: + xs, _, _ = get_xyzs(individual_or_population) + return np.mean(xs) + +def avr_y(individual_or_population): + if len(individual_or_population.shape) == 4: + ys_list = [] + for gen in individual_or_population: + gen_list = [] + for individual in gen: + ys = avr_y(individual) + gen_list.append(ys) + ys_list.append(gen_list) + return np.array(ys_list) + elif len(individual_or_population.shape) == 3: + ys_list = [] + for individual in individual_or_population: + ys = avr_y(individual) + ys_list.append(ys) + return np.array(ys_list) + else: + _, ys, _ = get_xyzs(individual_or_population) + return np.mean(ys) + +def avr_z(individual_or_population): + if len(individual_or_population.shape) == 4: + zs_list = [] + for gen in individual_or_population: + gen_list = [] + for individual in gen: + zs = avr_z(individual) + gen_list.append(zs) + zs_list.append(gen_list) + return np.array(zs_list) + elif len(individual_or_population.shape) == 3: + zs_list = [] + for individual in individual_or_population: + zs = avr_z(individual) + zs_list.append(zs) + return np.array(zs_list) + else: + _, _, zs = get_xyzs(individual_or_population) + return np.mean(zs) + +def var_x(individual_or_population): + if len(individual_or_population.shape) == 4: + xs_list = [] + for gen in individual_or_population: + gen_list = [] + for individual in gen: + xs = avr_x(individual) + gen_list.append(xs) + xs_list.append(gen_list) + return np.array(xs_list) + elif len(individual_or_population.shape) == 3: + xs_list = [] + for individual in individual_or_population: + xs = avr_x(individual) + xs_list.append(xs) + return np.array(xs_list) + else: + xs, _, _ = get_xyzs(individual_or_population) + return np.var(xs) + +def var_y(individual_or_population): + if len(individual_or_population.shape) == 4: + ys_list = [] + for gen in individual_or_population: + gen_list = [] + for individual in gen: + ys = avr_y(individual) + gen_list.append(ys) + ys_list.append(gen_list) + return np.array(ys_list) + elif len(individual_or_population.shape) == 3: + ys_list = [] + for individual in individual_or_population: + ys = avr_y(individual) + ys_list.append(ys) + return np.array(ys_list) + else: + _, ys, _ = get_xyzs(individual_or_population) + return np.var(ys) + +def var_z(individual_or_population): + if len(individual_or_population.shape) == 4: + zs_list = [] + for gen in individual_or_population: + gen_list = [] + for individual in gen: + zs = avr_z(individual) + gen_list.append(zs) + zs_list.append(gen_list) + return np.array(zs_list) + elif len(individual_or_population.shape) == 3: + zs_list = [] + for individual in individual_or_population: + zs = avr_z(individual) + zs_list.append(zs) + return np.array(zs_list) + else: + _, _, zs = get_xyzs(individual_or_population) + return np.var(zs) + +def x_size(individual_or_population): + if len(individual_or_population.shape) == 4: + xs_list = [] + for gen in individual_or_population: + gen_list = [] + for individual in gen: + xs = avr_x(individual) + gen_list.append(xs) + xs_list.append(gen_list) + return np.array(xs_list) + elif len(individual_or_population.shape) == 3: + xs_list = [] + for individual in individual_or_population: + xs = avr_x(individual) + xs_list.append(xs) + return np.array(xs_list) + else: + xs, _, _ = get_xyzs(individual_or_population) + return np.max(xs) - np.min(xs) + +def y_size(individual_or_population): + if len(individual_or_population.shape) == 4: + ys_list = [] + for gen in individual_or_population: + gen_list = [] + for individual in gen: + ys = avr_y(individual) + gen_list.append(ys) + ys_list.append(gen_list) + return np.array(ys_list) + elif len(individual_or_population.shape) == 3: + ys_list = [] + for individual in individual_or_population: + ys = avr_y(individual) + ys_list.append(ys) + return np.array(ys_list) + else: + _, ys, _ = get_xyzs(individual_or_population) + return np.max(ys) - np.min(ys) + +def z_size(individual_or_population): + if len(individual_or_population.shape) == 4: + zs_list = [] + for gen in individual_or_population: + gen_list = [] + for individual in gen: + zs = avr_z(individual) + gen_list.append(zs) + zs_list.append(gen_list) + return np.array(zs_list) + elif len(individual_or_population.shape) == 3: + zs_list = [] + for individual in individual_or_population: + zs = avr_z(individual) + zs_list.append(zs) + return np.array(zs_list) + else: + _, _, zs = get_xyzs(individual_or_population) + return np.max(zs) - np.min(zs) + +def avr_distance_between_points(individual_or_population): + if len(individual_or_population.shape) == 4: + distances_list = [] + for gen in individual_or_population: + gen_list = [] + for individual in gen: + distances = avr_distance_between_points(individual) + gen_list.append(distances) + distances_list.append(gen_list) + return np.array(distances_list) + elif len(individual_or_population.shape) == 3: + distances_list = [] + for individual in individual_or_population: + distances = avr_distance_between_points(individual) + distances_list.append(distances) + return np.array(distances_list) + else: + xs, ys, zs = get_xyzs(individual_or_population) + distances = np.sqrt(np.sum(np.square(xs)) + np.sum(np.square(ys)) + np.sum(np.square(zs))) + return distances + + + + + + diff --git a/src/ariel/ec/drone/inspection/number_sampled_cubes.py b/src/ariel/ec/drone/inspection/number_sampled_cubes.py new file mode 100644 index 000000000..14608c336 --- /dev/null +++ b/src/ariel/ec/drone/inspection/number_sampled_cubes.py @@ -0,0 +1,207 @@ +import numpy as np +import itertools, time +import matplotlib.pyplot as plt +from collections import defaultdict + +from ariel.ec.drone.inspection.animate_evolution import plot_population +from ariel.ec.drone.inspection.drone_visualizer import DroneVisualizer + +def get_first_x_primes(x): + if x < 1: + return [] + + # Estimate upper bound for nth prime using the prime number theorem + # This is a rough estimate and can be adjusted for better performance + n = int(x * (np.log(x) + np.log(np.log(x)))) if x > 5 else 15 + + is_prime = [True] * n + is_prime[0] = is_prime[1] = False + + for i in range(2, int(np.sqrt(n)) + 1): + if is_prime[i]: + for j in range(i * i, n, i): + is_prime[j] = False + + primes = [i for i, prime in enumerate(is_prime) if prime] + return primes[:x] + +class SearchSpace: + def __init__(self, bounds, num_bins): + self.bounds = bounds + self.num_bins = num_bins + self.visits = defaultdict(int) + self.points_in_cubes = defaultdict(list) + self.individuals_in_cubes = defaultdict(list) + self.gen_num_in_cubes = defaultdict(list) + self.bin_sizes = [(b[1] - b[0]) / num_bins if b[0] != b[1] else None for b in bounds] + + def visit(self, point, individual, generation_num): + cube = self._get_cube(point) + cube_key = self._hash_cube(cube) + self.visits[cube_key] += 1 + self.points_in_cubes[cube_key].append(point) + self.individuals_in_cubes[cube_key].append(individual) + self.gen_num_in_cubes[cube_key].append(generation_num) + + def _get_cube(self, point): + cube = [] + for p, b, bin_size in zip(point, self.bounds, self.bin_sizes): + if bin_size is None: + continue # Skip this dimension if bounds are equal + cube_index = int((p - b[0]) / bin_size) + cube.append(cube_index) + return tuple(cube) + + def get_cube_bounds(self, cube): + bounds = [] + for index, (b, bin_size) in zip(cube, zip(self.bounds, self.bin_sizes)): + if bin_size is None: + bounds.append((b[0], b[1])) # If bin_size is None, use the original bounds + else: + lower_bound = b[0] + index * bin_size + upper_bound = lower_bound + bin_size + bounds.append([lower_bound, upper_bound]) + return np.array(bounds) + + def _hash_cube(self, cube): + return hash(cube) + + def percentage_of_sampled_cubes(self): + return len(self.visits) / (self.num_bins ** len(self.bounds)) + + def spread_of_sampled_cubes(self): + points = list(self.visits.keys()) + distances = [np.linalg.norm(np.array(p1) - np.array(p2)) for p1, p2 in itertools.combinations(points, 2)] + return np.mean(distances), np.std(distances) + + def spread_of_points(self): + points = list(itertools.chain(*self.points_in_cubes.values())) + distances = [np.linalg.norm(np.array(p1) - np.array(p2)) for p1, p2 in itertools.combinations(points, 2)] + return np.mean(distances), np.std(distances) + + def most_popular_cube(self): + return max(self.visits, key=self.visits.get), self.visits[max(self.visits, key=self.visits.get)] + + def num_visited_cubes(self): + """ + Return the number of unique cubes visited. + + :return: Number of visited cubes. + """ + return len(self.visits) + +def get_search_space_info(point_data, population_data, bounds, num_bins=100): + point_num_gen, point_pop_size, point_nparams = point_data.shape + num_gen, pop_size, narms, nparams = population_data.shape + assert point_num_gen == num_gen + assert point_pop_size == pop_size + + search_space = SearchSpace(bounds, num_bins) + number_of_sampled_cubes = np.empty(num_gen) + rate_of_sampled_cubes = np.empty(num_gen) + mean_distance,std_distance = np.empty(num_gen), np.empty(num_gen) + prev_num_sampled_cubes = 0 + start = time.time() + for g in range(num_gen): + for i in range(pop_size): + point = point_data[g, i] + individual = population_data[g, i] + + search_space.visit(point, individual, g) + + num_samp_cubes = search_space.num_visited_cubes() + number_of_sampled_cubes[g] = num_samp_cubes + rate_of_sampled_cubes[g] = num_samp_cubes - prev_num_sampled_cubes + prev_num_sampled_cubes = num_samp_cubes + mean_distance[g], std_distance[g] = search_space.spread_of_sampled_cubes() + print(f"Generation {g}, time: {time.time() - start}") + start = time.time() + + return search_space, number_of_sampled_cubes, rate_of_sampled_cubes, mean_distance, std_distance + +def plot_num_sampled_cubes_info(number_of_sampled_cubes, rate_of_sampled_cubes, mean_distance, std_distance): + generations = np.arange(0,len(number_of_sampled_cubes)) + + fig, axs = plt.subplots(1,3) + axs[0].plot(generations, number_of_sampled_cubes, label="Num Sampled Cubes") + axs[0].set_xlabel('Generation') + axs[0].set_ylabel('Num of Sampled Cubes') + axs[0].grid() + axs[1].plot(generations, rate_of_sampled_cubes, label="Density Sampled Cubes") + axs[1].set_xlabel('Generation') + axs[1].set_ylabel('Number of Sampled Cubes Gained') + axs[1].grid() + axs[2].plot(generations, mean_distance, label="Mean Pairwise Distances") + axs[2].fill_between(generations, mean_distance-std_distance, mean_distance+std_distance, alpha=0.2, label='Std Dev Pairwise Distances') + axs[2].set_xlabel('Generation') + axs[2].set_ylabel('Distance between points') + axs[2].legend() + axs[2].grid() + +def plot_most_sampled_cubes(search_space, save_name=None, twod=True): + # Plot a bar chart of the top 10 most sampled cubes + top_10_cubes = sorted(search_space.visits.items(), key=lambda item: item[1], reverse=True)[:10] + + labels = [] + sizes = [] + for i, (hashed_cube, count) in enumerate(top_10_cubes): + + points_in_most_popular_cube = search_space.points_in_cubes[hashed_cube] + individuals_in_most_popular_cube = np.array(search_space.individuals_in_cubes[hashed_cube]) + gen_nums = np.array(search_space.gen_num_in_cubes[hashed_cube]) + + _, indices = np.unique(np.nan_to_num(individuals_in_most_popular_cube), return_index=True, axis=0) + unique_individuals = individuals_in_most_popular_cube[indices] + unique_gen_nums = gen_nums[indices] + + num_unique_individuals = unique_individuals.shape[0] + + cube = search_space._get_cube(points_in_most_popular_cube[0]) + cube_bounds = np.round(search_space.get_cube_bounds(cube), decimals=3) + + if num_unique_individuals > 1: + plot_population(unique_individuals, fitnesses=unique_gen_nums, title=f"Cube {i}, Bounds: {cube_bounds}", include_motor_orientation=1, twod=twod) + if save_name is not None: + plt.savefig(f"{save_name}_cube{i}.png") + elif num_unique_individuals == 1: + visualizer = DroneVisualizer() + if twod: + fig, ax = visualizer.plot_2d(unique_individuals[0], title=f"Cube {i}, Gen {unique_gen_nums[0]}, Bounds: {cube_bounds}") + else: + fig, ax = visualizer.plot_3d(unique_individuals[0], title=f"Cube {i}, Gen {unique_gen_nums[0]}, Bounds: {cube_bounds}") + if save_name is not None: + plt.savefig(f"{save_name}_cube{i}.png") + + labels.append(f"Ucount: {num_unique_individuals}\nCount: {count}") + sizes.append(count) + plt.figure(figsize=(10, 7)) + plt.bar(labels, sizes) + plt.grid() + plt.xlabel('Cube') + plt.ylabel('Number of Points') + plt.title('Top 10 Most Sampled Cubes') + plt.xticks(rotation=45) + if save_name is not None: + plt.savefig(f"{save_name}_bar.png") + +def make_params_unique(self, individual): + sorted_individual = sorted(individual, key=lambda x: self.arm_distance(x, self.arm_min_vals)) + normalized_individual = np.array([self.normalize(arm) for arm in sorted_individual]) + + unique_individual = np.empty(6) + + for param_idx in range(6): + exponents = np.arange(6) * 2 + unique_individual[param_idx] = np.sum(normalized_individual[:,0] / (10 ** exponents)) + + return unique_individual + +def get_unique_individuals(population_data, search_space): + ngens, pop_size, narms, nparams = population_data.shape + unique_individuals = np.empty((ngens, pop_size, nparams)) + for i, gen in enumerate(population_data): + for j, individual in enumerate(gen): + unique_individuals[i, j] = make_params_unique(search_space, individual) + + return unique_individuals + diff --git a/src/ariel/ec/drone/inspection/plot_diversity.py b/src/ariel/ec/drone/inspection/plot_diversity.py new file mode 100644 index 000000000..c435caa46 --- /dev/null +++ b/src/ariel/ec/drone/inspection/plot_diversity.py @@ -0,0 +1,76 @@ +from matplotlib import pyplot as plt +import numpy as np +from ariel.ec.drone.evaluators.edit_distance import compute_individual_population_edit_distance + +def plot_diversity(ax, gens, parameter_limits=None): + """ + Plot diversity across generations. + + Args: + ax: Matplotlib axis to plot on + gens: List of generations, each containing population data + parameter_limits: (min_vals, max_vals) tuple for distance calculation + """ + # Default parameter limits if not provided + if parameter_limits is None: + min_vals = np.array([0.09, 0, 0, 0, 0, 0]) + max_vals = np.array([0.4, 2*np.pi, 2*np.pi, 2*np.pi, 2*np.pi, 1]) + else: + min_vals, max_vals = parameter_limits + + diversity = np.zeros(len(gens)) + for g, pop in enumerate(gens): + novelties = np.zeros(len(pop)) + for i, ind in enumerate(pop): + novelties[i] = compute_individual_population_edit_distance(ind, pop, min_vals, max_vals) + + diversity[g] = np.mean(novelties) + + ax.plot(diversity) + ax.set_title('Diversity') + ax.set_xlabel('Generation') + ax.set_ylabel('Diversity') + ax.grid() + +def plot_diversity_from_amalgamated(ax, amalgamated, title='Diversity', label=None, color='b', + min_max_params=np.array([[0.09,0.4], [0, 2*np.pi], [0, 2*np.pi], [0, 2*np.pi], [0, 2*np.pi], [0,1]])): + """ + Plot diversity across generations from multiple experimental runs. + + Args: + ax: Matplotlib axis to plot on + amalgamated: List of experimental runs, each containing generations + title: Plot title + label: Legend label + color: Plot color + min_max_params: Parameter bounds array of shape (n_params, 2) + """ + # Extract min/max values from parameter bounds + min_vals = min_max_params[:, 0] + max_vals = min_max_params[:, 1] + + diversities = [] + for exp in amalgamated: + diversity = np.zeros(len(exp)) + for g, pop in enumerate(exp): + novelties = np.zeros(len(pop)) + for i, ind in enumerate(pop): + novelties[i] = compute_individual_population_edit_distance(ind, pop, min_vals, max_vals) + + diversity[g] = np.mean(novelties) + + diversities.append(diversity) + + mu = np.mean(diversities, axis=0) + std = np.std(diversities, axis=0) + + ax.plot(mu, label=label, color=color) + ax.fill_between(np.arange(len(mu)), mu-std, mu+std, alpha=0.2, color=color) + ax.set_title(title) + ax.set_xlabel('Generation') + ax.set_ylabel('Diversity') + ax.grid(True) + if label is not None: + ax.legend() + + diff --git a/src/ariel/ec/drone/inspection/plot_fitness.py b/src/ariel/ec/drone/inspection/plot_fitness.py new file mode 100644 index 000000000..f21fc4185 --- /dev/null +++ b/src/ariel/ec/drone/inspection/plot_fitness.py @@ -0,0 +1,92 @@ + +""" +Fitness plotting utilities for evolutionary runs. + +This module provides basic fitness visualization functionality for evolutionary +algorithms. It creates statistical plots showing mean, max, min, and standard +deviation of fitness over generations. + +# TODO: [HIGH] Add comprehensive docstrings with parameter descriptions +# TODO: [HIGH] Add proper type hints for all functions +# TODO: [MEDIUM] Standardize parameter naming (fitness_data vs population_data) +# TODO: [MEDIUM] Add input validation and error handling +# TODO: [MEDIUM] Expand functionality to match other visualization modules +# TODO: [LOW] Add more plot styling options and customization +""" + +import matplotlib.pyplot as plt +import numpy as np +from typing import Optional, Union +import numpy.typing as npt + +def plot_fitness( + ax, + fitness_data: npt.NDArray, + gen_line: Optional[int] = None, + log: bool = False, + pltmax: bool = True, + label: Optional[str] = None, + color: Optional[str] = None, + legend: bool = True +) -> None: + """ + Plot fitness evolution statistics over generations. + + Args: + ax: Matplotlib axes to plot on + fitness_data: Array of shape (n_generations, pop_size) with fitness values + gen_line: Optional generation to highlight with vertical line + log: Whether to apply log transformation to fitness values + pltmax: Whether to plot max and min fitness lines + label: Optional label prefix for legend entries + color: Optional color for plot elements + legend: Whether to show legend + + # TODO: [HIGH] Add proper error handling for invalid inputs + # TODO: [MEDIUM] Add parameter validation (check array shapes, etc.) + # TODO: [MEDIUM] Consider returning plot elements for further customization + """ + # TODO: [HIGH] Replace in-place modification with copy to avoid side effects + # ignore infinities and nans + fitness_data[fitness_data == -np.inf] = np.nan + fitness_data[fitness_data == np.inf] = np.nan + if log: + # TODO: [MEDIUM] Add validation that fitness values are negative for log transform + fitness_data = -np.log(-fitness_data) + + # Calculate statistics across population for each generation + means = np.nanmean(fitness_data, axis=1) + stds = np.nanstd(fitness_data, axis=1) + maxs = np.nanmax(fitness_data, axis=1) # TODO: [LOW] Rename to max_values for clarity + mins = np.nanmin(fitness_data, axis=1) # TODO: [LOW] Rename to min_values for clarity + + generations = np.arange(len(fitness_data)) + + # TODO: [MEDIUM] Use f-strings for cleaner string formatting + label1 = label+" Mean Fitness" if label != None else 'Mean Fitness' + label2 = label+" Max Fitness" if label != None else 'Max Fitness' + label3 = label+" Min Fitness" if label != None else 'Min Fitness' + ax.plot(generations, means, label=label1, color=color) + if pltmax: + ax.plot(generations, maxs, linestyle='--', label=label2, color=color) + ax.plot(generations, mins, linestyle='--', label=label3, color=color) + ax.fill_between(generations, means-stds, means+stds, alpha=0.2, color=color) + + # Add vertical line to highlight specific generation if requested + if gen_line != None: # TODO: [LOW] Use 'is not None' instead of '!= None' + the_max = np.max(maxs) + the_min = np.min(mins) # Fixed: was np.max(mins) which was incorrect + ax.plot([gen_line, gen_line], [the_min, the_max], color="black") + + # Set up axes labels and styling + ax.set_xlabel('Generation') + ax.set_ylabel('Fitness') + if legend: + ax.legend() + ax.grid() + + # TODO: [MEDIUM] Make axis limits configurable or computed more intelligently + # ax.set_xlim([np.min(means-stds), np.max(maxs)]) # TODO: [LOW] Remove commented code + mx = np.nanmax(maxs) * 1.1 if np.nanmax(maxs) > 0 else np.nanmax(maxs) * 0.9 + ax.set_ylim([np.nanmin(means), mx]) + diff --git a/src/ariel/ec/drone/inspection/plot_space.py b/src/ariel/ec/drone/inspection/plot_space.py new file mode 100644 index 000000000..ca06a60d8 --- /dev/null +++ b/src/ariel/ec/drone/inspection/plot_space.py @@ -0,0 +1,498 @@ +import os, pickle +import matplotlib.pyplot as plt +from bokeh.plotting import figure, show, output_file, save, curdoc +from bokeh.layouts import gridplot, column, row +from bokeh.io import export_png +from bokeh.models import ColorBar, LinearColorMapper, ColumnDataSource, CustomJS, TapTool, Div, HoverTool, BasicTicker, PrintfTickFormatter +from bokeh.transform import linear_cmap +import numpy as np +from scipy.stats import gaussian_kde +from scipy.interpolate import griddata +from matplotlib import gridspec +from matplotlib.pyplot import hexbin + +from ariel.ec.drone.inspection.drone_visualizer import DroneVisualizer + +def generate_individual_images(population_data, fitnesss_data, output_folder, include_motor_orientation=True, twod=True): + """ + Generates and saves images for each individual in the population data. + + Args: + population_data (list): List of individuals in the population. + output_folder (str): Folder to save the images. + """ + if not os.path.exists(output_folder): + os.makedirs(output_folder) + + for gen_idx, generation in enumerate(population_data): + for ind_idx, individual in enumerate(generation): + # Generate the image (this is just a placeholder, replace with actual image generation) + + visualizer = DroneVisualizer() + if twod: + fig, ax = visualizer.plot_2d(individual, title=f"Gen {gen_idx}: Fitness {fitnesss_data[gen_idx, ind_idx]:.2f}") + else: + fig, ax = visualizer.plot_3d(individual, title=f"Gen {gen_idx}: Fitness {fitnesss_data[gen_idx, ind_idx]:.2f}") + image_path = os.path.join(output_folder, f"gen{gen_idx}_ind{ind_idx}.png") + plt.savefig(image_path) + plt.close() + +def plot_space_interactive(data, fitness, param_names=None, save_dir=None, density=True): + ngen, pop_size, nparams = data.shape + all_individuals = data.reshape(ngen * pop_size, nparams) + + image_dir = save_dir+'html/' + 'images/' + dir = save_dir+'html/' + print(image_dir) + print(dir) + if not os.path.exists(dir): + os.makedirs(dir) + + + plots = [] + for i in range(nparams-1): + rows = [] + for j in range(nparams): + if i < j: + x = all_individuals[:, i] + y = all_individuals[:, j] + + slope, intercept = np.polyfit(x, y, 1) + trendline_y = [slope * xi + intercept for xi in x] + + # Interpolate the fitness data + + if density: + xy = np.vstack([x, y]) + xi, yi = np.linspace(x.min(), x.max(), 100), np.linspace(y.min(), y.max(), 100) + xi, yi = np.meshgrid(xi, yi) + + try: + zi = gaussian_kde(xy)(np.vstack([xi.flatten(), yi.flatten()])) + except: + zi = np.zeros(xi.shape) + + else: + grid_x, grid_y = np.mgrid[x.min():x.max():100j, y.min():y.max():100j] + points = np.vstack([x, y]).T + values = fitness.flatten() + grid_z = griddata(points, values, (grid_x, grid_y), method='cubic') + + # Handle NaN values in the interpolated grid + grid_z = np.nan_to_num(grid_z, nan=np.nanmin(values)) + + # Clear the current document + curdoc().clear() + + # Create a figure + p = figure(title=f'Scatter Plot of {param_names[i]} vs {param_names[j]}' if param_names else f'Scatter Plot of Param {i} vs Param {j}', + x_axis_label=param_names[i] if param_names else f'Param {i}', + y_axis_label=param_names[j] if param_names else f'Param {j}', + width=900, height=700, tools="tap,hover") + + # Plot background + if density: + # Plot density background + density_mapper = LinearColorMapper(palette="Magma256", low=zi.min(), high=zi.max()) + p.image(image=[zi.reshape(xi.shape)], x=x.min(), y=y.min(), dw=x.max()-x.min(), dh=y.max()-y.min(), color_mapper=density_mapper) + + # Add color bar for density + density_color_bar = ColorBar(color_mapper=density_mapper, ticker=BasicTicker(), + formatter=PrintfTickFormatter(format="%d"), + label_standoff=12, border_line_color=None, location=(0,0), + title="Density") + p.add_layout(density_color_bar, 'right') + else: + # Plot Fitness background + fitness_mapper = LinearColorMapper(palette="Magma256", low=np.nanmin(fitness), high=np.nanmax(fitness)) + p.image(image=[grid_z.T], x=x.min(), y=y.min(), dw=x.max()-x.min(), dh=y.max()-y.min(), color_mapper=fitness_mapper) + + # Add color bar for fitness + fitness_color_bar = ColorBar(color_mapper=fitness_mapper, ticker=BasicTicker(), + formatter=PrintfTickFormatter(format="%d"), + label_standoff=12, border_line_color=None, location=(0,0), + title="Fitness") + p.add_layout(fitness_color_bar, 'right') + + # Color points by their index + images = [os.path.abspath(os.path.join(image_dir, f'gen{g}_ind{i}.png')) for g in range(ngen) for i in range(pop_size)] + source = ColumnDataSource(data={'x': x, 'y': y, + 'gen': np.repeat(np.arange(ngen), pop_size), + 'ind': np.tile(np.arange(pop_size), ngen), + 'fitness': fitness.flatten(), + 'images': images}) + # Create a color mapper for generations + gen_mapper = LinearColorMapper(palette="Viridis256", low=0, high=ngen-1) + p.scatter('x', 'y', color={'field': 'gen', 'transform': gen_mapper}, source=source) + # p.line(x, trendline_y, line_width=2, color="red", legend_label="Trendline") + # Add color bar for generations + gen_color_bar = ColorBar(color_mapper=gen_mapper, ticker=BasicTicker(), + formatter=PrintfTickFormatter(format="%d"), + label_standoff=12, border_line_color=None, location=(0,0), + title="Generation") + p.add_layout(gen_color_bar, 'right') + + hover = p.select(dict(type=HoverTool)) + hover.tooltips = """ +
+
+ x:@x, y:@y, F:@fitness, G:@gen +
+
+ """ + + # Create a Div to display the image + div = Div(width=700, height=700) + + # CustomJS callback to update the image in the Div + callback = CustomJS(args=dict(source=source, image_div=div), code=""" + const indices = cb_data.index.indices; + if (indices.length > 0) { + const index = indices[0]; // Select the first index + const image_url = source.data['images'][index]; + image_div.text = ''; + } else { + image_div.text = ''; + } + """) + + # Add the callback to the HoverTool + hover.callback = callback + + layout = row(p, div) + rows.append(layout) + + # Save each pair in a separate figure + output_file(f'{dir}scatter_{param_names[i]}_{param_names[j]}.html') + save(layout) + show(layout) + plots.append(row) + +def plot_space(data, param_names=None, save_name=None, fitnesses=None, points=True, interpolation_method='tricontourf', point_size=5): + print(data.shape) + if fitnesses is not None: + print(fitnesses.shape) + ngen, pop_size, nparams = data.shape + all_individuals = data.reshape(ngen * pop_size, nparams) + + # Create a grid spec for the combined figure and color bars + fig = plt.figure(figsize=(15, 15)) + gs = gridspec.GridSpec(nparams-1, nparams-1) # Adjust grid spec to remove unused rows + + axes = np.empty((nparams-1, nparams-1), dtype=object) + for i in range(nparams-1): + for j in range(nparams): + if i < j: # Only plot above the diagonal + ax = fig.add_subplot(gs[i, j-1]) # Adjust indices to fit the new grid spec + axes[i, j-1] = ax + x = all_individuals[:, i] + y = all_individuals[:, j] + xy = np.vstack([x, y]) + if fitnesses is not None: + fitnesses_flat = fitnesses.reshape(ngen * pop_size) + filtered = np.logical_or(~np.any(np.isnan(xy), axis=0), np.isnan(fitnesses_flat)) + else: + filtered = ~np.any(np.isnan(xy), axis=0) + + x = x[filtered] + y = y[filtered] + if fitnesses is not None: + fitnesses_filtered = fitnesses_flat[filtered] + xy = xy[:,filtered] + + # assert len(x) == len(y) == len(fitnesses_filtered) + if fitnesses is not None: + if interpolation_method == 'tricontourf': + try: + density_plot = ax.tricontourf(x, y, fitnesses_filtered, cmap='viridis') + except: + pass + elif interpolation_method == 'hexbin': + hexd = ax.hexbin(x, y, C=fitnesses_filtered, gridsize=20, cmap='viridis') + ax.set(xlim=(min(x),max(x)), ylim=(min(y),max(y))) + elif interpolation_method == 'linear': + try: + xi, yi = np.linspace(x.min(), x.max(), 100), np.linspace(y.min(), y.max(), 100) + xi, yi = np.meshgrid(xi, yi) + zi = griddata((x, y), fitnesses_filtered, (xi, yi), method='linear') + density_plot = ax.contourf(xi, yi, zi, levels=100, cmap='viridis') + except: + pass + + else: + print('Interpolation method not recognized.') + return + else: + xi, yi = np.linspace(x.min(), x.max(), 100), np.linspace(y.min(), y.max(), 100) + xi, yi = np.meshgrid(xi, yi) + zi = gaussian_kde(xy)(np.vstack([xi.flatten(), yi.flatten()])) + density_plot = ax.contourf(xi, yi, zi.reshape(xi.shape), levels=100, cmap='viridis') + if points: + colors = np.repeat(np.arange(ngen).reshape((1,ngen)),pop_size,axis=1)[0] + colors = colors[filtered] + scatter = ax.scatter(x, y, c=colors, cmap='coolwarm', edgecolor='k', s=point_size) + + if param_names is not None: + ax.set_xlabel(param_names[i]) + ax.set_ylabel(param_names[j]) + else: + ax.set_xlabel(f'Param {i}') + ax.set_ylabel(f'Param {j}') + ax.set_xticks([]) + ax.set_yticks([]) + + # Plot each pair in a separate figure + fig_sep, ax_sep = plt.subplots(figsize=(8, 6)) + if fitnesses is None: + density_plot_sep = ax_sep.contourf(xi, yi, zi.reshape(xi.shape), levels=100, cmap='viridis') + else: + if interpolation_method == 'tricontourf': + try: + density_plot_sep = ax_sep.tricontourf(x, y, fitnesses_filtered, cmap='viridis') + except: + pass + elif interpolation_method == 'linear': + xi, yi = np.linspace(x.min(), x.max(), 100), np.linspace(y.min(), y.max(), 100) + xi, yi = np.meshgrid(xi, yi) + zi = griddata((x, y), fitnesses_filtered, (xi, yi), method='linear') + try: + density_plot_sep = ax_sep.contourf(xi, yi, zi, levels=100, cmap='viridis') + except: + pass + + elif interpolation_method == 'hexbin': + hexd_sep = ax_sep.hexbin(x, y, C=fitnesses_filtered, gridsize=20, cmap='viridis') + ax_sep.set(xlim=(min(x),max(x)), ylim=(min(y),max(y))) + if points: + zi = np.repeat(np.arange(ngen).reshape((1,ngen)),pop_size,axis=1)[0] + zi = zi[filtered] + scatter_sep = ax_sep.scatter(x, y, c=zi if fitnesses is not None else colors, cmap='coolwarm', edgecolor='k', s=point_size) + if param_names is not None: + ax_sep.set_xlabel(param_names[i]) + ax_sep.set_ylabel(param_names[j]) + ax_sep.set_title(f'Scatter Plot of {param_names[i]} vs {param_names[j]}') + else: + ax_sep.set_xlabel(f'Param {i}') + ax_sep.set_ylabel(f'Param {j}') + ax_sep.set_title(f'Scatter Plot of Param {i} vs Param {j}') + + # Add color bars for the separate figure on the right + fig_sep.subplots_adjust(right=0.7) # Adjust the right margin to make space for color bars + if fitnesses is None: + cbar_ax1_sep = fig_sep.add_axes([0.72, 0.1, 0.03, 0.8]) + fig_sep.colorbar(density_plot_sep, cax=cbar_ax1_sep, orientation='vertical', label='Density') + cbar_ax2_sep = fig_sep.add_axes([0.82, 0.1, 0.03, 0.8]) + + if points: + fig_sep.colorbar(scatter_sep, cax=cbar_ax2_sep, orientation='vertical', label='Fitness' if fitnesses is not None else 'Index') + # elif: + # fig_sep.colorbar(hexd_sep, cax=cbar_ax2_sep, orientation='vertical', label='Fitness' if fitnesses is not None else 'Index') + if save_name is not None: + plt.savefig(f'{save_name}_scatter_{param_names[i]}_{param_names[j]}.png') + + # Add color bars at the bottom for the combined figure + fig.subplots_adjust(bottom=0.2) + cbar_ax1 = fig.add_axes([0.55, 0.1, 0.35, 0.02]) + if points: + cbar_ax2 = fig.add_axes([0.1, 0.1, 0.35, 0.02]) + + if fitnesses is None: + fig.colorbar(density_plot, cax=cbar_ax1, orientation='horizontal', label='Density') + else: + if interpolation_method == 'hexbin': + fig.colorbar(hexd, cax=cbar_ax1, orientation='horizontal', label='Fitness') + else: + pass + + if points: + fig.colorbar(scatter, cax=cbar_ax2, orientation='horizontal', label='Generation') + if save_name is not None: + fig.savefig(f'{save_name}_scatter_combined.png') + # make animation of points over time + # plot 3d scatter of points, color represents generation + # plot animated 3d scatter of pointsx + + # other options for plots: PCA, t-SNE, UMAP, MDS, LDA, Isomap, LLE, Laplacian Eigenmaps, Hessian Eigenmaps, Diffusion Maps, Spectral Embedding, Neighborhood Components Analysis + +def plot_specific_morphological_descriptors_space(population_data, md_funcs, md_names, save_name=None, fitnesses=None, points=True, interpolation_method='tricontourf', point_size=5): + + # Get the data for the morphological descriptors + data = np.empty((population_data.shape[0], population_data.shape[1], len(md_funcs))) + for i, md_func in enumerate(md_funcs): + data[:,:,i] = md_func(population_data) + + # Save the data to a file + if save_name is not None: + os.makedirs(os.path.dirname(save_name), exist_ok=True) + try: + np.save(save_name+".npy", data) + except: + with open(save_name+".pkl", 'wb') as f: + pickle.dump(data, f) + # Plot the data + plot_space(data, param_names=md_names, save_name=save_name, fitnesses=fitnesses, points=points, interpolation_method=interpolation_method, point_size=point_size) + + +def plot_morphological_descriptors_space(population_data, save_name=None, twod=True, hover=False, fitnesses=None, points=True): + + from ariel.ec.drone.inspection.morphological_descriptors.area import compute_area + from ariel.ec.drone.inspection.morphological_descriptors.avr_arm_length import compute_avr_arm_length + from ariel.ec.drone.inspection.morphological_descriptors.mass import compute_total_mass + from ariel.ec.drone.inspection.morphological_descriptors.num_arms import compute_num_arms + from ariel.ec.drone.inspection.morphological_descriptors.proportion import compute_proportion + from ariel.ec.drone.inspection.morphological_descriptors.central_symmetry import compute_symmetry + from ariel.ec.drone.inspection.morphological_descriptors.var_arm_length import compute_var_arm_length + from ariel.ec.drone.inspection.morphological_descriptors.volume import compute_volume + from ariel.ec.drone.inspection.morphological_descriptors.hovering_info import compute_hovering_info + + num_arms_data = compute_num_arms(population_data) + mass_data = compute_total_mass(population_data) + avr_arm_length_data = compute_avr_arm_length(population_data) + var_arm_length_data = compute_var_arm_length(population_data) + proportion_data = compute_proportion(population_data) + symmetry_data = compute_symmetry(population_data) + if twod: + space_data = compute_area(population_data) + else: + space_data = compute_volume(population_data) + if hover: + hovering_data = compute_hovering_info(population_data) + can_hover = hovering_data[:,0] + weight_to_thrust = hovering_data[:,1] + input_cost = hovering_data[:,2] + rank_controlability = hovering_data[:,3] + controllability = hovering_data[:,4] + + if len(population_data.shape) == 4: + data = np.concatenate([np.expand_dims(num_arms_data, axis=2), + np.expand_dims(mass_data, axis=2), + np.expand_dims(avr_arm_length_data, axis=2), + np.expand_dims(var_arm_length_data, axis=2), + np.expand_dims(proportion_data, axis=2), + np.expand_dims(symmetry_data, axis=2), + np.expand_dims(space_data, axis=2), + np.expand_dims(can_hover, axis=2), + np.expand_dims(weight_to_thrust, axis=2), + np.expand_dims(input_cost, axis=2), + np.expand_dims(rank_controlability, axis=2), + np.expand_dims(controllability, axis=2)], axis=2) + elif len(population_data.shape) == 3: + data = np.expand_dims(np.concatenate([np.expand_dims(num_arms_data, axis=1), + np.expand_dims(mass_data, axis=1), + np.expand_dims(avr_arm_length_data, axis=1), + np.expand_dims(var_arm_length_data, axis=1), + np.expand_dims(proportion_data, axis=1), + np.expand_dims(symmetry_data, axis=1), + np.expand_dims(space_data, axis=1), + np.expand_dims(can_hover, axis=1), + np.expand_dims(weight_to_thrust, axis=1), + np.expand_dims(input_cost, axis=1), + np.expand_dims(rank_controlability, axis=1), + np.expand_dims(controllability, axis=1)], axis=1), axis=0) + + param_names = ['Number of Arms', 'Total Mass', 'Avr Arm Length', 'Variance of Arm lengths', + 'Proportion', 'Symmetry', 'Volume', 'Can Hover', 'Weight to Thrust Ratio', 'Input Cost', + 'Rank Controlability', 'Controllability'] + else: + if len(population_data.shape) == 4: + data = np.concatenate([np.expand_dims(num_arms_data, axis=2), + np.expand_dims(mass_data, axis=2), + np.expand_dims(avr_arm_length_data, axis=2), + np.expand_dims(var_arm_length_data, axis=2), + np.expand_dims(proportion_data, axis=2), + np.expand_dims(symmetry_data, axis=2), + np.expand_dims(space_data, axis=2)], axis=2) + elif len(population_data.shape) == 3: + data = np.expand_dims(np.concatenate([np.expand_dims(num_arms_data, axis=1), + np.expand_dims(mass_data, axis=1), + np.expand_dims(avr_arm_length_data, axis=1), + np.expand_dims(var_arm_length_data, axis=1), + np.expand_dims(proportion_data, axis=1), + np.expand_dims(symmetry_data, axis=1), + np.expand_dims(space_data, axis=1)], axis=1), axis=0) + + param_names = ['Number of Arms', 'Total Mass', 'Avr Arm Length', 'Variance of Arm lengths', + 'Proportion', 'Symmetry', 'Volume'] + + if twod: + param_names[6] = 'Area' + else: + param_names[6] = 'Volume' + + plot_space(data, param_names=param_names, save_name=save_name, points=points, fitnesses=fitnesses) + + +def show_html_files_in_directory(directory): + # List all files in the directory + files = os.listdir(directory) + + # Filter to include only HTML files + html_files = [f for f in files if f.endswith('.html')] + + for html_file in html_files: + # Construct the full file path + file_path = os.path.join(directory, html_file) + + # Output the file + output_file(file_path) + + # Create a simple plot (or load your plot from the file) + p = figure(title="HTML File: " + html_file) + + # Show the plot + show(p) + +import numpy as np +import matplotlib.pyplot as plt +from mpl_toolkits.mplot3d import Axes3D +from matplotlib.animation import FuncAnimation +from matplotlib import cm + +def plot_space_time(population_data, evaluator, xlabel="Area", ylabel="Proportion", zlabel="Mass"): + ngens, pop_size, narms, nparms = population_data.shape + points = np.empty((ngens, pop_size, 3)) + for i, pop in enumerate(population_data): + points[i] = evaluator.get_points_from_pop(pop) + + # Function to update the scatter plot and text + def update(num, data, scatter, text, colormap): + # Accumulate points up to the current frame + current_data = data[:num+1].reshape(-1, 3) # Combine all points from previous frames + colors = colormap(np.linspace(0, 1, num+1).repeat(pop_size)) # Color gradient over frames + + scatter._offsets3d = (current_data[:, 0], current_data[:, 1], current_data[:, 2]) + scatter.set_color(colors) # Apply the color map + + # Update the text to show the current generation/frame + text.set_text(f'Generation: {num+1}') + + return scatter, text + + # Set up the figure and 3D axis + fig = plt.figure() + ax = fig.add_subplot(111, projection='3d') + + # Set axis limits (optional, depending on your data) + ax.set_xlim(0, 1) + ax.set_ylim(0, 1) + ax.set_zlim(0, 1) + + ax.set_xlabel(xlabel) + ax.set_ylabel(ylabel) + ax.set_zlabel(zlabel) + # Initialize scatter plot with no points (start with an empty plot) + scatter = ax.scatter([], [], []) + + # Add initial text for generation + text = fig.text(0.5, 0.95, '', ha='center', va='top', fontsize=14, color='black') + + # Create a colormap (using 'viridis' or any other colormap of your choice) + colormap = cm.get_cmap('plasma') + + # Create the animation, accumulating points and changing color with each frame + ani = FuncAnimation(fig, update, frames=ngens, + fargs=(points, scatter, text, colormap), interval=200, blit=False) + + ani.save('animation.mp4', writer='ffmpeg', fps=10) + # Show the plot + plt.show() \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/population_filtering.py b/src/ariel/ec/drone/inspection/population_filtering.py new file mode 100644 index 000000000..6b49c26cc --- /dev/null +++ b/src/ariel/ec/drone/inspection/population_filtering.py @@ -0,0 +1,424 @@ +""" +Population selection and filtering utilities for evolutionary visualization. + +This module provides functions for selecting, filtering, and ranking individuals +from evolutionary populations based on fitness and similarity metrics. +""" + +import numpy as np +from typing import List, Tuple, Optional, Union +import numpy.typing as npt + +# Import edit distance functions +from ariel.ec.drone.evaluators.edit_distance import ( + compute_edit_distance, + compute_individual_population_edit_distance +) + + +def filter_by_unique_individuals( + population: npt.NDArray, + fitnesses: npt.NDArray, + similarity_threshold: float, + parameter_limits: Optional[npt.NDArray] = None, + max_num_arms: int = 6, + fitness_threshold: Optional[float] = None, + reverse: bool = False +) -> Tuple[npt.NDArray, npt.NDArray]: + """ + Filter population to keep only unique individuals based on similarity threshold. + + Args: + population: Array of individuals + fitnesses: Array of fitness values + similarity_threshold: Maximum similarity allowed between selected individuals + parameter_limits: Parameter bounds for edit distance calculation + max_num_arms: Maximum number of arms for distance normalization + fitness_threshold: Minimum fitness threshold for inclusion + reverse: If True, sort by ascending fitness (worst first) + + Returns: + Tuple of (selected_population, selected_fitnesses) + """ + # Apply fitness threshold filter + if fitness_threshold is not None: + fitnesses = np.array(fitnesses) + mask = fitnesses > fitness_threshold + population = population[mask] + fitnesses = fitnesses[mask] + + # Default parameter limits if not provided + if parameter_limits is None: + parameter_limits = np.array([ + [0.09, 0.4], # magnitude + [0, 2*np.pi], # azimuth rotation + [0, 2*np.pi], # azimuth pitch + [0, 2*np.pi], # motor rotation + [0, 2*np.pi], # motor pitch + [0, 1] # direction + ]) + + # Extract min/max values from parameter_limits + if parameter_limits.shape[1] == 2: + min_vals = parameter_limits[:, 0] + max_vals = parameter_limits[:, 1] + else: + raise ValueError("parameter_limits should have shape (n_params, 2)") + + selected_population = [] + selected_fitnesses = [] + + # Calculate diversity-adjusted fitness + updated_fitnesses = [] + for ind, fitness in zip(population, fitnesses): + distance = compute_individual_population_edit_distance(ind, population, min_vals, max_vals) + distance = min(distance, max_num_arms - 0.001) # Clamp to valid range + + # Add diversity bonus (normalized distance) + updated_fitness = fitness + distance / max_num_arms + updated_fitnesses.append(updated_fitness) + + updated_fitnesses = np.array(updated_fitnesses) + + # Sort by updated fitness + if reverse: + sorted_indices = np.argsort(updated_fitnesses) + else: + sorted_indices = np.argsort(updated_fitnesses)[::-1] + + # Select diverse individuals + for idx in sorted_indices: + ind1 = population[idx] + is_similar = False + + # Check similarity with already selected individuals + for selected_ind in selected_population: + if compute_edit_distance(ind1, selected_ind, min_vals, max_vals) < similarity_threshold: + is_similar = True + break + + if not is_similar: + selected_population.append(ind1) + selected_fitnesses.append(updated_fitnesses[idx]) + + return np.array(selected_population), np.array(selected_fitnesses) + + +def get_top_k_individuals( + population: Union[npt.NDArray, List[npt.NDArray]], + fitnesses: Union[npt.NDArray, List[npt.NDArray]], + k: int, + reverse: bool = False, + similarity_threshold: Optional[float] = None, + parameter_limits: Optional[npt.NDArray] = None, + max_num_arms: int = 8 +) -> Union[Tuple[List, List], Tuple[List, List, List]]: + """ + Select the top k individuals from a population or across generations. + + Args: + population: Individual population array or list of generation arrays + fitnesses: Individual fitness array or list of generation fitness arrays + k: Number of individuals to select + reverse: If True, select worst individuals instead of best + similarity_threshold: If provided, ensure selected individuals are diverse + parameter_limits: Parameter bounds for similarity calculation + max_num_arms: Maximum number of arms for distance normalization + + Returns: + If similarity_threshold is None: (selected_population, selected_fitnesses) + If similarity_threshold is not None: (selected_population, selected_fitnesses, selected_indices) + """ + # Check if we have multiple generations + is_multi_generation = isinstance(population, list) or ( + isinstance(population, np.ndarray) and population.ndim > 2 + ) + + if similarity_threshold is not None: + return _get_top_k_diverse_individuals( + population, fitnesses, k, reverse, similarity_threshold, + parameter_limits, max_num_arms, is_multi_generation + ) + else: + return _get_top_k_simple( + population, fitnesses, k, reverse, is_multi_generation + ) + + +def _get_top_k_diverse_individuals( + population: Union[npt.NDArray, List[npt.NDArray]], + fitnesses: Union[npt.NDArray, List[npt.NDArray]], + k: int, + reverse: bool, + similarity_threshold: float, + parameter_limits: Optional[npt.NDArray], + max_num_arms: int, + is_multi_generation: bool +) -> Tuple[List, List, List]: + """Helper function for diverse individual selection.""" + # Default parameter limits + if parameter_limits is None: + parameter_limits = np.array([ + [0.09, 0.4], [0, 2*np.pi], [0, 2*np.pi], + [0, 2*np.pi], [0, 2*np.pi], [0, 1] + ]) + + # Extract min/max values from parameter_limits + if parameter_limits.shape[1] == 2: + min_vals = parameter_limits[:, 0] + max_vals = parameter_limits[:, 1] + else: + raise ValueError("parameter_limits should have shape (n_params, 2)") + + selected_population = [] + selected_fitnesses = [] + selected_indices = [] + + # Create list of all individuals with their fitness and indices + all_individuals = [] + + if is_multi_generation: + for gen_idx, (generation, gen_fitnesses) in enumerate(zip(population, fitnesses)): + for ind_idx, (ind, fitness) in enumerate(zip(generation, gen_fitnesses)): + # Calculate diversity-adjusted fitness + distance = compute_individual_population_edit_distance(ind, generation, min_vals, max_vals) + distance = min(distance, max_num_arms - 0.001) # Clamp to valid range + updated_fitness = fitness + distance / max_num_arms + all_individuals.append((updated_fitness, gen_idx, ind_idx, ind, fitness)) + else: + for ind_idx, (ind, fitness) in enumerate(zip(population, fitnesses)): + distance = compute_individual_population_edit_distance(ind, population, min_vals, max_vals) + distance = min(distance, max_num_arms - 0.001) # Clamp to valid range + updated_fitness = fitness + distance / max_num_arms + all_individuals.append((updated_fitness, 0, ind_idx, ind, fitness)) + + # Sort by updated fitness + all_individuals.sort(key=lambda x: x[0], reverse=not reverse) + + # Select diverse individuals + for updated_fitness, gen_idx, ind_idx, ind, original_fitness in all_individuals: + if len(selected_population) >= k: + break + + is_similar = False + for selected_ind in selected_population: + if compute_edit_distance(ind, selected_ind, min_vals, max_vals) < similarity_threshold: + is_similar = True + break + + if not is_similar: + selected_population.append(ind) + selected_fitnesses.append(original_fitness) + selected_indices.append((gen_idx, ind_idx)) + + return selected_population, selected_fitnesses, selected_indices + + +def _get_top_k_simple( + population: Union[npt.NDArray, List[npt.NDArray]], + fitnesses: Union[npt.NDArray, List[npt.NDArray]], + k: int, + reverse: bool, + is_multi_generation: bool +) -> Tuple[List, List, List]: + """Helper function for simple top-k selection without diversity constraint.""" + all_individuals = [] + + if is_multi_generation: + for gen_idx, gen_fitnesses in enumerate(fitnesses): + for ind_idx, fitness in enumerate(gen_fitnesses): + all_individuals.append((fitness, gen_idx, ind_idx)) + else: + for ind_idx, fitness in enumerate(fitnesses): + all_individuals.append((fitness, 0, ind_idx)) + + # Sort by fitness + all_individuals.sort(key=lambda x: x[0], reverse=not reverse) + + # Select top k + top_k = all_individuals[:k] + + if is_multi_generation: + top_k_population = [population[gen_idx][ind_idx] for _, gen_idx, ind_idx in top_k] + else: + top_k_population = [population[ind_idx] for _, _, ind_idx in top_k] + + top_k_fitnesses = [fitness for fitness, _, _ in top_k] + top_k_indices = [(gen_idx, ind_idx) for _, gen_idx, ind_idx in top_k] + + return top_k_population, top_k_fitnesses, top_k_indices + + +def get_generation_indices_for_limit(num_generations: int, limit: int) -> npt.NDArray: + """ + Get evenly spaced generation indices for visualization with a specific limit. + + Args: + num_generations: Total number of generations + limit: Maximum number of generations to include + + Returns: + Array of generation indices including first and last generation + """ + if limit >= num_generations: + return np.arange(num_generations) + + if limit < 2: + return np.array([0]) + + step = np.round(num_generations / (limit - 2)) + indices = np.arange(step, num_generations, step=step) + + if len(indices) == 0: + indices = np.array([0]) + + # Adjust to get exactly limit-2 middle indices + while len(indices) != limit - 2: + if len(indices) < limit - 2: + indices = np.append(indices, indices[-1] + 1) + elif len(indices) > limit - 2: + indices = np.delete(indices, -1) + + # Add first and last generation + indices = np.insert(indices, 0, 0) + indices = np.append(indices, num_generations - 1) + + return indices.astype(int) + + +def select_best_per_generation( + population_data: npt.NDArray, + fitness_data: npt.NDArray, + worst: bool = False +) -> Tuple[npt.NDArray, npt.NDArray]: + """ + Select the best (or worst) individual from each generation. + + Args: + population_data: Array of shape (n_generations, pop_size, n_arms, n_params) + fitness_data: Array of shape (n_generations, pop_size) + worst: If True, select worst individuals instead of best + + Returns: + Tuple of (best_individuals, best_fitnesses) + """ + if worst: + arg_indices = np.argmin(fitness_data, axis=1) + else: + arg_indices = np.argmax(fitness_data, axis=1) + + best_individuals = population_data[np.arange(population_data.shape[0]), arg_indices] + best_fitnesses = fitness_data[np.arange(fitness_data.shape[0]), arg_indices] + + return best_individuals, best_fitnesses + + +def flatten_population_across_generations( + population_data: npt.NDArray, + fitness_data: npt.NDArray, + remove_nan: bool = True +) -> Tuple[npt.NDArray, npt.NDArray]: + """ + Flatten population data across all generations into a single population. + + Args: + population_data: Array of shape (n_generations, pop_size, n_arms, n_params) + fitness_data: Array of shape (n_generations, pop_size) + remove_nan: If True, remove individuals with NaN fitness + + Returns: + Tuple of (flattened_population, flattened_fitnesses) + """ + n_gens, pop_size, n_arms, n_params = population_data.shape + + # Reshape to combine all generations + flattened_population = population_data.reshape((n_gens * pop_size, n_arms, n_params)) + flattened_fitnesses = fitness_data.flatten() + + if remove_nan: + # Remove individuals with NaN fitness + mask = ~np.isnan(flattened_fitnesses) + flattened_population = flattened_population[mask] + flattened_fitnesses = flattened_fitnesses[mask] + + return flattened_population, flattened_fitnesses + + +def get_fitness_statistics(fitness_data: npt.NDArray) -> dict: + """ + Calculate statistics for fitness data across generations. + + Args: + fitness_data: Array of shape (n_generations, pop_size) + + Returns: + Dictionary with fitness statistics + """ + # Remove NaN values for statistics + valid_fitness = fitness_data[~np.isnan(fitness_data)] + + if len(valid_fitness) == 0: + return { + 'mean': np.nan, + 'std': np.nan, + 'min': np.nan, + 'max': np.nan, + 'median': np.nan, + 'q25': np.nan, + 'q75': np.nan + } + + return { + 'mean': np.mean(valid_fitness), + 'std': np.std(valid_fitness), + 'min': np.min(valid_fitness), + 'max': np.max(valid_fitness), + 'median': np.median(valid_fitness), + 'q25': np.percentile(valid_fitness, 25), + 'q75': np.percentile(valid_fitness, 75) + } + + +def get_generation_fitness_statistics(fitness_data: npt.NDArray) -> dict: + """ + Calculate fitness statistics for each generation. + + Args: + fitness_data: Array of shape (n_generations, pop_size) + + Returns: + Dictionary with per-generation statistics + """ + n_generations = fitness_data.shape[0] + + stats = { + 'mean': np.zeros(n_generations), + 'std': np.zeros(n_generations), + 'min': np.zeros(n_generations), + 'max': np.zeros(n_generations), + 'median': np.zeros(n_generations) + } + + for gen in range(n_generations): + gen_fitness = fitness_data[gen] + valid_fitness = gen_fitness[~np.isnan(gen_fitness)] + + if len(valid_fitness) > 0: + stats['mean'][gen] = np.mean(valid_fitness) + stats['std'][gen] = np.std(valid_fitness) + stats['min'][gen] = np.min(valid_fitness) + stats['max'][gen] = np.max(valid_fitness) + stats['median'][gen] = np.median(valid_fitness) + else: + stats['mean'][gen] = np.nan + stats['std'][gen] = np.nan + stats['min'][gen] = np.nan + stats['max'][gen] = np.nan + stats['median'][gen] = np.nan + + return stats + + +# Backward compatibility aliases +get_top_k_individuals_legacy = get_top_k_individuals +get_idxs_between = get_generation_indices_for_limit \ No newline at end of file diff --git a/src/ariel/ec/drone/inspection/utils.py b/src/ariel/ec/drone/inspection/utils.py new file mode 100644 index 000000000..97fd5353a --- /dev/null +++ b/src/ariel/ec/drone/inspection/utils.py @@ -0,0 +1,416 @@ +""" +Utility functions for coordinate conversions and transformations used in visualization. + +This module provides coordinate system conversions between different genome representations +and common transformation utilities for the airevolve inspection tools. +""" + +from __future__ import annotations +from typing import Union, Tuple +import numpy as np +import numpy.typing as npt + + +def convert_to_cartesian( + magnitude: float, + azimuth: float, + pitch: float, + in_degrees: bool = False +) -> Tuple[float, float, float]: + """ + Convert spherical/polar coordinates to Cartesian coordinates. + + Args: + magnitude: Distance from origin + azimuth: Azimuthal angle (rotation around z-axis) + pitch: Pitch angle (elevation from xy-plane) + in_degrees: If True, angles are in degrees, else radians + + Returns: + Tuple of (x, y, z) coordinates + """ + if in_degrees: + azimuth = np.radians(azimuth) + pitch = np.radians(pitch) + + x = magnitude * np.cos(pitch) * np.cos(azimuth) + y = magnitude * np.cos(pitch) * np.sin(azimuth) + z = magnitude * np.sin(pitch) + + return (x, y, z) + + +def convert_to_spherical( + x: float, + y: float, + z: float, + in_degrees: bool = False +) -> Tuple[float, float, float]: + """ + Convert Cartesian coordinates to spherical/polar coordinates. + + Args: + x: X coordinate + y: Y coordinate + z: Z coordinate + in_degrees: If True, return angles in degrees, else radians + + Returns: + Tuple of (magnitude, azimuth, pitch) + """ + magnitude = np.sqrt(x**2 + y**2 + z**2) + azimuth = np.arctan2(y, x) + pitch = np.arcsin(z / magnitude) if magnitude > 0 else 0.0 + + if in_degrees: + azimuth = np.degrees(azimuth) + pitch = np.degrees(pitch) + + return (magnitude, azimuth, pitch) + + +def create_rotation_matrix_euler( + roll: float, + pitch: float, + yaw: float +) -> npt.NDArray[np.floating]: + """ + Create a 3D rotation matrix from Euler angles (ZYX convention). + + Args: + roll: Rotation around x-axis (radians) + pitch: Rotation around y-axis (radians) + yaw: Rotation around z-axis (radians) + + Returns: + 3x3 rotation matrix + """ + # Rotation matrices for each axis + Rx = np.array([ + [1, 0, 0], + [0, np.cos(roll), -np.sin(roll)], + [0, np.sin(roll), np.cos(roll)] + ]) + + Ry = np.array([ + [np.cos(pitch), 0, np.sin(pitch)], + [0, 1, 0], + [-np.sin(pitch), 0, np.cos(pitch)] + ]) + + Rz = np.array([ + [np.cos(yaw), -np.sin(yaw), 0], + [np.sin(yaw), np.cos(yaw), 0], + [0, 0, 1] + ]) + + # Combined rotation matrix (ZYX order) + return Rz @ Ry @ Rx + +def create_rotation_matrix_quaternion( + quaternion: npt.NDArray[np.floating] +) -> npt.NDArray[np.floating]: + """ + Create a 3D rotation matrix from a quaternion. + + Args: + quaternion: A 4-element array-like representing the quaternion [w, x, y, z] + + Returns: + 3x3 rotation matrix + """ + w, x, y, z = quaternion + + # Compute the rotation matrix elements + R = np.array([ + [1 - 2 * (y**2 + z**2), 2 * (x * y - z * w), 2 * (x * z + y * w)], + [2 * (x * y + z * w), 1 - 2 * (x**2 + z**2), 2 * (y * z - x * w)], + [2 * (x * z - y * w), 2 * (y * z + x * w), 1 - 2 * (x**2 + y**2)] + ]) + + return R + +def create_rotation_matrix_motor_orientation( + motor_yaw: float, + motor_pitch: float +) -> npt.NDArray[np.floating]: + """ + Create a rotation matrix for motor orientation in polar coordinate system. + + Args: + motor_yaw: Motor yaw angle (radians) + motor_pitch: Motor pitch angle (radians) + + Returns: + 3x3 rotation matrix + """ + # For polar coordinates, we use a different convention + Ry = np.array([ + [np.cos(-motor_pitch), 0, np.sin(-motor_pitch)], + [0, 1, 0], + [-np.sin(-motor_pitch), 0, np.cos(-motor_pitch)] + ]) + + Rz = np.array([ + [np.cos(motor_yaw), -np.sin(motor_yaw), 0], + [np.sin(motor_yaw), np.cos(motor_yaw), 0], + [0, 0, 1] + ]) + + return Rz @ Ry + + +def normalize_angles(angles: Union[float, npt.NDArray]) -> Union[float, npt.NDArray]: + """ + Normalize angles to [-π, π] range. + + Args: + angles: Single angle or array of angles in radians + + Returns: + Normalized angles in [-π, π] range + """ + return ((angles + np.pi) % (2 * np.pi)) - np.pi + + +def extract_genome_data(genome_handler) -> dict: + """ + Extract visualization data from a Cartesian genome handler. + + Args: + genome_handler: CartesianEulerDroneGenomeHandler instance + + Returns: + Dictionary with positions, orientations, and directions + """ + return { + 'positions': genome_handler.get_motor_positions(), + 'orientations': genome_handler.get_motor_orientations(), + 'directions': genome_handler.get_propeller_directions(), + 'coordinate_system': 'cartesian' + } + + +def extract_polar_genome_data(genome_array: npt.NDArray) -> dict: + """ + Extract visualization data from a polar coordinate genome array. + + Args: + genome_array: Array with shape (n_arms, 6) containing + [magnitude, azimuth, pitch, motor_pitch, motor_yaw, direction] + + Returns: + Dictionary with converted data for visualization + """ + # Remove any invalid (NaN) entries + valid_mask = ~np.isnan(genome_array).any(axis=1) + valid_genome = genome_array[valid_mask] + + positions = [] + orientations = [] + directions = [] + + for arm in valid_genome: + mag, azimuth, pitch, motor_pitch, motor_yaw, direction = arm[:6] + + # Convert position to Cartesian + x, y, z = convert_to_cartesian(mag, azimuth, pitch) + positions.append([x, y, z]) + + # Store motor orientation + orientations.append([0, motor_pitch, motor_yaw]) # roll=0 for polar system + + # Store direction + directions.append(int(direction)) + + return { + 'positions': np.array(positions), + 'orientations': np.array(orientations), + 'directions': np.array(directions), + 'coordinate_system': 'polar' + } + +def extract_cartesian_genome_data(genome_array: npt.NDArray) -> dict: + """ + Extract visualization data from a Cartesian genome array. + + Args: + genome_array: Array with shape (n_arms, 7) containing + [x, y, z, roll, pitch, yaw, direction] + + Returns: + Dictionary with converted data for visualization + """ + # Remove any invalid (NaN) entries + valid_mask = ~np.isnan(genome_array).any(axis=1) + valid_genome = genome_array[valid_mask] + + positions = [] + orientations = [] + directions = [] + + for arm in valid_genome: + x, y, z, roll, pitch, yaw, direction = arm[:7] + + positions.append([x, y, z]) + orientations.append([roll, pitch, yaw]) + directions.append(int(direction)) + + return { + 'positions': np.array(positions), + 'orientations': np.array(orientations), + 'directions': np.array(directions), + 'coordinate_system': 'cartesian' + } + + +def auto_extract_genome_data(genome_data) -> dict: + """ + Automatically extract visualization data from different genome formats. + + Args: + genome_data: Either a genome handler object or numpy array + + Returns: + Dictionary with standardized visualization data + + Raises: + ValueError: If genome format is not recognized + """ + # Check if it's a genome handler with methods + if hasattr(genome_data, 'get_motor_positions'): + return extract_genome_data(genome_data) + + # Check if it's a numpy array (polar format) + elif isinstance(genome_data, np.ndarray): + if genome_data.ndim == 2 and genome_data.shape[1] == 6: + return extract_polar_genome_data(genome_data) + elif genome_data.ndim == 2 and genome_data.shape[1] == 7: + return extract_cartesian_genome_data(genome_data) + + # Check if it has a 'genome' attribute (genome handler) + elif hasattr(genome_data, 'genome'): + if hasattr(genome_data, 'get_motor_positions'): + return extract_cartesian_genome_data(genome_data) + else: + # Assume polar format in genome attribute + return extract_polar_genome_data(genome_data.genome) + + else: + raise ValueError(f"Unrecognized genome format: {type(genome_data)}") + + +def compute_visualization_bounds(positions: npt.NDArray, scale_factor: float = 1.2) -> dict: + """ + Compute appropriate bounds for visualization based on genome positions. + + Args: + positions: Array of positions with shape (n_arms, 3) + scale_factor: Factor to scale bounds beyond max position + + Returns: + Dictionary with xlim, ylim, zlim bounds + """ + if len(positions) == 0: + # Default bounds if no positions + default_lim = [-0.5, 0.5] + return {'xlim': default_lim, 'ylim': default_lim, 'zlim': default_lim} + + max_extent = np.max(np.abs(positions)) + limit = max_extent * scale_factor + + return { + 'xlim': [-limit, limit], + 'ylim': [-limit, limit], + 'zlim': [-limit, limit] + } + + +def evolution_dataframe_to_fitness_array(evolution_df, population_size: int = None) -> npt.NDArray[np.floating]: + """ + Convert pandas DataFrame from evolve() to fitness array format expected by plot_fitness(). + + Args: + evolution_df: DataFrame returned by evolve() with columns ['generation', 'fitness', 'in_pop'] + population_size: Expected population size. If None, inferred from data + + Returns: + 2D numpy array of shape (n_generations, pop_size) with fitness values + + Raises: + ValueError: If DataFrame is empty or missing required columns + """ + import pandas as pd + + if evolution_df.empty: + raise ValueError("Evolution DataFrame is empty") + + required_columns = ['generation', 'fitness'] + missing_columns = [col for col in required_columns if col not in evolution_df.columns] + if missing_columns: + raise ValueError(f"Missing required columns: {missing_columns}") + + # Get generation info + generations = sorted(evolution_df['generation'].unique()) + n_generations = len(generations) + + # Determine population size + if population_size is None: + # Use the maximum number of individuals in any generation + gen_counts = evolution_df['generation'].value_counts() + population_size = gen_counts.max() + + # Initialize fitness array with NaN + fitness_array = np.full((n_generations, population_size), np.nan) + + # Fill fitness values for each generation + for gen_idx, gen in enumerate(generations): + gen_data = evolution_df[evolution_df['generation'] == gen] + + # Get fitness values, sorted by fitness (best first) + fitness_values = gen_data['fitness'].sort_values(ascending=False).values + + # Fill as many values as we have, up to population_size + n_individuals = min(len(fitness_values), population_size) + fitness_array[gen_idx, :n_individuals] = fitness_values[:n_individuals] + + return fitness_array + + +def get_points(individual: npt.NDArray) -> npt.NDArray: + """Convert a phenotype array to 3D Cartesian points. + + Args: + individual: Array with shape (n_arms, 6) containing + [magnitude, azimuth, pitch, motor_pitch, motor_yaw, direction]. + Rows that are all-NaN are skipped. + + Returns: + Array of shape (n_valid_arms, 3) with Cartesian [x, y, z] coordinates. + """ + valid_mask = ~np.isnan(individual).any(axis=1) + valid = individual[valid_mask] + + points = [] + for arm in valid: + mag, azimuth, pitch = arm[0], arm[1], arm[2] + x, y, z = convert_to_cartesian(mag, azimuth, pitch) + points.append([x, y, z]) + + return np.array(points) if points else np.empty((0, 3)) + + +def ENU_to_NED(x, y, z): + """ + Convert Earth-Centered, Earth-Fixed (ENU) coordinates to North-East-Down (NED) coordinates. + + Parameters: + x (float): The x-coordinate in ENU. + y (float): The y-coordinate in ENU. + z (float): The z-coordinate in ENU. + + Returns: + tuple: The x, y, and z coordinates in NED. + """ + return (y, x, -z) + diff --git a/src/ariel/ec/drone/selectors/__init__.py b/src/ariel/ec/drone/selectors/__init__.py new file mode 100644 index 000000000..6cbd34e70 --- /dev/null +++ b/src/ariel/ec/drone/selectors/__init__.py @@ -0,0 +1 @@ +from ariel.ec.drone.selectors.tournament import tournament_selection diff --git a/src/ariel/ec/drone/selectors/tournament.py b/src/ariel/ec/drone/selectors/tournament.py new file mode 100644 index 000000000..16ddc6dd9 --- /dev/null +++ b/src/ariel/ec/drone/selectors/tournament.py @@ -0,0 +1,14 @@ +import pandas as pd + + +def tournament_selection(population: pd.DataFrame, tournament_size: int = 3, k: int = 1) -> pd.DataFrame: + """Tournament selection on a population DataFrame with a 'fitness' column.""" + assert len(population) > 0, "Population must not be empty" + + selected_individuals = [] + for _ in range(k): + tournament = population.sample(n=tournament_size, replace=True).reset_index(drop=True) + winner = tournament.loc[tournament["fitness"].idxmax()] + selected_individuals.append(winner.to_dict()) + + return pd.DataFrame(selected_individuals).reset_index(drop=True) diff --git a/src/ariel/ec/drone/strategies/__init__.py b/src/ariel/ec/drone/strategies/__init__.py new file mode 100644 index 000000000..9d1c8a03f --- /dev/null +++ b/src/ariel/ec/drone/strategies/__init__.py @@ -0,0 +1,2 @@ +# Drone-specific EC strategies +from ariel.ec.drone.strategies.neat import evolve_neat diff --git a/src/ariel/ec/drone/strategies/evolution_components.py b/src/ariel/ec/drone/strategies/evolution_components.py new file mode 100644 index 000000000..51c99c94d --- /dev/null +++ b/src/ariel/ec/drone/strategies/evolution_components.py @@ -0,0 +1,87 @@ +from __future__ import annotations + +import os +from typing import Callable, List, Optional + +import numpy as np +import pandas as pd + +from ariel.ec.drone.genome_handlers.base import GenomeHandler + + +def generate_population(pop_size: int, genome_handler: object = GenomeHandler) -> list: + return [genome_handler() for _ in range(pop_size)] + + +def evaluate_individual( + fitness_function: Callable, + genome: np.ndarray, + id: str, + generation: int, + parent_ids: List[str], + log_dir_base: str, +) -> dict: + if log_dir_base is not None: + gen_dir = os.path.join(log_dir_base, f"generation_{generation:02d}") + indiv_log_dir = os.path.join(gen_dir, f"individual_{id}") + os.makedirs(indiv_log_dir, exist_ok=True) + fitness = fitness_function(genome, indiv_log_dir) + return { + "id": id, + "generation": generation, + "genome": genome, + "log_dir": indiv_log_dir, + "parent_ids": parent_ids, + "in_pop": False, + "fitness": fitness, + } + + +def _evaluate_individual_worker(args): + fitness_function, genome, id, generation, parent_ids, log_dir_base = args + return evaluate_individual(fitness_function, genome, id, generation, parent_ids, log_dir_base) + + +def _pool_worker_init(): + os.environ["OMP_NUM_THREADS"] = "1" + os.environ["MKL_NUM_THREADS"] = "1" + os.environ["OPENBLAS_NUM_THREADS"] = "1" + try: + import torch + torch.set_num_threads(1) + except ImportError: + pass + + +def evaluate_population( + fitness_function: Callable, + population: list, + ids: List[str], + generation: int, + all_parent_ids: List[List[str]], + log_dir_base: str, + num_workers: int = 1, +) -> pd.DataFrame: + if num_workers > 1: + import multiprocessing + ctx = multiprocessing.get_context("spawn") + args_list = [ + (fitness_function, genome, ids[i], generation, all_parent_ids[i], log_dir_base) + for i, genome in enumerate(population) + ] + with ctx.Pool( + processes=min(num_workers, len(population)), + initializer=_pool_worker_init, + ) as pool: + evaluated = pool.map(_evaluate_individual_worker, args_list) + else: + evaluated = [] + for i, genome in enumerate(population): + evaluated.append( + evaluate_individual( + fitness_function, genome, ids[i], generation, + all_parent_ids[i], log_dir_base, + ) + ) + + return pd.DataFrame(evaluated) diff --git a/src/ariel/ec/drone/strategies/neat.py b/src/ariel/ec/drone/strategies/neat.py new file mode 100644 index 000000000..e8cb3d886 --- /dev/null +++ b/src/ariel/ec/drone/strategies/neat.py @@ -0,0 +1,337 @@ +"""NEAT evolution strategy with speciation-based diversity protection.""" + +from __future__ import annotations + +import time +from typing import Callable, Dict, List, Optional + +import numpy as np +import pandas as pd + +from ariel.ec.drone.genome_handlers.base import GenomeHandler +from ariel.ec.drone.strategies.evolution_components import evaluate_population +from ariel.ec.drone.strategies.speciation import SpeciationState + + +def evolve_neat( + fitness_function: Callable, + population_size: int, + num_generations: int, + crossover_rate: float, + parent_selection: Callable, + genome_handler: type = GenomeHandler, + # NEAT-specific parameters + compatibility_threshold: float = 3.0, + species_elitism: int = 1, + stagnation_limit: int = 15, + min_species_size: int = 2, + adjust_threshold: bool = True, + target_species_count: int = 5, + interspecies_mating_rate: float = 0.001, + mutate_after_crossover: bool = True, + # Standard parameters + initial_population: Optional[List] = None, + log_dir: str = "./logs", + verbose: bool = True, + num_workers: int = 1, +) -> pd.DataFrame: + """NEAT evolution with speciation. + + Returns a DataFrame with columns: id, generation, genome, log_dir, + parent_ids, in_pop, fitness, species_id. + """ + dummy = genome_handler() + handler_kwargs = _extract_handler_kwargs(dummy) + + evo_start = time.time() + + if initial_population is not None: + gene_pool = list(initial_population) + else: + pop_handlers = dummy.generate_random_population(population_size) + gene_pool = [h.genome for h in pop_handlers] + + ids = [str(i).zfill(4) for i in range(population_size)] + parent_ids_list = [[None, None] for _ in range(population_size)] + + population = evaluate_population( + fitness_function, gene_pool, ids, 0, parent_ids_list, + log_dir_base=log_dir, num_workers=num_workers, + ) + population["in_pop"] = True + + spec_state = SpeciationState(compatibility_threshold=compatibility_threshold) + assignments = spec_state.speciate(population, genome_handler, handler_kwargs) + population["species_id"] = population["id"].map(assignments) + spec_state.update_best_fitness(population) + + all_individuals = population.copy() + next_id = population_size + + if verbose: + _print_gen_stats(0, population, spec_state, time.time() - evo_start) + + for generation in range(1, num_generations + 1): + gen_start = time.time() + + if hasattr(genome_handler, "_innovation_counter"): + genome_handler._innovation_counter.reset_generation() + + spec_state.remove_stagnant_species(stagnation_limit) + + if not spec_state.species: + spec_state = SpeciationState( + compatibility_threshold=spec_state.compatibility_threshold, + ) + assignments = spec_state.speciate(population, genome_handler, handler_kwargs) + population["species_id"] = population["id"].map(assignments) + spec_state.update_best_fitness(population) + + species_offspring = _allocate_offspring( + population, spec_state, population_size, min_species_size, + ) + + new_genomes: List = [] + new_parent_ids: List = [] + elite_genomes: List = [] + elite_parent_ids: List = [] + + for sid, n_offspring in species_offspring.items(): + sp = spec_state.species.get(sid) + if sp is None or not sp.member_ids: + continue + + sp_df = population[population["id"].isin(sp.member_ids)].copy() + if sp_df.empty: + continue + + sp_df = sp_df.sort_values("fitness", ascending=False).reset_index(drop=True) + + n_elite = min(species_elitism, len(sp_df), n_offspring) + for i in range(n_elite): + elite_genomes.append(sp_df.iloc[i]["genome"]) + elite_parent_ids.append([sp_df.iloc[i]["id"], None]) + + remaining = n_offspring - n_elite + if remaining <= 0: + continue + + for _ in range(remaining): + if np.random.random() < crossover_rate and len(sp_df) >= 2: + parents = parent_selection(sp_df, k=2) + p1_genome = parents.iloc[0]["genome"] + p2_genome = parents.iloc[1]["genome"] + p1_id = parents.iloc[0]["id"] + p1_fitness = parents.iloc[0]["fitness"] + p2_id = parents.iloc[1]["id"] + p2_fitness = parents.iloc[1]["fitness"] + + if np.random.random() < interspecies_mating_rate: + other_sids = [s for s in spec_state.species if s != sid] + if other_sids: + other_sid = np.random.choice(other_sids) + other_sp = spec_state.species[other_sid] + other_df = population[population["id"].isin(other_sp.member_ids)] + if not other_df.empty: + mate = parent_selection(other_df, k=1) + p2_genome = mate.iloc[0]["genome"] + p2_id = mate.iloc[0]["id"] + p2_fitness = mate.iloc[0]["fitness"] + + p1_handler = genome_handler(genome=p1_genome, **handler_kwargs) + p2_handler = genome_handler(genome=p2_genome, **handler_kwargs) + p1_handler.fitness = p1_fitness + p2_handler.fitness = p2_fitness + + child_handler = p1_handler.crossover(p2_handler) + if mutate_after_crossover: + child_handler.mutate() + + new_genomes.append(child_handler.genome) + new_parent_ids.append([p1_id, p2_id]) + else: + parent = parent_selection(sp_df, k=1) + p_genome = parent.iloc[0]["genome"] + p_id = parent.iloc[0]["id"] + + handler = genome_handler(genome=p_genome, **handler_kwargs) + handler.mutate() + + new_genomes.append(handler.genome) + new_parent_ids.append([p_id, None]) + + all_new_genomes = elite_genomes + new_genomes + all_new_parent_ids = elite_parent_ids + new_parent_ids + + if not all_new_genomes: + pop_handlers = dummy.generate_random_population(population_size) + all_new_genomes = [h.genome for h in pop_handlers] + all_new_parent_ids = [[None, None]] * population_size + + new_ids = [str(i).zfill(4) for i in range(next_id, next_id + len(all_new_genomes))] + next_id += len(all_new_genomes) + + offspring_df = evaluate_population( + fitness_function, all_new_genomes, new_ids, generation, + all_new_parent_ids, log_dir_base=log_dir, num_workers=num_workers, + ) + offspring_df["in_pop"] = True + offspring_df["generation"] = generation + + population = offspring_df.nlargest(population_size, "fitness").copy() + assignments = spec_state.speciate(population, genome_handler, handler_kwargs) + population["species_id"] = population["id"].map(assignments) + + spec_state.update_representatives(population) + spec_state.update_best_fitness(population) + + if adjust_threshold: + spec_state.adjust_threshold(target_species_count) + + offspring_df["species_id"] = offspring_df["id"].map(assignments).fillna(-1).astype(int) + all_individuals = pd.concat([all_individuals, offspring_df], ignore_index=True) + + if verbose: + _print_gen_stats(generation, population, spec_state, time.time() - gen_start) + + if verbose: + print(f"Time taken to evolve: {time.time() - evo_start:.2f}s") + + return all_individuals + + +# --------------------------------------------------------------------------- +# Helpers +# --------------------------------------------------------------------------- + +def _extract_handler_kwargs(handler: GenomeHandler) -> dict: + """Extract constructor kwargs from a handler instance.""" + kwargs: dict = {} + + if hasattr(handler, "min_narms") and hasattr(handler, "max_narms"): + kwargs["min_max_narms"] = (handler.min_narms, handler.max_narms) + if hasattr(handler, "parameter_limits"): + kwargs["parameter_limits"] = handler.parameter_limits + + if hasattr(handler, "num_segments"): + kwargs["num_segments"] = handler.num_segments + if hasattr(handler, "initial_hidden_nodes"): + kwargs["initial_hidden_nodes"] = handler.initial_hidden_nodes + + for attr in [ + "prob_add_node", "prob_add_connection", "prob_remove_node", + "prob_remove_connection", "prob_mutate_weights", "prob_mutate_activation", + "prob_toggle_connection", "weight_perturb_std", "weight_replace_prob", + "weight_range", "bias_perturb_std", "bias_replace_prob", "bias_range", + ]: + if hasattr(handler, attr): + kwargs[attr] = getattr(handler, attr) + + if hasattr(handler, "prob_mutate_direct"): + kwargs["prob_mutate_direct"] = handler.prob_mutate_direct + if hasattr(handler, "direct_mutation_scale_pct"): + kwargs["direct_mutation_scale_pct"] = handler.direct_mutation_scale_pct + + if hasattr(handler, "repair_enabled"): + kwargs["repair"] = handler.repair_enabled + if hasattr(handler, "enable_collision_repair"): + kwargs["enable_collision_repair"] = handler.enable_collision_repair + for attr in [ + "propeller_radius", "inner_boundary_radius", "outer_boundary_radius", + "max_repair_iterations", "repair_step_size", "propeller_tolerance", + ]: + if hasattr(handler, attr): + kwargs[attr] = getattr(handler, attr) + + if hasattr(handler, "append_arm_chance"): + kwargs["append_arm_chance"] = handler.append_arm_chance + if hasattr(handler, "bilateral_plane_for_symmetry"): + kwargs["bilateral_plane_for_symmetry"] = handler.bilateral_plane_for_symmetry + + if hasattr(handler, "rng"): + kwargs["rng"] = handler.rng + elif hasattr(handler, "rnd"): + kwargs["rnd"] = handler.rnd + + return kwargs + + +def _allocate_offspring( + population: pd.DataFrame, + spec_state: SpeciationState, + population_size: int, + min_species_size: int, +) -> Dict[int, int]: + """Allocate offspring using largest-remainder method.""" + species_adj_fitness: Dict[int, float] = {} + + for sid, sp in spec_state.species.items(): + if not sp.member_ids: + continue + sp_df = population[population["id"].isin(sp.member_ids)] + if sp_df.empty: + continue + sp_size = len(sp_df) + adj_sum = float(sp_df["fitness"].sum() / sp_size) + species_adj_fitness[sid] = adj_sum + + if not species_adj_fitness: + return {} + + sorted_sids = sorted(species_adj_fitness, key=species_adj_fitness.get, reverse=True) + while len(sorted_sids) * min_species_size > population_size and len(sorted_sids) > 1: + dropped = sorted_sids.pop() + del species_adj_fitness[dropped] + + min_adj = min(species_adj_fitness.values()) + if min_adj <= 0: + shift = abs(min_adj) + 1e-6 + species_adj_fitness = {sid: adj + shift for sid, adj in species_adj_fitness.items()} + + total_adj = sum(species_adj_fitness.values()) + n_species = len(species_adj_fitness) + remainder = population_size - n_species * min_species_size + + allocation: Dict[int, int] = {} + fractional_parts: Dict[int, float] = {} + + for sid, adj in species_adj_fitness.items(): + exact_share = (adj / total_adj) * remainder if total_adj > 0 else 0.0 + floor_share = int(exact_share) + allocation[sid] = min_species_size + floor_share + fractional_parts[sid] = exact_share - floor_share + + leftover = population_size - sum(allocation.values()) + if leftover > 0: + ranked = sorted(fractional_parts, key=fractional_parts.get, reverse=True) + for i in range(leftover): + allocation[ranked[i % len(ranked)]] += 1 + + return allocation + + +def _print_gen_stats( + generation: int, + population: pd.DataFrame, + spec_state: SpeciationState, + elapsed: float, +) -> None: + fitnesses = population["fitness"].values + n_species = len(spec_state.species) + print( + f"G:{generation} Time:{elapsed:.2f}s " + f"MaxF={np.max(fitnesses):.4f} AvgF={np.mean(fitnesses):.4f} " + f"Species={n_species}", + flush=True, + ) + for sid, sp in sorted(spec_state.species.items()): + sp_df = population[population["id"].isin(sp.member_ids)] + if sp_df.empty: + continue + sp_fit = sp_df["fitness"].values + print( + f" S{sid}: size={len(sp_df)} " + f"best={np.max(sp_fit):.4f} avg={np.mean(sp_fit):.4f} " + f"stag={sp.generations_since_improvement}", + flush=True, + ) diff --git a/src/ariel/ec/drone/strategies/speciation.py b/src/ariel/ec/drone/strategies/speciation.py new file mode 100644 index 000000000..904b4571a --- /dev/null +++ b/src/ariel/ec/drone/strategies/speciation.py @@ -0,0 +1,150 @@ +"""Speciation state management for NEAT evolution.""" + +from __future__ import annotations + +from dataclasses import dataclass, field +from typing import Any, Dict, List + +import pandas as pd + + +@dataclass +class Species: + """A NEAT species: a group of genetically similar individuals.""" + id: int + representative_genome: Any + member_ids: List[str] + best_fitness: float + generations_since_improvement: int = 0 + + +@dataclass +class SpeciationState: + """Manages species assignments across generations.""" + species: Dict[int, Species] = field(default_factory=dict) + next_species_id: int = 0 + compatibility_threshold: float = 3.0 + + def speciate( + self, + population_df: pd.DataFrame, + genome_handler_class: type, + handler_kwargs: dict, + ) -> Dict[str, int]: + """Assign each individual to a species. + + Returns a mapping from individual ID to species ID. + """ + assignments: Dict[str, int] = {} + + # Clear existing member lists + for sp in self.species.values(): + sp.member_ids = [] + + for _, row in population_df.iterrows(): + ind_id = row["id"] + genome = row["genome"] + + # Wrap genome in a handler for distance computation + ind_handler = genome_handler_class(genome=genome, **handler_kwargs) + + assigned = False + for sp in self.species.values(): + rep_handler = genome_handler_class( + genome=sp.representative_genome, **handler_kwargs + ) + dist = ind_handler.compatibility_distance(rep_handler) + if dist < self.compatibility_threshold: + sp.member_ids.append(ind_id) + assignments[ind_id] = sp.id + assigned = True + break + + if not assigned: + new_id = self.next_species_id + self.next_species_id += 1 + self.species[new_id] = Species( + id=new_id, + representative_genome=genome, + member_ids=[ind_id], + best_fitness=float("-inf"), + ) + assignments[ind_id] = new_id + + # Remove empty species + empty = [sid for sid, sp in self.species.items() if not sp.member_ids] + for sid in empty: + del self.species[sid] + + return assignments + + def update_representatives(self, population_df: pd.DataFrame) -> None: + """Update species representatives after selection. + + Per the original NEAT paper, the representative is always a random + member of the species from the current generation. + """ + import random + + id_to_genome = dict(zip(population_df["id"], population_df["genome"])) + + for sp in self.species.values(): + if not sp.member_ids: + continue + chosen_id = random.choice(sp.member_ids) + if chosen_id in id_to_genome: + sp.representative_genome = id_to_genome[chosen_id] + + def update_best_fitness(self, population_df: pd.DataFrame) -> None: + """Track best fitness per species and update stagnation counters.""" + id_to_fitness = dict(zip(population_df["id"], population_df["fitness"])) + + for sp in self.species.values(): + if not sp.member_ids: + continue + member_fitnesses = [ + id_to_fitness[mid] + for mid in sp.member_ids + if mid in id_to_fitness + ] + if not member_fitnesses: + continue + current_best = max(member_fitnesses) + if current_best > sp.best_fitness: + sp.best_fitness = current_best + sp.generations_since_improvement = 0 + else: + sp.generations_since_improvement += 1 + + def adjust_threshold(self, target_species_count: int, delta: float = 0.3) -> None: + """Adjust compatibility threshold toward target species count.""" + current = len(self.species) + if current > target_species_count: + self.compatibility_threshold += delta + elif current < target_species_count: + self.compatibility_threshold = max(0.1, self.compatibility_threshold - delta) + + def remove_stagnant_species( + self, stagnation_limit: int, protect_top_n: int = 2 + ) -> None: + """Remove species that haven't improved for stagnation_limit generations. + + Always protect the top N species by best_fitness. + """ + if len(self.species) <= protect_top_n: + return + + # Sort species by best fitness descending + sorted_species = sorted( + self.species.values(), key=lambda s: s.best_fitness, reverse=True + ) + protected_ids = {s.id for s in sorted_species[:protect_top_n]} + + to_remove = [ + sid + for sid, sp in self.species.items() + if sp.generations_since_improvement >= stagnation_limit + and sid not in protected_ids + ] + for sid in to_remove: + del self.species[sid] diff --git a/src/ariel/simulation/drone/__init__.py b/src/ariel/simulation/drone/__init__.py new file mode 100644 index 000000000..8fac4062b --- /dev/null +++ b/src/ariel/simulation/drone/__init__.py @@ -0,0 +1,3 @@ +from ariel.simulation.drone.propeller_data import create_standard_propeller_config, get_extended_prop_params, GRAVITY +from ariel.simulation.drone.drone_simulator import DroneSimulator, create_quadrotor, create_hexarotor, create_tricopter, create_octorotor +from ariel.simulation.drone.drone_interface import DroneInterface diff --git a/src/ariel/simulation/drone/controllers/__init__.py b/src/ariel/simulation/drone/controllers/__init__.py new file mode 100644 index 000000000..3f4ebfd79 --- /dev/null +++ b/src/ariel/simulation/drone/controllers/__init__.py @@ -0,0 +1 @@ +# Drone controllers package diff --git a/src/ariel/simulation/drone/controllers/lee_control/__init__.py b/src/ariel/simulation/drone/controllers/lee_control/__init__.py new file mode 100644 index 000000000..66ab3af31 --- /dev/null +++ b/src/ariel/simulation/drone/controllers/lee_control/__init__.py @@ -0,0 +1,3 @@ +""" +Lee Geometric Control module +""" diff --git a/src/ariel/simulation/drone/controllers/lee_control/acceleration_control.py b/src/ariel/simulation/drone/controllers/lee_control/acceleration_control.py new file mode 100644 index 000000000..841c35208 --- /dev/null +++ b/src/ariel/simulation/drone/controllers/lee_control/acceleration_control.py @@ -0,0 +1,49 @@ +import numpy as np +import logging +from .lee_math_utils import * +from .base_lee_controller import BaseLeeController, calculate_desired_orientation_from_forces_and_yaw, euler_rates_to_body_rates + +logger = logging.getLogger("acceleration_controller") + + +class LeeAccelerationController(BaseLeeController): + def __init__(self, config, mass=1.0, inertia=None, gravity=None, orient="NED"): + super().__init__(config, mass, inertia, gravity) + self.orient = orient + self.init_controller_gains() + + def update(self, command_actions): + """ + Lee acceleration controller + :param command_actions: array of shape (4,) with [ax, ay, az, yaw_rate] acceleration command and yaw rate + :return: wrench command [fx, fy, fz, tx, ty, tz] + """ + command_actions = np.array(command_actions) + self.reset_commands() + + # Set desired acceleration directly (WORLD frame) + self.accel = command_actions[0:3].copy() + # Convert to WORLD frame forces + forces = self.mass * (self.accel - self.gravity) + + # Set complete force command (WORLD frame forces) + self.wrench_command[0:3] = forces + + # Calculate desired orientation from WORLD frame forces and current yaw + self.desired_quat = calculate_desired_orientation_from_forces_and_yaw( + forces, self.robot_euler_angles[2], self.orient + ) + + # Set desired angular rates (zero roll/pitch rates, commanded yaw rate) + self.euler_angle_rates[0:2] = 0.0 + self.euler_angle_rates[2] = command_actions[3] + self.desired_body_angvel = euler_rates_to_body_rates( + self.robot_euler_angles, self.euler_angle_rates, self.rotation_matrix_buffer + ) + + # Compute body torques + self.wrench_command[3:6] = self.compute_body_torque( + self.desired_quat, self.desired_body_angvel + ) + + return self.wrench_command.copy() \ No newline at end of file diff --git a/src/ariel/simulation/drone/controllers/lee_control/attitude_control.py b/src/ariel/simulation/drone/controllers/lee_control/attitude_control.py new file mode 100644 index 000000000..eb6e03d43 --- /dev/null +++ b/src/ariel/simulation/drone/controllers/lee_control/attitude_control.py @@ -0,0 +1,46 @@ +import numpy as np +import logging +from .lee_math_utils import * +from .base_lee_controller import BaseLeeController, euler_rates_to_body_rates + +logger = logging.getLogger("attitude_controller") + + +class LeeAttitudeController(BaseLeeController): + def __init__(self, config, mass=1.0, inertia=None, gravity=None, orient="NED"): + super().__init__(config, mass, inertia, gravity) + self.orient = orient + self.init_controller_gains() + + def update(self, command_actions): + """ + Lee attitude controller + :param command_actions: array of shape (4,) with [thrust, roll, pitch, yaw_rate] attitude command + :return: wrench command [fx, fy, fz, tx, ty, tz] + """ + command_actions = np.array(command_actions) + self.reset_commands() + + # Thrust command (normalized thrust input) + self.wrench_command[2] = ( + (command_actions[0] + 1.0) * self.mass * np.linalg.norm(self.gravity) + ) + + # Set desired angular rates (zero roll/pitch rates, commanded yaw rate) + self.euler_angle_rates[0:2] = 0.0 + self.euler_angle_rates[2] = command_actions[3] + self.desired_body_angvel = euler_rates_to_body_rates( + self.robot_euler_angles, self.euler_angle_rates, self.rotation_matrix_buffer + ) + + # Desired euler angles: commanded roll, commanded pitch, current yaw + quat_desired = quat_from_euler_xyz( + command_actions[1], command_actions[2], self.robot_euler_angles[2] + ) + + # Compute body torques + self.wrench_command[3:6] = self.compute_body_torque( + quat_desired, self.desired_body_angvel + ) + + return self.wrench_command.copy() \ No newline at end of file diff --git a/src/ariel/simulation/drone/controllers/lee_control/base_lee_controller.py b/src/ariel/simulation/drone/controllers/lee_control/base_lee_controller.py new file mode 100644 index 000000000..eb0c567e0 --- /dev/null +++ b/src/ariel/simulation/drone/controllers/lee_control/base_lee_controller.py @@ -0,0 +1,359 @@ +import numpy as np +import logging +from .lee_math_utils import * + +logger = logging.getLogger("base_lee_controller") + + +class BaseLeeController: + """ + This class will operate as the base class for all controllers. + It will be inherited by the specific controller classes. + """ + + def __init__(self, control_config, mass=1.0, inertia=None, gravity=None): + self.cfg = control_config + self.mass = mass + + # Default inertia matrix (3x3 identity scaled by mass if not provided) + if inertia is None: + self.robot_inertia = np.eye(3) * mass * 0.1 # Default inertia + else: + self.robot_inertia = np.array(inertia) + + # Default gravity vector (will be overridden by Lee controller with correct coordinate frame) + if gravity is None: + self.gravity = np.array([0.0, 0.0, -9.81]) # Default ENU, but Lee controller will override + else: + self.gravity = np.array(gravity) + + def update_state(self, robot_state): + """Update robot state from external source + robot_state should be a dict containing: + - position: [x, y, z] + - orientation: [qx, qy, qz, qw] quaternion + - linear_velocity: [vx, vy, vz] + - angular_velocity: [wx, wy, wz] + - euler_angles: [roll, pitch, yaw] + """ + self.robot_position = np.array(robot_state.get("position", [0.0, 0.0, 0.0])) + self.robot_orientation = np.array(robot_state.get("orientation", [0.0, 0.0, 0.0, 1.0])) + self.robot_linvel = np.array(robot_state.get("linear_velocity", [0.0, 0.0, 0.0])) + self.robot_angvel = np.array(robot_state.get("angular_velocity", [0.0, 0.0, 0.0])) + self.robot_euler_angles = np.array(robot_state.get("euler_angles", [0.0, 0.0, 0.0])) + + # Angular velocity from simulator is already in body frame + self.robot_body_angvel = self.robot_angvel.copy() + # Linear velocity from simulator is in world frame, body frame would need rotation + self.robot_body_linvel = self.robot_linvel.copy() # Keep world frame for now + + # Vehicle frame orientation (only yaw component) + from .lee_math_utils import vehicle_frame_quat_from_quat + self.robot_vehicle_orientation = vehicle_frame_quat_from_quat(self.robot_orientation) + self.robot_vehicle_linvel = self.robot_linvel.copy() # Simplified for now + + def init_controller_gains(self): + """Initialize controller gains from configuration""" + # Get gains from config (defaults only used if config doesn't provide them) + self.K_pos_max = np.array(getattr(self.cfg, 'K_pos_tensor_max', [2.0, 2.0, 3.0])) + self.K_pos_min = np.array(getattr(self.cfg, 'K_pos_tensor_min', [2.0, 2.0, 3.0])) + self.K_linvel_max = np.array(getattr(self.cfg, 'K_vel_tensor_max', [3.0, 3.0, 4.0])) + self.K_linvel_min = np.array(getattr(self.cfg, 'K_vel_tensor_min', [3.0, 3.0, 4.0])) + self.K_rot_max = np.array(getattr(self.cfg, 'K_rot_tensor_max', [0.3, 0.3, 0.1])) # Scaled for direct SO(3) control + self.K_rot_min = np.array(getattr(self.cfg, 'K_rot_tensor_min', [0.3, 0.3, 0.1])) # Same as max + self.K_angvel_max = np.array(getattr(self.cfg, 'K_angvel_tensor_max', [0.05, 0.05, 0.03])) # Rate damping gain + self.K_angvel_min = np.array(getattr(self.cfg, 'K_angvel_tensor_min', [0.05, 0.05, 0.03])) # Same as max + + # Use the values directly (since min=max, averaging gives the same result) + # This ensures we use the configured gains without dilution + self.K_pos_current = (self.K_pos_max + self.K_pos_min) / 2.0 + self.K_linvel_current = (self.K_linvel_max + self.K_linvel_min) / 2.0 + self.K_rot_current = (self.K_rot_max + self.K_rot_min) / 2.0 # Will equal K_rot_max since min=max + self.K_angvel_current = (self.K_angvel_max + self.K_angvel_min) / 2.0 # Will equal K_angvel_max since min=max + + # Working variables that are needed later in the controller + self.accel = np.zeros(3) + self.wrench_command = np.zeros(6) # [fx, fy, fz, tx, ty, tz] + + # Control variables + self.desired_quat = np.array([0.0, 0.0, 0.0, 1.0]) + self.desired_body_angvel = np.zeros(3) + self.euler_angle_rates = np.zeros(3) + + # Buffer for rotation matrix calculations + self.rotation_matrix_buffer = np.zeros((3, 3)) + + def __call__(self, *args, **kwargs): + return self.update(*args, **kwargs) + + def reset_commands(self): + """Reset wrench command to zero""" + self.wrench_command.fill(0.0) + + def reset(self): + """Reset controller state""" + self.randomize_params() + + def randomize_params(self): + """Randomize controller parameters within configured bounds""" + if not getattr(self.cfg, 'randomize_params', False): + return + + self.K_pos_current = rand_float_uniform(self.K_pos_min, self.K_pos_max) + self.K_linvel_current = rand_float_uniform(self.K_linvel_min, self.K_linvel_max) + self.K_rot_current = rand_float_uniform(self.K_rot_min, self.K_rot_max) + self.K_angvel_current = rand_float_uniform(self.K_angvel_min, self.K_angvel_max) + + def compute_acceleration(self, setpoint_position, setpoint_velocity): + """Compute desired acceleration from position and velocity setpoints""" + position_error_world_frame = np.array(setpoint_position) - self.robot_position + + # setpoint_velocity is already in world frame, no rotation needed + setpoint_velocity_world_frame = np.array(setpoint_velocity) + velocity_error = setpoint_velocity_world_frame - self.robot_linvel + + accel_command = ( + self.K_pos_current * position_error_world_frame + + self.K_linvel_current * velocity_error + ) + + # FIXED: Much more aggressive saturation to prevent force explosion + max_accel = 5.0 # m/s² (conservative limit - was 20.0 causing huge forces) + accel_magnitude = np.linalg.norm(accel_command) + if accel_magnitude > max_accel: + accel_command = accel_command / accel_magnitude * max_accel + + return accel_command + + def compute_body_torque(self, setpoint_orientation, setpoint_angvel): + """Compute body torque from orientation and angular velocity setpoints""" + setpoint_angvel = np.array(setpoint_angvel) + max_yaw_rate = getattr(self.cfg, 'max_yaw_rate', 2.0) # Default max yaw rate + setpoint_angvel[2] = np.clip(setpoint_angvel[2], -max_yaw_rate, max_yaw_rate) + + RT_Rd_quat = quat_mul(quat_inverse(self.robot_orientation), + np.array(setpoint_orientation)) + RT_Rd = quat_to_rotation_matrix(RT_Rd_quat) + + # Ensure RT_Rd is 2D for vee map computation + if RT_Rd.ndim == 3: + RT_Rd = RT_Rd.squeeze() + + skew_symmetric = RT_Rd.T - RT_Rd + rotation_error = 0.5 * compute_vee_map(skew_symmetric) + + # Ensure rotation_error is 1D + if rotation_error.ndim > 1: + rotation_error = rotation_error.flatten()[:3] + + angvel_error = self.robot_body_angvel - quat_rotate(RT_Rd_quat, setpoint_angvel) + + # Feed-forward body rates (gyroscopic effects) + inertia_angvel = self.robot_inertia @ self.robot_body_angvel + feed_forward_body_rates = np.cross(self.robot_body_angvel, inertia_angvel) + + # Lee geometric control on SO(3): M = -K_R·e_R - K_omega·e_omega + ω×J·ω. + # `rotation_error` already equals Lee's e_R (sign convention from + # `0.5·vee(R_d^T R - R^T R_d)`), and `angvel_error` equals e_omega, so all + # three terms emit body torque in physical N·m with no downstream negation. + torque = ( + -self.K_rot_current * rotation_error + - self.K_angvel_current * angvel_error + + feed_forward_body_rates + ) + + # Debug: Print torque calculation details periodically (disabled for performance) + # if not hasattr(self, '_torque_debug_counter'): + # self._torque_debug_counter = 0 + # self._torque_debug_counter += 1 + # if self._torque_debug_counter % 100 == 1: # Print every 100 calls + # print(f"\nTORQUE CALCULATION DEBUG:") + # print(f" rotation_error: {rotation_error}") + # print(f" K_rot_current: {self.K_rot_current}") + # print(f" K_rot * rot_err: {self.K_rot_current * rotation_error}") + # print(f" angvel_error: {angvel_error}") + # print(f" K_angvel_current: {self.K_angvel_current}") + # print(f" K_angvel * angvel_err: {self.K_angvel_current * angvel_error}") + # print(f" feed_forward: {feed_forward_body_rates}") + # print(f" TOTAL torque: {torque}") + + return torque + + +def calculate_desired_orientation_from_forces_and_yaw(forces_command, yaw_setpoint, orient="NED"): + """Calculate desired orientation from force command and yaw setpoint + + Args: + forces_command: Force command in WORLD frame [Fx, Fy, Fz] + yaw_setpoint: Desired yaw angle + orient: Coordinate system ("NED" or "ENU") + """ + forces_command = np.array(forces_command) + yaw_setpoint = np.array(yaw_setpoint) + + if forces_command.ndim == 1: + # Single vector case - align body Z-axis with world force direction + # The sign depends on coordinate system and motor configuration + if orient == "NED": + # In NED: motors point upward (negative Z), so body Z should oppose force + b3_c = -forces_command / np.linalg.norm(forces_command) + else: # ENU + # In ENU: motors point upward (positive Z), so body Z should align with force + b3_c = forces_command / np.linalg.norm(forces_command) + + if orient == "NED": + # NED: X=North, Y=East, Z=Down - follow PX4 approach + temp_dir = np.array([np.cos(yaw_setpoint), np.sin(yaw_setpoint), 0.0]) + b2_c = np.cross(b3_c, temp_dir) # Calculate b2 first: b3 × desired_heading + b2_c = b2_c / np.linalg.norm(b2_c) + b1_c = np.cross(b2_c, b3_c) # Complete right-handed frame: b2 × b3 + else: # ENU + # ENU: Original cross product order + temp_dir = np.array([np.cos(yaw_setpoint), np.sin(yaw_setpoint), 0.0]) + b2_c = np.cross(b3_c, temp_dir) + b2_c = b2_c / np.linalg.norm(b2_c) + b1_c = np.cross(b2_c, b3_c) + + rotation_matrix_desired = np.column_stack([b1_c, b2_c, b3_c]) + quat_desired = matrix_to_quaternion(rotation_matrix_desired) + else: + # Array case - align body Z-axis with world force direction + if orient == "NED": + # In NED: motors point upward (negative Z), so body Z should oppose force + b3_c = -forces_command / np.linalg.norm(forces_command, axis=-1, keepdims=True) + else: # ENU + # In ENU: motors point upward (positive Z), so body Z should align with force + b3_c = forces_command / np.linalg.norm(forces_command, axis=-1, keepdims=True) + + temp_dir = np.zeros_like(forces_command) + temp_dir[..., 0] = np.cos(yaw_setpoint) + temp_dir[..., 1] = np.sin(yaw_setpoint) + + b2_c = np.cross(b3_c, temp_dir, axis=-1) + b2_c = b2_c / np.linalg.norm(b2_c, axis=-1, keepdims=True) + b1_c = np.cross(b2_c, b3_c, axis=-1) + + # Build rotation matrices + batch_size = forces_command.shape[0] + rotation_matrices = np.zeros((batch_size, 3, 3)) + rotation_matrices[..., :, 0] = b1_c + rotation_matrices[..., :, 1] = b2_c + rotation_matrices[..., :, 2] = b3_c + + quat_desired = matrix_to_quaternion(rotation_matrices) + + return quat_desired + + +def calculate_desired_orientation_for_position_velocity_control( + forces_command, yaw_setpoint, rotation_matrix_buffer=None, orient="NED" +): + """Calculate desired orientation for position/velocity control + + Args: + forces_command: Force command in WORLD frame [Fx, Fy, Fz] + yaw_setpoint: Desired yaw angle + rotation_matrix_buffer: Optional buffer for rotation matrix + orient: Coordinate system ("NED" or "ENU") + """ + forces_command = np.array(forces_command) + yaw_setpoint = np.array(yaw_setpoint) + + if forces_command.ndim == 1: + # Single vector case - align body Z-axis with world force direction + # The sign depends on coordinate system and motor configuration + if orient == "NED": + # In NED: motors point upward (negative Z), so body Z should oppose force + b3_c = -forces_command / np.linalg.norm(forces_command) + else: # ENU + # In ENU: motors point upward (positive Z), so body Z should align with force + b3_c = forces_command / np.linalg.norm(forces_command) + + if orient == "NED": + # NED: X=North, Y=East, Z=Down - follow PX4 approach + temp_dir = np.array([np.cos(yaw_setpoint), np.sin(yaw_setpoint), 0.0]) + b2_c = np.cross(b3_c, temp_dir) # Calculate b2 first: b3 × desired_heading + b2_c = b2_c / np.linalg.norm(b2_c) + b1_c = np.cross(b2_c, b3_c) # Complete right-handed frame: b2 × b3 + else: # ENU + # ENU: Original cross product order + temp_dir = np.array([np.cos(yaw_setpoint), np.sin(yaw_setpoint), 0.0]) + b2_c = np.cross(b3_c, temp_dir) + b2_c = b2_c / np.linalg.norm(b2_c) + b1_c = np.cross(b2_c, b3_c) + + rotation_matrix_desired = np.column_stack([b1_c, b2_c, b3_c]) + quat_desired = matrix_to_quaternion(rotation_matrix_desired) + else: + # Array case - align body Z-axis with world force direction + # The sign depends on coordinate system and motor configuration + if orient == "NED": + # In NED: motors point upward (negative Z), so body Z should oppose force + b3_c = -forces_command / np.linalg.norm(forces_command, axis=-1, keepdims=True) + else: # ENU + # In ENU: motors point upward (positive Z), so body Z should align with force + b3_c = forces_command / np.linalg.norm(forces_command, axis=-1, keepdims=True) + temp_dir = np.zeros_like(forces_command) + temp_dir[..., 0] = np.cos(yaw_setpoint) + temp_dir[..., 1] = np.sin(yaw_setpoint) + + if orient == "NED": + # NED: Follow PX4 approach for array case + b2_c = np.cross(b3_c, temp_dir, axis=-1) # Calculate b2 first: b3 × desired_heading + b2_c = b2_c / np.linalg.norm(b2_c, axis=-1, keepdims=True) + b1_c = np.cross(b2_c, b3_c, axis=-1) # Complete right-handed frame: b2 × b3 + else: # ENU + # ENU: Original cross product order + b2_c = np.cross(b3_c, temp_dir, axis=-1) + b2_c = b2_c / np.linalg.norm(b2_c, axis=-1, keepdims=True) + b1_c = np.cross(b2_c, b3_c, axis=-1) + + # Build rotation matrices + batch_size = forces_command.shape[0] + rotation_matrices = np.zeros((batch_size, 3, 3)) + rotation_matrices[..., :, 0] = b1_c + rotation_matrices[..., :, 1] = b2_c + rotation_matrices[..., :, 2] = b3_c + + quat_desired = matrix_to_quaternion(rotation_matrices) + + return quat_desired + + +def euler_rates_to_body_rates(robot_euler_angles, desired_euler_rates, rotmat_buffer=None): + """Convert Euler angle rates to body frame angular rates""" + robot_euler_angles = np.array(robot_euler_angles) + desired_euler_rates = np.array(desired_euler_rates) + + if robot_euler_angles.ndim == 1: + # Single vector case + s_pitch = np.sin(robot_euler_angles[1]) + c_pitch = np.cos(robot_euler_angles[1]) + s_roll = np.sin(robot_euler_angles[0]) + c_roll = np.cos(robot_euler_angles[0]) + + rotmat_euler_to_body_rates = np.array([ + [1.0, 0.0, -s_pitch], + [0.0, c_roll, s_roll * c_pitch], + [0.0, -s_roll, c_roll * c_pitch] + ]) + + return rotmat_euler_to_body_rates @ desired_euler_rates + else: + # Array case (batch processing) + s_pitch = np.sin(robot_euler_angles[..., 1]) + c_pitch = np.cos(robot_euler_angles[..., 1]) + s_roll = np.sin(robot_euler_angles[..., 0]) + c_roll = np.cos(robot_euler_angles[..., 0]) + + batch_size = robot_euler_angles.shape[0] + rotmat_euler_to_body_rates = np.zeros((batch_size, 3, 3)) + + rotmat_euler_to_body_rates[:, 0, 0] = 1.0 + rotmat_euler_to_body_rates[:, 1, 1] = c_roll + rotmat_euler_to_body_rates[:, 0, 2] = -s_pitch + rotmat_euler_to_body_rates[:, 2, 1] = -s_roll + rotmat_euler_to_body_rates[:, 1, 2] = s_roll * c_pitch + rotmat_euler_to_body_rates[:, 2, 2] = c_roll * c_pitch + + return np.einsum('bij,bj->bi', rotmat_euler_to_body_rates, desired_euler_rates) \ No newline at end of file diff --git a/src/ariel/simulation/drone/controllers/lee_control/fully_actuated_control.py b/src/ariel/simulation/drone/controllers/lee_control/fully_actuated_control.py new file mode 100644 index 000000000..be46ffe49 --- /dev/null +++ b/src/ariel/simulation/drone/controllers/lee_control/fully_actuated_control.py @@ -0,0 +1,43 @@ +import numpy as np +import logging +from .lee_math_utils import * +from .base_lee_controller import BaseLeeController + +logger = logging.getLogger("fully_actuated_controller") + + +class FullyActuatedController(BaseLeeController): + def __init__(self, config, mass=1.0, inertia=None, gravity=None): + super().__init__(config, mass, inertia, gravity) + self.init_controller_gains() + + def update(self, command_actions): + """ + Fully actuated controller. Input is position and orientation setpoints. + command_actions = [p_x, p_y, p_z, qx, qy, qz, qw] + Position setpoint is in the world frame + Orientation reference is w.r.t world frame + """ + command_actions = np.array(command_actions) + self.reset_commands() + + # Normalize quaternion command + command_actions[3:7] = normalize(command_actions[3:7]) + + # Compute desired acceleration for position tracking + self.accel = self.compute_acceleration( + command_actions[0:3], np.zeros(3) + ) + forces = self.mass * (self.accel - self.gravity) + + # Full force control (all three axes) + self.wrench_command[0:3] = quat_rotate_inverse(self.robot_orientation, forces) + + # Set desired orientation from command + self.desired_quat = command_actions[3:7].copy() + + # Compute body torques for orientation tracking (zero angular velocity setpoint) + self.wrench_command[3:6] = self.compute_body_torque( + self.desired_quat, np.zeros(3) + ) + return self.wrench_command.copy() \ No newline at end of file diff --git a/src/ariel/simulation/drone/controllers/lee_control/lee_controller.py b/src/ariel/simulation/drone/controllers/lee_control/lee_controller.py new file mode 100644 index 000000000..04cb2070d --- /dev/null +++ b/src/ariel/simulation/drone/controllers/lee_control/lee_controller.py @@ -0,0 +1,361 @@ +# -*- coding: utf-8 -*- +""" +Lee Geometric Controller for Arbitrary Drone Configurations + +This controller implements the Lee geometric control algorithm and provides +the same interface as GeneralizedControl for seamless integration with the +existing simulation framework. + +Based on "Geometric tracking control of a quadrotor UAV on SE(3)" by Lee, Leok, and McClamroch. + +author: Implementation compatible with John Bass framework +license: MIT +""" + +import numpy as np +from numpy import pi, sin, cos, tan, sqrt +from numpy.linalg import norm, pinv +import ariel.simulation.drone.controllers.utils as utils + +from .position_control import LeePositionController +from .attitude_control import LeeAttitudeController +from .velocity_control import LeeVelocityController +from .lee_math_utils import * + +rad2deg = 180.0/pi +deg2rad = pi/180.0 + +class LeeGeometricControl: + """ + Lee Geometric Controller for Arbitrary Drone Configurations. + + This controller implements the Lee geometric control algorithm while maintaining + the same interface as GeneralizedControl for seamless integration. + """ + + def __init__(self, quad, yawType, orient="NED", + # Lee control gains - Tuned for direct SO(3) control (not cascaded like PX4). + # Defaults are calibrated for a heavier ~1 kg drone; pass auto_scale_gains=True + # (or override att/rate gains) for small drones where the legacy defaults + # demand torques exceeding motor allocation capacity. + pos_P_gain=None, # Position gains [kx, ky, kz] + vel_P_gain=None, # Velocity gains [kvx, kvy, kvz] + att_P_gain=None, # Attitude gains [kR_roll, kR_pitch, kR_yaw] + rate_P_gain=None, # Angular rate gains + auto_scale_gains=False, # Scale att/rate gains by inertia + # Interface compatibility (unused parameters for compatibility with PID controllers) + **kwargs): # Catches vel_D_gain, vel_I_gain, rate_D_gain, tilt_max, rate_max, vel_max, etc. + """ + Initialize Lee geometric controller. + + The Lee controller uses a fundamentally different approach than PID cascade controllers. + It directly computes forces and torques from geometric tracking errors. + + Args: + quad: ConfigurableQuadcopter instance + yawType: Yaw control type (0=disabled, 1=enabled) + orient: Coordinate frame ("NED" or "ENU") + + # Lee Control Gains (the core parameters; pass None for built-in defaults) + pos_P_gain: Position control gains [kx, ky, kz] + vel_P_gain: Velocity control gains [kvx, kvy, kvz] + att_P_gain: Attitude control gains [kR_roll, kR_pitch, kR_yaw] + rate_P_gain: Angular rate gains [komega_roll, komega_pitch, komega_yaw] + auto_scale_gains: If True and att/rate gains are not user-provided, + derive them from the drone's inertia (K_rot = I·ω_n², K_angvel = 2·I·ω_n + for a critically damped second-order attitude response). Required for + small drones (e.g. 2-inch quads, Izz ≈ 1e-4) where the heavy-drone + defaults saturate the motor allocation immediately. + + **kwargs: Unused PID parameters (vel_D_gain, vel_I_gain, rate_D_gain, + tilt_max, rate_max, vel_max, aggressiveness, etc.) kept for interface compatibility + """ + # Store drone reference and configuration + self.quad = quad + self.drone_config = quad.drone_sim.config + self.num_motors = self.drone_config.num_motors + self.orient = orient + + # Built-in defaults (calibrated for ~1 kg drone with heavy inertia). + if pos_P_gain is None: + pos_P_gain = np.array([2.0, 2.0, 3.0]) + if vel_P_gain is None: + vel_P_gain = np.array([3.0, 3.0, 4.0]) + + # Auto-scale att/rate gains from inertia. The Lee controller emits torques + # directly (N·m), so K_rot must scale with inertia to give a consistent + # closed-loop bandwidth. Underlying second-order shape: + # I·θ̈ + K_angvel·θ̇ + K_rot·θ = 0 → K_rot = I·ω_n², K_angvel = 2·I·ω_n. + if auto_scale_gains and att_P_gain is None and rate_P_gain is None: + I_diag = np.diag(np.asarray(quad.params["IB"])) + omega_n_att = 12.0 # rad/s; closed-loop attitude natural frequency + att_P_gain = I_diag * omega_n_att ** 2 + rate_P_gain = 2.0 * I_diag * omega_n_att + + if att_P_gain is None: + att_P_gain = np.array([0.3, 0.3, 0.1]) + if rate_P_gain is None: + rate_P_gain = np.array([0.05, 0.05, 0.03]) + + # Store control gains (Lee control uses different structure than PID) + self.pos_P_gain = np.asarray(pos_P_gain, dtype=float).copy() + self.vel_P_gain = np.asarray(vel_P_gain, dtype=float).copy() + self.att_P_gain = np.asarray(att_P_gain, dtype=float).copy() + self.rate_P_gain = np.asarray(rate_P_gain, dtype=float).copy() + + # Extract unused parameters from kwargs for interface compatibility (not enforced) + self.tilt_max = kwargs.get('tilt_max', 50.0*deg2rad) # Only used for reporting + self.rate_max = kwargs.get('rate_max', np.array([200.0*deg2rad, 200.0*deg2rad, 150.0*deg2rad])) # Only used for reporting + self.vel_max = kwargs.get('vel_max', np.array([5.0, 5.0, 5.0])) # Only used for reporting + self.vel_max_all = kwargs.get('vel_max_all', 5.0) # Only used for reporting + self.aggressiveness = kwargs.get('aggressiveness', 1.0) # Only used for reporting + + # Initialize Lee controller components + self._init_lee_controllers(quad) + + # Initialize state variables + + # Initialize motor commands + self.w_cmd = np.ones(self.num_motors) * self._get_hover_speed(quad) + + # Setup yaw control + if (yawType == 0): + self.att_P_gain[2] = 0 + + + # Variables for interface compatibility and logging + self.sDesCalc = np.zeros(16) # Calculated desired state (for logging) + + # Lee control specific variables + self.desired_orientation = np.array([0.0, 0.0, 0.0, 1.0]) + self.wrench_command = np.zeros(6) # [fx, fy, fz, tx, ty, tz] + + def _init_lee_controllers(self, quad): + """Initialize Lee controller components""" + # Create a simple config object for the Lee controllers + class LeeConfig: + def __init__(self, pos_gains, vel_gains, att_gains, rate_gains): + self.K_pos_tensor_max = pos_gains + self.K_pos_tensor_min = pos_gains + self.K_vel_tensor_max = vel_gains + self.K_vel_tensor_min = vel_gains + self.K_rot_tensor_max = att_gains + self.K_rot_tensor_min = att_gains + self.K_angvel_tensor_max = rate_gains + self.K_angvel_tensor_min = rate_gains + self.randomize_params = False + self.max_yaw_rate = 2.0 + + config = LeeConfig(self.pos_P_gain, self.vel_P_gain, self.att_P_gain, self.rate_P_gain) + + # Get drone properties + mass = quad.params["mB"] + inertia = quad.params["IB"] # Already a 3x3 matrix + gravity = np.array([0.0, 0.0, quad.params["g"]]) # NED frame + if self.orient == "ENU": + gravity = np.array([0.0, 0.0, -quad.params["g"]]) # ENU frame + + # Initialize position controller + self.position_controller = LeePositionController(config, mass, inertia, gravity, self.orient) + + # Initialize velocity controller + self.velocity_controller = LeeVelocityController(config, mass, inertia, gravity, self.orient) + + # Initialize attitude controller + self.attitude_controller = LeeAttitudeController(config, mass, inertia, gravity, self.orient) + + def _get_hover_speed(self, quad): + """Calculate hover speed for each motor.""" + hover_speeds = [] + hover_thrust_per_motor = (quad.params["mB"] * quad.params["g"]) / self.num_motors + + for prop in self.drone_config.propellers: + k_f, k_m = prop["constants"] + w_hover = sqrt(hover_thrust_per_motor / k_f) + hover_speeds.append(w_hover) + + return np.array(hover_speeds) + + def controller(self, sDes, quad, ctrl_type, Ts): + """ + Main Lee controller function. + + Args: + sDes: Desired state vector [pos(3), vel(3), acc(3), thrust(3), eul(3), pqr(3), yawRate] + quad: ConfigurableQuadcopter instance + ctrl_type: Control type ("xyz_pos", "xyz_vel", etc.) + Ts: Time step + """ + # Extract desired state + pos_sp = sDes[0:3].copy() + vel_sp = sDes[3:6].copy() + thrust_sp = sDes[9:12].copy() + eul_sp = sDes[12:15].copy() + yawFF = sDes[18] if len(sDes) > 18 else 0.0 + + # Update Lee controller state from quadcopter + self._update_lee_controller_state(quad) + + # Apply control based on control type + if (ctrl_type == "xyz_vel"): + self._lee_velocity_control(vel_sp, quad, Ts, yawFF) + elif (ctrl_type == "xyz_pos"): + self._lee_position_control(pos_sp, eul_sp, quad, Ts) + + # Convert Lee control output to motor commands + self._wrench_to_motor_commands(quad) + + # Update calculated desired states for logging (interface compatibility) + self.sDesCalc[0:3] = pos_sp + self.sDesCalc[3:6] = vel_sp + self.sDesCalc[6:9] = thrust_sp + self.sDesCalc[9:13] = self.desired_orientation + self.sDesCalc[13:16] = np.zeros(3) # Rate setpoint (not used in Lee control) + + def _update_lee_controller_state(self, quad): + """Update Lee controller state from quadcopter state""" + # CRITICAL FIX: Convert quaternion from simulator's [w, x, y, z] format to Lee math utils' [x, y, z, w] format + quat_wxyz = quad.quat.copy() # Simulator format: [w, x, y, z] + quat_xyzw = np.array([quat_wxyz[1], quat_wxyz[2], quat_wxyz[3], quat_wxyz[0]]) # Lee format: [x, y, z, w] + + robot_state = { + "position": quad.pos.copy(), + "orientation": quat_xyzw, # Now in correct [x, y, z, w] format for Lee math utils + "linear_velocity": quad.vel.copy(), + "angular_velocity": quad.omega.copy(), + "euler_angles": quad.euler.copy() + } + + # Update all controller states + self.position_controller.update_state(robot_state) + self.velocity_controller.update_state(robot_state) + self.attitude_controller.update_state(robot_state) + + def _lee_velocity_control(self, vel_sp, quad, Ts, yaw_rate=0.0): + """Lee geometric velocity control""" + + + # Update velocity controller state + self._update_lee_controller_state(quad) + + # Create velocity command: [vx, vy, vz, yaw_rate] + command_actions = np.concatenate([vel_sp, [yaw_rate]]) + + # Use velocity controller + self.wrench_command = self.velocity_controller.update(command_actions) + + # Store desired orientation for logging + self.desired_orientation = self.velocity_controller.desired_quat + + def _lee_position_control(self, pos_sp, eul_sp, quad, Ts): + """Lee geometric position control""" + # Update position controller state + self._update_lee_controller_state(quad) + + # Create position command: [px, py, pz, yaw] + command_actions = np.concatenate([pos_sp, [eul_sp[2]]]) + + # Use position controller + self.wrench_command = self.position_controller.update(command_actions) + + # Store desired orientation for logging + self.desired_orientation = self.position_controller.desired_quat + + def _wrench_to_motor_commands(self, quad): + """Convert Lee control wrench output to motor commands""" + # Extract force and moment from wrench command + force_command = self.wrench_command[0:3] + moment_command = self.wrench_command[3:6] + + # FIXED: Use Z-component like PX4 controller, not magnitude + # The thrust command represents the motor thrust magnitude (always positive) + # In NED: force Z is negative for upward, so negate to get positive thrust + # In ENU: force Z is positive for upward, use directly + if self.orient == "NED": + # In NED: negate Z component to convert upward force to positive thrust + thrust_command = -force_command[2] + # Debug: remove after confirming fix + if abs(thrust_command) > 100 or thrust_command < 0: + print(f"WARNING: Unusual thrust_command = {thrust_command:.2f} N from force = {force_command}") + else: # ENU + # In ENU: Z component is already positive for upward + thrust_command = force_command[2] + + # `compute_body_torque` already emits Lee's M_des in physical body N·m, + # and the mixerFM rows are physical (T per W², τ per W²), so we pass the + # moment through directly. (The earlier `torque_scale=-1.0` predated the + # base-controller sign fix and reversed angular-rate damping.) + roll_torque = moment_command[0] + pitch_torque = moment_command[1] + yaw_torque = moment_command[2] + + # Create command vector [thrust, roll_torque, pitch_torque, yaw_torque] + t = np.array([thrust_command, roll_torque, pitch_torque, yaw_torque]) + + # FIXED: Add safety limits to prevent motor saturation + max_thrust = quad.params["maxThr"] * 1.0 # Use 80% of max thrust + min_thrust = quad.params["minThr"] * 1.0 # Allow zero thrust + thrust_command = np.clip(thrust_command, min_thrust, max_thrust) + t[0] = thrust_command + + # DEBUG: Print allocation matrix usage (disabled for performance) + # if not hasattr(self, '_allocation_debug_counter'): + # self._allocation_debug_counter = 0 + # self._allocation_debug_counter += 1 + # if self._allocation_debug_counter % 100 == 1: + # print(f"\nALLOCATION DEBUG:") + # print(f" Input t (thrust, Mx, My, Mz): {t}") + # print(f" mixerFM (what w²=1 for all motors produces):") + # max_capability = np.dot(quad.params["mixerFM"], np.ones(4)) + # print(f" {max_capability}") + # print(f" mixerFMinv shape: {quad.params['mixerFMinv'].shape}") + + # Convert to motor commands using allocation matrix (same as GeneralizedControl) + w_squared_normalized = np.dot(quad.params["mixerFMinv"], t) + + # if self._allocation_debug_counter % 100 == 1: + # print(f" w_squared_normalized: {w_squared_normalized}") + # # Verify by multiplying back + # verification = np.dot(quad.params["mixerFM"], w_squared_normalized) + # print(f" Verification (should equal t): {verification}") + + # Convert from normalized to actual motor speeds + w_max_values = np.array([prop["wmax"] for prop in quad.drone_sim.config.propellers]) + w_squared_actual = w_squared_normalized * (w_max_values**2) + + # Apply limits and take square root + self.w_cmd = np.sqrt(np.clip(w_squared_actual, + quad.params["minWmotor"]**2, + quad.params["maxWmotor"]**2)) + + # if self._allocation_debug_counter % 100 == 1: + # print(f" w_cmd (motor speeds): {self.w_cmd}") + # # Calculate expected thrust + # expected_thrust_per_motor = quad.params["kTh"] * self.w_cmd**2 + # expected_total_thrust = np.sum(expected_thrust_per_motor) + # print(f" Expected thrust per motor: {expected_thrust_per_motor}") + # print(f" Expected total thrust: {expected_total_thrust:.2f} N") + # print(f" Commanded thrust was: {t[0]:.2f} N") + # print(f" Ratio: {expected_total_thrust / t[0]:.2f}x") + + + def get_control_info(self): + """Get comprehensive control configuration information.""" + info = { + 'num_motors': self.num_motors, + 'controller_type': 'Lee Geometric Control', + 'coordinate_frame': self.orient, + 'control_gains': { + 'position_P': self.pos_P_gain.tolist(), + 'velocity_P': self.vel_P_gain.tolist(), + 'attitude_P': self.att_P_gain.tolist(), + 'rate_P': self.rate_P_gain.tolist() + }, + 'control_limits': { + 'max_velocity': self.vel_max.tolist(), + 'max_velocity_norm': self.vel_max_all, + 'max_tilt_angle': self.tilt_max * rad2deg, # Reported for compatibility (not enforced) + 'max_rates': (self.rate_max * rad2deg).tolist() # Reported for compatibility (not enforced) + }, + } + return info \ No newline at end of file diff --git a/src/ariel/simulation/drone/controllers/lee_control/lee_math_utils.py b/src/ariel/simulation/drone/controllers/lee_control/lee_math_utils.py new file mode 100644 index 000000000..f7896f81f --- /dev/null +++ b/src/ariel/simulation/drone/controllers/lee_control/lee_math_utils.py @@ -0,0 +1,306 @@ +# -*- coding: utf-8 -*- +""" +Lee Control Mathematical Utilities +NumPy-based implementations of mathematical functions for Lee geometric controller +Adapted from PyTorch tensor operations to work with NumPy arrays +""" + +import numpy as np +from numpy import sin, cos, pi +from numpy.linalg import norm +import logging + +# Set up simple logging +logger = logging.getLogger("lee_control") + + +def normalize(x, eps=1e-9): + """Normalize a vector or array of vectors""" + if x.ndim == 1: + return x / max(norm(x), eps) + else: + norms = np.linalg.norm(x, axis=-1, keepdims=True) + return x / np.maximum(norms, eps) + + +def quat_multiply(q, p): + """Quaternion multiplication for arrays of quaternions + q, p: arrays of shape (..., 4) where [..., :] = [x, y, z, w] + """ + if q.ndim == 1 and p.ndim == 1: + # Single quaternion case + qx, qy, qz, qw = q[0], q[1], q[2], q[3] + px, py, pz, pw = p[0], p[1], p[2], p[3] + + w = qw*pw - qx*px - qy*py - qz*pz + x = qw*px + qx*pw + qy*pz - qz*py + y = qw*py - qx*pz + qy*pw + qz*px + z = qw*pz + qx*py - qy*px + qz*pw + + return np.array([x, y, z, w]) + else: + # Array case + q = np.atleast_2d(q) + p = np.atleast_2d(p) + + qx, qy, qz, qw = q[..., 0], q[..., 1], q[..., 2], q[..., 3] + px, py, pz, pw = p[..., 0], p[..., 1], p[..., 2], p[..., 3] + + w = qw*pw - qx*px - qy*py - qz*pz + x = qw*px + qx*pw + qy*pz - qz*py + y = qw*py - qx*pz + qy*pw + qz*px + z = qw*pz + qx*py - qy*px + qz*pw + + return np.stack([x, y, z, w], axis=-1) + + +def quat_mul(a, b): + """Alias for quat_multiply for compatibility""" + return quat_multiply(a, b) + + +def quat_conjugate(q): + """Quaternion conjugate""" + q_conj = q.copy() + q_conj[..., :3] *= -1 # Negate x, y, z components + return q_conj + + +def quat_inverse(q): + """Quaternion inverse""" + return quat_conjugate(q) + + +def quat_rotate(q, v): + """Rotate vector v by quaternion q + q: quaternion array (..., 4) [x, y, z, w] + v: vector array (..., 3) [x, y, z] + """ + if q.ndim == 1: + q = q.reshape(1, -1) + v = v.reshape(1, -1) + single = True + else: + single = False + + q_w = q[..., 3:4] # w component + q_vec = q[..., :3] # xyz components + + a = v * (2.0 * q_w**2 - 1.0) + b = np.cross(q_vec, v, axis=-1) * q_w * 2.0 + c = q_vec * np.sum(q_vec * v, axis=-1, keepdims=True) * 2.0 + + result = a + b + c + return result[0] if single else result + + +def quat_rotate_inverse(q, v): + """Rotate vector v by inverse of quaternion q""" + return quat_rotate(quat_inverse(q), v) + + +def quat_to_rotation_matrix(q): + """Convert quaternion to rotation matrix + q: quaternion array (..., 4) [x, y, z, w] + Returns: rotation matrix array (..., 3, 3) + """ + if q.ndim == 1: + q = q.reshape(1, -1) + single = True + else: + single = False + + x, y, z, w = q[..., 0], q[..., 1], q[..., 2], q[..., 3] + + xx, xy, xz, xw = x*x, x*y, x*z, x*w + yy, yz, yw = y*y, y*z, y*w + zz, zw = z*z, z*w + + m = np.zeros((*q.shape[:-1], 3, 3)) + + m[..., 0, 0] = 1 - 2*(yy + zz) + m[..., 0, 1] = 2*(xy - zw) + m[..., 0, 2] = 2*(xz + yw) + m[..., 1, 0] = 2*(xy + zw) + m[..., 1, 1] = 1 - 2*(xx + zz) + m[..., 1, 2] = 2*(yz - xw) + m[..., 2, 0] = 2*(xz - yw) + m[..., 2, 1] = 2*(yz + xw) + m[..., 2, 2] = 1 - 2*(xx + yy) + + return m[0] if single else m + + +def quat_from_euler_xyz(roll, pitch, yaw): + """Convert Euler angles to quaternion + Returns quaternion in [x, y, z, w] format + """ + if np.isscalar(roll): + # Single value case + cy = cos(yaw * 0.5) + sy = sin(yaw * 0.5) + cr = cos(roll * 0.5) + sr = sin(roll * 0.5) + cp = cos(pitch * 0.5) + sp = sin(pitch * 0.5) + + qw = cy * cr * cp + sy * sr * sp + qx = cy * sr * cp - sy * cr * sp + qy = cy * cr * sp + sy * sr * cp + qz = sy * cr * cp - cy * sr * sp + + return np.array([qx, qy, qz, qw]) + else: + # Array case + roll = np.atleast_1d(roll) + pitch = np.atleast_1d(pitch) + yaw = np.atleast_1d(yaw) + + cy = np.cos(yaw * 0.5) + sy = np.sin(yaw * 0.5) + cr = np.cos(roll * 0.5) + sr = np.sin(roll * 0.5) + cp = np.cos(pitch * 0.5) + sp = np.sin(pitch * 0.5) + + qw = cy * cr * cp + sy * sr * sp + qx = cy * sr * cp - sy * cr * sp + qy = cy * cr * sp + sy * sr * cp + qz = sy * cr * cp - cy * sr * sp + + return np.stack([qx, qy, qz, qw], axis=-1) + + +def quat_from_euler_xyz_tensor(euler_xyz): + """Convert Euler angle array to quaternion array + euler_xyz: array of shape (..., 3) [roll, pitch, yaw] + Returns: quaternion array (..., 4) [x, y, z, w] + """ + roll = euler_xyz[..., 0] + pitch = euler_xyz[..., 1] + yaw = euler_xyz[..., 2] + return quat_from_euler_xyz(roll, pitch, yaw) + + +def get_euler_xyz_tensor(q): + """Convert quaternion to Euler angles + q: quaternion array (..., 4) [x, y, z, w] + Returns: Euler angles (..., 3) [roll, pitch, yaw] + """ + if q.ndim == 1: + q = q.reshape(1, -1) + single = True + else: + single = False + + qx, qy, qz, qw = q[..., 0], q[..., 1], q[..., 2], q[..., 3] + + # Roll (x-axis rotation) + sinr_cosp = 2 * (qw * qx + qy * qz) + cosr_cosp = qw**2 - qx**2 - qy**2 + qz**2 + roll = np.arctan2(sinr_cosp, cosr_cosp) + + # Pitch (y-axis rotation) + sinp = 2 * (qw * qy - qz * qx) + pitch = np.where(np.abs(sinp) >= 1, + np.sign(sinp) * pi / 2.0, + np.arcsin(sinp)) + + # Yaw (z-axis rotation) + siny_cosp = 2 * (qw * qz + qx * qy) + cosy_cosp = qw**2 + qx**2 - qy**2 - qz**2 + yaw = np.arctan2(siny_cosp, cosy_cosp) + + result = np.stack([roll % (2 * pi), pitch % (2 * pi), yaw % (2 * pi)], axis=-1) + return result[0] if single else result + + +def compute_vee_map(skew_matrix): + """Extract vector from skew-symmetric matrix + skew_matrix: array of shape (..., 3, 3) + Returns: vector array (..., 3) + """ + vee_map = np.stack([ + -skew_matrix[..., 1, 2], + skew_matrix[..., 0, 2], + -skew_matrix[..., 0, 1] + ], axis=-1) + return vee_map + + +def matrix_to_quaternion(rotation_matrix): + """Convert rotation matrix to quaternion + Simple implementation to replace pytorch3d.transforms.matrix_to_quaternion + """ + if rotation_matrix.ndim == 2: + rotation_matrix = rotation_matrix.reshape(1, 3, 3) + single = True + else: + single = False + + batch_size = rotation_matrix.shape[0] + quaternions = np.zeros((batch_size, 4)) + + for i in range(batch_size): + R = rotation_matrix[i] + + # Shepperd's method + trace = np.trace(R) + + if trace > 0: + s = np.sqrt(trace + 1.0) * 2 # s = 4 * qw + qw = 0.25 * s + qx = (R[2, 1] - R[1, 2]) / s + qy = (R[0, 2] - R[2, 0]) / s + qz = (R[1, 0] - R[0, 1]) / s + elif R[0, 0] > R[1, 1] and R[0, 0] > R[2, 2]: + s = np.sqrt(1.0 + R[0, 0] - R[1, 1] - R[2, 2]) * 2 # s = 4 * qx + qw = (R[2, 1] - R[1, 2]) / s + qx = 0.25 * s + qy = (R[0, 1] + R[1, 0]) / s + qz = (R[0, 2] + R[2, 0]) / s + elif R[1, 1] > R[2, 2]: + s = np.sqrt(1.0 + R[1, 1] - R[0, 0] - R[2, 2]) * 2 # s = 4 * qy + qw = (R[0, 2] - R[2, 0]) / s + qx = (R[0, 1] + R[1, 0]) / s + qy = 0.25 * s + qz = (R[1, 2] + R[2, 1]) / s + else: + s = np.sqrt(1.0 + R[2, 2] - R[0, 0] - R[1, 1]) * 2 # s = 4 * qz + qw = (R[1, 0] - R[0, 1]) / s + qx = (R[0, 2] + R[2, 0]) / s + qy = (R[1, 2] + R[2, 1]) / s + qz = 0.25 * s + + # Convert from [w, x, y, z] to [x, y, z, w] format + quaternions[i] = [qx, qy, qz, qw] + + return quaternions[0] if single else quaternions + + +def vehicle_frame_quat_from_quat(body_quat): + """Get vehicle frame quaternion from body quaternion (only yaw component)""" + body_euler = get_euler_xyz_tensor(body_quat) * np.array([0.0, 0.0, 1.0]) + return quat_from_euler_xyz_tensor(body_euler) + + +def rand_float_uniform(lower, upper, shape=None): + """Generate random float values between lower and upper bounds""" + if shape is None and np.isscalar(lower) and np.isscalar(upper): + return np.random.uniform(lower, upper) + else: + if np.isscalar(lower): + lower = np.full(shape, lower) + if np.isscalar(upper): + upper = np.full(shape, upper) + return np.random.uniform(lower, upper, shape) + + +def pd_control(pos_error, vel_error, stiffness, damping): + """PD controller implementation""" + return stiffness * pos_error + damping * vel_error + + +def ssa(angle): + """Smallest signed angle - wrap angle to [-pi, pi]""" + return np.remainder(angle + pi, 2 * pi) - pi \ No newline at end of file diff --git a/src/ariel/simulation/drone/controllers/lee_control/position_control.py b/src/ariel/simulation/drone/controllers/lee_control/position_control.py new file mode 100644 index 000000000..793ae7d98 --- /dev/null +++ b/src/ariel/simulation/drone/controllers/lee_control/position_control.py @@ -0,0 +1,67 @@ +import numpy as np +import logging +from .lee_math_utils import * +from .base_lee_controller import BaseLeeController, calculate_desired_orientation_for_position_velocity_control + +logger = logging.getLogger("lee_position_controller") + + +class LeePositionController(BaseLeeController): + def __init__(self, config, mass=1.0, inertia=None, gravity=None, orient="NED"): + super().__init__(config, mass, inertia, gravity) + self.orient = orient + self.init_controller_gains() + + def update(self, command_actions): + """ + Lee position controller + :param command_actions: array of shape (4,) with [px, py, pz, yaw] position setpoint and yaw command + :return: wrench command [fx, fy, fz, tx, ty, tz] + """ + command_actions = np.array(command_actions) + self.reset_commands() + + # Compute desired acceleration + self.accel = self.compute_acceleration( + setpoint_position=command_actions[0:3], + setpoint_velocity=np.zeros(3), # Zero velocity setpoint + ) + + # Convert acceleration to forces (WORLD frame) + # self.accel is in world frame, self.gravity is in world frame + forces = (self.accel - self.gravity) * self.mass # Forces needed to overcome gravity and achieve desired acceleration + + # DEBUG: Print force calculation details (disabled for performance) + # if hasattr(self, '_debug_count') == False: + # self._debug_count = 0 + # self._debug_count += 1 + # if self._debug_count % 50 == 1: # Print every 50 calls + # print(f"POSITION CONTROL DEBUG:") + # print(f" setpoint_position: {command_actions[0:3]}") + # print(f" robot_position: {self.robot_position}") + # print(f" position_error: {command_actions[0:3] - self.robot_position}") + # print(f" accel command: {self.accel}") + # print(f" gravity: {self.gravity}") + # print(f" accel - gravity: {self.accel - self.gravity}") + # print(f" mass: {self.mass}") + # print(f" forces: {forces}") + # print(f" orient: {self.orient}") + + # Set complete force command (WORLD frame forces) + self.wrench_command[0:3] = forces + + # Calculate desired orientation from forces and yaw setpoint + self.desired_quat = calculate_desired_orientation_for_position_velocity_control( + forces, command_actions[3], self.rotation_matrix_buffer, self.orient + ) + + # Zero angular velocity setpoint for position control + self.euler_angle_rates.fill(0.0) + self.desired_body_angvel.fill(0.0) + + # Compute body torques + self.wrench_command[3:6] = self.compute_body_torque( + self.desired_quat, self.desired_body_angvel + ) + + return self.wrench_command.copy() \ No newline at end of file diff --git a/src/ariel/simulation/drone/controllers/lee_control/rates_control.py b/src/ariel/simulation/drone/controllers/lee_control/rates_control.py new file mode 100644 index 000000000..efcef7741 --- /dev/null +++ b/src/ariel/simulation/drone/controllers/lee_control/rates_control.py @@ -0,0 +1,31 @@ +import numpy as np +import logging +from .lee_math_utils import * +from .base_lee_controller import BaseLeeController + +logger = logging.getLogger("rates_controller") + + +class LeeRatesController(BaseLeeController): + def __init__(self, config, mass=1.0, inertia=None, gravity=None): + super().__init__(config, mass, inertia, gravity) + self.init_controller_gains() + + def update(self, command_actions): + """ + Lee rates controller (direct angular rate control) + :param command_actions: array of shape (4,) with [thrust, wx, wy, wz] thrust and angular rate commands + :return: wrench command [fx, fy, fz, tx, ty, tz] + """ + command_actions = np.array(command_actions) + self.reset_commands() + + # Direct thrust command + self.wrench_command[2] = (command_actions[0] - np.linalg.norm(self.gravity)) * self.mass + + # Direct angular rate control - maintain current orientation, track desired rates + self.wrench_command[3:6] = self.compute_body_torque( + self.robot_orientation, command_actions[1:4] + ) + + return self.wrench_command.copy() \ No newline at end of file diff --git a/src/ariel/simulation/drone/controllers/lee_control/velocity_control.py b/src/ariel/simulation/drone/controllers/lee_control/velocity_control.py new file mode 100644 index 000000000..3391239c3 --- /dev/null +++ b/src/ariel/simulation/drone/controllers/lee_control/velocity_control.py @@ -0,0 +1,54 @@ +import numpy as np +import logging +from .lee_math_utils import * +from .base_lee_controller import BaseLeeController, calculate_desired_orientation_for_position_velocity_control, euler_rates_to_body_rates + +logger = logging.getLogger("velocity_controller") + + +class LeeVelocityController(BaseLeeController): + def __init__(self, config, mass=1.0, inertia=None, gravity=None, orient="NED"): + super().__init__(config, mass, inertia, gravity) + self.orient = orient + self.init_controller_gains() + + def update(self, command_actions): + """ + Lee velocity controller + :param command_actions: array of shape (4,) with [vx, vy, vz, yaw_rate] velocity setpoint and yaw rate command + :return: wrench command [fx, fy, fz, tx, ty, tz] + """ + command_actions = np.array(command_actions) + self.reset_commands() + + # Compute desired acceleration (maintaining current position, tracking velocity) + self.accel = self.compute_acceleration( + setpoint_position=self.robot_position, # Maintain current position + setpoint_velocity=command_actions[0:3], # Track desired velocity + ) + + # Convert acceleration to forces (WORLD frame) + # self.accel is in world frame, self.gravity is in world frame + forces = (self.accel - self.gravity) * self.mass + + # Set complete force command (WORLD frame forces) + self.wrench_command[0:3] = forces + + # Calculate desired orientation from WORLD frame forces and current yaw + self.desired_quat = calculate_desired_orientation_for_position_velocity_control( + forces, self.robot_euler_angles[2], self.rotation_matrix_buffer, self.orient + ) + + # Set desired angular rates (zero roll/pitch rates, commanded yaw rate) + self.euler_angle_rates[0:2] = 0.0 + self.euler_angle_rates[2] = command_actions[3] + self.desired_body_angvel = euler_rates_to_body_rates( + self.robot_euler_angles, self.euler_angle_rates, self.rotation_matrix_buffer + ) + + # Compute body torques + self.wrench_command[3:6] = self.compute_body_torque( + self.desired_quat, self.desired_body_angvel + ) + + return self.wrench_command.copy() \ No newline at end of file diff --git a/src/ariel/simulation/drone/controllers/lee_control/velocity_steeing_angle_controller.py b/src/ariel/simulation/drone/controllers/lee_control/velocity_steeing_angle_controller.py new file mode 100644 index 000000000..361e8c666 --- /dev/null +++ b/src/ariel/simulation/drone/controllers/lee_control/velocity_steeing_angle_controller.py @@ -0,0 +1,53 @@ +import numpy as np +import logging +from .lee_math_utils import * +from .base_lee_controller import BaseLeeController, calculate_desired_orientation_for_position_velocity_control, euler_rates_to_body_rates + +logger = logging.getLogger("velocity_steering_controller") + + +class LeeVelocitySteeringAngleController(BaseLeeController): + def __init__(self, config, mass=1.0, inertia=None, gravity=None, orient="NED"): + super().__init__(config, mass, inertia, gravity) + self.orient = orient + self.init_controller_gains() + self.euler_angle_rates = np.zeros(3) + + def update(self, command_actions): + """ + Lee velocity steering angle controller + :param command_actions: array of shape (4,) with [vx, vy, vz, steering_angle] velocity and steering command + :return: wrench command [fx, fy, fz, tx, ty, tz] + """ + command_actions = np.array(command_actions) + self.reset_commands() + + # Compute desired acceleration (maintaining current position, tracking velocity) + self.accel = self.compute_acceleration( + setpoint_position=self.robot_position, # Maintain current position + setpoint_velocity=command_actions[0:3], # Track desired velocity + ) + + # Convert acceleration to forces + forces = (self.accel - self.gravity) * self.mass + + # Set complete force command (WORLD frame forces) + self.wrench_command[0:3] = forces + + # Calculate desired orientation from forces and steering angle + self.desired_quat = calculate_desired_orientation_for_position_velocity_control( + forces, command_actions[3], self.rotation_matrix_buffer, self.orient + ) + + # Zero angular velocity setpoint + self.euler_angle_rates.fill(0.0) + self.desired_body_angvel = euler_rates_to_body_rates( + self.robot_euler_angles, self.euler_angle_rates, self.rotation_matrix_buffer + ) + + # Compute body torques + self.wrench_command[3:6] = self.compute_body_torque( + self.desired_quat, self.desired_body_angvel + ) + + return self.wrench_command.copy() \ No newline at end of file diff --git a/src/ariel/simulation/drone/controllers/trajectory_generation/__init__.py b/src/ariel/simulation/drone/controllers/trajectory_generation/__init__.py new file mode 100644 index 000000000..5f9341eac --- /dev/null +++ b/src/ariel/simulation/drone/controllers/trajectory_generation/__init__.py @@ -0,0 +1 @@ +# B-spline trajectory generation for drone gate racing diff --git a/src/ariel/simulation/drone/controllers/trajectory_generation/bspline_gate_trajectory.py b/src/ariel/simulation/drone/controllers/trajectory_generation/bspline_gate_trajectory.py new file mode 100644 index 000000000..bd942818a --- /dev/null +++ b/src/ariel/simulation/drone/controllers/trajectory_generation/bspline_gate_trajectory.py @@ -0,0 +1,611 @@ +# -*- coding: utf-8 -*- +""" +B-Spline Gate Trajectory Generator + +This module provides automatic trajectory generation for gate-based racing +using periodic B-spline curves. Control points are initialized at gate positions +with tension-based offsets for exact interpolation, and can be further optimized +to find the fastest path through gates. + +Author: Generated for AirEvolve project +License: MIT +""" + +import numpy as np +from typing import Optional, Tuple, Dict, Any +from .bspline_utils import BSplineCurve, generate_knot_vector, evaluate_bspline_derivative +from ..utils.gate_configs import GateConfig + + +class BSplineGateTrajectory: + """ + B-spline trajectory generator optimized for gate passing. + + This class creates a smooth periodic trajectory that passes through gates + in a racing configuration. Gate control points are optimizable within gate + bounds. A tension parameter controls how tightly the curve follows gate + positions (default: exact interpolation through gates). + + Parameters can be optimized using CMA-ES or other optimization algorithms. + """ + + def __init__(self, gate_config: GateConfig, + degree: int = 3, gate_offset_scale: float = 1.0, + tension: float = 1.0): + """ + Initialize B-spline gate trajectory with SINGLE periodic spline for C2 continuity. + + The trajectory uses ONE periodic B-spline through gate control points: + gate[0] → gate[1] → ... → gate[N-1] → wraps back to gate[0] + + This ensures C2 continuity (smooth position, velocity, AND acceleration) throughout. + + Args: + gate_config: Gate configuration with positions and yaws + degree: B-spline degree (default: 3 for cubic) + gate_offset_scale: Scale factor for gate offset bounds (default: 1.0) + Offsets are bounded by ±gate_size * gate_offset_scale + tension: How tightly the B-spline follows gate positions (0.0–1.0). + At 0.0, control points equal gate positions (default B-spline approximation). + At 1.0, control points are adjusted so the curve interpolates exactly + through gate positions. Default: 1.0. + """ + self.gate_config = gate_config + self.degree = degree + self.gate_offset_scale = gate_offset_scale + self.tension = tension + + # Extract gate information + self.gate_positions = np.array(gate_config.gate_pos, dtype=np.float64) + self.gate_yaws = np.array(gate_config.gate_yaw, dtype=np.float64) + self.gate_size = gate_config.gate_size + self.n_gates = len(self.gate_positions) + self.periodic = getattr(gate_config, 'periodic', True) + + # Control points: gate[0], gate[1], ..., gate[N-1] (periodic) + self.n_total_control_points = self.n_gates + + # Default parameters (will be overridden by set_parameters) + self.gate_offsets = None + self.total_time = 20.0 + self.velocity_scale = 1.0 + self.startup_time = 3.0 # Time for quintic ramp from rest (seconds) + + # Initialize with default values + self._initialize_default_parameters() + + # Single B-spline curve (periodic, includes all control points) + self.spline = None + self._rebuild_spline() + + def _initialize_default_parameters(self): + """Initialize control points with default values including tension-based offsets.""" + # Gate offsets: initialize with tension-based correction + # The offset compensates for B-spline approximation error so the curve + # interpolates through gate positions when tension=1.0. + # Formula: offset_i = tension * (2*G_i - G_{i-1} - G_{i+1}) / 4 + self.gate_offsets = np.zeros((self.n_gates, 3)) + for i in range(self.n_gates): + if self.periodic: + prev_gate = self.gate_positions[(i - 1) % self.n_gates] + next_gate = self.gate_positions[(i + 1) % self.n_gates] + else: + prev_gate = self.gate_positions[max(0, i - 1)] + next_gate = self.gate_positions[min(self.n_gates - 1, i + 1)] + self.gate_offsets[i] = self.tension * (2 * self.gate_positions[i] - prev_gate - next_gate) / 4 + + def get_all_control_points(self) -> np.ndarray: + """ + Get all control points for the single periodic spline. + + Returns: + Array of control points: [gate[0]+offset[0], ..., gate[N-1]+offset[N-1]] + """ + return self.gate_positions + self.gate_offsets + + def _rebuild_spline(self): + """Rebuild the single periodic B-spline curve.""" + all_cps = self.get_all_control_points() + + # Create spline with appropriate boundary condition + boundary = 'periodic' if self.periodic else 'clamped' + self.spline = BSplineCurve(all_cps, degree=self.degree, boundary=boundary) + + # Find the best starting parameter u for the trajectory (closest to desired starting position) + self._find_optimal_start_parameter() + + def _find_optimal_start_parameter(self): + """ + Find the parameter u on the spline that is closest to the desired starting position + AND that leads naturally toward gate 0 (not away from it). + + This ensures that in gate-only mode, the drone starts near the configured starting position + and moves in the correct direction through the gates. + """ + # For non-periodic splines, start at the beginning of the curve + if not self.periodic: + self._u_start = self.spline.u_min + return + + # Get the desired starting position and first gate position + desired_start = self.get_start_position() + first_gate_pos = self.gate_positions[0] + self.gate_offsets[0] + + # Sample the spline at many points to find candidates close to start position + u_min = self.spline.u_min + u_max = self.spline.u_max + u_samples = np.linspace(u_min, u_max - 0.01, 200) # Sample 200 points along spline + + # Find all points close to the starting position (within 2m) + candidates = [] + for u in u_samples: + pos = self.spline.position(u) + distance_to_start = np.linalg.norm(pos - desired_start) + if distance_to_start < 2.5: # Within 2.5m of starting position + candidates.append((u, pos, distance_to_start)) + + if not candidates: + # Fallback: just use u_min if no candidates found + self._u_start = u_min + return + + # Among candidates, choose the one where the trajectory moves TOWARD gate 0 + # Check which direction the spline goes from each candidate by looking ahead + best_u = u_min + best_score = float('inf') + + for u_candidate, pos_candidate, dist_to_start in candidates: + # Look ahead a bit on the trajectory (0.5 parameter units) + u_ahead = u_candidate + 0.5 + if self.periodic: + if u_ahead >= u_max: + u_ahead = u_min + (u_ahead - u_min) % (u_max - u_min) + else: + u_ahead = min(u_ahead, u_max - 1e-10) + + pos_ahead = self.spline.position(u_ahead) + + # Calculate distance from ahead position to first gate + dist_ahead_to_gate0 = np.linalg.norm(pos_ahead - first_gate_pos) + dist_candidate_to_gate0 = np.linalg.norm(pos_candidate - first_gate_pos) + + # We want the trajectory to be getting CLOSER to gate 0, not farther + # Positive value means moving toward gate, negative means moving away + approach_score = dist_candidate_to_gate0 - dist_ahead_to_gate0 + + # Score combines: close to start position AND moving toward gate 0 + # We prioritize moving toward gate 0 (higher weight) + score = dist_to_start * 0.3 - approach_score * 2.0 + + if score < best_score: + best_score = score + best_u = u_candidate + + # Store the optimal starting parameter + self._u_start = best_u + + def set_parameters(self, params: np.ndarray): + """ + Set trajectory parameters from optimization vector. + + Parameter vector structure: + [ + # Gate position offsets (n_gates × 3) + g0_dx, g0_dy, g0_dz, g1_dx, g1_dy, g1_dz, ... + + # Timing/velocity parameters (3) + total_time, velocity_scale, startup_time + ] + + Args: + params: Parameter vector + """ + expected_length = self.n_gates * 3 + 3 + + if len(params) != expected_length: + raise ValueError(f"Expected {expected_length} parameters, got {len(params)}") + + idx = 0 + + # Extract gate offsets + gate_offsets_flat = params[idx:idx + self.n_gates * 3] + self.gate_offsets = gate_offsets_flat.reshape((self.n_gates, 3)) + idx += self.n_gates * 3 + + # Extract timing parameters + self.total_time = params[idx] + self.velocity_scale = params[idx + 1] + self.startup_time = params[idx + 2] + + # Rebuild spline with new parameters + self._rebuild_spline() + + def get_default_parameters(self) -> np.ndarray: + """ + Get default parameter vector for initialization. + + Returns: + Default parameter vector + """ + params = [] + + # Gate offsets + params.extend(self.gate_offsets.flatten()) + + # Timing parameters + params.extend([self.total_time, self.velocity_scale, self.startup_time]) + + return np.array(params) + + def get_parameter_bounds(self) -> Tuple[np.ndarray, np.ndarray]: + """ + Get bounds for optimization parameters. + + Returns: + Tuple of (lower_bounds, upper_bounds) + """ + lower = [] + upper = [] + + # Bounds for gate offsets (limited by gate size) + max_offset = self.gate_size * self.gate_offset_scale + for _ in range(self.n_gates): + lower.extend([-max_offset, -max_offset, -max_offset]) + upper.extend([max_offset, max_offset, max_offset]) + + # Bounds for timing parameters + lower.extend([5.0, 0.3, 1.0]) # total_time, velocity_scale, startup_time + upper.extend([30.0, 2.0, 10.0]) # total_time, velocity_scale, startup_time + + return np.array(lower), np.array(upper) + + def evaluate(self, t: float) -> Tuple[np.ndarray, np.ndarray, np.ndarray]: + """ + Evaluate trajectory at time t using single periodic spline. + + The spline is naturally C2 continuous everywhere since it's a single curve. + Time parameterization uses quintic ramp for smooth startup from rest. + + Args: + t: Time in seconds + + Returns: + Tuple of (position, velocity, acceleration) + Each is a numpy array of shape (3,) + """ + if self.spline is None: + raise RuntimeError("Spline not initialized. Call set_parameters first.") + + # Map time to spline parameter + u, du_dt, d2u_dt2 = self._time_to_parameter(t) + + # Evaluate single spline (guaranteed C2 continuous!) + position = self.spline.position(u) + velocity = self.spline.velocity(u, du_dt) + acceleration = self.spline.acceleration(u, du_dt, d2u_dt2) + + return position, velocity, acceleration + + def _time_to_parameter(self, t: float) -> Tuple[float, float, float]: + """ + Map time to B-spline parameter using piecewise parameterization: + - Startup phase (0 to startup_time): Quintic ramp from rest + - Loop phase (startup_time to total_time): Constant speed completing full periodic cycle + + For proper looping: + - Startup goes from optimal start point (u_start) to some point on the spline + - Loop completes a FULL cycle: one complete traversal of the periodic spline (u_range distance) + - At t=total_time, we return to the same u as at t=startup_time, ensuring continuity + + Args: + t: Time in seconds + + Returns: + Tuple of (u, du/dt, d²u/dt²) + """ + u_min = self.spline.u_min + u_max = self.spline.u_max + u_range = u_max - u_min + + # Start from optimal position (closest to desired starting position) + # This is computed in _find_optimal_start_parameter() + u_start = getattr(self, '_u_start', u_min) + + # For a looping trajectory, the loop phase should traverse the full spline range + # This ensures when t wraps from total_time to startup_time, position/velocity/acceleration are continuous + loop_time = self.total_time - self.startup_time + + # The loop phase traverses a full u_range for periodic, or the remaining range for non-periodic + loop_u_distance = u_range + loop_speed = loop_u_distance / loop_time if loop_time > 0 else 1.0 + + # For non-periodic splines, the startup already covers some parameter distance, + # so the loop phase only needs to cover the remainder to reach u_max exactly + if not self.periodic: + startup_u_consumed = loop_speed * self.startup_time + remaining_u = u_range - startup_u_consumed + loop_u_distance = max(remaining_u, 0.0) + + if t < self.startup_time: + # Startup phase: quintic ramp from rest at u_start + # We want to ramp up to the loop speed smoothly + T = self.startup_time + t_clamped = np.clip(t, 0.0, T) + + # Quintic: u(t) = u_start + c*t³ + d*t⁴ + e*t⁵ + # Constraints: + # u(0) = u_start + # u(T) = u_start + loop_speed * T (distance traveled during startup) + # du/dt(0) = 0, d²u/dt²(0) = 0 (start from rest) + # du/dt(T) = loop_speed, d²u/dt²(T) = 0 (match loop speed) + + # Distance traveled during startup at constant loop speed + startup_u_distance = loop_speed * T + + # Solve quintic system for coefficients + A = np.array([ + [T**3, T**4, T**5], + [3*T**2, 4*T**3, 5*T**4], + [6*T, 12*T**2, 20*T**3] + ]) + b = np.array([startup_u_distance, loop_speed, 0.0]) + + try: + coeffs = np.linalg.solve(A, b) + c, d, e = coeffs + except np.linalg.LinAlgError: + # Fallback: simple quintic with zero boundary conditions + c = 10.0 * startup_u_distance / (T ** 3) + d = -15.0 * startup_u_distance / (T ** 4) + e = 6.0 * startup_u_distance / (T ** 5) + + u = u_start + c * t_clamped ** 3 + d * t_clamped ** 4 + e * t_clamped ** 5 + du_dt = (3.0 * c * t_clamped ** 2 + 4.0 * d * t_clamped ** 3 + 5.0 * e * t_clamped ** 4) * self.velocity_scale + d2u_dt2 = (6.0 * c * t_clamped + 12.0 * d * t_clamped ** 2 + 20.0 * e * t_clamped ** 3) * self.velocity_scale + + else: + # Loop phase: constant speed completing full periodic cycle + t_loop = t - self.startup_time + + # Map loop time to spline parameter + if loop_time > 0: + if self.periodic: + # Use modulo for repeated loops (allows t > total_time) + t_normalized = (t_loop % loop_time) / loop_time + else: + # Clamp for non-periodic: traverse once then hold at end + t_normalized = min(t_loop / loop_time, 1.0) + + # Start from where startup ended and traverse full u_range + u_startup_end = u_start + loop_speed * self.startup_time + u = u_startup_end + loop_u_distance * t_normalized + du_dt = loop_speed * self.velocity_scale + else: + u = u_start + du_dt = 0.0 + + d2u_dt2 = 0.0 + + # Handle parameter bounds + if self.periodic: + # Wrap parameter for periodic spline + if u >= u_max: + u = u_min + (u - u_min) % u_range + else: + # Clamp parameter for non-periodic spline + u = np.clip(u, u_min, u_max - 1e-10) + + u = np.clip(u, u_min, u_max - 1e-10) + + return u, du_dt, d2u_dt2 + + def sample_trajectory(self, dt: float = 0.01) -> Dict[str, np.ndarray]: + """ + Sample the entire trajectory at regular time intervals. + + Args: + dt: Time step in seconds + + Returns: + Dictionary with keys: + - 'time': Array of time values + - 'position': Array of positions (N, 3) + - 'velocity': Array of velocities (N, 3) + - 'acceleration': Array of accelerations (N, 3) + """ + n_samples = int(self.total_time / dt) + 1 + times = np.linspace(0, self.total_time, n_samples) + + positions = [] + velocities = [] + accelerations = [] + + for t in times: + pos, vel, acc = self.evaluate(t) + positions.append(pos) + velocities.append(vel) + accelerations.append(acc) + + return { + 'time': times, + 'position': np.array(positions), + 'velocity': np.array(velocities), + 'acceleration': np.array(accelerations) + } + + def check_gate_proximity(self, dt: float = 0.01) -> np.ndarray: + """ + Check minimum distance from trajectory to each gate. + + Args: + dt: Time step for sampling trajectory + + Returns: + Array of minimum distances to each gate + """ + trajectory = self.sample_trajectory(dt) + positions = trajectory['position'] + + min_distances = np.full(self.n_gates, np.inf) + + for gate_idx in range(self.n_gates): + gate_pos = self.gate_positions[gate_idx] + distances = np.linalg.norm(positions - gate_pos, axis=1) + min_distances[gate_idx] = np.min(distances) + + return min_distances + + def get_parameter_count(self) -> int: + """Get total number of parameters.""" + return self.n_gates * 3 + 3 # gate offsets + timing + + def get_gate_offset_count(self) -> int: + """Get number of gate offset parameters.""" + return self.n_gates * 3 + + def get_timing_parameter_count(self) -> int: + """Get number of timing parameters.""" + return 3 + + def get_gate_offset_parameters(self) -> np.ndarray: + """ + Get gate offset parameters as a flat array. + + Returns: + Flattened array of gate offsets [g0_dx, g0_dy, g0_dz, g1_dx, ...] + """ + return self.gate_offsets.flatten() + + def get_timing_parameters(self) -> np.ndarray: + """ + Get timing/velocity parameters. + + Returns: + Array of [total_time, velocity_scale, startup_time] + """ + return np.array([self.total_time, self.velocity_scale, self.startup_time]) + + def set_gate_offset_parameters(self, params: np.ndarray): + """ + Set gate offset parameters and rebuild spline. + + Args: + params: Flat array of gate offsets (n_gates * 3 elements) + """ + expected_length = self.n_gates * 3 + if len(params) != expected_length: + raise ValueError(f"Expected {expected_length} gate offset parameters, got {len(params)}") + + self.gate_offsets = params.reshape((self.n_gates, 3)) + self._rebuild_spline() + + def set_timing_parameters(self, params: np.ndarray): + """ + Set timing/velocity parameters (no spline rebuild needed). + + Args: + params: Array of [total_time, velocity_scale, startup_time] + """ + if len(params) != 3: + raise ValueError(f"Expected 3 timing parameters, got {len(params)}") + + self.total_time = params[0] + self.velocity_scale = params[1] + self.startup_time = params[2] + + def get_parameter_bounds_by_group(self) -> Dict[str, Tuple[np.ndarray, np.ndarray]]: + """ + Get parameter bounds organized by group. + + Returns: + Dictionary with keys 'gate_offsets' and 'timing', each containing + (lower_bounds, upper_bounds) tuples + """ + # Gate offset bounds + max_offset = self.gate_size * self.gate_offset_scale + gate_lower = np.full(self.n_gates * 3, -max_offset) + gate_upper = np.full(self.n_gates * 3, max_offset) + + # Timing parameter bounds + timing_lower = np.array([5.0, 0.3, 1.0]) # total_time, velocity_scale, startup_time + timing_upper = np.array([30.0, 2.0, 10.0]) # total_time, velocity_scale, startup_time + + return { + 'gate_offsets': (gate_lower, gate_upper), + 'timing': (timing_lower, timing_upper) + } + + def get_start_position(self) -> np.ndarray: + """ + Get the starting position for the trajectory. + + Always uses starting_pos from gate configuration if available, + otherwise calculates position behind gate 0. + + Note: This returns the physical starting position for the drone, + NOT necessarily a point on the B-spline curve. In gate-only mode, + the drone starts here but the trajectory is a periodic loop through gates. + + Returns: + Starting position [x, y, z] + """ + # Use starting position from gate config if available (preferred) + if hasattr(self.gate_config, 'starting_pos') and self.gate_config.starting_pos is not None: + return np.array(self.gate_config.starting_pos, dtype=np.float64) + + # Fallback: calculate start position behind gate 0 by 2 meters + first_gate = self.gate_positions[0] + first_gate_yaw = self.gate_yaws[0] + + distance_behind = 2.0 # meters + start_pos = first_gate - distance_behind * np.array([ + np.cos(first_gate_yaw), + np.sin(first_gate_yaw), + 0.0 + ]) + + return start_pos + + def get_info(self) -> Dict[str, Any]: + """ + Get trajectory information. + + Returns: + Dictionary with trajectory configuration + """ + return { + 'n_gates': self.n_gates, + 'n_total_control_points': self.n_total_control_points, + 'degree': self.degree, + 'tension': self.tension, + 'total_time': self.total_time, + 'velocity_scale': self.velocity_scale, + 'startup_time': self.startup_time, + 'n_parameters': self.get_parameter_count(), + 'gate_size': self.gate_size, + 'gate_offset_scale': self.gate_offset_scale, + 'spline_type': 'single_periodic' if self.periodic else 'single_clamped' + } + + +def create_gate_trajectory_from_config(gate_config_name: str) -> BSplineGateTrajectory: + """ + Convenience function to create trajectory from gate configuration name. + + Args: + gate_config_name: Name of gate configuration ('figure8', 'circle', etc.) + + Returns: + BSplineGateTrajectory instance + + Example: + >>> from ariel.simulation.drone.controllers.utils.gate_configs import GATE_CONFIGS + >>> traj = create_gate_trajectory_from_config('figure8') + """ + from ..utils.gate_configs import GATE_CONFIGS + + if gate_config_name not in GATE_CONFIGS: + raise ValueError(f"Unknown gate configuration: {gate_config_name}") + + gate_config = GATE_CONFIGS[gate_config_name] + return BSplineGateTrajectory(gate_config) diff --git a/src/ariel/simulation/drone/controllers/trajectory_generation/bspline_utils.py b/src/ariel/simulation/drone/controllers/trajectory_generation/bspline_utils.py new file mode 100644 index 000000000..a19fd212e --- /dev/null +++ b/src/ariel/simulation/drone/controllers/trajectory_generation/bspline_utils.py @@ -0,0 +1,414 @@ +# -*- coding: utf-8 -*- +""" +B-Spline Utilities for Trajectory Generation + +This module provides core B-spline mathematical functions for generating +smooth trajectories. Implements cubic B-splines (degree 3) with support +for clamped and periodic boundary conditions. + +Author: Generated for AirEvolve project +License: MIT +""" + +import numpy as np +from typing import Tuple, Optional + + +def generate_knot_vector(n_control_points: int, degree: int, + boundary: str = 'clamped') -> np.ndarray: + """ + Generate knot vector for B-spline curve. + + Args: + n_control_points: Number of control points + degree: Degree of B-spline (use 3 for cubic) + boundary: Boundary condition - 'clamped' or 'periodic' + 'clamped': curve interpolates first and last control points + 'periodic': curve forms a closed loop + + Returns: + Knot vector of length (n_control_points + degree + 1) + + Example: + For 5 control points, degree 3, clamped: + knots = [0, 0, 0, 0, 1, 2, 3, 3, 3, 3] + (4 repeated at start, 4 repeated at end) + """ + if boundary == 'clamped': + # Clamped B-spline: repeat first and last knots (degree+1) times + # Internal knots are uniform + n_internal = n_control_points - degree + if n_internal < 1: + raise ValueError(f"Need at least {degree+1} control points for degree {degree}") + + # Create uniform internal knots strictly between 0 and max_knot + # For n CPs and degree p, we need n-p-1 distinct internal knots + if n_internal == 1: + # Minimal case: only boundary knots + internal_knots = np.array([]) + max_knot = 1.0 + else: + internal_knots = np.arange(1, n_internal) + max_knot = n_internal + + # Add repeated boundary knots + knots = np.concatenate([ + np.zeros(degree + 1), # Repeated start knots (degree+1 times) + internal_knots, # Internal knots + np.full(degree + 1, max_knot if n_internal > 1 else 1.0) # Repeated end knots + ]) + + elif boundary == 'periodic': + # Periodic B-spline: uniform knots for closed loop + # Need n + 2*degree + 1 knots for proper periodic spline + n_knots = n_control_points + 2 * degree + 1 + knots = np.arange(n_knots) - degree + + else: + raise ValueError(f"Unknown boundary condition: {boundary}") + + return knots + + +def basis_function(i: int, p: int, u: float, knots: np.ndarray) -> float: + """ + Compute B-spline basis function N_{i,p}(u) using Cox-de Boor recursion. + + Args: + i: Index of basis function + p: Degree of basis function + u: Parameter value + knots: Knot vector + + Returns: + Value of basis function at u + + Note: + This implements the Cox-de Boor recursion formula: + N_{i,0}(u) = 1 if knots[i] <= u < knots[i+1], else 0 + N_{i,p}(u) = ((u - knots[i]) / (knots[i+p] - knots[i])) * N_{i,p-1}(u) + + ((knots[i+p+1] - u) / (knots[i+p+1] - knots[i+1])) * N_{i+1,p-1}(u) + """ + # Base case: degree 0 + if p == 0: + return 1.0 if knots[i] <= u < knots[i + 1] else 0.0 + + # Recursive case + # Handle division by zero (when knot span is zero) + denom1 = knots[i + p] - knots[i] + term1 = ((u - knots[i]) / denom1) * basis_function(i, p - 1, u, knots) if denom1 != 0 else 0.0 + + denom2 = knots[i + p + 1] - knots[i + 1] + term2 = ((knots[i + p + 1] - u) / denom2) * basis_function(i + 1, p - 1, u, knots) if denom2 != 0 else 0.0 + + return term1 + term2 + + +def basis_function_derivative(i: int, p: int, u: float, knots: np.ndarray, + deriv_order: int = 1) -> float: + """ + Compute derivative of B-spline basis function. + + Args: + i: Index of basis function + p: Degree of basis function + u: Parameter value + knots: Knot vector + deriv_order: Order of derivative (1 for first derivative, 2 for second) + + Returns: + Value of basis function derivative at u + + Note: + First derivative: N'_{i,p}(u) = p * (N_{i,p-1}(u) / (knots[i+p] - knots[i]) + - N_{i+1,p-1}(u) / (knots[i+p+1] - knots[i+1])) + """ + if deriv_order == 0: + return basis_function(i, p, u, knots) + + if p == 0: + return 0.0 + + # First derivative + denom1 = knots[i + p] - knots[i] + term1 = basis_function_derivative(i, p - 1, u, knots, deriv_order - 1) / denom1 if denom1 != 0 else 0.0 + + denom2 = knots[i + p + 1] - knots[i + 1] + term2 = basis_function_derivative(i + 1, p - 1, u, knots, deriv_order - 1) / denom2 if denom2 != 0 else 0.0 + + return p * (term1 - term2) + + +def evaluate_bspline(u: float, control_points: np.ndarray, knots: np.ndarray, + degree: int = 3) -> np.ndarray: + """ + Evaluate B-spline curve at parameter u. + + Args: + u: Parameter value (typically in range [0, max_u]) + control_points: Array of control points, shape (n, d) where d is dimension (usually 3 for xyz) + knots: Knot vector + degree: Degree of B-spline (default 3 for cubic) + + Returns: + Point on curve at parameter u, shape (d,) + + Example: + >>> control_points = np.array([[0, 0, 0], [1, 1, 0], [2, 0, 0], [3, 1, 0]]) + >>> knots = generate_knot_vector(4, 3, 'clamped') + >>> point = evaluate_bspline(0.5, control_points, knots, 3) + """ + n = len(control_points) + + # Clamp u to valid range + u = np.clip(u, knots[degree], knots[n]) + + # Handle edge case at the end + if u == knots[n]: + u = knots[n] - 1e-10 + + # Find which knot span u is in + span = np.searchsorted(knots, u, side='right') - 1 + span = max(degree, min(span, n - 1)) + + # Compute point using basis functions + point = np.zeros(control_points.shape[1]) + for i in range(n): + basis = basis_function(i, degree, u, knots) + point += basis * control_points[i] + + return point + + +def evaluate_bspline_derivative(u: float, control_points: np.ndarray, + knots: np.ndarray, degree: int = 3, + deriv_order: int = 1) -> np.ndarray: + """ + Evaluate derivative of B-spline curve at parameter u. + + Args: + u: Parameter value + control_points: Array of control points, shape (n, d) + knots: Knot vector + degree: Degree of B-spline + deriv_order: Order of derivative (1 for velocity, 2 for acceleration) + + Returns: + Derivative vector at parameter u, shape (d,) + + Note: + For first derivative (velocity), this returns dC(u)/du + For second derivative (acceleration), this returns d²C(u)/du² + These need to be scaled by du/dt to get physical velocity/acceleration + """ + n = len(control_points) + + # Clamp u to valid range + u = np.clip(u, knots[degree], knots[n]) + + # Handle edge case at the end + if u == knots[n]: + u = knots[n] - 1e-10 + + # Compute derivative using basis function derivatives + derivative = np.zeros(control_points.shape[1]) + for i in range(n): + basis_deriv = basis_function_derivative(i, degree, u, knots, deriv_order) + derivative += basis_deriv * control_points[i] + + return derivative + + +class BSplineCurve: + """ + B-spline curve class for convenient evaluation. + + This class wraps the B-spline functions and provides methods for + evaluating position, velocity, and acceleration along the curve. + """ + + def __init__(self, control_points: np.ndarray, degree: int = 3, + boundary: str = 'clamped'): + """ + Initialize B-spline curve. + + Args: + control_points: Array of control points, shape (n, d) + degree: Degree of B-spline (default 3 for cubic) + boundary: Boundary condition - 'clamped' or 'periodic' + """ + self.control_points = np.array(control_points) + self.degree = degree + self.boundary = boundary + self.n_points = len(control_points) + + # Generate knot vector + self.knots = generate_knot_vector(self.n_points, degree, boundary) + + # Parameter range + self.u_min = self.knots[degree] + if boundary == 'periodic': + # For periodic splines, one full period spans n_points parameter units + self.u_max = self.u_min + self.n_points + else: + # For clamped splines, use the last knot + self.u_max = self.knots[self.n_points] + + def __call__(self, u: float) -> np.ndarray: + """Evaluate curve at parameter u (position).""" + return evaluate_bspline(u, self.control_points, self.knots, self.degree) + + def position(self, u: float) -> np.ndarray: + """Evaluate position at parameter u.""" + # For periodic splines, handle wrapping properly + if self.boundary == 'periodic': + return self._evaluate_periodic(u) + else: + return evaluate_bspline(u, self.control_points, self.knots, self.degree) + + def velocity(self, u: float, du_dt: float = 1.0) -> np.ndarray: + """ + Evaluate velocity at parameter u. + + Args: + u: Parameter value + du_dt: Time derivative of parameter (du/dt) + + Returns: + Velocity vector = dC/du * du/dt + """ + if self.boundary == 'periodic': + deriv = self._evaluate_periodic_derivative(u, deriv_order=1) + else: + deriv = evaluate_bspline_derivative(u, self.control_points, self.knots, + self.degree, deriv_order=1) + return deriv * du_dt + + def acceleration(self, u: float, du_dt: float = 1.0, d2u_dt2: float = 0.0) -> np.ndarray: + """ + Evaluate acceleration at parameter u. + + Args: + u: Parameter value + du_dt: First time derivative of parameter (du/dt) + d2u_dt2: Second time derivative of parameter (d²u/dt²) + + Returns: + Acceleration vector = d²C/du² * (du/dt)² + dC/du * d²u/dt² + """ + if self.boundary == 'periodic': + first_deriv = self._evaluate_periodic_derivative(u, deriv_order=1) + second_deriv = self._evaluate_periodic_derivative(u, deriv_order=2) + else: + first_deriv = evaluate_bspline_derivative(u, self.control_points, self.knots, + self.degree, deriv_order=1) + second_deriv = evaluate_bspline_derivative(u, self.control_points, self.knots, + self.degree, deriv_order=2) + + return second_deriv * (du_dt ** 2) + first_deriv * d2u_dt2 + + def _evaluate_periodic(self, u: float) -> np.ndarray: + """ + Evaluate periodic B-spline at parameter u with proper control point wrapping. + + For periodic splines, control points wrap: P_i = P_{i mod n} + """ + # Clamp to valid range + u = np.clip(u, self.u_min, self.u_max - 1e-10) + + # For periodic splines, we need to sum over all basis functions that might be non-zero + # At parameter u, basis functions N_{i,p}(u) for i in a certain range are non-zero + # We need to check basis functions that might reference our control points (with wrapping) + point = np.zeros(self.control_points.shape[1]) + + # For degree p, at most p+1 basis functions are non-zero at any u + # Find the knot span and check basis functions around it + # Check all basis functions and use wrapped control point indices + for i in range(len(self.knots) - self.degree - 1): + basis = basis_function(i, self.degree, u, self.knots) + if abs(basis) > 1e-10: # Only accumulate if non-zero + # Wrap control point index + cp_idx = i % self.n_points + point += basis * self.control_points[cp_idx] + + return point + + def _evaluate_periodic_derivative(self, u: float, deriv_order: int = 1) -> np.ndarray: + """ + Evaluate derivative of periodic B-spline at parameter u with proper control point wrapping. + """ + # Clamp to valid range + u = np.clip(u, self.u_min, self.u_max - 1e-10) + + # Compute derivative using basis function derivatives with wrapped control points + derivative = np.zeros(self.control_points.shape[1]) + + for i in range(len(self.knots) - self.degree - 1): + basis_deriv = basis_function_derivative(i, self.degree, u, self.knots, deriv_order) + if abs(basis_deriv) > 1e-10: # Only accumulate if non-zero + # Wrap control point index + cp_idx = i % self.n_points + derivative += basis_deriv * self.control_points[cp_idx] + + return derivative + + def sample_curve(self, n_samples: int = 100) -> np.ndarray: + """ + Sample the curve at uniformly spaced parameter values. + + Args: + n_samples: Number of samples + + Returns: + Array of points on curve, shape (n_samples, d) + """ + u_values = np.linspace(self.u_min, self.u_max, n_samples) + return np.array([self.position(u) for u in u_values]) + + +def uniform_time_parameterization(spline: BSplineCurve, total_time: float, + velocity_scale: float = 1.0) -> Tuple[callable, callable, callable]: + """ + Create time-parameterized functions for a B-spline curve. + + This function creates a uniform time parameterization where the parameter u + varies linearly with time: u(t) = (u_max - u_min) * (t / total_time) + u_min + + Args: + spline: BSplineCurve object + total_time: Total time to traverse the curve + velocity_scale: Scale factor for velocity (>1 = faster, <1 = slower) + + Returns: + Tuple of (position_func, velocity_func, acceleration_func) + Each function takes time t and returns the corresponding vector + + Example: + >>> pos_func, vel_func, acc_func = uniform_time_parameterization(spline, 10.0) + >>> position_at_5s = pos_func(5.0) + """ + u_range = spline.u_max - spline.u_min + + # du/dt is constant for uniform parameterization + du_dt = (u_range / total_time) * velocity_scale + + def position_func(t: float) -> np.ndarray: + """Get position at time t.""" + u = spline.u_min + (u_range * t / total_time) + u = np.clip(u, spline.u_min, spline.u_max) + return spline.position(u) + + def velocity_func(t: float) -> np.ndarray: + """Get velocity at time t.""" + u = spline.u_min + (u_range * t / total_time) + u = np.clip(u, spline.u_min, spline.u_max) + return spline.velocity(u, du_dt) + + def acceleration_func(t: float) -> np.ndarray: + """Get acceleration at time t.""" + u = spline.u_min + (u_range * t / total_time) + u = np.clip(u, spline.u_min, spline.u_max) + # d²u/dt² = 0 for uniform parameterization + return spline.acceleration(u, du_dt, 0.0) + + return position_func, velocity_func, acceleration_func diff --git a/src/ariel/simulation/drone/controllers/trajectory_generation/trajectory.py b/src/ariel/simulation/drone/controllers/trajectory_generation/trajectory.py new file mode 100644 index 000000000..22e5de3fe --- /dev/null +++ b/src/ariel/simulation/drone/controllers/trajectory_generation/trajectory.py @@ -0,0 +1,155 @@ +# -*- coding: utf-8 -*- +""" +Trajectory Generation - B-spline Gate Trajectories + +Simplified trajectory module supporting only B-spline trajectories for gate racing. +All waypoint-based and figure-8 trajectory methods have been removed. + +author: John Bass +email: john.bobzwik@gmail.com +license: MIT +Please feel free to use and modify this, but keep the above information. Thanks! +""" + +import numpy as np +from numpy import pi +from ariel.simulation.drone.controllers.trajectory_generation.bspline_gate_trajectory import BSplineGateTrajectory + + +class Trajectory: + """ + Trajectory class for drone control - B-spline gate trajectories only. + + This class generates desired states (position, velocity, acceleration, yaw) + for the controller to follow B-spline trajectories through racing gates. + + Args: + quad: Quadcopter instance + ctrlType: Control type ('xyz_pos', 'xy_vel_z_pos', 'xyz_vel') + trajSelect: Trajectory selection [xyzType, yawType, averVel] + - xyzType: Must be 15 (B-spline gate trajectory) + - yawType: Yaw control type (0=none, 1=follow trajectory, 3=velocity-based) + - averVel: Not used for B-spline trajectories + gate_config: Gate configuration object (required for B-spline) + bspline_params: Dictionary of B-spline parameters (optional) + """ + + def __init__(self, quad, ctrlType, trajSelect, gate_config=None, bspline_params=None): + + self.ctrlType = ctrlType + self.xyzType = trajSelect[0] + self.yawType = trajSelect[1] + self.averVel = trajSelect[2] + + # Validate trajectory type - only B-spline supported + if self.xyzType != 15: + raise ValueError( + f"Only B-spline gate trajectories (xyzType=15) are supported. " + f"Got xyzType={self.xyzType}. " + f"Old waypoint-based and figure-8 trajectories have been removed." + ) + + # B-spline trajectory setup (required) + if gate_config is None: + raise ValueError("gate_config must be provided for B-spline trajectory (xyzType=15)") + + self.gate_config = gate_config + self.bspline_trajectory = BSplineGateTrajectory(gate_config) + + # Initialize placeholder waypoint arrays for compatibility + # (some visualization code may still reference these) + self.t_wps = np.array([0]) + self.wps = np.array([[0, 0, 0]]) + self.y_wps = np.array([0]) + self.v_wp = 1.0 + self.end_reached = 0 + + # Get initial heading from quad + self.current_heading = quad.psi + + # Initialize trajectory setpoint + self.desPos = np.zeros(3) # Desired position (x, y, z) + self.desVel = np.zeros(3) # Desired velocity (xdot, ydot, zdot) + self.desAcc = np.zeros(3) # Desired acceleration (xdotdot, ydotdot, zdotdot) + self.desThr = np.zeros(3) # Desired thrust in N-E-D directions (or E-N-U, if selected) + self.desEul = np.zeros(3) # Desired orientation in the world frame (phi, theta, psi) + self.desPQR = np.zeros(3) # Desired angular velocity in the body frame (p, q, r) + self.desYawRate = 0.0 # Desired yaw speed + self.sDes = np.hstack((self.desPos, self.desVel, self.desAcc, self.desThr, + self.desEul, self.desPQR, self.desYawRate)).astype(float) + + def desiredState(self, t, Ts, quad): + """ + Calculate desired state at time t for B-spline trajectory. + + Args: + t: Current time + Ts: Time step + quad: Quadcopter instance + + Returns: + sDes: Desired state vector [pos, vel, acc, thr, eul, pqr, yawRate] + """ + + # Reset desired state + self.desPos = np.zeros(3) + self.desVel = np.zeros(3) + self.desAcc = np.zeros(3) + self.desThr = np.zeros(3) + self.desEul = np.zeros(3) + self.desPQR = np.zeros(3) + self.desYawRate = 0.0 + + # Evaluate B-spline gate trajectory + if self.bspline_trajectory is None: + raise RuntimeError("B-spline trajectory not initialized") + + # Get trajectory state + position, velocity, acceleration = self.bspline_trajectory.evaluate(t) + + # Set desired states + self.desPos = position + self.desVel = velocity + self.desAcc = acceleration + + # Handle yaw control + if self.yawType == 0: + # No yaw control + pass + + elif self.yawType == 1: + # Fixed yaw (maintain initial heading) + self.desEul[2] = 0.0 + + elif self.yawType == 3: + # Yaw follows velocity direction. At t=0 the spline has zero velocity + # (quintic startup ramp), so peek forward 0.05s to recover the heading + # — keeps the yaw setpoint aligned with the drone's initial yaw and + # avoids a spurious large yaw error on the first controller step. + if np.linalg.norm(self.desVel[:2]) < 1e-6: + _, future_vel, _ = self.bspline_trajectory.evaluate(t + 0.05) + if np.linalg.norm(future_vel[:2]) > 1e-6: + self.desEul[2] = np.arctan2(future_vel[1], future_vel[0]) + else: + self.desEul[2] = self.current_heading + else: + # Calculate desired yaw from velocity vector + self.desEul[2] = np.arctan2(self.desVel[1], self.desVel[0]) + + # Handle wrap-around discontinuity at ±π + if (np.sign(self.desEul[2]) != np.sign(self.current_heading) and + abs(self.desEul[2] - self.current_heading) >= 2*pi - 0.1): + self.current_heading = self.current_heading + np.sign(self.desEul[2]) * 2*pi + + # Calculate yaw rate + delta_psi = self.desEul[2] - self.current_heading + self.desYawRate = delta_psi / Ts + + # Update current heading for next iteration + self.current_heading = self.desEul[2] + + # Package desired state + self.sDes = np.hstack((self.desPos, self.desVel, self.desAcc, self.desThr, + self.desEul, self.desPQR, self.desYawRate)).astype(float) + + return self.sDes diff --git a/src/ariel/simulation/drone/controllers/utils/__init__.py b/src/ariel/simulation/drone/controllers/utils/__init__.py new file mode 100644 index 000000000..15ea25b34 --- /dev/null +++ b/src/ariel/simulation/drone/controllers/utils/__init__.py @@ -0,0 +1,5 @@ +from .rotation_conversion import * +from .state_conversions import * +from .display import * +from .animation import * +from .quaternion_functions import * \ No newline at end of file diff --git a/src/ariel/simulation/drone/controllers/utils/animation.py b/src/ariel/simulation/drone/controllers/utils/animation.py new file mode 100644 index 000000000..c57c30e78 --- /dev/null +++ b/src/ariel/simulation/drone/controllers/utils/animation.py @@ -0,0 +1,250 @@ +# -*- coding: utf-8 -*- +""" +author: John Bass +email: john.bobzwik@gmail.com +license: MIT +Please feel free to use and modify this, but keep the above information. Thanks! +""" + +import os +from datetime import datetime +import numpy as np +from numpy import pi +import matplotlib.pyplot as plt +import mpl_toolkits.mplot3d.axes3d as p3 +from matplotlib import animation + +from . import rotation_conversion, quaternion_functions + +numFrames = 8 + +def sameAxisAnimation(t_all, waypoints, pos_all, quat_all, sDes_tr_all, Ts, params, xyzType, yawType, ifsave, orient="NED", gate_pos=None, gate_yaw=None, gate_size=1.0, bspline_traj=None, save_path=None): + + x = pos_all[:,0] + y = pos_all[:,1] + z = pos_all[:,2] + + xDes = sDes_tr_all[:,0] + yDes = sDes_tr_all[:,1] + zDes = sDes_tr_all[:,2] + + x_wp = waypoints[:,0] + y_wp = waypoints[:,1] + z_wp = waypoints[:,2] + + if (orient == "NED"): + z = -z + zDes = -zDes + z_wp = -z_wp + + fig = plt.figure() + ax = p3.Axes3D(fig,auto_add_to_figure=False) + fig.add_axes(ax) + line1, = ax.plot([], [], [], lw=2, color='red') + line2, = ax.plot([], [], [], lw=2, color='blue') + line3, = ax.plot([], [], [], '--', lw=1, color='blue') + + # Setting the axes properties + extraEachSide = 0.5 + maxRange = 0.5*np.array([x.max()-x.min(), y.max()-y.min(), z.max()-z.min()]).max() + extraEachSide + mid_x = 0.5*(x.max()+x.min()) + mid_y = 0.5*(y.max()+y.min()) + mid_z = 0.5*(z.max()+z.min()) + + ax.set_xlim3d([mid_x-maxRange, mid_x+maxRange]) + ax.set_xlabel('X') + if (orient == "NED"): + ax.set_ylim3d([mid_y+maxRange, mid_y-maxRange]) + elif (orient == "ENU"): + ax.set_ylim3d([mid_y-maxRange, mid_y+maxRange]) + ax.set_ylabel('Y') + ax.set_zlim3d([mid_z-maxRange, mid_z+maxRange]) + ax.set_zlabel('Altitude') + + titleTime = ax.text2D(0.05, 0.95, "", transform=ax.transAxes) + + trajType = '' + yawTrajType = '' + + # Only B-spline gate trajectories are supported (xyzType == 15) + if (xyzType == 15): + trajType = 'B-spline Gate Trajectory' + # Plot desired trajectory path + ax.plot(xDes, yDes, zDes, ':', lw=1.3, color='green') + else: + # Legacy trajectory types are no longer supported + trajType = f'Unsupported (xyzType={xyzType})' + + # Draw gates if provided + if gate_pos is not None and gate_yaw is not None: + from mpl_toolkits.mplot3d.art3d import Poly3DCollection + + for gate_idx, (gpos, gyaw) in enumerate(zip(gate_pos, gate_yaw)): + # Create gate corners as a vertical square (standing up) + # In the gate's local frame, the gate is perpendicular to the forward direction + half_size = gate_size / 2.0 + + # Gate corners in local frame: gate is vertical, perpendicular to X-axis + # Y-axis goes left-right, Z-axis goes up-down + local_corners = np.array([ + [0, -half_size, -half_size], # Bottom left + [0, half_size, -half_size], # Bottom right + [0, half_size, half_size], # Top right + [0, -half_size, half_size] # Top left + ]) + + # Rotation matrix for yaw (rotation around Z-axis in NED) + cos_yaw = np.cos(gyaw) + sin_yaw = np.sin(gyaw) + + # Rotation matrix (Z-axis rotation) + R = np.array([ + [cos_yaw, -sin_yaw, 0], + [sin_yaw, cos_yaw, 0], + [0, 0, 1] + ]) + + # Transform corners to world frame + gate_corners_3d = [] + for corner in local_corners: + # Rotate corner + rotated = R @ corner + + # Translate to gate position + world_pos = rotated + gpos + + # Adjust for NED orientation if needed (flip Z) + if orient == "NED": + gate_corners_3d.append([world_pos[0], world_pos[1], -world_pos[2]]) + else: + gate_corners_3d.append([world_pos[0], world_pos[1], world_pos[2]]) + + # Draw gate as a polygon + gate_poly = Poly3DCollection([gate_corners_3d], alpha=0.3, facecolor='orange', edgecolor='darkorange', linewidths=2) + ax.add_collection3d(gate_poly) + + # Draw gate center marker with order number + if orient == "NED": + gate_z_pos = -gpos[2] + else: + gate_z_pos = gpos[2] + + ax.scatter([gpos[0]], [gpos[1]], [gate_z_pos], color='darkorange', marker='o', s=100, edgecolors='black', linewidths=1.5, zorder=6) + + # Add order number on the gate (1-indexed) + gate_num = gate_idx + 1 + ax.text(gpos[0], gpos[1], gate_z_pos, f'{gate_num}', fontsize=12, + color='white', weight='bold', ha='center', va='center', zorder=7, + bbox=dict(boxstyle='circle,pad=0.3', facecolor='darkorange', + edgecolor='black', linewidth=2)) + + # Draw B-spline control points if provided + if bspline_traj is not None: + # Get all control points (all are gate control points) + gate_cps = bspline_traj.get_all_control_points() + + # Visualize gate control points + gate_x = gate_cps[:, 0] + gate_y = gate_cps[:, 1] + gate_z = gate_cps[:, 2] + + if orient == "NED": + gate_z = -gate_z + + # Draw gate control points + ax.scatter(gate_x, gate_y, gate_z, color='purple', marker='o', s=100, + alpha=0.7, label='Gate Control Points', edgecolors='black', linewidths=1.5, zorder=5) + + # Draw lines connecting gate control points (periodic - close the loop back to first gate) + gate_x_closed = np.append(gate_x, gate_x[0]) + gate_y_closed = np.append(gate_y, gate_y[0]) + gate_z_closed = np.append(gate_z, gate_z[0]) + ax.plot(gate_x_closed, gate_y_closed, gate_z_closed, color='purple', linestyle='--', + linewidth=1.5, alpha=0.4, zorder=4) + + # Add legend with better positioning to avoid overlap + ax.legend(loc='upper left', bbox_to_anchor=(0.0, 0.95), fontsize=8, + framealpha=0.95, edgecolor='black', fancybox=True, shadow=True) + + if (yawType == 0): + yawTrajType = 'None' + elif (yawType == 1): + yawTrajType = 'Waypoints' + elif (yawType == 2): + yawTrajType = 'Interpolation' + elif (yawType == 3): + yawTrajType = 'Follow' + elif (yawType == 4): + yawTrajType = 'Zero' + + + + titleType1 = ax.text2D(0.95, 0.95, trajType, transform=ax.transAxes, horizontalalignment='right') + titleType2 = ax.text2D(0.95, 0.91, 'Yaw: '+ yawTrajType, transform=ax.transAxes, horizontalalignment='right') + + def updateLines(i): + + time = t_all[i*numFrames] + pos = pos_all[i*numFrames] + x = pos[0] + y = pos[1] + z = pos[2] + + x_from0 = pos_all[0:i*numFrames,0] + y_from0 = pos_all[0:i*numFrames,1] + z_from0 = pos_all[0:i*numFrames,2] + + dxm = params["dxm"] + dym = params["dym"] + dzm = params["dzm"] + + quat = quat_all[i*numFrames] + + if (orient == "NED"): + z = -z + z_from0 = -z_from0 + quat = np.array([quat[0], -quat[1], -quat[2], quat[3]]) + + R = rotation_conversion.quat2Dcm(quat) + motorPoints = np.array([[dxm, -dym, dzm], [0, 0, 0], [dxm, dym, dzm], [-dxm, dym, dzm], [0, 0, 0], [-dxm, -dym, dzm]]) + motorPoints = np.dot(R, np.transpose(motorPoints)) + motorPoints[0,:] += x + motorPoints[1,:] += y + motorPoints[2,:] += z + + line1.set_data(motorPoints[0,0:3], motorPoints[1,0:3]) + line1.set_3d_properties(motorPoints[2,0:3]) + line2.set_data(motorPoints[0,3:6], motorPoints[1,3:6]) + line2.set_3d_properties(motorPoints[2,3:6]) + line3.set_data(x_from0, y_from0) + line3.set_3d_properties(z_from0) + titleTime.set_text(u"Time = {:.2f} s".format(time)) + + return line1, line2 + + + def ini_plot(): + + line1.set_data(np.empty([1]), np.empty([1])) + line1.set_3d_properties(np.empty([1])) + line2.set_data(np.empty([1]), np.empty([1])) + line2.set_3d_properties(np.empty([1])) + line3.set_data(np.empty([1]), np.empty([1])) + line3.set_3d_properties(np.empty([1])) + + return line1, line2, line3 + + + # Creating the Animation object + line_ani = animation.FuncAnimation(fig, updateLines, init_func=ini_plot, frames=len(t_all[0:-2:numFrames]), interval=(Ts*1000*numFrames), blit=False) + + if (ifsave): + if save_path is None: + timestamp = datetime.now().strftime('%Y%m%d_%H%M%S') + save_path = '__data__/animations/animation_{0:.0f}_{1:.0f}_{2}.mp4'.format( + xyzType, yawType, timestamp) + os.makedirs(os.path.dirname(save_path) or '.', exist_ok=True) + line_ani.save(save_path, dpi=80, writer='ffmpeg', fps=25) + print(f"Animation saved to: {save_path}") + + return line_ani \ No newline at end of file diff --git a/src/ariel/simulation/drone/controllers/utils/display.py b/src/ariel/simulation/drone/controllers/utils/display.py new file mode 100644 index 000000000..151045153 --- /dev/null +++ b/src/ariel/simulation/drone/controllers/utils/display.py @@ -0,0 +1,202 @@ +# -*- coding: utf-8 -*- +""" +author: John Bass +email: john.bobzwik@gmail.com +license: MIT +Please feel free to use and modify this, but keep the above information. Thanks! +""" + +import numpy as np +from numpy import pi +import matplotlib.pyplot as plt +from . import rotation_conversion, quaternion_functions + +rad2deg = 180.0/pi +deg2rad = pi/180.0 +rads2rpm = 60.0/(2.0*pi) +rpm2rads = 2.0*pi/60.0 + +# Print complete vector or matrices +def fullprint(*args, **kwargs): + opt = np.get_printoptions() + np.set_printoptions(threshold=np.inf) + print(*args, **kwargs) + np.set_printoptions(opt) + + +def makeFigures(params, time, pos_all, vel_all, quat_all, omega_all, euler_all, commands, wMotor_all, thrust, torque, sDes_traj, sDes_calc): + x = pos_all[:,0] + y = pos_all[:,1] + z = pos_all[:,2] + q0 = quat_all[:,0] + q1 = quat_all[:,1] + q2 = quat_all[:,2] + q3 = quat_all[:,3] + xdot = vel_all[:,0] + ydot = vel_all[:,1] + zdot = vel_all[:,2] + p = omega_all[:,0]*rad2deg + q = omega_all[:,1]*rad2deg + r = omega_all[:,2]*rad2deg + + wM1 = wMotor_all[:,0]*rads2rpm + wM2 = wMotor_all[:,1]*rads2rpm + wM3 = wMotor_all[:,2]*rads2rpm + wM4 = wMotor_all[:,3]*rads2rpm + + phi = euler_all[:,0]*rad2deg + theta = euler_all[:,1]*rad2deg + psi = euler_all[:,2]*rad2deg + + x_sp = sDes_calc[:,0] + y_sp = sDes_calc[:,1] + z_sp = sDes_calc[:,2] + Vx_sp = sDes_calc[:,3] + Vy_sp = sDes_calc[:,4] + Vz_sp = sDes_calc[:,5] + x_thr_sp = sDes_calc[:,6] + y_thr_sp = sDes_calc[:,7] + z_thr_sp = sDes_calc[:,8] + q0Des = sDes_calc[:,9] + q1Des = sDes_calc[:,10] + q2Des = sDes_calc[:,11] + q3Des = sDes_calc[:,12] + pDes = sDes_calc[:,13]*rad2deg + qDes = sDes_calc[:,14]*rad2deg + rDes = sDes_calc[:,15]*rad2deg + + x_tr = sDes_traj[:,0] + y_tr = sDes_traj[:,1] + z_tr = sDes_traj[:,2] + Vx_tr = sDes_traj[:,3] + Vy_tr = sDes_traj[:,4] + Vz_tr = sDes_traj[:,5] + Ax_tr = sDes_traj[:,6] + Ay_tr = sDes_traj[:,7] + Az_tr = sDes_traj[:,8] + yaw_tr = sDes_traj[:,14]*rad2deg + + uM1 = commands[:,0]*rads2rpm + uM2 = commands[:,1]*rads2rpm + uM3 = commands[:,2]*rads2rpm + uM4 = commands[:,3]*rads2rpm + + x_err = x_sp - x + y_err = y_sp - y + z_err = z_sp - z + + psiDes = np.zeros(q0Des.shape[0]) + thetaDes = np.zeros(q0Des.shape[0]) + phiDes = np.zeros(q0Des.shape[0]) + for ii in range(q0Des.shape[0]): + YPR = rotation_conversion.quatToYPR_ZYX(sDes_calc[ii,9:13]) + psiDes[ii] = YPR[0]*rad2deg + thetaDes[ii] = YPR[1]*rad2deg + phiDes[ii] = YPR[2]*rad2deg + + plt.show() + + plt.figure() + plt.plot(time, x, time, y, time, z) + plt.plot(time, x_sp, '--', time, y_sp, '--', time, z_sp, '--') + plt.grid(True) + plt.legend(['x','y','z','x_sp','y_sp','z_sp']) + plt.xlabel('Time (s)') + plt.ylabel('Position (m)') + plt.draw() + + + + plt.figure() + plt.plot(time, xdot, time, ydot, time, zdot) + plt.plot(time, Vx_sp, '--', time, Vy_sp, '--', time, Vz_sp, '--') + plt.grid(True) + plt.legend(['Vx','Vy','Vz','Vx_sp','Vy_sp','Vz_sp']) + plt.xlabel('Time (s)') + plt.ylabel('Velocity (m/s)') + plt.draw() + + plt.figure() + plt.plot(time, x_thr_sp, time, y_thr_sp, time, z_thr_sp) + plt.grid(True) + plt.legend(['x_thr_sp','y_thr_sp','z_thr_sp']) + plt.xlabel('Time (s)') + plt.ylabel('Desired Thrust (N)') + plt.draw() + + plt.figure() + plt.plot(time, phi, time, theta, time, psi) + plt.plot(time, phiDes, '--', time, thetaDes, '--', time, psiDes, '--') + plt.plot(time, yaw_tr, '-.') + plt.grid(True) + plt.legend(['roll','pitch','yaw','roll_sp','pitch_sp','yaw_sp','yaw_tr']) + plt.xlabel('Time (s)') + plt.ylabel('Euler Angle (°)') + plt.draw() + + plt.figure() + plt.plot(time, p, time, q, time, r) + plt.plot(time, pDes, '--', time, qDes, '--', time, rDes, '--') + plt.grid(True) + plt.legend(['p','q','r','p_sp','q_sp','r_sp']) + plt.xlabel('Time (s)') + plt.ylabel('Angular Velocity (°/s)') + plt.draw() + + plt.figure() + plt.plot(time, wM1, time, wM2, time, wM3, time, wM4) + plt.plot(time, uM1, '--', time, uM2, '--', time, uM3, '--', time, uM4, '--') + plt.grid(True) + plt.legend(['w1','w2','w3','w4']) + plt.xlabel('Time (s)') + plt.ylabel('Motor Angular Velocity (RPM)') + plt.draw() + + plt.figure() + plt.subplot(2,1,1) + plt.plot(time, thrust[:,0], time, thrust[:,1], time, thrust[:,2], time, thrust[:,3]) + plt.grid(True) + plt.legend(['thr1','thr2','thr3','thr4'], loc='upper right') + plt.xlabel('Time (s)') + plt.ylabel('Rotor Thrust (N)') + plt.draw() + + plt.subplot(2,1,2) + plt.plot(time, torque[:,0], time, torque[:,1], time, torque[:,2], time, torque[:,3]) + plt.grid(True) + plt.legend(['tor1','tor2','tor3','tor4'], loc='upper right') + plt.xlabel('Time (s)') + plt.ylabel('Rotor Torque (N*m)') + plt.draw() + + plt.figure() + plt.subplot(3,1,1) + plt.title('Trajectory Setpoints') + plt.plot(time, x_tr, time, y_tr, time, z_tr) + plt.grid(True) + plt.legend(['x','y','z'], loc='upper right') + plt.xlabel('Time (s)') + plt.ylabel('Position (m)') + + plt.subplot(3,1,2) + plt.plot(time, Vx_tr, time, Vy_tr, time, Vz_tr) + plt.grid(True) + plt.legend(['Vx','Vy','Vz'], loc='upper right') + plt.xlabel('Time (s)') + plt.ylabel('Velocity (m/s)') + + plt.subplot(3,1,3) + plt.plot(time, Ax_tr, time, Ay_tr, time, Az_tr) + plt.grid(True) + plt.legend(['Ax','Ay','Az'], loc='upper right') + plt.xlabel('Time (s)') + plt.ylabel('Acceleration (m/s^2)') + plt.draw() + + plt.figure() + plt.plot(time, x_err, time, y_err, time, z_err) + plt.grid(True) + plt.legend(['Pos x error','Pos y error','Pos z error']) + plt.xlabel('Time (s)') + plt.ylabel('Position Error (m)') + plt.draw() \ No newline at end of file diff --git a/src/ariel/simulation/drone/controllers/utils/gate_configs.py b/src/ariel/simulation/drone/controllers/utils/gate_configs.py new file mode 100644 index 000000000..0c268afa6 --- /dev/null +++ b/src/ariel/simulation/drone/controllers/utils/gate_configs.py @@ -0,0 +1,107 @@ +# -*- coding: utf-8 -*- +""" +Gate Configurations for Drone Racing/Navigation + +This module provides predefined gate configurations for drone racing and +navigation tasks. Gates are defined by their positions and orientations (yaw angles). + +Usage: + from ariel.simulation.drone.controllers.utils.gate_configs import GATE_CONFIGS + + # Get figure-8 configuration + config = GATE_CONFIGS['figure8'] + gate_positions = config.gate_pos + gate_yaws = config.gate_yaw +""" + +import numpy as np + + +class GateConfig: + """Base class for gate configurations""" + gate_pos = None + gate_yaw = None + gate_size = 1.0 # Gate size in meters + x_bounds = [-10, 10] + y_bounds = [-10, 10] + z_bounds = [-2, 2] + starting_pos = None # Initial drone position + periodic = True # Whether the trajectory loops back to gate 0 + + +class Figure8Gates(GateConfig): + """ + Figure-8 gate configuration + + This configuration matches the gate setup used in gate_train.py for the figure8 task. + Gates are ordered according to the trajectory path starting from [0.0, -1.5, 0.0]. + The trajectory follows a figure-8 pattern and encounters gates in this sequence. + """ + gate_pos = np.array([ + [ 1.5, -1.5, 0.0], # Gate 0: Lower right + [ 3.0, 0.0, 0.0], # Gate 1: Far right + [ 1.5, 1.5, 0.0], # Gate 2: Upper right + [ 0.0, 0.0, 0.0], # Gate 3: Center + [ -1.5, -1.5, 0.0], # Gate 4: Lower left + [ -3.0, 0.0, 0.0], # Gate 5: Far left + [ -1.5, 1.5, 0.0], # Gate 6: Upper left + [ 0.0, 0.0, 0.0], # Gate 7: Return to center + ], dtype=np.float64) + gate_yaw = np.array([0, -1, 0, 1, 2, -1, 2, 1], dtype=np.float64) * np.pi / 2 + x_bounds = np.array([-4, 4], dtype=np.float64) + y_bounds = np.array([-2.5, 2.5], dtype=np.float64) + z_bounds = np.array([-1, 1], dtype=np.float64) + starting_pos = np.array([0.0, -1.5, 0.0], dtype=np.float64) + + +class CircleGates(GateConfig): + """Circular gate configuration""" + gate_pos = np.array([ + [ 0.0, -1.5, 0.0], + [ 1.5, 0.0, 0.0], + [ 0.0, 1.5, 0.0], + [-1.5, 0.0, 0.0] + ], dtype=np.float64) + gate_yaw = np.array([0, 1, 2, 3], dtype=np.float64) * np.pi / 2 + x_bounds = np.array([-3, 3], dtype=np.float64) + y_bounds = np.array([-3, 3], dtype=np.float64) + z_bounds = np.array([-1, 1], dtype=np.float64) + starting_pos = np.array([-1.5, -1.5, 0.0], dtype=np.float64) + + +class SlalomGates(GateConfig): + """Slalom gate configuration""" + num_gates = 100 + gate_pos = np.array([[x, (i % 2) * (1 if i % 4 == 1 else -1), 0] + for i, x in enumerate(range(0, num_gates*2, 2))], + dtype=np.float64) + gate_yaw = np.tile([1, 0, -1, 0], num_gates) * np.pi / 2 + x_bounds = np.array([-2, num_gates*2+2], dtype=np.float64) + y_bounds = np.array([-3, 3], dtype=np.float64) + z_bounds = np.array([-1, 1], dtype=np.float64) + starting_pos = np.array([0, -1, 0], dtype=np.float64) + periodic = False # Slalom is a one-way linear path + + +class BackAndForthGates(GateConfig): + """Back and forth gate configuration""" + gate_pos = np.array([ + [ 2.0, 0.0, 0.0], + [ 8.0, 0.0, 0.0], + [ 8.0, 0.0, 0.0], + [ 2.0, 0.0, 0.0], + ], dtype=np.float64) + gate_yaw = np.array([0, 0, 2, 2], dtype=np.float64) * np.pi / 2 + x_bounds = np.array([-1, 11], dtype=np.float64) + y_bounds = np.array([-1, 1], dtype=np.float64) + z_bounds = np.array([-1, 1], dtype=np.float64) + starting_pos = np.array([0.0, 0.0, 0.0], dtype=np.float64) + + +# Dictionary mapping gate configuration names to classes +GATE_CONFIGS = { + 'figure8': Figure8Gates, + 'circle': CircleGates, + 'slalom': SlalomGates, + 'backandforth': BackAndForthGates +} diff --git a/src/ariel/simulation/drone/controllers/utils/quaternion_functions.py b/src/ariel/simulation/drone/controllers/utils/quaternion_functions.py new file mode 100644 index 000000000..fb16d3324 --- /dev/null +++ b/src/ariel/simulation/drone/controllers/utils/quaternion_functions.py @@ -0,0 +1,31 @@ +# -*- coding: utf-8 -*- +""" +author: John Bass +email: john.bobzwik@gmail.com +license: MIT +Please feel free to use and modify this, but keep the above information. Thanks! +""" + +import numpy as np +from numpy import sin, cos +from numpy.linalg import norm + + +# Normalize quaternion, or any vector +def vectNormalize(q): + return q/norm(q) + + +# Quaternion multiplication +def quatMultiply(q, p): + Q = np.array([[q[0], -q[1], -q[2], -q[3]], + [q[1], q[0], -q[3], q[2]], + [q[2], q[3], q[0], -q[1]], + [q[3], -q[2], q[1], q[0]]]) + return Q@p + + +# Inverse quaternion +def inverse(q): + qinv = np.array([q[0], -q[1], -q[2], -q[3]])/norm(q) + return qinv \ No newline at end of file diff --git a/src/ariel/simulation/drone/controllers/utils/rotation_conversion.py b/src/ariel/simulation/drone/controllers/utils/rotation_conversion.py new file mode 100644 index 000000000..3d4f21261 --- /dev/null +++ b/src/ariel/simulation/drone/controllers/utils/rotation_conversion.py @@ -0,0 +1,150 @@ +# -*- coding: utf-8 -*- + +import numpy as np +from numpy import sin, cos +from numpy.linalg import norm + +def quatToYPR_ZYX(q): + # [q0 q1 q2 q3] = [w x y z] + q0 = q[0] + q1 = q[1] + q2 = q[2] + q3 = q[3] + + YPR = threeaxisrot( 2.0*(q1*q2 + q0*q3), \ + q0**2 + q1**2 - q2**2 - q3**2, \ + -2.0*(q1*q3 - q0*q2), \ + 2.0*(q2*q3 + q0*q1), \ + q0**2 - q1**2 - q2**2 + q3**2) + + # YPR = [Yaw, pitch, roll] = [psi, theta, phi] + return YPR + +def threeaxisrot(r11, r12, r21, r31, r32): + r1 = np.arctan2(r11, r12) + r2 = np.arcsin(r21) + r3 = np.arctan2(r31, r32) + + return np.array([r1, r2, r3]) + +def YPRToQuat(r1, r2, r3): + # For ZYX, Yaw-Pitch-Roll + # psi = RPY[0] = r1 + # theta = RPY[1] = r2 + # phi = RPY[2] = r3 + + cr1 = cos(0.5*r1) + cr2 = cos(0.5*r2) + cr3 = cos(0.5*r3) + sr1 = sin(0.5*r1) + sr2 = sin(0.5*r2) + sr3 = sin(0.5*r3) + + q0 = cr1*cr2*cr3 + sr1*sr2*sr3 + q1 = cr1*cr2*sr3 - sr1*sr2*cr3 + q2 = cr1*sr2*cr3 + sr1*cr2*sr3 + q3 = sr1*cr2*cr3 - cr1*sr2*sr3 + + # e0,e1,e2,e3 = qw,qx,qy,qz + q = np.array([q0,q1,q2,q3]) + # q = q*np.sign(e0) + + q = q/norm(q) + + return q + +def quat2Dcm(q): + dcm = np.zeros([3,3]) + + dcm[0,0] = q[0]**2 + q[1]**2 - q[2]**2 - q[3]**2 + dcm[0,1] = 2.0*(q[1]*q[2] - q[0]*q[3]) + dcm[0,2] = 2.0*(q[1]*q[3] + q[0]*q[2]) + dcm[1,0] = 2.0*(q[1]*q[2] + q[0]*q[3]) + dcm[1,1] = q[0]**2 - q[1]**2 + q[2]**2 - q[3]**2 + dcm[1,2] = 2.0*(q[2]*q[3] - q[0]*q[1]) + dcm[2,0] = 2.0*(q[1]*q[3] - q[0]*q[2]) + dcm[2,1] = 2.0*(q[2]*q[3] + q[0]*q[1]) + dcm[2,2] = q[0]**2 - q[1]**2 - q[2]**2 + q[3]**2 + + return dcm + +def RotToQuat(R): + + R11 = R[0, 0] + R12 = R[0, 1] + R13 = R[0, 2] + R21 = R[1, 0] + R22 = R[1, 1] + R23 = R[1, 2] + R31 = R[2, 0] + R32 = R[2, 1] + R33 = R[2, 2] + # From page 68 of MotionGenesis book + tr = R11 + R22 + R33 + + if tr > R11 and tr > R22 and tr > R33: + e0 = 0.5 * np.sqrt(1 + tr) + r = 0.25 / e0 + e1 = (R32 - R23) * r + e2 = (R13 - R31) * r + e3 = (R21 - R12) * r + elif R11 > R22 and R11 > R33: + e1 = 0.5 * np.sqrt(1 - tr + 2*R11) + r = 0.25 / e1 + e0 = (R32 - R23) * r + e2 = (R12 + R21) * r + e3 = (R13 + R31) * r + elif R22 > R33: + e2 = 0.5 * np.sqrt(1 - tr + 2*R22) + r = 0.25 / e2 + e0 = (R13 - R31) * r + e1 = (R12 + R21) * r + e3 = (R23 + R32) * r + else: + e3 = 0.5 * np.sqrt(1 - tr + 2*R33) + r = 0.25 / e3 + e0 = (R21 - R12) * r + e1 = (R13 + R31) * r + e2 = (R23 + R32) * r + + # e0,e1,e2,e3 = qw,qx,qy,qz + q = np.array([e0,e1,e2,e3]) + q = q*np.sign(e0) + + q = q/np.sqrt(np.sum(q[0]**2 + q[1]**2 + q[2]**2 + q[3]**2)) + + return q + + +# def RPYtoRot_ZYX(RPY): + +# phi = RPY[0] +# theta = RPY[1] +# psi = RPY[2] + +# # R = np.array([[cos(psi)*cos(theta) - sin(phi)*sin(psi)*sin(theta), +# # cos(theta)*sin(psi) + cos(psi)*sin(phi)*sin(theta), +# # -cos(phi)*sin(theta)], +# # [-cos(phi)*sin(psi), +# # cos(phi)*cos(psi), +# # sin(phi)], +# # [cos(psi)*sin(theta) + cos(theta)*sin(phi)*sin(psi), +# # sin(psi)*sin(theta) - cos(psi)*cos(theta)*sin(phi), +# # cos(phi)*cos(theta)]]) + +# r1 = psi +# r2 = theta +# r3 = phi +# # Rotation ZYX from page 277 of MotionGenesis book +# R = np.array([[cos(r1)*cos(r2), +# -sin(r1)*cos(r3) + sin(r2)*sin(r3)*cos(r1), +# sin(r1)*sin(r3) + sin(r2)*cos(r1)*cos(r3)], +# [sin(r1)*cos(r2), +# cos(r1)*cos(r3) + sin(r1)*sin(r2)*sin(r3), +# -sin(r3)*cos(r1) + sin(r1)*sin(r2)*cos(r3)], +# [-sin(r2), +# sin(r3)*cos(r2), +# cos(r2)*cos(r3)]]) + +# return R + diff --git a/src/ariel/simulation/drone/controllers/utils/state_conversions.py b/src/ariel/simulation/drone/controllers/utils/state_conversions.py new file mode 100644 index 000000000..e73b8bdf6 --- /dev/null +++ b/src/ariel/simulation/drone/controllers/utils/state_conversions.py @@ -0,0 +1,54 @@ +# -*- coding: utf-8 -*- +""" +author: John Bass +email: john.bobzwik@gmail.com +license: MIT +Please feel free to use and modify this, but keep the above information. Thanks! +""" + +import numpy as np +from numpy import sin, cos, tan + +def phiThetaPsiDotToPQR(phi, theta, psi, phidot, thetadot, psidot): + + p = -sin(theta)*psidot + phidot + + q = sin(phi)*cos(theta)*psidot + cos(phi)*thetadot + + r = -sin(phi)*thetadot + cos(phi)*cos(theta)*psidot + + return np.array([p, q, r]) + + +def xyzDotToUVW_euler(phi, theta, psi, xdot, ydot, zdot): + u = xdot*cos(psi)*cos(theta) + ydot*sin(psi)*cos(theta) - zdot*sin(theta) + + v = (sin(phi)*sin(psi)*sin(theta) + cos(phi)*cos(psi))*ydot + (sin(phi)*sin(theta)*cos(psi) - sin(psi)*cos(phi))*xdot + zdot*sin(phi)*cos(theta) + + w = (sin(phi)*sin(psi) + sin(theta)*cos(phi)*cos(psi))*xdot + (-sin(phi)*cos(psi) + sin(psi)*sin(theta)*cos(phi))*ydot + zdot*cos(phi)*cos(theta) + + return np.array([u, v, w]) + + +def xyzDotToUVW_Flat_euler(phi, theta, psi, xdot, ydot, zdot): + uFlat = xdot * cos(psi) + ydot * sin(psi) + + vFlat = -xdot * sin(psi) + ydot * cos(psi) + + wFlat = zdot + + return np.array([uFlat, vFlat, wFlat]) + +def xyzDotToUVW_Flat_quat(q, xdot, ydot, zdot): + q0 = q[0] + q1 = q[1] + q2 = q[2] + q3 = q[3] + + uFlat = 2*(q0*q3 - q1*q2)*ydot + (q0**2 - q1**2 + q2**2 - q3**2)*xdot + + vFlat = -2*(q0*q3 + q1*q2)*xdot + (q0**2 + q1**2 - q2**2 - q3**2)*ydot + + wFlat = zdot + + return np.array([uFlat, vFlat, wFlat]) diff --git a/src/ariel/simulation/drone/controllers/utils/wind_model.py b/src/ariel/simulation/drone/controllers/utils/wind_model.py new file mode 100644 index 000000000..77f01705b --- /dev/null +++ b/src/ariel/simulation/drone/controllers/utils/wind_model.py @@ -0,0 +1,109 @@ +# -*- coding: utf-8 -*- +""" +author: John Bass +email: john.bobzwik@gmail.com +license: MIT +Please feel free to use and modify this, but keep the above information. Thanks! +""" + +import numpy as np +from numpy import sin, cos, pi +import random as rd + +deg2rad = pi/180.0 + +class Wind: + + def __init__(self, *args): + + if (len(args) == 0): + self.windType = 'NONE' + elif not isinstance(args[0], str): + raise Exception('Not a valid wind type.') + else: + self.windType = args[0].upper() + + if (self.windType == 'SINE') or (self.windType == 'RANDOMSINE'): + + if (self.windType == 'SINE'): + + self.velW_med = args[1] + self.qW1_med = args[2]*deg2rad + self.qW2_med = args[3]*deg2rad + + elif (self.windType == 'RANDOMSINE'): + + # Wind Velocity + velW_max = args[1] # m/s + velW_min = args[2] # m/s + # Wind Heading + qW1_max = args[3] # deg + qW1_min = args[4] # deg + # Wind Elevation (positive = upwards wind in NED, positive = downwards wind in ENU) + qW2_max = args[5] # deg + qW2_min = args[6] # deg + + # Median values + self.velW_med = (velW_max - velW_min)*rd.random() + velW_min + self.qW1_med = ((qW1_max - qW1_min)*rd.random() + qW1_min)*deg2rad + self.qW2_med = ((qW2_max - qW2_min)*rd.random() + qW2_min)*deg2rad + + # Wind Velocity + self.velW_a1 = 1.5 # Wind velocity amplitude 1 + self.velW_f1 = 0.7 # Wind velocity frequency 1 + self.velW_d1 = 0 # Wind velocity delay (offset) 1 + self.velW_a2 = 1.1 # Wind velocity amplitude 2 + self.velW_f2 = 1.2 # Wind velocity frequency 2 + self.velW_d2 = 1.3 # Wind velocity delay (offset) 2 + self.velW_a3 = 0.8 # Wind velocity amplitude 3 + self.velW_f3 = 2.3 # Wind velocity frequency 3 + self.velW_d3 = 2.0 # Wind velocity delay (offset) 3 + + # Wind Heading + self.qW1_a1 = 15.0*deg2rad # Wind heading amplitude 1 + self.qW1_f1 = 0.1 # Wind heading frequency 1 + self.qW1_d1 = 0 # Wind heading delay (offset) 1 + self.qW1_a2 = 3.0*deg2rad # Wind heading amplitude 2 + self.qW1_f2 = 0.54 # Wind heading frequency 2 + self.qW1_d2 = 0 # Wind heading delay (offset) 2 + + # Wind Elevation + self.qW2_a1 = 4.0*deg2rad # Wind elevation amplitude 1 + self.qW2_f1 = 0.1 # Wind elevation frequency 1 + self.qW2_d1 = 0 # Wind elevation delay (offset) 1 + self.qW2_a2 = 0.8*deg2rad # Wind elevation amplitude 2 + self.qW2_f2 = 0.54 # Wind elevation frequency 2 + self.qW2_d2 = 0 # Wind elevation delay (offset) 2 + + elif (self.windType == 'FIXED'): + + self.velW_med = args[1] + self.qW1_med = args[2]*deg2rad + self.qW2_med = args[3]*deg2rad + + elif (self.windType == 'NONE'): + + self.velW_med = 0 + self.qW1_med = 0 + self.qW2_med = 0 + + else: + + raise Exception('Not a valid wind type.') + + + def randomWind(self, t): + if (self.windType == 'SINE') or (self.windType == 'RANDOMSINE'): + + velW = self.velW_a1*sin(self.velW_f1*t - self.velW_d1) + self.velW_a2*sin(self.velW_f2*t - self.velW_d2) + self.velW_a3*sin(self.velW_f3*t - self.velW_d3) + self.velW_med + qW1 = self.qW1_a1*sin(self.qW1_f1*t - self.qW1_d1) + self.qW1_a2*sin(self.qW1_f2*t - self.qW1_d2) + self.qW1_med + qW2 = self.qW2_a1*sin(self.qW2_f1*t - self.qW2_d1) + self.qW2_a2*sin(self.qW2_f2*t - self.qW2_d2) + self.qW2_med + + velW = max([0, velW]) + + elif (self.windType == 'FIXED') or (self.windType == 'NONE'): + velW = self.velW_med + qW1 = self.qW1_med + qW2 = self.qW2_med + + return velW, qW1, qW2 \ No newline at end of file diff --git a/src/ariel/simulation/drone/drone_configuration.py b/src/ariel/simulation/drone/drone_configuration.py new file mode 100644 index 000000000..36c886cff --- /dev/null +++ b/src/ariel/simulation/drone/drone_configuration.py @@ -0,0 +1,333 @@ +""" +Drone Configuration Class + +This module provides automatic computation of drone physical properties and allocation +matrices from propeller configurations. Integrates algorithms from drone-hover package +for realistic mass, center of gravity, inertia, and control allocation calculation. +""" + +import numpy as np +from numpy.linalg import norm, inv +from .propeller_data import ( + get_propeller_specs, validate_propeller_config, + GRAVITY, CONTROLLER_MASS, BATTERY_MASS, BEAM_DENSITY, +) + +# Battery mounted under the frame (NED: +z is down). +BATTERY_POS = np.array([0.0, 0.0, 0.02]) + +class DroneConfiguration: + """ + Automatically compute drone physical properties from propeller configuration. + + This class takes a list of propeller specifications and computes: + - Total mass including controller, motors, and structure + - Center of gravity location + - Inertia matrix (Ix, Iy, Iz, Ixy, Ixz, Iyz) + - Force allocation matrix (Bf) mapping motor commands to body forces + - Moment allocation matrix (Bm) mapping motor commands to body moments + """ + + def __init__(self, propellers): + """ + Initialize drone configuration from propeller specifications. + + Args: + propellers (list): List of propeller dictionaries, each containing: + - "loc": [x, y, z] position in body frame (meters) + - "dir": [x, y, z, rotation] thrust direction and spin direction + - "propsize": propeller size in inches (4-8) + + Example: + propellers = [ + {"loc": [0.11, 0.11, 0], "dir": [0, 0, -1, "ccw"], "propsize": 5}, + {"loc": [-0.11, 0.11, 0], "dir": [0, 0, -1, "cw"], "propsize": 5}, + # ... more propellers + ] + """ + # Validate input format + validate_propeller_config(propellers) + + self.propellers = propellers + self.num_motors = len(propellers) + + # Add propeller specifications to each propeller + self._add_propeller_specs() + + # Compute physical properties + self._compute_mass_and_cg() + self._compute_inertia() + self._compute_allocation_matrices() + + def _add_propeller_specs(self): + """Add force/moment constants and specifications to each propeller.""" + for prop in self.propellers: + specs = get_propeller_specs(prop["propsize"]) + prop["constants"] = specs["constants"] # [k_f, k_m] + prop["wmax"] = specs["wmax"] + prop["mass"] = specs["mass"] + + def _compute_mass_and_cg(self): + """Compute total mass and center of gravity location.""" + # Total mass = controller + battery + per-prop (propeller + beam). + self.mass = CONTROLLER_MASS + BATTERY_MASS + for prop in self.propellers: + beam_length = norm(np.array(prop["loc"])) + self.mass += prop["mass"] + BEAM_DENSITY * beam_length + + # Center of gravity. Controller sits at origin, battery at BATTERY_POS, + # propellers at their loc, beams at their midpoint. + self.cg = (BATTERY_MASS / self.mass) * BATTERY_POS + for prop in self.propellers: + prop_mass = prop["mass"] + prop_loc = np.array(prop["loc"]) + beam_length = norm(prop_loc) + beam_mass = BEAM_DENSITY * beam_length + self.cg += (prop_mass / self.mass) * prop_loc + self.cg += (beam_mass / self.mass) * prop_loc * 0.5 + + def _compute_inertia(self): + """Compute inertia matrix components using parallel axis theorem.""" + # Controller inertia about its own center (approximated as rectangular block) + # Typical flight controller dimensions: 105mm x 36mm x 35mm + controller_Ix = (1/12) * CONTROLLER_MASS * (0.036**2 + 0.035**2) + controller_Iy = (1/12) * CONTROLLER_MASS * (0.105**2 + 0.035**2) + controller_Iz = (1/12) * CONTROLLER_MASS * (0.105**2 + 0.036**2) + + # Translate controller inertia to center of gravity using parallel axis theorem + cg_offset_sq = np.dot(self.cg, self.cg) + self.Ix = controller_Ix + CONTROLLER_MASS * (self.cg[1]**2 + self.cg[2]**2) + self.Iy = controller_Iy + CONTROLLER_MASS * (self.cg[0]**2 + self.cg[2]**2) + self.Iz = controller_Iz + CONTROLLER_MASS * (self.cg[0]**2 + self.cg[1]**2) + + # Initialize products of inertia + self.Ixy = -CONTROLLER_MASS * self.cg[0] * self.cg[1] + self.Ixz = -CONTROLLER_MASS * self.cg[0] * self.cg[2] + self.Iyz = -CONTROLLER_MASS * self.cg[1] * self.cg[2] + + # Battery contribution (treated as a point mass at BATTERY_POS). + r_bat = BATTERY_POS - self.cg + self.Ix += BATTERY_MASS * (r_bat[1] ** 2 + r_bat[2] ** 2) + self.Iy += BATTERY_MASS * (r_bat[0] ** 2 + r_bat[2] ** 2) + self.Iz += BATTERY_MASS * (r_bat[0] ** 2 + r_bat[1] ** 2) + self.Ixy -= BATTERY_MASS * r_bat[0] * r_bat[1] + self.Ixz -= BATTERY_MASS * r_bat[0] * r_bat[2] + self.Iyz -= BATTERY_MASS * r_bat[1] * r_bat[2] + + # Add contributions from propellers and beams + for prop in self.propellers: + prop_mass = prop["mass"] + pos = np.array(prop["loc"]) + beam_length = norm(pos) + beam_mass = BEAM_DENSITY * beam_length + + # Propeller position relative to CG + r_prop = pos - self.cg + + # Propeller contributions (treated as point mass) + self.Ix += prop_mass * (r_prop[1]**2 + r_prop[2]**2) + self.Iy += prop_mass * (r_prop[0]**2 + r_prop[2]**2) + self.Iz += prop_mass * (r_prop[0]**2 + r_prop[1]**2) + self.Ixy -= prop_mass * r_prop[0] * r_prop[1] + self.Ixz -= prop_mass * r_prop[0] * r_prop[2] + self.Iyz -= prop_mass * r_prop[1] * r_prop[2] + + # Beam contributions (rod along beam direction) + beam_center = pos * 0.5 # Beam center at midpoint + r_beam = beam_center - self.cg + + # For a rod along the beam direction, add both translational and rotational inertia + beam_direction = pos / beam_length # Unit vector along beam + + # Perpendicular moment of inertia for rod: I_perp = (1/12) * m * L² + I_beam_perp = (1/12) * beam_mass * beam_length**2 + + # Add translational inertia (parallel axis theorem) + self.Ix += beam_mass * (r_beam[1]**2 + r_beam[2]**2) + I_beam_perp * (beam_direction[1]**2 + beam_direction[2]**2) + self.Iy += beam_mass * (r_beam[0]**2 + r_beam[2]**2) + I_beam_perp * (beam_direction[0]**2 + beam_direction[2]**2) + self.Iz += beam_mass * (r_beam[0]**2 + r_beam[1]**2) + I_beam_perp * (beam_direction[0]**2 + beam_direction[1]**2) + + # Add products of inertia + self.Ixy -= beam_mass * r_beam[0] * r_beam[1] + self.Ixz -= beam_mass * r_beam[0] * r_beam[2] + self.Iyz -= beam_mass * r_beam[1] * r_beam[2] + + # Create inertia matrix with numerical stability improvements + self.inertia_matrix = np.array([ + [self.Ix, self.Ixy, self.Ixz], + [self.Ixy, self.Iy, self.Iyz], + [self.Ixz, self.Iyz, self.Iz] + ]) + + # Clean up extremely small values that cause numerical instability + # Values smaller than 1e-12 are likely numerical noise + tolerance = 1e-12 + self.inertia_matrix[np.abs(self.inertia_matrix) < tolerance] = 0.0 + + # Ensure matrix is symmetric (fix any tiny asymmetries from numerical errors) + self.inertia_matrix = 0.5 * (self.inertia_matrix + self.inertia_matrix.T) + + # Ensure positive definite by checking eigenvalues + eigenvals = np.linalg.eigvals(self.inertia_matrix) + if np.any(eigenvals <= 0): + print(f"Warning: Non-positive eigenvalues detected: {eigenvals}") + # Add small positive value to diagonal to ensure positive definiteness + min_eigenval = max(1e-6, -np.min(eigenvals) + 1e-6) + self.inertia_matrix += min_eigenval * np.eye(3) + + # Note: Minimum inertia clamping is skipped here to preserve morphological diversity. + # Numerical stability is instead handled via method selection in get_inertia_inverse(): + # - "clamp" method applies min_inertia threshold before standard inversion + # - "svd" method uses pseudo-inverse which naturally handles small singular values + + def get_inertia_inverse(self, method: str = "clamp", min_inertia: float = 0.01, rcond: float = 1e-10): + """Return a numerically stable inverse of the inertia matrix. + + Args: + method: "clamp" to use diagonal clamping then invert, + or "svd" to use pseudo-inverse via SVD (does NOT use clamping). + min_inertia: Minimum diagonal inertia for the "clamp" method only. + rcond: Relative cutoff for singular values in the "svd" method. + """ + if method == "clamp": + inertia = self.inertia_matrix.copy() + inertia[0, 0] = max(inertia[0, 0], min_inertia) + inertia[1, 1] = max(inertia[1, 1], min_inertia) + inertia[2, 2] = max(inertia[2, 2], min_inertia) + return np.linalg.inv(inertia) + elif method == "svd": + # SVD-based pseudo-inverse: no clamping, handles singular values via rcond + return np.linalg.pinv(self.inertia_matrix, rcond=rcond) + else: + raise ValueError(f"Unknown inertia inversion method: {method}") + + def _compute_allocation_matrices(self): + """Compute force and moment allocation matrices.""" + self.Bf = np.zeros((3, self.num_motors)) + self.Bm = np.zeros((3, self.num_motors)) + + for idx, prop in enumerate(self.propellers): + k_f, k_m = prop["constants"] + w_max = prop["wmax"] + prop_loc = np.array(prop["loc"]) + prop_r = prop_loc - self.cg # Position relative to CG + + # Thrust direction (normalized) + prop_dir = np.array(prop["dir"][:3]) + prop_dir = prop_dir / norm(prop_dir) + + # Rotation direction (-1 for CCW, +1 for CW when viewed from above) + prop_rot = -1 if prop["dir"][-1] == "ccw" else 1 + + # Force allocation (thrust in prop_dir direction) + self.Bf[:, idx] = k_f * w_max**2 * prop_dir + + # Moment allocation (cross product + propeller torque) + moment_from_thrust = np.cross(prop_r, k_f * w_max**2 * prop_dir) + moment_from_torque = k_m * w_max**2 * prop_rot * prop_dir + self.Bm[:, idx] = moment_from_thrust + moment_from_torque + + # Store unscaled matrices for reference + self.Bf_unscaled = self.Bf.copy() + self.Bm_unscaled = self.Bm.copy() + + # Store original matrices without pre-scaling + # The dynamics equations will handle the mass/inertia scaling to avoid numerical issues + + # Combined allocation matrix for control allocation + self.B_combined = np.vstack([self.Bf, self.Bm]) # (6 x num_motors) + + # Clean up tiny numerical values in allocation matrices to prevent NaN propagation + tolerance = 1e-15 + self.Bf[np.abs(self.Bf) < tolerance] = 0.0 + self.Bm[np.abs(self.Bm) < tolerance] = 0.0 + self.B_combined[np.abs(self.B_combined) < tolerance] = 0.0 + + # Compute pseudo-inverse with enhanced numerical stability + try: + self.B_pinv = np.linalg.pinv(self.B_combined, rcond=1e-10) + except np.linalg.LinAlgError: + print("Warning: Using fallback pseudo-inverse computation") + # Fallback: use SVD decomposition with explicit tolerance + U, s, Vt = np.linalg.svd(self.B_combined, full_matrices=False) + s_inv = np.where(s > 1e-10, 1/s, 0) + self.B_pinv = Vt.T @ np.diag(s_inv) @ U.T + + # Clean up tiny values in pseudo-inverse to prevent NaN propagation + self.B_pinv[np.abs(self.B_pinv) < tolerance] = 0.0 + + def get_physical_properties(self): + """ + Get physical properties dictionary. + + Returns: + dict: Physical properties including mass, CG, inertia components + """ + return { + 'mass': self.mass, + 'center_of_gravity': self.cg.tolist(), + 'Ix': self.Ix, + 'Iy': self.Iy, + 'Iz': self.Iz, + 'Ixy': self.Ixy, + 'Ixz': self.Ixz, + 'Iyz': self.Iyz, + 'inertia_matrix': self.inertia_matrix.tolist(), + 'num_motors': self.num_motors + } + + def get_allocation_matrices(self): + """ + Get force and moment allocation matrices. + + Returns: + tuple: (Bf, Bm) force and moment allocation matrices + """ + return self.Bf.copy(), self.Bm.copy() + + def get_control_allocation(self): + """ + Get combined allocation matrix and its pseudo-inverse. + + Returns: + tuple: (B_combined, B_pinv) for control allocation + """ + return self.B_combined.copy(), self.B_pinv.copy() + + def is_over_actuated(self): + """ + Check if drone is over-actuated (more motors than DOF). + + Returns: + bool: True if over-actuated (num_motors > 6) + """ + return self.num_motors > 6 + + def get_motor_configuration_info(self): + """ + Get comprehensive motor configuration information. + + Returns: + dict: Configuration analysis including ranks, condition numbers, etc. + """ + rank_f = np.linalg.matrix_rank(self.Bf) + rank_m = np.linalg.matrix_rank(self.Bm) + rank_combined = np.linalg.matrix_rank(self.B_combined) + + # Condition numbers for numerical analysis + cond_f = np.linalg.cond(self.Bf @ self.Bf.T) + cond_m = np.linalg.cond(self.Bm @ self.Bm.T) + cond_combined = np.linalg.cond(self.B_combined @ self.B_combined.T) + + return { + 'num_motors': self.num_motors, + 'is_over_actuated': self.is_over_actuated(), + 'force_rank': rank_f, + 'moment_rank': rank_m, + 'combined_rank': rank_combined, + 'force_condition_number': cond_f, + 'moment_condition_number': cond_m, + 'combined_condition_number': cond_combined, + 'mass': self.mass, + 'center_of_gravity': self.cg.tolist() + } \ No newline at end of file diff --git a/src/ariel/simulation/drone/drone_interface.py b/src/ariel/simulation/drone/drone_interface.py new file mode 100644 index 000000000..252000e09 --- /dev/null +++ b/src/ariel/simulation/drone/drone_interface.py @@ -0,0 +1,136 @@ +""" +DroneInterface - Controller compatibility wrapper for DroneSimulator + +This module provides a wrapper class that makes DroneSimulator compatible with +existing controller frameworks while supporting any multi-rotor configuration. +""" + +import numpy as np +from .drone_simulator import DroneSimulator + + +class DroneInterface: + """ + Wrapper that makes DroneSimulator compatible with existing controller framework. + + Despite the legacy "quadcopter" terminology in variable names, this class works + with ANY multi-rotor configuration (quad, hex, tri, octo, custom). + + This class adapts the modern DroneSimulator to legacy controller interfaces, + providing backward compatibility while enabling flexible drone configurations. + """ + + def __init__(self, Ti, propellers=None, drone_type="quad", arm_length=0.11, prop_size=5): + """ + Initialize drone interface. + + Args: + Ti: Initial time + propellers: Custom propeller configuration (optional) + drone_type: Standard drone type if propellers not specified + arm_length: Arm length for standard configurations + prop_size: Propeller size for standard configurations + """ + # Create drone simulator + if propellers is not None: + self.drone_sim = DroneSimulator(propellers=propellers, dt=0.005) + else: + self.drone_sim = DroneSimulator.create_standard_drone( + drone_type, arm_length, prop_size, dt=0.005 + ) + + # Get parameters in compatible format + self.params = self.drone_sim.get_params() + + # Initialize state variables in compatible format + self._update_state_variables() + + # Initialize extended state variables + self.extended_state() + + # Store initial time + self.Ti = Ti + + def _update_state_variables(self): + """Update all state variables from drone simulator.""" + quad_state = self.drone_sim.get_drone_state() + + # Copy all state variables to be compatible with existing code + self.state = quad_state['state'] + self.pos = quad_state['pos'] + self.vel = quad_state['vel'] + self.quat = quad_state['quat'] + self.omega = quad_state['omega'] + self.euler = quad_state['euler'] + self.wMotor = quad_state['wMotor'] + self.vel_dot = quad_state['vel_dot'] + self.omega_dot = quad_state['omega_dot'] + self.acc = quad_state['acc'] + self.thr = quad_state['thr'] + self.tor = quad_state['tor'] + self.dcm = quad_state['dcm'] + + def extended_state(self): + """Update extended state variables (quaternion to euler conversion, etc.).""" + # Import here to avoid circular dependencies + import ariel.simulation.drone.controllers.utils as utils + + # Update DCM from quaternion + self.dcm = utils.quat2Dcm(self.quat) + + # Update Euler angles from quaternion + YPR = utils.quatToYPR_ZYX(self.quat) + self.euler = YPR[::-1] # flip YPR so that euler state = phi, theta, psi + self.psi = YPR[0] + self.theta = YPR[1] + self.phi = YPR[2] + + def forces(self): + """Calculate rotor thrusts and torques.""" + # Read actual motor speeds (rad/s) from sim state. The previous + # `sqrt(motor_commands) * maxWmotor` form was for the legacy + # action-in-[0,1] convention; under the reference-form dynamics + # motor_commands lives in [-1, 1] and `sqrt` of negative values + # propagates NaN downstream. + motor_speeds = self.drone_sim._get_actual_motor_speeds() + + # Calculate thrusts and torques + self.thr = self.params["kTh"] * motor_speeds * motor_speeds + self.tor = self.params["kTo"] * motor_speeds * motor_speeds + + # Pad to 4 motors for compatibility + if len(self.thr) < 4: + self.thr = np.pad(self.thr, (0, 4 - len(self.thr))) + self.tor = np.pad(self.tor, (0, 4 - len(self.tor))) + + def update(self, t, Ts, cmd, wind): + """ + Update simulation state. + + Args: + t: Current time + Ts: Time step + cmd: Motor commands + wind: Wind model + """ + # Store full motor command for drones with >4 motors + if hasattr(self, 'w_cmd_full'): + self.drone_sim.w_cmd_full = self.w_cmd_full + + # Update drone simulator + new_t = self.drone_sim.update_from_controller(t, Ts, cmd, wind) + + # Update state variables + self._update_state_variables() + self.extended_state() + self.forces() + + return new_t + + def get_configuration_info(self): + """Get comprehensive configuration information.""" + return self.drone_sim.get_configuration_info() + + def get_propeller_info(self): + """Get propeller configuration details.""" + return self.drone_sim.get_propeller_info() diff --git a/src/ariel/simulation/drone/drone_simulator.py b/src/ariel/simulation/drone/drone_simulator.py new file mode 100644 index 000000000..8916b7ba1 --- /dev/null +++ b/src/ariel/simulation/drone/drone_simulator.py @@ -0,0 +1,482 @@ +""" +Drone Simulator with Propeller-Based Configuration + +Reference-form symbolic dynamics. Mirrors +`optimal_quad_control_RL/quad_race_env.py:22-103` (the sysid'd 5-inch +canonical model) but parameterized by airevolve's morphology. + +Per-step parity against the reference is verified at machine precision +(<1e-9 rel err) by `unit_tests/test_dynamics_parity.py`. + +See `experimentation/RUNTIME_DYNAMICS_MIGRATION.md` (the migration plan) +and `experimentation/RL_TRAINING_FIXES.md` (the diagnostic chain that +justified the rewrite). +""" + +import warnings +import numpy as np +from sympy import Array, Matrix, cos, lambdify, sin, sqrt, symbols, tan +from .drone_configuration import DroneConfiguration +from .propeller_data import create_standard_propeller_config +from .dynamics_params import derive_reference_params, W_MAX_N, W_MIN_N + + +def _invert_sqrt_poly(Wc, w_max, w_min, k): + """Solve `Wc = (w_max - w_min)·sqrt(k·U² + (1-k)·U) + w_min` for U∈[0,1]. + + Used by `update_from_controller` to convert a controller's commanded + steady-state motor speed (rad/s) into the env action. + """ + Wc = float(np.clip(Wc, w_min, w_max)) + z = (Wc - w_min) / (w_max - w_min) + z2 = z * z + if abs(k) < 1e-12: + return z2 + disc = (1.0 - k) ** 2 + 4.0 * k * z2 + return (-(1.0 - k) + np.sqrt(disc)) / (2.0 * k) + +class DroneSimulator: + """ + Core drone simulation framework using reference-form sysid'd dynamics. + + State vector (length 12 + N where N = num_motors): + [x, y, z, vx, vy, vz, phi, theta, psi, p, q, r, w_1..w_N] + where w_i ∈ [-1, 1] is the normalized motor speed (W_i = (w_i+1)/2 · + W_MAX_N + W_MIN_N rad/s; W_MAX_N=3000, W_MIN_N=0). + + Action vector (length N): u_i ∈ [-1, 1]. + + `dynamics_func(full_state, action) → full_state_dot` is lambdified; + motor model (sqrt-poly mapping + first-order lag) is baked in. + + The reference's `Bf, Bm` allocation matrices are kept as decorative + attributes for API compatibility with consumers that read them; the + new dynamics path uses per-motor coefficients in `self.params` instead. + """ + + def __init__(self, propellers=None, mountpoints=None, dt=0.005, gravity=9.81): + """ + Initialize drone simulator from propeller configuration. + + Args: + propellers (list): List of propeller dictionaries, each containing: + - "loc": [x, y, z] position in body frame (meters) + - "dir": [x, y, z, rotation] thrust direction and spin direction + - "propsize": propeller size in inches (2-8) or "matched" + mountpoints (list, optional): Accepted for API compat; + DroneConfiguration does not currently consume it. + dt (float): Integration time step + gravity (float): Gravitational acceleration + + Example: + # Standard quadrotor + propellers = [ + {"loc": [0.11, 0.11, 0], "dir": [0, 0, -1, "ccw"], "propsize": 5}, + {"loc": [-0.11, 0.11, 0], "dir": [0, 0, -1, "cw"], "propsize": 5}, + {"loc": [-0.11, -0.11, 0], "dir": [0, 0, -1, "ccw"], "propsize": 5}, + {"loc": [0.11, -0.11, 0], "dir": [0, 0, -1, "cw"], "propsize": 5} + ] + drone = DroneSimulator(propellers=propellers) + """ + + if propellers is None: + propellers = create_standard_propeller_config("quad", arm_length=0.11, prop_size=2) + + self.config = DroneConfiguration(propellers) + + # Decorative — kept for API compatibility with consumers that read + # them (e.g., scripts using get_params for the legacy controller). + # The dynamics_func uses `self.params` (per-motor coefficients) instead. + self.Bf, self.Bm = self.config.get_allocation_matrices() + self.num_motors = self.config.num_motors + self.mass = self.config.mass + self.inertia = self.config.inertia_matrix + self.center_of_gravity = self.config.cg + + # All propellers are assumed to share the same prop_size (current + # airevolve convention). For asymmetric prop sizes, derive_reference_params + # would need per-motor extended params. + prop_size = propellers[0].get("propsize", 2) + self.prop_size = prop_size + + self.params = derive_reference_params( + propellers=propellers, + mass=float(self.mass), + inertia=np.asarray(self.inertia), + prop_size=prop_size, + gravity=gravity, + ) + + self.dt = dt + self.g = gravity + + self._setup_dynamics() + + # Full state: [base 12 dims, motor speeds w_1..w_N], all w in [-1, 1]. + # The mid-range value (w=0) corresponds to W = W_MAX_N/2 = 1500 rad/s, + # which is *not* a meaningful "stopped" value. Initialize at the + # idle floor instead: W = w_min, i.e., w_init = 2·w_min/W_MAX_N - 1. + self._w_init = 2.0 * self.params["w_min"] / (W_MAX_N - W_MIN_N) - 1.0 + self.state = np.zeros(12 + self.num_motors, dtype=np.float64) + self.state[12:12 + self.num_motors] = self._w_init + # Action: u_i in [-1, 1]. + self.actions = np.zeros(self.num_motors, dtype=np.float64) + # Legacy alias kept for API compatibility (interpreted as action). + self.motor_commands = self.actions + + self.time_history = [] + self.state_history = [] + self.control_history = [] + + @classmethod + def create_standard_drone(cls, drone_type="quad", arm_length=0.11, prop_size=2, **kwargs): + """ + Create standard drone configuration. + + Args: + drone_type (str): Type of drone ('quad', 'hex', 'tri', 'octo') + arm_length (float): Length of drone arms in meters + prop_size (int): Propeller size in inches (4-8) + **kwargs: Additional arguments for DroneSimulator + + Returns: + DroneSimulator: Configured drone simulator + """ + propellers = create_standard_propeller_config(drone_type, arm_length, prop_size) + return cls(propellers=propellers, **kwargs) + + def _setup_dynamics(self): + """Build the lambdified reference-form dynamics function. + + Mirrors `experimentation/reference_drone_sim.py:_build_dynamics_func` + but generalized to N motors via `self.params` (per-motor signed + coefficients computed by `derive_reference_params`). Per-step parity + against the reference for the canonical 4-motor 2-inch quad is + verified by `unit_tests/test_dynamics_parity.py`. + + The lambdified function has signature + `(full_state[12+N], action[N]) → full_state_dot[12+N]`. Motor model + (sqrt-poly mapping U → Wc, then first-order lag dW = (Wc-W)/tau) is + baked in. F and M are treated as accelerations directly — mass and + inertia are absorbed into the per-motor coefficients. + """ + n = self.num_motors + + # Base state symbols (12 dims). + base_state_syms = symbols('x y z v_x v_y v_z phi theta psi p q r') + x, y, z, vx, vy, vz, phi, theta, psi, p, q, r = base_state_syms + # Motor state symbols (N dims). + motor_state_syms = list(symbols(f'w_1:{n + 1}')) + full_state_syms = list(base_state_syms) + motor_state_syms + # Control (action) symbols (N dims). + control_syms = list(symbols(f'u_1:{n + 1}')) + + # Rotation matrix (body → world). + Rx = Matrix([[1, 0, 0], [0, cos(phi), -sin(phi)], [0, sin(phi), cos(phi)]]) + Ry = Matrix([[cos(theta), 0, sin(theta)], [0, 1, 0], [-sin(theta), 0, cos(theta)]]) + Rz = Matrix([[cos(psi), -sin(psi), 0], [sin(psi), cos(psi), 0], [0, 0, 1]]) + R = Rz * Ry * Rx + + # Body-frame velocity (drag computed in body frame). + vbx, vby, _vbz = R.T @ Matrix([vx, vy, vz]) + + # Unnormalize motor speed: w in [-1, 1] → W in [W_MIN_N, W_MAX_N] rad/s. + # W_MAX_N=3000 is independent of the physical w_max — intentional in the + # reference; state may exceed [-1, 1] under hard throttle (transient). + W = [(w_i + 1) / 2 * (W_MAX_N - W_MIN_N) + W_MIN_N for w_i in motor_state_syms] + # Action: u in [-1, 1] → U in [0, 1]. + U = [(u_i + 1) / 2 for u_i in control_syms] + + p_dict = self.params + k_w = p_dict["k_w"] + k_x = p_dict["k_x"] + k_y = p_dict["k_y"] + k_p_signed = p_dict["k_p_signed"] + k_q_signed = p_dict["k_q_signed"] + k_r_signed = p_dict["k_r_signed"] + k_r_react_signed = p_dict["k_r_react_signed"] + tau = p_dict["tau"] + k = p_dict["k"] + w_min = p_dict["w_min"] + w_max = p_dict["w_max"] + + # Motor command: action U → target speed Wc via sqrt-polynomial. + Wc = [(w_max - w_min) * sqrt(k * U_i**2 + (1 - k) * U_i) + w_min for U_i in U] + # First-order lag. + d_W = [(Wc_i - W_i) / tau for Wc_i, W_i in zip(Wc, W)] + # Convert dW (rad/s²) back to normalized derivative (1/s). + d_w = [d_W_i / (W_MAX_N - W_MIN_N) * 2 for d_W_i in d_W] + + # Forces (treated as accelerations directly — mass implicit in k_w). + sum_W = sum(W) + sum_W2 = sum(W_i**2 for W_i in W) + T = -k_w * sum_W2 + Dx = -k_x * vbx * sum_W + Dy = -k_y * vby * sum_W + + # Moments (treated as angular accelerations directly — inertia + # absorbed into k_p/k_q/k_r). Signs are baked into the per-motor + # coefficients by derive_reference_params (so the symbolic build + # is morphology-agnostic). + Mx = sum(k_p_signed[i] * W[i]**2 for i in range(n)) + My = sum(k_q_signed[i] * W[i]**2 for i in range(n)) + Mz = ( + sum(k_r_signed[i] * W[i] for i in range(n)) + + sum(k_r_react_signed[i] * d_W[i] for i in range(n)) + ) + + # Translational kinematics. + d_x = vx + d_y = vy + d_z = vz + + # Translational dynamics: gravity + body-frame forces rotated to world. + accel = Matrix([0, 0, self.g]) + R @ Matrix([Dx, Dy, T]) + d_vx, d_vy, d_vz = accel + + # Euler-angle kinematics (singular at theta=±π/2; reset envs guard against this). + d_phi = p + q * sin(phi) * tan(theta) + r * cos(phi) * tan(theta) + d_theta = q * cos(phi) - r * sin(phi) + d_psi = q * sin(phi) / cos(theta) + r * cos(phi) / cos(theta) + + # Rotational dynamics — direct, no inertia inversion. + d_p = Mx + d_q = My + d_r = Mz + + state_dot = [ + d_x, d_y, d_z, + d_vx, d_vy, d_vz, + d_phi, d_theta, d_psi, + d_p, d_q, d_r, + ] + d_w # length 12 + n + + self.dynamics_func = lambdify( + (Array(full_state_syms), Array(control_syms)), + Array(state_dot), + 'numpy', + ) + + def get_configuration_info(self): + """ + Get comprehensive drone configuration information. + + Returns: + dict: Complete configuration including physical properties and capabilities + """ + info = self.config.get_physical_properties() + info.update(self.config.get_motor_configuration_info()) + info['propeller_configuration'] = self.config.propellers + return info + + def get_propeller_info(self): + """ + Get propeller configuration details. + + Returns: + list: List of propeller specifications + """ + return [prop.copy() for prop in self.config.propellers] + + def set_state(self, position=None, velocity=None, attitude=None, angular_velocity=None): + """ + Set drone state. + + Args: + position: [x, y, z] in world frame + velocity: [vx, vy, vz] in world frame + attitude: [phi, theta, psi] (roll, pitch, yaw) in radians + angular_velocity: [p, q, r] in body frame + """ + if position is not None: + self.state[0:3] = position + if velocity is not None: + self.state[3:6] = velocity + if attitude is not None: + self.state[6:9] = attitude + if angular_velocity is not None: + self.state[9:12] = angular_velocity + + def get_state(self): + """Get current state as dictionary.""" + return { + 'position': self.state[0:3].copy(), + 'velocity': self.state[3:6].copy(), + 'attitude': self.state[6:9].copy(), + 'angular_velocity': self.state[9:12].copy(), + 'time': len(self.time_history) * self.dt + } + + def set_motor_commands(self, commands): + """ + Set actions (motor inputs in [-1, 1]). + + Args: + commands: Array of actions in range [-1, 1]. Legacy callers + passing [0, 1] will get clipped to [-1, 1] but should migrate + to the new range — the env layer (DroneGateEnv) maps actions + in [-1, 1] directly into dynamics_func. + """ + self.actions = np.clip(commands, -1, 1) + self.motor_commands = self.actions + + def step(self, motor_commands=None): + """ + Advance simulation by one time step using RK4 integration on the + full 12+N state. The dynamics_func handles the motor model + internally; pass actions in [-1, 1]. + + Args: + motor_commands: Optional actions for this step (in [-1, 1]). + """ + if motor_commands is not None: + self.set_motor_commands(motor_commands) + + with np.errstate(all='ignore'): + k1 = self.dt * np.asarray(self.dynamics_func(self.state, self.actions)) + k2 = self.dt * np.asarray(self.dynamics_func(self.state + 0.5 * k1, self.actions)) + k3 = self.dt * np.asarray(self.dynamics_func(self.state + 0.5 * k2, self.actions)) + k4 = self.dt * np.asarray(self.dynamics_func(self.state + k3, self.actions)) + self.state = self.state + (k1 + 2*k2 + 2*k3 + k4) / 6.0 + + # Detect numerical divergence (e.g. Euler angle singularity at ±90° pitch) + if np.any(np.isnan(self.state)) or np.any(np.isinf(self.state)): + raise RuntimeError("Numerical divergence in drone state (likely Euler angle singularity)") + + self.time_history.append(len(self.time_history) * self.dt) + self.state_history.append(self.state.copy()) + self.control_history.append(self.actions.copy()) + + return self.get_state() + + def simulate(self, time_span, control_function=None): + """ + Run simulation for specified time span. + + Args: + time_span: Total simulation time + control_function: Function that takes (time, state) and returns motor commands + """ + num_steps = int(time_span / self.dt) + + for i in range(num_steps): + current_time = i * self.dt + current_state = self.get_state() + + if control_function is not None: + commands = control_function(current_time, current_state) + self.step(commands) + else: + self.step() + + def reset(self): + """Reset simulation to initial conditions.""" + self.state = np.zeros(12 + self.num_motors) + self.state[12:12 + self.num_motors] = self._w_init + self.actions = np.zeros(self.num_motors) + self.motor_commands = self.actions + self.time_history = [] + self.state_history = [] + self.control_history = [] + + def _get_actual_motor_speeds(self): + """Convert normalized motor speeds (in self.state[12:]) to rad/s.""" + motor_speeds = np.zeros(max(4, self.num_motors)) + if len(self.state) >= 12 + self.num_motors: + w_norm = self.state[12:12 + self.num_motors] + for i in range(self.num_motors): + # W = (w + 1) / 2 * (W_MAX_N - W_MIN_N) + W_MIN_N + motor_speeds[i] = (w_norm[i] + 1) / 2 * (W_MAX_N - W_MIN_N) + W_MIN_N + return motor_speeds[:4] + + def get_params(self): + """Get parameters in format compatible with existing controller framework.""" + Bm_corrected = self.Bm.copy() + A_control = np.vstack([-self.Bf[2:3, :], Bm_corrected]) + mixer_fm = A_control + first_prop = self.config.propellers[0] + k_f, k_m = first_prop["constants"] + w_max = first_prop["wmax"] + hover_thrust_per_motor = (self.mass * self.g) / self.num_motors + w_hover = np.sqrt(hover_thrust_per_motor / k_f) + + return { + "mB": self.mass, "g": self.g, "IB": self.inertia, "invI": np.linalg.inv(self.inertia), + "dxm": np.mean([abs(p["loc"][0]) for p in self.config.propellers if p["loc"][0] != 0]), + "dym": np.mean([abs(p["loc"][1]) for p in self.config.propellers if p["loc"][1] != 0]), + "dzm": 0.05, "kTh": k_f, "kTo": k_m, "w_hover": w_hover, "thr_hover": hover_thrust_per_motor, + "mixerFM": mixer_fm, "mixerFMinv": np.linalg.pinv(mixer_fm), + "minThr": 0.1 * self.num_motors, "maxThr": k_f * w_max**2 * self.num_motors, + "minWmotor": 75, "maxWmotor": w_max, + # Read tau from the reference-form params (set per prop in propeller_data.py). + # The pre-migration value was hardcoded 0.015s; reference-form is 0.04s. + "tau": float(self.params["tau"]), "kp": 1.0, "damp": 1.0, + "motorc1": 8.49, "motorc0": 74.7, "motordeadband": 1, "Cd": 0.1, "IRzz": 2.7e-5, + "useIntergral": False, "FF": (w_hover - 74.7) / 8.49 + } + + def get_drone_state(self): + """Get state in format compatible with existing controller interfaces.""" + phi, theta, psi = self.state[6:9] + cy, sy = np.cos(psi * 0.5), np.sin(psi * 0.5) + cp, sp = np.cos(theta * 0.5), np.sin(theta * 0.5) + cr, sr = np.cos(phi * 0.5), np.sin(phi * 0.5) + quat = np.array([cr*cp*cy + sr*sp*sy, sr*cp*cy - cr*sp*sy, cr*sp*cy + sr*cp*sy, cr*cp*sy - sr*sp*cy]) + + actual_speeds = self._get_actual_motor_speeds() + extended_state = np.zeros(21) + extended_state[0:3], extended_state[3:7] = self.state[0:3], quat + extended_state[7:10], extended_state[10:13] = self.state[3:6], self.state[9:12] + for i in range(min(4, self.num_motors)): + extended_state[13 + i*2] = actual_speeds[i] + + return { + 'state': extended_state, 'pos': self.state[0:3], 'vel': self.state[3:6], 'quat': quat, + 'omega': self.state[9:12], 'euler': np.array([0, 0, 0]), 'wMotor': actual_speeds, + 'vel_dot': np.zeros(3), 'omega_dot': np.zeros(3), 'acc': np.zeros(3), + 'thr': self.actions[:4] if self.num_motors >= 4 else np.pad(self.actions, (0, 4-self.num_motors)), + 'tor': self.actions[:4] if self.num_motors >= 4 else np.pad(self.actions, (0, 4-self.num_motors)), + 'dcm': np.eye(3) + } + + def update_from_controller(self, t, Ts, w_cmd, wind=None): + """Update simulation using commands from controller framework. + + Maps the controller's commanded steady-state motor speeds (rad/s) + into the action range [-1, 1] by inverting the reference-form + sqrt-poly motor model + + Wc = (w_max - w_min) · sqrt(k · U² + (1 - k) · U) + w_min + + for U ∈ [0, 1], then `action = 2 · U - 1`. Without this inverse, + a hover-throttle w_cmd ≈ W_hover under-commands by ~2× because of + the sqrt curvature and non-zero w_min idle floor. + """ + full_w_cmd = self.w_cmd_full if hasattr(self, 'w_cmd_full') and self.w_cmd_full is not None else w_cmd + w_min = self.params["w_min"] + k = self.params["k"] + propeller_w_max = [prop["wmax"] for prop in self.config.propellers] + actions = np.zeros(self.num_motors) + for i in range(min(len(full_w_cmd), self.num_motors)): + w_max = propeller_w_max[i] if i < len(propeller_w_max) else propeller_w_max[0] + actions[i] = 2.0 * _invert_sqrt_poly(full_w_cmd[i], w_max, w_min, k) - 1.0 + self.step(actions) + return t + Ts + + +# Factory functions for easy drone creation +def create_quadrotor(arm_length=0.11, prop_size=2, **kwargs): + """Create standard quadrotor configuration.""" + return DroneSimulator.create_standard_drone("quad", arm_length, prop_size, **kwargs) + +def create_hexarotor(arm_length=0.10, prop_size=4, **kwargs): + """Create standard hexarotor configuration.""" + return DroneSimulator.create_standard_drone("hex", arm_length, prop_size, **kwargs) + +def create_tricopter(arm_length=0.12, prop_size=6, **kwargs): + """Create standard tricopter configuration.""" + return DroneSimulator.create_standard_drone("tri", arm_length, prop_size, **kwargs) + +def create_octorotor(arm_length=0.09, prop_size=4, **kwargs): + """Create standard octorotor configuration.""" + return DroneSimulator.create_standard_drone("octo", arm_length, prop_size, **kwargs) diff --git a/src/ariel/simulation/drone/dynamics_params.py b/src/ariel/simulation/drone/dynamics_params.py new file mode 100644 index 000000000..fcf4df20d --- /dev/null +++ b/src/ariel/simulation/drone/dynamics_params.py @@ -0,0 +1,149 @@ +"""Reference-form dynamics parameter derivation. + +Maps an airevolve propeller configuration into the 22-parameter reference +dynamics form (matching optimal_quad_control_RL/randomization.py:5-10's +`params_5inch` schema, but with per-motor coefficients computed from the +actual airevolve morphology rather than sysid'd from flight data). + +This is the airevolve runtime equivalent of +`experimentation/reference_drone_sim.py:derive_params_2inch_from_airevolve`. +The runtime version generalizes to any prop size via +`get_extended_prop_params` (Phase 1) and to any 4-motor symmetric or +asymmetric quad. Generalization to N motors arrives in Phase 4. + +Sign convention: we bake position and spin signs into the per-motor +coefficients themselves, so the downstream symbolic build is +morphology-agnostic. The reference's `_build_dynamics_func` hardcodes signs +for a specific motor layout (see reference_drone_sim.py:280-291); our +runtime pulls those signs out of the formula and into the parameter dict. + +* `k_p_signed[i] = -y_i · k_f / Ixx` so that `Mx = sum_i k_p_signed[i] · W_i²`. +* `k_q_signed[i] = +x_i · k_f / Iyy` so that `My = sum_i k_q_signed[i] · W_i²`. +* `k_r_signed[i] = spin_i · 2 · k_m · W_hover / Izz` for the linear-W yaw term. +* `k_r_react_signed[i] = spin_i · k_r_react_borrow` for the dW yaw term. + +Where spin_i = +1 for "ccw", -1 for "cw" (the convention is verified via +the per-step parity test in unit_tests/test_dynamics_parity.py). + +See `experimentation/RUNTIME_DYNAMICS_MIGRATION.md` Phase 2.1. +""" +from __future__ import annotations + +import numpy as np + +from .propeller_data import get_extended_prop_params + + +def _spin_sign(rotation: str) -> float: + """+1 for ccw, -1 for cw. Consistent with the reference's convention + (verified against optimal_quad_control_RL via the V0 parity test).""" + if rotation == "ccw": + return 1.0 + if rotation == "cw": + return -1.0 + raise ValueError(f"unknown rotation direction: {rotation!r}") + + +def derive_reference_params( + propellers: list, + mass: float, + inertia: np.ndarray, + prop_size, + gravity: float = 9.81, +) -> dict: + """Derive a reference-form parameter dict for an airevolve drone config. + + Args: + propellers: list of propeller dicts (`loc`, `dir`, `propsize`). + mass: total drone mass in kg (from DroneConfiguration.mass). + inertia: 3x3 inertia matrix in body frame. + prop_size: prop size for fetching aerodynamic constants + (k_drag, k_r_react, k, w_min). All propellers assumed same size. + gravity: m/s². + + Returns: + dict with keys: + n_motors (int): number of motors + k_w (float): thrust acceleration coefficient (a_z = -k_w · sum(W²)) + k_x, k_y (float): body-frame drag accel coefficients (single values, all motors) + k_p_signed (list[float]): per-motor roll-moment coefficient (signed) + k_q_signed (list[float]): per-motor pitch-moment coefficient (signed) + k_r_signed (list[float]): per-motor yaw-moment coefficient (linear W, signed) + k_r_react_signed (list[float]): per-motor yaw-moment from dW (signed) + tau, k, w_min, w_max (float): motor model parameters + + Notes: + * Asymmetric morphologies are supported via per-motor `k_p_i, k_q_i` + computed from the actual `loc`. Spin asymmetry is supported via + per-motor `k_r_signed`. + * `k_x, k_y, k, w_min, k_r_react, tau` are single per-prop-size values + (borrowed from the closest sysid set in propeller_data.py). Per-motor + variation in these is a Phase 6 polish item. + * `k_r_signed` is a *linearization* at hover throttle. For hover, + `dMz/dW ≈ 2·k_m·W_hover`. Away from hover this loses fidelity; the + reference accepts this as a sysid-level approximation. + """ + n = len(propellers) + if n == 0: + raise ValueError("derive_reference_params: no propellers in config") + + extended = get_extended_prop_params(prop_size) + k_f, k_m = extended["constants"] + w_max = float(extended["wmax"]) + + Ixx = float(inertia[0, 0]) + Iyy = float(inertia[1, 1]) + Izz = float(inertia[2, 2]) + m = float(mass) + + # Hover motor speed (per motor) for linearizing the yaw torque term. + F_hover_per_motor = m * gravity / n + if F_hover_per_motor <= 0 or k_f <= 0: + raise ValueError( + f"derive_reference_params: invalid hover-thrust calc " + f"(F_hover={F_hover_per_motor}, k_f={k_f})" + ) + W_hover = float(np.sqrt(F_hover_per_motor / k_f)) + + k_p_signed = [] + k_q_signed = [] + k_r_signed = [] + k_r_react_signed = [] + for prop in propellers: + x_i = float(prop["loc"][0]) + y_i = float(prop["loc"][1]) + spin = _spin_sign(prop["dir"][3]) + + # M_x = sum_i (-y_i · F_z_i) / Ixx = sum_i (-y_i · k_f · W_i²) / Ixx + k_p_signed.append(-y_i * k_f / Ixx) + # M_y = sum_i (+x_i · F_z_i) / Iyy = sum_i (+x_i · k_f · W_i²) / Iyy + k_q_signed.append(+x_i * k_f / Iyy) + # M_z (steady, linearized at hover): spin_i · 2 · k_m · W_hover / Izz + k_r_signed.append(spin * 2.0 * k_m * W_hover / Izz) + # M_z (motor-acceleration reaction): spin_i · k_r_react + k_r_react_signed.append(spin * float(extended["k_r_react"])) + + return { + "n_motors": n, + "k_w": k_f / m, + "k_x": float(extended["k_x_drag"]), + "k_y": float(extended["k_y_drag"]), + "k_p_signed": k_p_signed, + "k_q_signed": k_q_signed, + "k_r_signed": k_r_signed, + "k_r_react_signed": k_r_react_signed, + "tau": float(extended["tau"]), + "k": float(extended["k"]), + "w_min": float(extended["w_min"]), + "w_max": w_max, + } + + +# Reference's normalization constants (verified against +# optimal_quad_control_RL/quad_race_env.py:41-42 via the V0 parity test). +# These are intentionally independent of physical w_max; the motor state +# `w_i ∈ [-1, 1]` represents `W_i ∈ [W_MIN_N, W_MAX_N] = [0, 3000]` rad/s. +# At full throttle, Wc may exceed W_MAX_N; the state can go outside [-1, 1] +# during transients. This is intentional in the reference. +W_MIN_N = 0.0 +W_MAX_N = 3000.0 diff --git a/src/ariel/simulation/drone/propeller_data.py b/src/ariel/simulation/drone/propeller_data.py new file mode 100644 index 000000000..9ea0006e6 --- /dev/null +++ b/src/ariel/simulation/drone/propeller_data.py @@ -0,0 +1,276 @@ +""" +Propeller Library and Physical Constants + +This module contains propeller specifications including force/moment constants, +maximum RPM, and mass properties for different propeller sizes. + +Data extracted from drone-hover package for integration with geometric control framework. +""" + +import numpy as np + +# Propeller library with specifications for different sizes. +# +# Reference-form physics constants (w_min, k, k_r_react, k_drag_x_norm, +# k_drag_y_norm, tau) are sourced from optimal_quad_control_RL/randomization.py +# (params_5inch and params_3inch — the only two sysid'd sets that exist). +# For prop sizes without a real sysid, values are borrowed from the closest +# sysid'd entry (3-inch for prop2/prop4, 5-inch for prop6/prop7/prop8/matched); +# this is reasonable because these constants are physics-of-the-rotor (mostly +# aerodynamic), not whole-drone sysid. Reactions to migration: see +# experimentation/RUNTIME_DYNAMICS_MIGRATION.md Phase 1. +PROPELLER_LIBRARY = { + "prop2": { + "constants": [8.12e-08, 6.40e-10], # [k_f, k_m] force and moment constants + "wmax": 5000, # Maximum angular velocity (rad/s) + "mass": 0.0046, # Propeller + motor mass (kg) + # Borrowed from params_3inch (closest sysid set; prop2 has no real sysid). + "w_min": 305.40, + "k": 0.84, + "k_r_react": 1.14e-03, + "k_x_drag": 3.36e-05, + "k_y_drag": 3.73e-05, + "tau": 0.04, + }, + "prop3": { + # New entry: 3-inch sysid'd from optimal_quad_control_RL/randomization.py:29-35. + # k_f / k_m / wmax derived from params_3inch: k_w = k_f/m → k_f = k_w·m; + # m chosen as 0.3 kg (typical 3" build; mass ↑ slightly compared to prop2's 0.0046 + # because prop3 is bigger). For exact parity with params_3inch, see Phase 3.2 of + # the migration doc — may need a `prop3_real` entry that derives [k_f, k_m, wmax] + # to exactly reproduce params_3inch's k_w/k_r1..4. + "constants": [1.80e-07, 2.89e-09], # [k_f, k_m] (k_f = k_w·m_canonical, rough) + "wmax": 4887, + "mass": 0.012, + "w_min": 305.40, + "k": 0.84, + "k_r_react": 1.14e-03, + "k_x_drag": 3.36e-05, + "k_y_drag": 3.73e-05, + "tau": 0.04, + }, + "prop4": { + "constants": [7.24e-07, 8.20e-09], # [k_f, k_m] force and moment constants + "wmax": 3927, # Maximum angular velocity (rad/s) + "mass": 0.018, # Propeller + motor mass (kg) + # Borrowed from params_3inch (closest sysid set). + "w_min": 305.40, + "k": 0.84, + "k_r_react": 1.14e-03, + "k_x_drag": 3.36e-05, + "k_y_drag": 3.73e-05, + "tau": 0.04, + }, + "prop5": { + "constants": [1.08e-06, 1.22e-08], + "wmax": 3142, + "mass": 0.0196, + # Sysid: params_5inch from optimal_quad_control_RL/randomization.py:5-10. + "w_min": 238.49, + "k": 0.95, + "k_r_react": 1.97e-03, + "k_x_drag": 4.85e-05, + "k_y_drag": 7.28e-05, + "tau": 0.04, + }, + "prop6": { + "constants": [2.21e-06, 2.74e-08], + "wmax": 2618, + "mass": 0.0252, + # Borrowed from params_5inch (closest sysid set). + "w_min": 238.49, + "k": 0.95, + "k_r_react": 1.97e-03, + "k_x_drag": 4.85e-05, + "k_y_drag": 7.28e-05, + "tau": 0.04, + }, + "prop7": { + "constants": [4.65e-06, 6.62e-08], + "wmax": 2244, + "mass": 0.046, + # Borrowed from params_5inch (closest sysid set). + "w_min": 238.49, + "k": 0.95, + "k_r_react": 1.97e-03, + "k_x_drag": 4.85e-05, + "k_y_drag": 7.28e-05, + "tau": 0.04, + }, + "prop8": { + "constants": [7.60e-06, 1.14e-07], + "wmax": 1963, + "mass": 0.056, + # Borrowed from params_5inch (closest sysid set). + "w_min": 238.49, + "k": 0.95, + "k_r_react": 1.97e-03, + "k_x_drag": 4.85e-05, + "k_y_drag": 7.28e-05, + "tau": 0.04, + }, + "matched": { + "constants": [1.076e-05, 1.61e-07], # Matched to original framework (kTh = 1.076e-5) + "wmax": 1963, + "mass": 0.300, # Increased to match original 1.2kg total mass exactly + # Borrowed from params_5inch (closest sysid set). + "w_min": 238.49, + "k": 0.95, + "k_r_react": 1.97e-03, + "k_x_drag": 4.85e-05, + "k_y_drag": 7.28e-05, + "tau": 0.04, + } +} + +# Physical constants +GRAVITY = 9.81 # m/s^2 + +# Material properties for mass/inertia calculations +# Updated to match drone-hover small drone configuration +CONTROLLER_MASS = 0.0136 # kg, speedybee f405 aio flight controller +BATTERY_MASS = 0.043 # kg, 3s 450mah lipo battery +BEAM_DENSITY = 0.034 # kg/m, carbon fiber tube: 8mm outer diameter, 6mm inner diameter + +def get_propeller_specs(prop_size): + """ + Get propeller specifications for a given size. + + Args: + prop_size (int or str): Propeller size in inches (4-8) or "matched" + + Returns: + dict: Propeller specifications including constants, wmax, and mass + + Raises: + ValueError: If propeller size is not available + """ + if prop_size == "matched": + prop_key = "matched" + else: + prop_key = f"prop{prop_size}" + + if prop_key not in PROPELLER_LIBRARY: + available_sizes = [int(key[4:]) if key.startswith('prop') else key for key in PROPELLER_LIBRARY.keys()] + raise ValueError(f"Propeller size {prop_size} not available. " + f"Available sizes: {available_sizes}") + + return PROPELLER_LIBRARY[prop_key].copy() + +def get_extended_prop_params(prop_size): + """Return all reference-form physics constants for a prop size. + + Returns a dict containing both the original DroneSimulator-consumed + fields (`constants`, `wmax`, `mass`) and the reference-form fields + needed by `derive_reference_params` in dynamics_params.py + (`w_min`, `k`, `k_r_react`, `k_drag_x_norm`, `k_drag_y_norm`, `tau`). + + Args: + prop_size (int or str): Propeller size in inches (2-8) or "matched". + + Returns: + dict: Full extended specification. + """ + return get_propeller_specs(prop_size) + +def validate_propeller_config(props): + """ + Validate propeller configuration format. + + Args: + props (list): List of propeller dictionaries + + Raises: + KeyError: If required keys are missing + ValueError: If values are invalid + """ + required_keys = ["loc", "dir", "propsize"] + + for i, prop in enumerate(props): + # Check required keys + for key in required_keys: + if key not in prop: + raise KeyError(f"'{key}' is missing in propeller {i}") + + # Validate propeller size + if prop["propsize"] not in [2, 3, 4, 5, 6, 7, 8, "matched"]: + raise ValueError(f"Invalid propeller size {prop['propsize']} in propeller {i}. " + f"Available sizes: [2, 3, 4, 5, 6, 7, 8, 'matched']") + + # Validate direction format + if len(prop["dir"]) != 4: + raise ValueError(f"Direction must have 4 elements [x, y, z, rotation] for propeller {i}") + + if prop["dir"][-1] not in ["ccw", "cw"]: + raise ValueError(f"Invalid rotation direction '{prop['dir'][-1]}' for propeller {i}. " + f"Use 'ccw' or 'cw'") + + # Validate location format + if len(prop["loc"]) != 3: + raise ValueError(f"Location must have 3 elements [x, y, z] for propeller {i}") + +def create_standard_propeller_config(config_type, arm_length=0.11, prop_size=2): + """ + Create standard propeller configurations for common drone types. + + Args: + config_type (str): Type of configuration ('quad', 'hex', 'tri', 'octo') + arm_length (float): Length of drone arms in meters + prop_size (int): Propeller size in inches + + Returns: + list: List of propeller dictionaries + """ + if config_type == "quad" or config_type == "quadrotor": + # Standard X configuration quadcopter + return [ + {"loc": [arm_length * np.cos(np.pi/4), arm_length * np.sin(np.pi/4), 0], + "dir": [0, 0, -1, "ccw"], "propsize": prop_size}, + {"loc": [arm_length * np.cos(3*np.pi/4), arm_length * np.sin(3*np.pi/4), 0], + "dir": [0, 0, -1, "cw"], "propsize": prop_size}, + {"loc": [arm_length * np.cos(5*np.pi/4), arm_length * np.sin(5*np.pi/4), 0], + "dir": [0, 0, -1, "ccw"], "propsize": prop_size}, + {"loc": [arm_length * np.cos(7*np.pi/4), arm_length * np.sin(7*np.pi/4), 0], + "dir": [0, 0, -1, "cw"], "propsize": prop_size} + ] + + elif config_type == "hex" or config_type == "hexarotor": + # Standard hexacopter configuration + return [ + {"loc": [arm_length, 0, 0], "dir": [0, 0, -1, "ccw"], "propsize": prop_size}, + {"loc": [arm_length * np.cos(np.pi/3), arm_length * np.sin(np.pi/3), 0], + "dir": [0, 0, -1, "cw"], "propsize": prop_size}, + {"loc": [arm_length * np.cos(2*np.pi/3), arm_length * np.sin(2*np.pi/3), 0], + "dir": [0, 0, -1, "ccw"], "propsize": prop_size}, + {"loc": [arm_length * np.cos(np.pi), arm_length * np.sin(np.pi), 0], + "dir": [0, 0, -1, "cw"], "propsize": prop_size}, + {"loc": [arm_length * np.cos(4*np.pi/3), arm_length * np.sin(4*np.pi/3), 0], + "dir": [0, 0, -1, "ccw"], "propsize": prop_size}, + {"loc": [arm_length * np.cos(5*np.pi/3), arm_length * np.sin(5*np.pi/3), 0], + "dir": [0, 0, -1, "cw"], "propsize": prop_size} + ] + + elif config_type == "tri" or config_type == "tricopter": + # Standard tricopter configuration (no tilt rotor) + return [ + {"loc": [arm_length, 0, 0], "dir": [0, 0, -1, "ccw"], "propsize": prop_size}, + {"loc": [arm_length * np.cos(2*np.pi/3), arm_length * np.sin(2*np.pi/3), 0], + "dir": [0, 0, -1, "cw"], "propsize": prop_size}, + {"loc": [arm_length * np.cos(4*np.pi/3), arm_length * np.sin(4*np.pi/3), 0], + "dir": [0, 0, -1, "ccw"], "propsize": prop_size} + ] + + elif config_type == "octo" or config_type == "octorotor": + # Standard octacopter configuration + angles = [i * np.pi/4 for i in range(8)] + spin_dirs = ["ccw", "cw"] * 4 # Alternating pattern + + return [ + {"loc": [arm_length * np.cos(angle), arm_length * np.sin(angle), 0], + "dir": [0, 0, -1, spin_dir], "propsize": prop_size} + for angle, spin_dir in zip(angles, spin_dirs) + ] + + else: + raise ValueError(f"Unknown configuration type: {config_type}. " + f"Available types: ['quad', 'hex', 'tri', 'octo']") \ No newline at end of file diff --git a/src/ariel/simulation/drone/test_simulation.py b/src/ariel/simulation/drone/test_simulation.py new file mode 100644 index 000000000..43442b38b --- /dev/null +++ b/src/ariel/simulation/drone/test_simulation.py @@ -0,0 +1,12 @@ + + +from drone_simulator import DroneSimulator + +drone = DroneSimulator(propellers=None, dt=0.01, gravity=9.81) + +number_of_steps = 100 + +for i in range(number_of_steps): + drone.step([0.1, 0.1, 0.1, 0.1]) # Step the simulation by 0.01 seconds + state = drone.get_state() + print(f"Step {i+1}, P: {state['position']}, V: {state['velocity']}, O: {state['attitude']}, W: {state['angular_velocity']}") diff --git a/src/ariel/simulation/tasks/drone_gate_env.py b/src/ariel/simulation/tasks/drone_gate_env.py new file mode 100644 index 000000000..27deee1f7 --- /dev/null +++ b/src/ariel/simulation/tasks/drone_gate_env.py @@ -0,0 +1,554 @@ +import torch +import stable_baselines3 +import sys +import numpy as np + +# Device is managed per-instance, not globally. +# Do NOT call torch.set_default_device() here — it is a global side effect +# that interferes with explicit device='cpu' passed to PPO/environments. + +# Efficient vectorized version of the environment +from gymnasium import spaces +from stable_baselines3.common.vec_env import VecEnv + +# Import new simulation API +from ariel.simulation.drone.drone_simulator import DroneSimulator +from ariel.simulation.drone.drone_configuration import DroneConfiguration +from ariel.ec.drone.genome_handlers.mounting_points import ( + generate_disc_mounting_points, assign_nearest_mounting_point +) + +# DEFINE RACE TRACK +r = 1.5 +gate_pos = np.array([ + [ r, -r, -1.5], + [ 0, 0, -1.5], + [-r, r, -1.5], + [ 0, 2*r, -1.5], + [ r, r, -1.5], + [ 0, 0, -1.5], + [-r, -r, -1.5], + [ 0,-2*r, -1.5] +]) +gate_yaw = np.array([1,2,1,0,-1,-2,-1,0])*np.pi/2 +start_pos = gate_pos[0] + np.array([0,-1.,0]) + +class DroneGateEnv(VecEnv): + + metadata = {'render_modes': ['rgb_array', 'human']} + render_mode = 'rgb_array' + + def __init__(self, + num_envs, + propellers=None, + individual=None, + gates_pos=gate_pos, + gate_yaw=gate_yaw, + start_pos=start_pos, + x_bounds=[-5,5], + y_bounds=[-5,5], + z_bounds=[-5,5], + gates_ahead=2, + pause_if_collision=False, + motor_limit=1.0, + initialize_at_random_gates=True, + num_state_history=0, + num_action_history=0, + history_step_size=1, + seed=None, + render_mode=None, + device=None, + dt=0.01, + action_filter_alpha=1.0, + max_steps=1200, + ): + + # Set device + if device is not None: + self.device = device + torch.set_default_device(device) + + self.render_mode = render_mode if render_mode is not None else self.render_mode + + self.x_bounds = x_bounds + self.y_bounds = y_bounds + self.z_bounds = z_bounds + + # set seed + self.seed = seed + if self.seed is not None: + np.random.seed(self.seed) + torch.manual_seed(self.seed) + + # Initialize drone simulator + if propellers is not None: + # Use new API with propeller configuration + self.drone_sim = DroneSimulator(propellers=propellers, dt=dt) + elif individual is not None: + # Convert legacy individual array to propeller configuration + propellers, mountpoints = self._convert_individual_to_propellers(individual) + self.drone_sim = DroneSimulator(propellers=propellers, mountpoints=mountpoints, dt=dt) + else: + # Default quadrotor configuration + self.drone_sim = DroneSimulator.create_standard_drone("quad", dt=dt) + + # Get allocation matrices from the configured simulator + self.Bf, self.Bm = self.drone_sim.config.get_allocation_matrices() + + num_motors = self.drone_sim.num_motors + + # Motor time constant for first-order dynamics (matches reference 5-inch sysid). + self.motor_tau = 0.04 + + # Define the race track + self.start_pos = start_pos.astype(np.float32) + self.gate_pos = gates_pos.astype(np.float32) + self.gate_yaw = gate_yaw.astype(np.float32) + self.num_gates = gates_pos.shape[0] + self.gates_ahead = gates_ahead + + # Pause if collision + self.pause_if_collision = pause_if_collision + + # Motor limit + self.motor_limit = motor_limit + + # Initialize at random gates + self.initialize_at_random_gates = initialize_at_random_gates + + # state, action history + self.num_state_history = num_state_history + self.num_action_history = num_action_history + self.history_step_size = history_step_size + + # Calculate relative gates + # pos,yaw of gate i in reference frame of gate i-1 (assumes a looped track) + self.gate_pos_rel = np.zeros((self.num_gates,3), dtype=np.float32) + self.gate_yaw_rel = np.zeros(self.num_gates, dtype=np.float32) + for i in range(0,self.num_gates): + self.gate_pos_rel[i] = self.gate_pos[i] - self.gate_pos[i-1] + # Rotation matrix + R = np.array([ + [np.cos(self.gate_yaw[i-1]), np.sin(self.gate_yaw[i-1])], + [-np.sin(self.gate_yaw[i-1]), np.cos(self.gate_yaw[i-1])] + ]) + self.gate_pos_rel[i,0:2] = R@self.gate_pos_rel[i,0:2] + self.gate_yaw_rel[i] = self.gate_yaw[i] - self.gate_yaw[i-1] + # wrap yaw + self.gate_yaw_rel[i] %= 2*np.pi + if self.gate_yaw_rel[i] > np.pi: + self.gate_yaw_rel[i] -= 2*np.pi + elif self.gate_yaw_rel[i] < -np.pi: + self.gate_yaw_rel[i] += 2*np.pi + + # Define the target gate for each environment + self.target_gates = np.zeros(num_envs, dtype=int) + + # Initialize number of gates passed + self.num_gates_passed = np.zeros(num_envs, dtype=int) + + # action space: [cmd1, cmd2, cmd3, cmd4] + # U = (u+1)/2 --> u = 2U-1 + u_lim = 2*self.motor_limit-1 + action_space = spaces.Box(low=-1, high=u_lim, shape=(num_motors,), dtype=np.float64) + + # observation space: pos[G], vel[G], att[eulerB->G], rates[B], rpms, future_gates[G], future_gate_dirs[G] + # [G] = reference frame aligned with target gate + # [B] = body frame + self.state_len = 12+num_motors+4*self.gates_ahead+4*self.num_action_history + self.obs_len = self.state_len*(1+self.num_state_history) + observation_space = spaces.Box( + low = np.array([-np.inf]*self.obs_len), + high = np.array([ np.inf]*self.obs_len), dtype=np.float64 + ) + + # Initialize the VecEnv + VecEnv.__init__(self, num_envs, observation_space, action_space) + + # world state: pos[W], vel[W], att[eulerB->W], rates[B], rpms + self.world_states = np.zeros((num_envs,12+num_motors), dtype=np.float32) + # observation state + self.states = np.zeros((num_envs,self.obs_len), dtype=np.float32) + # state history tracking + num_hist = 40 + self.state_hist = np.zeros((num_envs,num_hist,self.state_len), dtype=np.float32) + # action history tracking + self.action_hist = np.zeros((num_envs,num_hist,num_motors), dtype=np.float32) + + # Define any other environment-specific parameters + self.max_steps = int(max_steps) # Maximum number of steps in an episode + self.dt = np.float32(dt) # Time step duration + + # Action low-pass filter (one-pole IIR) modeling a flight controller's + # RC-smoothing / setpoint-shaping stage. alpha=1.0 = pass-through (no + # filter, default for backward compat). alpha<1.0 smooths actions: + # filtered_a = alpha · raw_a + (1 - alpha) · prev_filtered_a + # At dt=0.01 (100 Hz), alpha=0.3 corresponds to roughly a 6 Hz cutoff, + # alpha=0.5 → ~16 Hz, alpha=1.0 → no smoothing (raw policy output). + # Real Betaflight RC smoothing typically targets 20-30 Hz cutoff. + self.action_filter_alpha = float(action_filter_alpha) + self.filtered_actions = np.zeros((num_envs, num_motors), dtype=np.float32) + + self.step_counts = np.zeros(num_envs, dtype=int) + self.actions = np.zeros((num_envs,num_motors), dtype=np.float32) + self.prev_actions = np.zeros((num_envs,num_motors), dtype=np.float32) + self.dones = np.zeros(num_envs, dtype=bool) + self.final_gate_passed = np.zeros(num_envs, dtype=bool) + + self.update_states = self.update_states_gate + + self.pause = False + + self.num_motors = num_motors + + def _convert_individual_to_propellers(self, individual): + """ + Convert legacy individual array to propeller configuration. + + Uses the same NED coordinate conventions as get_sim() in hovering_info.py: + - Position: spherical → ENU cartesian → NED via (x,y,z) → (y,x,-z) + - Thrust: orientation_to_unit_vector(0, pitch, yaw) with internal ENU→NED transform + + Returns: + (propellers, mounting_points): Propeller configs and disc mounting points, + matching the conventions used by get_sim() in hovering_info.py. + """ + # Remove NaN rows + valid_rows = ~np.isnan(individual).any(axis=1) + individual_clean = individual[valid_rows] + + propellers = [] + propeller_positions = [] + for row in individual_clean: + magnitude, arm_yaw, arm_pitch, mot_pitch, mot_yaw, direction = row + + # Position: spherical to ENU cartesian + enu_x = magnitude * np.cos(arm_pitch) * np.cos(arm_yaw) + enu_y = magnitude * np.cos(arm_pitch) * np.sin(arm_yaw) + enu_z = magnitude * np.sin(arm_pitch) + + # ENU to NED: (x, y, z) → (y, x, -z) + x, y, z = enu_y, enu_x, -enu_z + + # Thrust direction in NED frame + # Matches orientation_to_unit_vector(0, mot_pitch, mot_yaw) from hovering_info.py: + # R = ENU_to_NED @ euler_R(0, pitch, yaw); thrust = R @ [0, 0, -1] + sp, cp = np.sin(mot_pitch), np.cos(mot_pitch) + sy, cy = np.sin(mot_yaw), np.cos(mot_yaw) + thrust_x = -sy * sp + thrust_y = -cy * sp + thrust_z = cp + + # Rotation direction + rotation = "cw" if direction > 0.5 else "ccw" + + propellers.append({ + "loc": [x, y, z], + "dir": [thrust_x, thrust_y, thrust_z, rotation], + "propsize": 2 # Default prop size + }) + propeller_positions.append([x, y, z]) + + # Compute mounting points matching get_sim() in hovering_info.py + disc_mounting_points = generate_disc_mounting_points(num_points=8, diameter=0.060) + mounting_points = assign_nearest_mounting_point(propeller_positions, disc_mounting_points) + + return propellers, mounting_points + + def reset_seed(self): + if self.seed is not None: + np.random.seed(self.seed) + torch.manual_seed(self.seed) + + def update_states_gate(self): + # Transform pos and vel in gate frame + gate_pos = self.gate_pos[self.target_gates%self.num_gates] + gate_yaw = self.gate_yaw[self.target_gates%self.num_gates] + + # Rotation matrix from world frame to gate frame + R = np.array([ + [np.cos(gate_yaw), np.sin(gate_yaw)], + [-np.sin(gate_yaw), np.cos(gate_yaw)] + ]).transpose((2,1,0)) + + # new state array to prevent the weird bug related to indexing ([:] syntax) + new_states = np.zeros((self.num_envs,self.state_len), dtype=np.float32) + + # Update positions + pos_W = self.world_states[:,0:3] + pos_G = (pos_W[:,np.newaxis,0:2] - gate_pos[:,np.newaxis,0:2]) @ R + new_states[:,0:2] = pos_G[:,0,:] + new_states[:,2] = pos_W[:,2] - gate_pos[:,2] + + # Update velocities + vel_W = self.world_states[:,3:6] + vel_G = (vel_W[:,np.newaxis,0:2]) @ R + new_states[:,3:5] = vel_G[:,0,:] + new_states[:,5] = vel_W[:,2] + + # Update attitude + new_states[:,6:8] = self.world_states[:,6:8] + yaw = self.world_states[:,8] - gate_yaw + yaw %= 2*np.pi + yaw[yaw > np.pi] -= 2*np.pi + yaw[yaw < -np.pi] += 2*np.pi + new_states[:,8] = yaw + + # Update rates + new_states[:,9:12] = self.world_states[:,9:12] + + # Update rpms + new_states[:,12:12+self.num_motors] = self.world_states[:,12:12+self.num_motors] + + # Update future gates relative to current gate + for i in range(self.gates_ahead): + indices = (self.target_gates+i+1) + # loop when out of bounds + indices = indices % self.num_gates + valid = indices < self.num_gates + new_states[valid,12+self.num_motors+4*i:12+self.num_motors+4*i+3] = self.gate_pos_rel[indices[valid]] + new_states[valid,12+self.num_motors+4*i+3] = self.gate_yaw_rel[indices[valid]] + + # update action history + self.action_hist = np.roll(self.action_hist, 1, axis=1) + self.action_hist[:,0] = self.actions + + for i in range(self.num_action_history): + new_states[:,12+self.num_motors+4*self.gates_ahead+4*i:12+self.num_motors+4*self.gates_ahead+4*i+4] = self.action_hist[:,(i+1)*self.history_step_size-1] + + # update state history + self.state_hist = np.roll(self.state_hist, 1, axis=1) + self.state_hist[:,0] = new_states + + # stack history up to self.num_state_history + self.states = self.state_hist[:,0:(self.num_state_history+1)*self.history_step_size:self.history_step_size].reshape((self.num_envs,-1)) + + def reset_(self, dones): + num_reset = dones.sum() + # Track number of gates passed + self.num_gates_passed[dones] = np.zeros(num_reset) + + if self.initialize_at_random_gates: + # set target gates to random gates + self.target_gates[dones] = np.random.randint(0,self.num_gates, size=num_reset) + # set position to 1m in front of the target gate + # gate_pos + [cos(gate_yaw), sin(gate_yaw), 0] + pos = self.gate_pos[self.target_gates[dones]%self.num_gates] + yaw = self.gate_yaw[self.target_gates[dones]%self.num_gates] + + pos = pos - np.array([np.cos(yaw), np.sin(yaw), np.zeros_like(yaw)]).T + x0, y0, z0 = pos.T + + vx0 = np.random.uniform(-0.5,0.5, size=(num_reset,)) + vy0 = np.random.uniform(-0.5,0.5, size=(num_reset,)) + vz0 = np.random.uniform(-0.5,0.5, size=(num_reset,)) + + phi0 = np.random.uniform(-np.pi/9,np.pi/9, size=(num_reset,)) + theta0 = np.random.uniform(-np.pi/9,np.pi/9, size=(num_reset,)) + psi0 = np.random.uniform(-np.pi,np.pi, size=(num_reset,)) + + p0 = np.random.uniform(-0.1,0.1, size=(num_reset,)) + q0 = np.random.uniform(-0.1,0.1, size=(num_reset,)) + r0 = np.random.uniform(-0.1,0.1, size=(num_reset,)) + + # Motor speeds w_i are in [-1, 1] (reference-form normalization; + # see DroneSimulator state convention). Was [0, 1] under the old + # dynamics — see Phase 2.3 in RUNTIME_DYNAMICS_MIGRATION.md. + w0 = np.random.uniform(-1, 1, size=(num_reset,self.num_motors)) + + else: # always start at the first gate, fixed orientation + # set target gates to 0 + self.target_gates[dones] = np.zeros(num_reset, dtype=int) + # use start_pos + x0 = 0*np.random.uniform(-0.5,0.5, size=(num_reset,)) + self.start_pos[0] + y0 = 0*np.random.uniform(-0.5,0.5, size=(num_reset,)) + self.start_pos[1] + z0 = 0*np.random.uniform(-0.5,0.5, size=(num_reset,)) + self.start_pos[2] + + vx0 = np.zeros((num_reset,)) + vy0 = np.zeros((num_reset,)) + vz0 = np.zeros((num_reset,)) + + phi0 = np.zeros((num_reset,)) + theta0 = np.zeros((num_reset,)) + psi0 = np.zeros((num_reset,)) + + p0 = np.zeros((num_reset,)) + q0 = np.zeros((num_reset,)) + r0 = np.zeros((num_reset,)) + + w0 = np.zeros((num_reset,self.num_motors)) + + w0 = np.hsplit(w0, self.num_motors) + + state_vars = [x0, y0, z0, vx0, vy0, vz0, phi0, theta0, psi0, p0, q0, r0] + state_vars = [var.reshape(num_reset, 1) for var in state_vars] + + self.world_states[dones] = np.concatenate(state_vars + list(w0), axis=1) + self.step_counts[dones] = np.zeros(num_reset) + # Clear the action-filter memory for envs that just reset, so the + # next action isn't smoothed against a stale pre-reset action. + self.filtered_actions[dones] = 0.0 + + # update states + self.update_states() + return self.states + + def reset(self): + return self.reset_(np.ones(self.num_envs, dtype=bool)) + + def step_async(self, actions): + self.prev_actions = self.actions + self.actions = actions + + def step_wait(self): + # Reference-form dynamics: dynamics_func takes the full 12+N state + # and the action directly. Motor model (sqrt-poly mapping U → Wc, + # then first-order lag) is baked into the symbolic equations. + # Action is in [-1, 1]; motor state w_i is in [-1, 1]. + # + # Apply the action low-pass filter (FC setpoint shaping) before the + # action enters the dynamics. alpha=1.0 is a no-op. + if self.action_filter_alpha < 1.0: + self.filtered_actions = ( + self.action_filter_alpha * self.actions + + (1.0 - self.action_filter_alpha) * self.filtered_actions + ).astype(np.float32) + action_for_dynamics = self.filtered_actions + else: + action_for_dynamics = self.actions + + full_state = self.world_states # (num_envs, 12+N) + full_state_dot = self.drone_sim.dynamics_func( + full_state.T, action_for_dynamics.T + ).T # (num_envs, 12+N) + new_states = (full_state + self.dt * full_state_dot).astype(np.float32) + + # Detect numerical divergence (NaN, Inf, or excessively large finite values) + diverged = np.any(~np.isfinite(new_states) | (np.abs(new_states) > 1e6), axis=1) + if np.any(diverged): + new_states[diverged] = self.world_states[diverged] + + self.step_counts += 1 + + pos_old = self.world_states[:,0:3] + pos_new = new_states[:,0:3] + pos_gate = self.gate_pos[self.target_gates%self.num_gates] + yaw_gate = self.gate_yaw[self.target_gates%self.num_gates] + + # Rewards + d2g_old = np.linalg.norm(pos_old - pos_gate, axis=1) + d2g_new = np.linalg.norm(pos_new - pos_gate, axis=1) + rat_penalty = 0.001*np.linalg.norm(new_states[:,9:12], axis=1) + action_penalty_delta = 0.001*np.linalg.norm((self.actions-self.prev_actions), axis=1) + + prog_rewards = d2g_old - d2g_new + rewards = prog_rewards - rat_penalty + + # Gate passing/collision + normal = np.array([np.cos(yaw_gate), np.sin(yaw_gate)]).T + # dot product of normal and position vector over axis 1 + pos_old_projected = (pos_old[:,0]-pos_gate[:,0])*normal[:,0] + (pos_old[:,1]-pos_gate[:,1])*normal[:,1] + pos_new_projected = (pos_new[:,0]-pos_gate[:,0])*normal[:,0] + (pos_new[:,1]-pos_gate[:,1])*normal[:,1] + passed_gate_plane = (pos_old_projected < 0) & (pos_new_projected > 0) + gate_size = 1.5 + gate_passed = passed_gate_plane & np.all(np.abs(pos_new - pos_gate) self.x_bounds[1]) + y_bounds_broken = np.logical_or(new_states[:,1] < self.y_bounds[0], new_states[:,1] > self.y_bounds[1]) + z_bounds_broken = np.logical_or(new_states[:,2] < self.z_bounds[0], new_states[:,2] > self.z_bounds[1]) + out_of_bounds = x_bounds_broken | y_bounds_broken | z_bounds_broken + + rewards[out_of_bounds] = -10 + rewards[diverged] = -10 + + # Check number of steps + max_steps_reached = self.step_counts >= self.max_steps + + # Update target gate + self.target_gates[gate_passed] += 1 + self.target_gates[gate_passed] %= self.num_gates + + # Track number of gates passed + self.num_gates_passed[gate_passed] += 1 + + # Check if the episode is done + dones = max_steps_reached | out_of_bounds | diverged + self.dones = dones + + # Save gates passed before reset (for info dict) + gates_passed_before_reset = self.num_gates_passed.copy() + + # Pause if collision + if self.pause: + dones = dones & ~dones + self.dones = dones + elif self.pause_if_collision: + update = ~dones + # Update world states + self.world_states[update] = new_states[update] + self.update_states() + else: + # Update world states + self.world_states = new_states + # reset env if done (and update states) + self.reset_(dones) + + # Write info dicts + infos = [{} for _ in range(self.num_envs)] + for i in range(self.num_envs): + if dones[i]: + infos[i]["terminal_observation"] = self.states[i] + if max_steps_reached[i]: + infos[i]["TimeLimit.truncated"] = True + # extra info for debugging + infos[i]["out_of_bounds"] = out_of_bounds[i] + infos[i]["gate_passed"] = gate_passed[i] + infos[i]["num_gates_passed"] = gates_passed_before_reset + + return self.states, rewards, dones, infos + + def close(self): + pass + + def seed(self, seed=None): + pass + + def get_attr(self, attr_name, indices=None): + raise AttributeError() + + def set_attr(self, attr_name, value, indices=None): + pass + + def env_method(self, method_name, *method_args, indices=None, **method_kwargs): + pass + + def env_is_wrapped(self, wrapper_class, indices=None): + return [False]*self.num_envs + + def render(self, mode='human'): + # Define base state variable names + state_keys = ['x', 'y', 'z', 'vx', 'vy', 'vz', 'phi', 'theta', 'psi', 'p', 'q', 'r'] + + # Dynamically create RPM keys based on the number of motors + rpm_keys = [f'w{i+1}' for i in range(self.num_motors)] + + # Combine all keys + state_keys += rpm_keys + + # Convert `self.world_states.T` into a dictionary + state_dict = dict(zip(state_keys, self.world_states.T)) + + # Rescale actions to [0,1] for rendering + action_keys = [f'u{i+1}' for i in range(self.num_motors)] + action_dict = dict(zip(action_keys, (np.array(self.actions.T) + 1) / 2)) + + return {**state_dict, **action_dict} \ No newline at end of file diff --git a/src/ariel/visualisation/drone/__init__.py b/src/ariel/visualisation/drone/__init__.py new file mode 100644 index 000000000..172e53ee6 --- /dev/null +++ b/src/ariel/visualisation/drone/__init__.py @@ -0,0 +1,2 @@ +from ariel.visualisation.drone.drone_visualization import create_drone, set_thrust +from ariel.visualisation.drone.graphics_3d import Mesh, Force diff --git a/src/ariel/visualisation/drone/animation.py b/src/ariel/visualisation/drone/animation.py new file mode 100644 index 000000000..a3dfe7d3c --- /dev/null +++ b/src/ariel/visualisation/drone/animation.py @@ -0,0 +1,755 @@ +""" +Animation and Real-time Visualization + +This module provides OpenCV-based animation and real-time visualization +capabilities for drone simulation including trajectory playback and recording. + +Functions: + view: Real-time drone state visualization with interactive controls + animate: Trajectory playback with timeline control and recording + get_drone_state_zero: Default drone state for testing + nothing: Placeholder function for OpenCV trackbars +""" + +import numpy as np +import cv2 +import time +import os +import copy + +from .graphics_3d import Camera +from .drone_visualization import create_grid, create_path, create_drone, set_thrust + +# Screen and visualization constants +DEFAULT_WIDTH = 864 +DEFAULT_HEIGHT = 700 +DEFAULT_FPS = 100 +THRUST_SCALE = 0.2 +ZOOM_FACTOR = 1.05 +GATE_SIZE = 1.5 +GRID_SIZE = 20 +DRONE_BOX_SIZE = [0.02, 0.02, 0.02] +PROP_RADIUS = 0.0254 # 2-inch propeller radius in meters +PATH_SUBSAMPLE = 5 +THRUST_BASE_LEN = 0.0 # Base arrow length so direction is visible at low thrust + +# Camera constants +CAMERA_MATRIX = np.array([[1.e+3, 0., DEFAULT_WIDTH/2], [0., 1.e+3, DEFAULT_HEIGHT/2], [0., 0., 1.]]) +DIST_COEFFS = np.array([0., 0., 0., 0., 0.]) + +# Color mappings for OpenCV (BGR format) +COLORS_BGR = { + 'red': (0, 0, 255), + 'blue': (255, 0, 0), + 'green': (0, 255, 0), + 'orange': (0, 165, 255), + 'purple': (128, 0, 128), + 'brown': (42, 42, 165), + 'white': (255, 255, 255), + 'black': (0, 0, 0), + 'gray': (200, 200, 200), + 'gate_orange': (0, 140, 255) +} + +def nothing(x): + """Placeholder function for OpenCV trackbar callbacks.""" + pass + + +_OVERLAY_POSITIONS = { + 'upper left', 'upper right', 'lower left', 'lower right', + 'top left', 'top right', 'bottom left', 'bottom right', +} + + +def _overlay_anchor(position, text_w, text_h, frame_w, frame_h, pad=15): + """Resolve a corner keyword to an (x, y) anchor for cv2.putText. + + cv2.putText's origin is the text's baseline-left, so ``y`` must be below + the top of the text box. + """ + position = (position or 'lower right').lower() + if position not in _OVERLAY_POSITIONS: + position = 'lower right' + top = position.startswith('upper') or position.startswith('top') + left = position.endswith('left') + x = pad if left else (frame_w - text_w - pad) + y = (pad + text_h) if top else (frame_h - pad) + return x, y + +def create_camera(view_type='iso', width=DEFAULT_WIDTH, height=DEFAULT_HEIGHT): + """ + Create a camera with predefined settings based on view type. + + Args: + view_type: Camera view type ('top', 'iso', 'isometric', or other) + width: Screen width + height: Screen height + + Returns: + Camera: Configured camera object + """ + if view_type == 'top': + cam = Camera( + pos=np.array([-12., 0., 0.]), + theta=[0., -np.pi/2, 0.], + cameraMatrix=CAMERA_MATRIX, + distCoeffs=DIST_COEFFS + ) + cam.r = [-3.8, 0, 0] + elif view_type in ['isometric', 'iso']: + cam = Camera( + pos=np.array([0., 0., 0.]), + theta=[0,-np.pi/8,-np.pi/4], + cameraMatrix=CAMERA_MATRIX, + distCoeffs=DIST_COEFFS + ) + cam.r = [-2.6, 0, 0] + else: + cam = Camera( + pos=np.array([0., 0., 0.]), + theta=[0,-np.pi/8,-np.pi/4], + cameraMatrix=CAMERA_MATRIX, + distCoeffs=DIST_COEFFS + ) + cam.r = [-15, 0, 0] + + return cam + +def create_gate_geometry(gate_size=None): + """ + Create gate geometry objects for visualization. + + Args: + gate_size: Gate size in meters. If None, uses GATE_SIZE constant. + + Returns: + tuple: (gate, gate_collision_box) path objects + """ + n = gate_size if gate_size is not None else GATE_SIZE + gate = create_path(np.array([ + [0, n/2, n/2], + [0, n/2, -n/2], + [0, -n/2, -n/2], + [0, -n/2, n/2] + ]), loop=True) + + gate_collision_box = create_path(np.array([ + [0, 1., 1.], + [0, 1., -1.], + [0, -1., -1.], + [0, -1., 1.] + ]), loop=True) + + return gate, gate_collision_box + +def handle_keyboard_input_view(key, cam, auto_play, follow, draw_forces, draw_path, record, out, record_file): + """ + Handle keyboard input for the view function. + + Returns: + tuple: (auto_play, follow, draw_forces, draw_path, record, should_exit) + """ + should_exit = False + + if key == 27: # ESC - exit + if record: + print('recording ended') + out.release() + print('recording saved in ' + record_file) + should_exit = True + elif key == ord('p'): # P - toggle auto-play + auto_play = not auto_play + elif key == ord('f'): # F - toggle follow mode + follow = not follow + elif key == ord('s'): # S - toggle force display + draw_forces = not draw_forces + elif key == ord('d'): # D - toggle path display + draw_path = not draw_path + elif key == ord('1'): # 1 - zoom in + cam.zoom(ZOOM_FACTOR) + elif key == ord('2'): # 2 - zoom out + cam.zoom(1/ZOOM_FACTOR) + elif key == ord('r'): # R - toggle recording + if record: + print('recording ended') + out.release() + print('recording saved in ' + record_file) + else: + print('recording started') + record = not record + + return auto_play, follow, draw_forces, draw_path, record, should_exit + +def draw_drone_and_forces(drone, forces, pos, ori, u, state, draw_forces, scl, frame, cam): + """ + Draw drone(s) and force vectors. + + Note: ``u`` here is the policy action in [-1, 1]. Under the reference-form + motor model (Session 5 dynamics migration), the physical motor thrust + magnitude scales with U = (u + 1) / 2 ∈ [0, 1] (motor never reverses; + minimum is the idle speed w_min). We therefore render arrow length using + that mapping so arrows point in the actual thrust direction at all + throttles, rather than flipping backward whenever u < 0. + """ + if len(pos.shape) == 1: # Single drone + drone.translate(pos-drone.pos) + drone.rotate(ori) + thrust_magnitude = (np.asarray(u, dtype=float) + 1.0) / 2.0 + set_thrust(drone, forces, thrust_magnitude * scl, base_len=THRUST_BASE_LEN) + drone.draw(frame, cam, color=COLORS_BGR['black'], pt=2) + + if draw_forces: + for force in forces: + c = force.color if force.color is not None else COLORS_BGR['red'] + force.draw(frame, cam, color=c, pt=2) + else: # Multiple drones + for i in range(pos.shape[0]): + drone.translate(pos[i]-drone.pos) + drone.rotate(ori[i]) + thrust_magnitude_i = (np.asarray(u[i], dtype=float) + 1.0) / 2.0 + set_thrust(drone, forces, thrust_magnitude_i * scl, base_len=THRUST_BASE_LEN) + + # Draw drone with custom color if available + if 'color' in state and len(state['color']) > i: + drone.draw(frame, cam, color=state['color'][i], pt=2) + else: + drone.draw(frame, cam, color=COLORS_BGR['black'], pt=2) + + if draw_forces: + for force in forces: + c = force.color if force.color is not None else COLORS_BGR['red'] + force.draw(frame, cam, color=c, pt=2) + +def get_drone_state_zero(): + """ + Return default zero drone state for testing and initialization. + + Returns: + dict: Default drone state with position, orientation, and control inputs + """ + return { + 'x': 0, + 'y': 0, + 'z': 0, + 'phi': 0, + 'theta': 0, + 'psi': 0, + 'u1': 0, + 'u2': 0, + 'u3': 0, + 'u4': 0 + } + +def view(propellers, + get_drone_state=get_drone_state_zero, + fps=100, + gate_pos=[], + gate_yaw=[], + gate_size=None, + record_steps=0, + record_file='output.mp4', + show_window=True, + view_type='iso', + follow=False, + draw_forces=True, + draw_path=False, + auto_play=True, + record=False, + motor_colors=['red', 'blue', 'green', 'orange', 'purple', 'brown'], + overlay_text_position='lower right', + overlay_text_scale=6.0, + ): + """ + Real-time 3D visualization of drone state with interactive controls. + + This function creates a real-time 3D viewer that continuously updates + the drone visualization based on the provided state function. Supports + interactive camera controls, force visualization, and video recording. + + Args: + propellers: List of propeller dictionaries defining drone configuration + get_drone_state: Function that returns current drone state dict + fps: Target frames per second for display/recording + gate_pos: List of gate positions for course visualization + gate_yaw: List of gate orientations + gate_size: Gate size in meters. If None, uses GATE_SIZE constant. + record_steps: Number of steps to record (0 = no recording) + record_file: Output video filename + show_window: Whether to display the window + view_type: Camera view type ('top', 'iso', 'isometric') + follow: Whether camera should follow the drone + draw_forces: Whether to display thrust force vectors + draw_path: Whether to display trajectory path + auto_play: Whether animation auto-plays + record: Whether to start recording immediately + motor_colors: List of color names for motor visualization + + Controls: + Mouse: Rotate camera view + P: Toggle auto-play + F: Toggle follow mode (camera tracks drone) + S: Toggle force vector display + D: Toggle path display + 1/2: Zoom in/out + R: Toggle recording + ESC: Exit + """ + num_arms = len(propellers) + + # Screen resolution + width = DEFAULT_WIDTH + height = DEFAULT_HEIGHT + + # Initialize camera + cam = create_camera(view_type, width, height) + + # Create scene elements + big_grid = create_grid(GRID_SIZE, GRID_SIZE, 1) + + # Convert motor colors to BGR format for OpenCV + motor_colors_bgr = [COLORS_BGR.get(color, COLORS_BGR['white']) for color in motor_colors] + + drone, forces = create_drone(propellers, box_size=DRONE_BOX_SIZE, prop_radius=PROP_RADIUS, scale=1, motor_colors=motor_colors_bgr) + + # Create gate geometry + gate, gate_collision_box = create_gate_geometry(gate_size) + + # Visualization parameters + scl = THRUST_SCALE # Thrust vector scale + + # Control flags (parameters passed in as initial values) + + # Target point visualization + target = create_path(np.array([[0,0,0],[0,0,0.01]])) + + # Video recording setup + fourcc = cv2.VideoWriter_fourcc(*'mp4v') + if '/' in record_file: + os.makedirs(os.path.dirname(record_file), exist_ok=True) + out = cv2.VideoWriter(record_file, fourcc, fps=fps, frameSize=(width, height)) + + # Auto-recording setup + steps = 0 + if record_steps > 0: + record = True + + # Window setup + if show_window: + cv2.namedWindow('animation') + cv2.setMouseCallback('animation', cam.mouse_control) + + # Main visualization loop + while True: + # Update step counter + if auto_play: + steps += 1 + if 0 < record_steps < steps: + out.release() + break + + # Get current drone state + state = get_drone_state() + prev_state = copy.deepcopy(state) + else: + state = prev_state + + # Extract state information + pos = np.stack([state['x'], state['y'], state['z']]).T + ori = np.stack([state['phi'], state['theta'], state['psi']]).T + u = np.stack([state[f'u{i}'] for i in range(1,num_arms+1)]).T + + # Update camera + if follow: + cam.set_center(drone.pos) + else: + cam.set_center(np.zeros(3)) + + # Create frame + frame = 255*np.ones((height, width, 3), dtype=np.uint8) + + # Draw grid + big_grid.draw(frame, cam, color=COLORS_BGR['gray'], pt=1) + + # Draw trajectory targets if available + if 'traj_x' in state: + target_pos = np.stack([state['traj_x'], state['traj_y'], state['traj_z']]).T + + # Draw target trajectory ghost line + if len(target_pos) > 1 and draw_path: + target_path = create_path([tp for tp in target_pos[0::PATH_SUBSAMPLE]]) # Subsample for performance + target_path.draw(frame, cam, color=COLORS_BGR['green'], pt=1) # Green ghost line + + # Draw current target points + for tp in target_pos: + target.translate(tp-target.pos) + target.draw(frame, cam, color=COLORS_BGR['green'], pt=10) + + # Draw drone(s) and forces + draw_drone_and_forces(drone, forces, pos, ori, u, state, draw_forces, scl, frame, cam) + + # Draw gates + for pos_gate, yaw in zip(gate_pos, gate_yaw): + gate.translate(pos_gate-gate.pos) + gate_collision_box.translate(pos_gate-gate_collision_box.pos) + gate.rotate([0,0,yaw]) + gate_collision_box.rotate([0,0,yaw]) + gate.draw(frame, cam, color=(0,140,255), pt=4) + + # Gates-passed counter (drawn before the recording write so it appears + # in the output file). + if 'gates_passed' in state: + label = f"{state['gates_passed']}" + thickness = max(1, int(round(overlay_text_scale * 3))) + (tw, th), _ = cv2.getTextSize(label, cv2.FONT_HERSHEY_SIMPLEX, + overlay_text_scale, thickness) + tx, ty = _overlay_anchor(overlay_text_position, tw, th, width, height) + cv2.putText(frame, label, (tx, ty), cv2.FONT_HERSHEY_SIMPLEX, + overlay_text_scale, COLORS_BGR['black'], + thickness=thickness) + + # Recording indicator + if record: + out.write(frame) + cv2.putText(frame, '[recording]', (10, 40), cv2.FONT_HERSHEY_SIMPLEX, 0.5, COLORS_BGR['black']) + + # Handle keyboard input + key = cv2.waitKeyEx(1) + auto_play, follow, draw_forces, draw_path, record, should_exit = handle_keyboard_input_view( + key, cam, auto_play, follow, draw_forces, draw_path, record, out, record_file) + + if should_exit: + break + + # Display frame + if show_window: + cv2.imshow('animation', frame) + + cv2.destroyAllWindows() + +def animate(t, x, y, z, phi, theta, psi, u, + autopilot_mode=[], + target=[], + waypoints=[], + file='output.mp4', + multiple_trajectories=False, + simultaneous=False, + colors=[], + names=[], + alpha=0, + step=1, + gate_pos=[], + gate_yaw=[], + **kwargs): + """ + Trajectory playback animation with timeline control and recording. + + This function creates an interactive animation player for pre-recorded + trajectories with timeline scrubbing, path visualization, and recording capabilities. + + Args: + t: Time array or list of time arrays + x, y, z: Position arrays or lists of position arrays + phi, theta, psi: Attitude arrays or lists of attitude arrays + u: Control input arrays or lists of control arrays + autopilot_mode: Array indicating autopilot status + target: Target trajectory points + waypoints: Waypoint markers to display + file: Output video filename + multiple_trajectories: Whether data contains multiple trajectories + simultaneous: Whether to show multiple trajectories simultaneously + colors: Colors for multiple trajectories + names: Names for trajectory labels + gate_pos, gate_yaw: Gate positions and orientations + **kwargs: Additional options (follow, auto_play, draw_path, draw_forces, etc.) + + Controls: + Mouse: Rotate camera view + Timeline slider: Scrub through time + SPACE: Toggle auto-play + F: Toggle follow mode + P: Toggle path display + S: Toggle force display + R: Toggle recording + J/L: Previous/next trajectory (if multiple) + 1/2: Zoom in/out + ESC: Exit + """ + # Extract control options + follow = kwargs.get('follow', False) + auto_play = kwargs.get('auto_play', False) + draw_path = kwargs.get('draw_path', False) + draw_forces = kwargs.get('draw_forces', False) + record = False + + traj_index = 0 + + # Handle multiple trajectories + if simultaneous: + traj_index = np.argmax(np.array([ti[-1] for ti in t])) + + if multiple_trajectories: + t_ = t[traj_index] + pos = np.stack([x[traj_index],y[traj_index],z[traj_index]]).T + ori = np.stack([phi[traj_index],theta[traj_index],psi[traj_index]]).T + u_ = u[traj_index] + else: + t_ = t + pos = np.stack([x,y,z]).T + ori = np.stack([phi,theta,psi]).T + u_ = u + + # Create default quadrotor for animation if no specific configuration provided + propellers = kwargs.get('propellers', [ + {"loc": [0.5*np.cos(np.pi/4), 0.5*np.sin(np.pi/4), 0], "dir": [0, 0, -1, "ccw"], "propsize": 5}, + {"loc": [0.5*np.cos(3*np.pi/4), 0.5*np.sin(3*np.pi/4), 0], "dir": [0, 0, -1, "cw"], "propsize": 5}, + {"loc": [0.5*np.cos(5*np.pi/4), 0.5*np.sin(5*np.pi/4), 0], "dir": [0, 0, -1, "ccw"], "propsize": 5}, + {"loc": [0.5*np.cos(7*np.pi/4), 0.5*np.sin(7*np.pi/4), 0], "dir": [0, 0, -1, "cw"], "propsize": 5} + ]) + + # Screen resolution + width = DEFAULT_WIDTH + height = DEFAULT_HEIGHT + + # Initialize camera (default view for animation) + cam = create_camera('top', width, height) + cam.pos = np.array([-5., 0., 0.]) + cam.theta = np.zeros(3) + cam.r[0] = -12. + + # Create scene elements + big_grid = create_grid(10, 10, 1) + drone, forces = create_drone(propellers, box_size=DRONE_BOX_SIZE, prop_radius=PROP_RADIUS, scale=1) + + # Gate setup + gate, gate_collision_box = create_gate_geometry(kwargs.get('gate_size')) + + scl = THRUST_SCALE # Thrust scale + + # Window setup + cv2.namedWindow('animation') + cv2.setMouseCallback('animation', cam.mouse_control) + cv2.createTrackbar('t', 'animation', 0, t_.shape[0]-1, nothing) + + # Create path visualizations + paths = [] + if simultaneous: + for i in range(len(t)): + p = np.stack([x[i],y[i],z[i]]).T + paths.append(create_path([pi for pi in p[0::PATH_SUBSAMPLE]])) + + path = create_path([p for p in pos[0::PATH_SUBSAMPLE]]) + + # Create waypoint markers + waypoints = [create_path([v,v+[0,0,0.01]]) for v in waypoints] + + # Animation state + start_time = time.time() + time_index = 0 + video_step = 1 + + # Main animation loop + while True: + + # Update time index + if auto_play: + if record: + if time_index < len(t_) - video_step: + time_index += video_step + else: + current_time = time.time() - start_time + for i in range(len(t_)): + if t_[i] > current_time: + time_index = i + break + if time_index == -1: + current_time = t_[time_index] + else: + time_index = cv2.getTrackbarPos('t', 'animation') + current_time = t_[time_index] + + # Check for recording time limit + if 'record_time' in kwargs: + if t_[time_index] >= kwargs['record_time']: + if record: + print('recording ended') + out.release() + print('recording saved in ' + file) + break + + # Update drone state + drone.translate(pos[time_index] - drone.pos) + drone.rotate(ori[time_index]) + + T = u_[time_index] # Thrust values + set_thrust(drone, forces, T*scl) + + # Update camera + if follow: + cam.set_center(drone.pos) + else: + cam.set_center(np.zeros(3)) + + # Create frame + frame = 255*np.ones((height, width, 3), dtype=np.uint8) + + # Draw scene elements + big_grid.draw(frame, cam, color=COLORS_BGR['gray'], pt=1) + + # Draw waypoints + for w in waypoints: + w.draw(frame, cam, color=COLORS_BGR['red'], pt=4) + + # Draw target trajectory ghost line + if len(target) > 1: + target_path = create_path([t for t in target[0::PATH_SUBSAMPLE]]) # Subsample for performance + target_path.draw(frame, cam, color=COLORS_BGR['green'], pt=1) # Green ghost line + + # Draw current target + if time_index < len(target): + tt = target[time_index] + tt_graphic = create_path([tt,tt+[0,0,0.01]]) + tt_graphic.draw(frame, cam, color=COLORS_BGR['green'], pt=10) + + # Draw trajectory paths + if draw_path and not simultaneous: + path.draw(frame, cam, color=COLORS_BGR['green'], pt=2) + + # Handle simultaneous trajectories + if simultaneous: + if draw_path: + for i in range(len(t)): + color = colors[i] if len(colors) > i else COLORS_BGR['green'] + paths[i].draw(frame, cam, color=color, pt=1) + + for i in range(len(t)): + pos_i = np.stack([x[i],y[i],z[i]]).T + ori_i = np.stack([phi[i],theta[i],psi[i]]).T + u_i = u[i] + time_index_i = 0 + for j in range(len(t[i])): + time_index_i = j + if t[i][j] > t_[time_index]: + break + + drone.translate(pos_i[time_index_i] - drone.pos) + drone.rotate(ori_i[time_index_i]) + T_i = u_i[time_index_i] + set_thrust(drone, forces, T_i*scl) + + color = colors[i] if len(colors) > i else COLORS_BGR['blue'] + drone.draw(frame, cam, color=color, pt=2) + + if draw_forces: + for force in forces: + force.draw(frame, cam, pt=2) + else: + # Single trajectory rendering + if multiple_trajectories and len(colors) > traj_index: + drone.draw(frame, cam, color=colors[traj_index], pt=2) + elif pos[time_index][2] > 0: + drone.draw(frame, cam, color=COLORS_BGR['red'], pt=2) + elif len(autopilot_mode) > 0: + if autopilot_mode[time_index] == 0 or True: + drone.draw(frame, cam, color=COLORS_BGR['blue'], pt=2) + else: + drone.draw(frame, cam, color=COLORS_BGR['green'], pt=2) + cv2.putText(frame, '[gcnet active]', (10, 60), + cv2.FONT_HERSHEY_SIMPLEX, 0.5, COLORS_BGR['green']) + else: + drone.draw(frame, cam, color=COLORS_BGR['blue'], pt=2) + + if draw_forces and not simultaneous: + for force in forces: + force.draw(frame, cam, pt=2) + + # Draw gates + for gpos, gyaw in zip(gate_pos, gate_yaw): + gate.translate(gpos-gate.pos) + gate_collision_box.translate(gpos-gate_collision_box.pos) + gate.rotate([0,0,gyaw]) + gate_collision_box.rotate([0,0,gyaw]) + gate.draw(frame, cam, color=(0,140,255), pt=4) + + # Add text overlays + cv2.putText(frame, "t = " + str(round(t_[time_index], 2)), (10, 20), + cv2.FONT_HERSHEY_SIMPLEX, 0.5, COLORS_BGR['black']) + + if 'title' in kwargs: + cv2.putText(frame, kwargs['title'], (300, 20), cv2.FONT_HERSHEY_SIMPLEX, 0.5, COLORS_BGR['black'], thickness=2) + + for i in range(len(names)): + color = colors[i] if len(colors) > i else COLORS_BGR['black'] + cv2.putText(frame, names[i], (700, 20*(i+1)), cv2.FONT_HERSHEY_SIMPLEX, 0.5, color, thickness=2) + + if record: + out.write(frame) + cv2.putText(frame, '[recording]', (10, 40), cv2.FONT_HERSHEY_SIMPLEX, 0.5, COLORS_BGR['black']) + + # Handle keyboard input + control = cv2.waitKeyEx(1) + + # Trajectory switching (J/L keys) + if control == 106 and multiple_trajectories: # J - previous trajectory + time_index = 0 + start_time = time.time() - t_[time_index] + traj_index = max(0, traj_index-step) + t_ = t[traj_index] + pos = np.stack([x[traj_index],y[traj_index],z[traj_index]]).T + ori = np.stack([phi[traj_index],theta[traj_index],psi[traj_index]]).T + u_ = u[traj_index] + path = create_path([p for p in pos[0::5]]) + if control == 108 and multiple_trajectories: # L - next trajectory + time_index = 0 + start_time = time.time() - t_[time_index] + traj_index = min(len(t)-1, traj_index+step) + t_ = t[traj_index] + pos = np.stack([x[traj_index],y[traj_index],z[traj_index]]).T + ori = np.stack([phi[traj_index],theta[traj_index],psi[traj_index]]).T + u_ = u[traj_index] + path = create_path([p for p in pos[0::5]]) + + # Auto-record trigger + if 'record' in kwargs: + if kwargs['record'] and not record: + control = 114 # Trigger record + + if control == 114: # R - toggle recording + if record: + print('recording ended') + out.release() + print('recording saved in ' + file) + else: + print('recording started') + # Setup video writer + fourcc = cv2.VideoWriter_fourcc(*'mp4v') + + # Calculate appropriate framerate (max 100 fps) + dt = np.mean(t_[1:]-t_[:-1]) + fps = 1/dt + while fps > 100: + video_step += 1 + fps = 1/(dt*video_step) + fps = int(fps) + print(f"Recording at {fps} fps") + out = cv2.VideoWriter(file, fourcc, fps=fps, frameSize=(width, height)) + record = not record + elif control == 102: # F - follow mode + follow = not follow + elif control == 112: # P - path display + draw_path = not draw_path + elif control == 115: # S - force display + draw_forces = not draw_forces + elif control == 32: # SPACE - auto-play + auto_play = not auto_play + start_time = time.time() - t_[time_index] + elif control == 49: # 1 - zoom in + cam.zoom(ZOOM_FACTOR) + elif control == 50: # 2 - zoom out + cam.zoom(1/ZOOM_FACTOR) + elif control == 27: # ESC - exit + break + + cv2.imshow('animation', frame) + + cv2.destroyAllWindows() \ No newline at end of file diff --git a/src/ariel/visualisation/drone/demo_plotting.py b/src/ariel/visualisation/drone/demo_plotting.py new file mode 100644 index 000000000..04851decc --- /dev/null +++ b/src/ariel/visualisation/drone/demo_plotting.py @@ -0,0 +1,402 @@ +""" +Demo Plotting and Analysis Visualization + +This module provides matplotlib-based plotting and analysis functions +for drone demonstration results including trajectory plots, performance +metrics, and comparative analysis. + +Functions: + plot_demo_results: Plot comprehensive results for a single demo + plot_single_demo: Internal function for plotting individual demo + compare_demos: Create comparison plots across multiple demos +""" + +import numpy as np +import matplotlib.pyplot as plt +from mpl_toolkits.mplot3d import Axes3D + +def plot_demo_results(demos, demo_idx=None, save_plots=False): + """ + Plot results from demonstrations. + + Args: + demos: List of demo result dictionaries + demo_idx: Index of demo to plot (None for all) + save_plots: Whether to save plots to files + """ + if not demos: + print("No demo results to plot") + return + + demos_to_plot = [demo_idx] if demo_idx is not None else range(len(demos)) + + for idx in demos_to_plot: + if idx >= len(demos): + continue + + demo = demos[idx] + plot_single_demo(demo, save_plots) + +def plot_single_demo(demo, save_plots=False): + """ + Plot results for a single demo. + + Args: + demo: Demo result dictionary containing simulation data + save_plots: Whether to save plot to file + """ + states = demo['state_history'] + times = demo['time_history'] + controls = demo['control_history'] + + if len(states) == 0: + print(f"No data to plot for {demo['name']}") + return + + # Extract data arrays + positions = states[:, 0:3] + velocities = states[:, 3:6] + attitudes = states[:, 6:9] * 180/np.pi # Convert to degrees + angular_velocities = states[:, 9:12] * 180/np.pi # Convert to deg/s + + # Create comprehensive figure with subplots + fig = plt.figure(figsize=(15, 12)) + fig.suptitle(f"Demo: {demo['name']}", fontsize=16, fontweight='bold') + + # 1. 3D trajectory plot + ax1 = fig.add_subplot(2, 3, 1, projection='3d') + + # Plot target trajectory ghost line if available + if 'target_trajectory' in demo: + target_pos = demo['target_trajectory'] + ax1.plot(target_pos[:, 0], target_pos[:, 1], target_pos[:, 2], + 'g--', linewidth=1, alpha=0.6, label='Target') + + # Plot actual trajectory + ax1.plot(positions[:, 0], positions[:, 1], positions[:, 2], 'b-', linewidth=2, label='Actual') + ax1.scatter(positions[0, 0], positions[0, 1], positions[0, 2], c='g', s=100, label='Start') + ax1.scatter(positions[-1, 0], positions[-1, 1], positions[-1, 2], c='r', s=100, label='End') + ax1.set_xlabel('X [m]') + ax1.set_ylabel('Y [m]') + ax1.set_zlabel('Z [m]') + ax1.set_title('3D Trajectory') + ax1.legend() + ax1.grid(True) + + # 2. Position vs time + ax2 = fig.add_subplot(2, 3, 2) + + # Plot target positions if available + if 'target_trajectory' in demo: + target_pos = demo['target_trajectory'] + target_times = demo['target_time_points'] + ax2.plot(target_times, target_pos[:, 0], 'r--', alpha=0.6, linewidth=1, label='Target X') + ax2.plot(target_times, target_pos[:, 1], 'g--', alpha=0.6, linewidth=1, label='Target Y') + ax2.plot(target_times, target_pos[:, 2], 'b--', alpha=0.6, linewidth=1, label='Target Z') + + # Plot actual positions + ax2.plot(times, positions[:, 0], 'r-', label='Actual X') + ax2.plot(times, positions[:, 1], 'g-', label='Actual Y') + ax2.plot(times, positions[:, 2], 'b-', label='Actual Z') + ax2.set_xlabel('Time [s]') + ax2.set_ylabel('Position [m]') + ax2.set_title('Position vs Time') + ax2.legend() + ax2.grid(True) + + # 3. Velocity vs time + ax3 = fig.add_subplot(2, 3, 3) + ax3.plot(times, velocities[:, 0], 'r-', label='Vx') + ax3.plot(times, velocities[:, 1], 'g-', label='Vy') + ax3.plot(times, velocities[:, 2], 'b-', label='Vz') + ax3.set_xlabel('Time [s]') + ax3.set_ylabel('Velocity [m/s]') + ax3.set_title('Velocity vs Time') + ax3.legend() + ax3.grid(True) + + # 4. Attitude vs time + ax4 = fig.add_subplot(2, 3, 4) + ax4.plot(times, attitudes[:, 0], 'r-', label='Roll') + ax4.plot(times, attitudes[:, 1], 'g-', label='Pitch') + ax4.plot(times, attitudes[:, 2], 'b-', label='Yaw') + ax4.set_xlabel('Time [s]') + ax4.set_ylabel('Attitude [deg]') + ax4.set_title('Attitude vs Time') + ax4.legend() + ax4.grid(True) + + # 5. Motor commands vs time + ax5 = fig.add_subplot(2, 3, 5) + num_motors = controls.shape[1] + colors = plt.cm.tab10(np.linspace(0, 1, num_motors)) + for i in range(num_motors): + ax5.plot(times, controls[:, i], color=colors[i], label=f'Motor {i+1}') + ax5.set_xlabel('Time [s]') + ax5.set_ylabel('Motor Command [-1,1]') + ax5.set_title(f'Motor Commands ({num_motors} motors)') + ax5.legend() + ax5.grid(True) + + # 6. Angular velocities vs time + ax6 = fig.add_subplot(2, 3, 6) + ax6.plot(times, angular_velocities[:, 0], 'r-', label='p (roll rate)') + ax6.plot(times, angular_velocities[:, 1], 'g-', label='q (pitch rate)') + ax6.plot(times, angular_velocities[:, 2], 'b-', label='r (yaw rate)') + ax6.set_xlabel('Time [s]') + ax6.set_ylabel('Angular Velocity [deg/s]') + ax6.set_title('Angular Velocities vs Time') + ax6.legend() + ax6.grid(True) + + plt.tight_layout() + + if save_plots: + filename = f"demo_{demo['name'].replace(' ', '_').lower()}.png" + plt.savefig(filename, dpi=300, bbox_inches='tight') + print(f"Plot saved as {filename}") + + plt.show() + +def compare_demos(demos, demo_indices=None): + """ + Compare multiple demonstrations with overlay plots. + + Args: + demos: List of demo result dictionaries + demo_indices: List of demo indices to compare (None for all) + """ + if demo_indices is None: + demo_indices = range(len(demos)) + + # Create comparison figure + fig, axes = plt.subplots(2, 2, figsize=(12, 10)) + fig.suptitle('Demo Comparison', fontsize=16, fontweight='bold') + + colors = plt.cm.tab10(np.linspace(0, 1, len(demo_indices))) + + for i, idx in enumerate(demo_indices): + if idx >= len(demos): + continue + + demo = demos[idx] + states = demo['state_history'] + times = demo['time_history'] + + if len(states) == 0: + continue + + positions = states[:, 0:3] + velocities = states[:, 3:6] + attitudes = states[:, 6:9] * 180/np.pi + + color = colors[i] + label = demo['name'] + + # Position magnitude + pos_mag = np.linalg.norm(positions, axis=1) + axes[0,0].plot(times, pos_mag, color=color, label=label) + + # Velocity magnitude + vel_mag = np.linalg.norm(velocities, axis=1) + axes[0,1].plot(times, vel_mag, color=color, label=label) + + # Altitude + axes[1,0].plot(times, positions[:, 2], color=color, label=label) + + # Yaw angle + axes[1,1].plot(times, attitudes[:, 2], color=color, label=label) + + # Configure subplot properties + axes[0,0].set_title('Position Magnitude') + axes[0,0].set_xlabel('Time [s]') + axes[0,0].set_ylabel('|Position| [m]') + axes[0,0].legend() + axes[0,0].grid(True) + + axes[0,1].set_title('Velocity Magnitude') + axes[0,1].set_xlabel('Time [s]') + axes[0,1].set_ylabel('|Velocity| [m/s]') + axes[0,1].legend() + axes[0,1].grid(True) + + axes[1,0].set_title('Altitude') + axes[1,0].set_xlabel('Time [s]') + axes[1,0].set_ylabel('Z [m]') + axes[1,0].legend() + axes[1,0].grid(True) + + axes[1,1].set_title('Yaw Angle') + axes[1,1].set_xlabel('Time [s]') + axes[1,1].set_ylabel('Yaw [deg]') + axes[1,1].legend() + axes[1,1].grid(True) + + plt.tight_layout() + plt.show() + +def plot_performance_metrics(demos): + """ + Create a performance metrics summary plot. + + Args: + demos: List of demo result dictionaries + """ + if not demos: + print("No demos to analyze") + return + + # Extract metrics for each demo + demo_names = [] + max_positions = [] + max_velocities = [] + max_attitudes = [] + final_positions = [] + simulation_times = [] + num_motors = [] + + for demo in demos: + states = demo['state_history'] + if len(states) == 0: + continue + + demo_names.append(demo['name']) + + positions = states[:, 0:3] + velocities = states[:, 3:6] + attitudes = states[:, 6:9] * 180/np.pi + + max_positions.append(np.max(np.abs(positions), axis=0)) + max_velocities.append(np.max(np.abs(velocities), axis=0)) + max_attitudes.append(np.max(np.abs(attitudes), axis=0)) + final_positions.append(positions[-1]) + simulation_times.append(demo['simulation_time']) + num_motors.append(demo['num_motors']) + + if not demo_names: + print("No valid demo data for metrics") + return + + # Create metrics visualization + fig, axes = plt.subplots(2, 3, figsize=(15, 10)) + fig.suptitle('Performance Metrics Summary', fontsize=16, fontweight='bold') + + x_pos = np.arange(len(demo_names)) + + # Max position components + max_pos_array = np.array(max_positions) + axes[0,0].bar(x_pos - 0.2, max_pos_array[:, 0], 0.2, label='X', alpha=0.8) + axes[0,0].bar(x_pos, max_pos_array[:, 1], 0.2, label='Y', alpha=0.8) + axes[0,0].bar(x_pos + 0.2, max_pos_array[:, 2], 0.2, label='Z', alpha=0.8) + axes[0,0].set_title('Max Position [m]') + axes[0,0].set_xticks(x_pos) + axes[0,0].set_xticklabels(demo_names, rotation=45) + axes[0,0].legend() + axes[0,0].grid(True, alpha=0.3) + + # Max velocity components + max_vel_array = np.array(max_velocities) + axes[0,1].bar(x_pos - 0.2, max_vel_array[:, 0], 0.2, label='Vx', alpha=0.8) + axes[0,1].bar(x_pos, max_vel_array[:, 1], 0.2, label='Vy', alpha=0.8) + axes[0,1].bar(x_pos + 0.2, max_vel_array[:, 2], 0.2, label='Vz', alpha=0.8) + axes[0,1].set_title('Max Velocity [m/s]') + axes[0,1].set_xticks(x_pos) + axes[0,1].set_xticklabels(demo_names, rotation=45) + axes[0,1].legend() + axes[0,1].grid(True, alpha=0.3) + + # Max attitude components + max_att_array = np.array(max_attitudes) + axes[0,2].bar(x_pos - 0.2, max_att_array[:, 0], 0.2, label='Roll', alpha=0.8) + axes[0,2].bar(x_pos, max_att_array[:, 1], 0.2, label='Pitch', alpha=0.8) + axes[0,2].bar(x_pos + 0.2, max_att_array[:, 2], 0.2, label='Yaw', alpha=0.8) + axes[0,2].set_title('Max Attitude [deg]') + axes[0,2].set_xticks(x_pos) + axes[0,2].set_xticklabels(demo_names, rotation=45) + axes[0,2].legend() + axes[0,2].grid(True, alpha=0.3) + + # Final position error magnitude + final_pos_array = np.array(final_positions) + final_pos_mag = np.linalg.norm(final_pos_array, axis=1) + axes[1,0].bar(x_pos, final_pos_mag, alpha=0.8, color='orange') + axes[1,0].set_title('Final Position Error [m]') + axes[1,0].set_xticks(x_pos) + axes[1,0].set_xticklabels(demo_names, rotation=45) + axes[1,0].grid(True, alpha=0.3) + + # Simulation performance + sim_times = np.array(simulation_times) + axes[1,1].bar(x_pos, sim_times, alpha=0.8, color='green') + axes[1,1].set_title('Simulation Time [s]') + axes[1,1].set_xticks(x_pos) + axes[1,1].set_xticklabels(demo_names, rotation=45) + axes[1,1].grid(True, alpha=0.3) + + # Number of motors + motors = np.array(num_motors) + axes[1,2].bar(x_pos, motors, alpha=0.8, color='purple') + axes[1,2].set_title('Number of Motors') + axes[1,2].set_xticks(x_pos) + axes[1,2].set_xticklabels(demo_names, rotation=45) + axes[1,2].grid(True, alpha=0.3) + + plt.tight_layout() + plt.show() + +def plot_trajectory_3d_comparison(demos, demo_indices=None): + """ + Create a 3D comparison plot of multiple trajectories. + + Args: + demos: List of demo result dictionaries + demo_indices: List of demo indices to compare (None for all) + """ + if demo_indices is None: + demo_indices = range(len(demos)) + + fig = plt.figure(figsize=(12, 9)) + ax = fig.add_subplot(111, projection='3d') + + colors = plt.cm.tab10(np.linspace(0, 1, len(demo_indices))) + + for i, idx in enumerate(demo_indices): + if idx >= len(demos): + continue + + demo = demos[idx] + states = demo['state_history'] + + if len(states) == 0: + continue + + positions = states[:, 0:3] + color = colors[i] + label = demo['name'] + + # Plot target trajectory ghost line if available + if 'target_trajectory' in demo: + target_pos = demo['target_trajectory'] + ax.plot(target_pos[:, 0], target_pos[:, 1], target_pos[:, 2], + color=color, linewidth=1, linestyle='--', alpha=0.4, + label=f'{label} (Target)') + + # Plot actual trajectory + ax.plot(positions[:, 0], positions[:, 1], positions[:, 2], + color=color, linewidth=2, label=f'{label} (Actual)', alpha=0.8) + + # Mark start and end points + ax.scatter(positions[0, 0], positions[0, 1], positions[0, 2], + c=color, s=100, marker='o', alpha=0.9) + ax.scatter(positions[-1, 0], positions[-1, 1], positions[-1, 2], + c=color, s=100, marker='s', alpha=0.9) + + ax.set_xlabel('X [m]') + ax.set_ylabel('Y [m]') + ax.set_zlabel('Z [m]') + ax.set_title('3D Trajectory Comparison\n(Circles: Start, Squares: End)') + ax.legend() + ax.grid(True) + + plt.tight_layout() + plt.show() \ No newline at end of file diff --git a/src/ariel/visualisation/drone/drone_visualization.py b/src/ariel/visualisation/drone/drone_visualization.py new file mode 100644 index 000000000..da776dba5 --- /dev/null +++ b/src/ariel/visualisation/drone/drone_visualization.py @@ -0,0 +1,375 @@ +""" +Drone Visualization Components + +This module provides drone-specific graphics functions including mesh creation, +coordinate transformations, and drone configuration utilities. + +Functions: + Coordinate Conversion: + - convert_to_cartesian: Convert magnitude/angles to cartesian coordinates + - ENU_to_NED: Convert between coordinate systems + - euler_to_rotation_matrix: Create rotation matrices from euler angles + + Mesh Creation: + - create_grid: Create ground grid mesh + - create_path: Create path/line mesh from points + - create_circle: Create circular mesh (for propellers) + - group: Combine multiple meshes + + Drone Construction: + - create_drone: Build complete drone mesh from individual configuration + - set_thrust: Update force vectors for thrust visualization + - create_individual_from_config: Generate drone configuration arrays +""" + +import numpy as np +from .graphics_3d import Mesh, Force, rotation_matrix + +def convert_to_cartesian(magnitude, yaw, pitch, in_degrees=False): + """ + Convert a vector from magnitude, yaw, and pitch to Cartesian coordinates (x, y, z). + + Parameters: + magnitude (float): The magnitude of the vector. + yaw (float): The yaw angle in degrees or radians. + pitch (float): The pitch angle in degrees or radians. + in_degrees (bool): Whether the yaw and pitch angles are given in degrees. Default is True. + + Returns: + tuple: Cartesian coordinates (x, y, z). + """ + if in_degrees: + yaw = np.radians(yaw) + pitch = np.radians(pitch) + + # Calculate Cartesian coordinates + x = magnitude * np.cos(pitch) * np.cos(yaw) + y = magnitude * np.cos(pitch) * np.sin(yaw) + z = magnitude * np.sin(pitch) + + return (x, y, z) + +def ENU_to_NED(x, y, z): + """ + Convert Earth-Centered, Earth-Fixed (ENU) coordinates to North-East-Down (NED) coordinates. + + Parameters: + x (float): The x-coordinate in ENU. + y (float): The y-coordinate in ENU. + z (float): The z-coordinate in ENU. + + Returns: + tuple: The x, y, and z coordinates in NED. + """ + return (y, x, -z) + +def euler_to_rotation_matrix(roll, pitch, yaw): + """ + Converts Euler angles (roll, pitch, yaw) to a rotation matrix. + The rotation matrix follows the z-y-x convention (yaw-pitch-roll). + + Args: + roll, pitch, yaw: Euler angles in radians + + Returns: + 3x3 rotation matrix + """ + # Compute individual rotation matrices + R_z = np.array([ + [np.cos(yaw), -np.sin(yaw), 0], + [np.sin(yaw), np.cos(yaw), 0], + [0, 0, 1] + ]) + + R_y = np.array([ + [np.cos(pitch), 0, np.sin(pitch)], + [0, 1, 0 ], + [-np.sin(pitch), 0, np.cos(pitch)] + ]) + + R_x = np.array([ + [1, 0, 0 ], + [0, np.cos(roll), -np.sin(roll)], + [0, np.sin(roll), np.cos(roll)] + ]) + + # Combined rotation matrix + R = np.dot(R_z, np.dot(R_y, R_x)) + return R + +def create_grid(rows, cols, length): + """ + Create a grid mesh for ground plane visualization. + + Args: + rows: Number of rows + cols: Number of columns + length: Grid cell size + + Returns: + Mesh object representing the grid + """ + rows, cols = rows+1, cols+1 # extra vertex in each direction + vertices = np.zeros([rows * cols, 3]) + edges = [] + for i in range(rows): + for j in range(cols): + vertices[i * cols + j] = [ + i * length - (rows - 1) * length / 2, + j * length - (cols - 1) * length / 2, + 0. + ] + if i != 0: + edges.append((cols * (i - 1) + j, cols * i + j)) + if j != 0: + edges.append((cols * i + j - 1, cols * i + j)) + return Mesh(vertices, np.array(edges)) + +def create_path(vertices, loop=False): + """ + Create a path mesh connecting vertices in sequence. + + Args: + vertices: Array of 3D points to connect + loop: Whether to connect last point back to first + + Returns: + Mesh object representing the path + """ + edges = [(i, i+1) for i in range(len(vertices)-1)] + if loop: + edges.append((0, len(vertices)-1)) + return Mesh(np.array(vertices), np.array(edges)) + +def create_circle(r, px, py, pz, num=20, angle_x=0, angle_y=0, angle_z=0): + """ + Create a circular mesh (used for propellers). + + Args: + r: Radius of circle + px, py, pz: Center position + num: Number of vertices around circle + angle_x, angle_y, angle_z: Rotation angles + + Returns: + Mesh object representing the circle + """ + vertices = np.array([[ + r * np.cos(i * 2 * np.pi / num), + r * np.sin(i * 2 * np.pi / num), + 0 + ] for i in range(num)]) + + R = euler_to_rotation_matrix(0, angle_y, angle_z) + transform_from_ENU_to_NED = np.array([[0, 1, 0], [1, 0, 0], [0, 0, -1]]) + + R = transform_from_ENU_to_NED @ R + + vertices = (R @ vertices.T).T + vertices += np.array([px, py, pz]) + + return create_path(vertices, loop=True) + +def create_circle_oriented(r, px, py, pz, normal, num=20): + """ + Create a circular mesh perpendicular to a given normal vector. + + Args: + r: Radius of circle + px, py, pz: Center position + normal: 3-vector; the circle's plane is perpendicular to this (the + disk's normal will equal this direction, normalized). + num: Number of vertices around circle + + Returns: + Mesh object representing the circle + """ + n = np.asarray(normal, dtype=float) + nlen = np.linalg.norm(n) + if nlen < 1e-9: + n = np.array([0.0, 0.0, 1.0]) + else: + n = n / nlen + + # Pick a reference axis that isn't parallel to the normal + ref = np.array([0.0, 0.0, 1.0]) if abs(n[2]) < 0.9 else np.array([1.0, 0.0, 0.0]) + u = np.cross(ref, n) + u /= np.linalg.norm(u) + v = np.cross(n, u) + + angles = np.arange(num) * (2 * np.pi / num) + vertices = (np.outer(np.cos(angles), u) + np.outer(np.sin(angles), v)) * r + vertices += np.array([px, py, pz]) + + return create_path(vertices, loop=True) + +def group(mesh_list): + """ + Combine multiple meshes into a single mesh. + + Args: + mesh_list: List of Mesh objects to combine + + Returns: + Combined Mesh object + """ + vertices = np.concatenate([ + mesh.vertices for mesh in mesh_list + ]) + index_shifts = np.cumsum( + [0] + [len(mesh.vertices) for mesh in mesh_list][:-1] + ) + edges = np.concatenate([ + mesh.edges + shift for (mesh, shift) in zip(mesh_list, index_shifts) + ]) + return Mesh(vertices, edges) + +def create_drone(propellers, box_size=[0.2,0.2,0.2], prop_radius=0.0254, scale=0.5, motor_colors=None): + """ + Create a complete drone mesh from propeller configuration. + + Args: + propellers: List of propeller dictionaries, each containing: + - "loc": [x, y, z] position in body frame (meters) + - "dir": [x, y, z, rotation] thrust direction and spin direction + - "propsize": propeller size in inches (optional, not used for visualization) + box_size: [width, depth, height] of central body + prop_radius: Radius of propeller circles + scale: Overall scale factor + + Returns: + tuple: (drone_mesh, force_objects) + drone_mesh: Complete Mesh object for the drone + force_objects: List of Force objects for thrust visualization + """ + + box_size = np.array(box_size) * scale + prop_radius *= scale + + # Create central body box + bot_box = create_path(np.array([ + [ box_size[0]/2, box_size[1]/2, box_size[2]/2], + [-box_size[0]/2, box_size[1]/2, box_size[2]/2], + [-box_size[0]/2, -box_size[1]/2, box_size[2]/2], + [ box_size[0]/2, -box_size[1]/2, box_size[2]/2], + ]), loop=True) + + top_box = create_path(np.array([ + [ box_size[0]/2, box_size[1]/2, -box_size[2]/2], + [-box_size[0]/2, box_size[1]/2, -box_size[2]/2], + [-box_size[0]/2, -box_size[1]/2, -box_size[2]/2], + [ box_size[0]/2, -box_size[1]/2, -box_size[2]/2], + ]), loop=True) + + # Create vertical edges connecting top and bottom + box_side_line1 = create_path(np.array([ + [ box_size[0]/2, box_size[1]/2, box_size[2]/2], + [ box_size[0]/2, box_size[1]/2,-box_size[2]/2], + ])) + + box_side_line2 = create_path(np.array([ + [-box_size[0]/2, box_size[1]/2, box_size[2]/2], + [-box_size[0]/2, box_size[1]/2,-box_size[2]/2], + ])) + + box_side_line3 = create_path(np.array([ + [-box_size[0]/2, -box_size[1]/2, box_size[2]/2], + [-box_size[0]/2, -box_size[1]/2,-box_size[2]/2], + ])) + + box_side_line4 = create_path(np.array([ + [ box_size[0]/2, -box_size[1]/2, box_size[2]/2], + [ box_size[0]/2, -box_size[1]/2,-box_size[2]/2], + ])) + + # Start with central body components + drawings = [bot_box, top_box, box_side_line1, box_side_line2, box_side_line3, box_side_line4] + num_body_meshes = len(drawings) + centres = [] + + # Create arms and propellers based on propeller configuration + for prop in propellers: + # Get propeller location and direction directly + loc = np.array(prop["loc"]) * scale + x, y, z = loc[0], loc[1], loc[2] + + # Motor thrust direction (body frame, NED). The propeller disk's normal + # equals this direction, so the disk lies perpendicular to the thrust. + motor_dir = np.array(prop["dir"][:3], dtype=float) + + # Create propeller disk perpendicular to thrust direction + circle = create_circle_oriented(prop_radius, x, y, z, normal=motor_dir, num=20) + # Create arm line from center to propeller + arm_line = create_path(np.array([[0, 0, 0], [x, y, z]])) + + drawings.append(circle) + drawings.append(arm_line) + centres.append([x, y, z]) + + # Combine all mesh components + drone = group(drawings) + + # Per-edge colors: body stays default, each propeller's circle + arm get its motor color. + # Matches the edge order produced by group() above. + if motor_colors is not None: + edge_colors = [] + for m in drawings[:num_body_meshes]: + edge_colors.extend([None] * len(m.edges)) + prop_drawings = drawings[num_body_meshes:] + for prop_idx in range(len(propellers)): + color = motor_colors[prop_idx % len(motor_colors)] + circle = prop_drawings[2 * prop_idx] + arm_line = prop_drawings[2 * prop_idx + 1] + edge_colors.extend([color] * len(circle.edges)) + edge_colors.extend([color] * len(arm_line.edges)) + drone.edge_colors = edge_colors + + # Add propeller centers as additional vertices for force attachment + drone.vertices = np.concatenate([ + drone.vertices, + np.array(centres) # centers of the circles + ]) + + # Create force objects at each propeller location. Each force carries the + # motor's thrust direction (body frame) and color, so the arrow points the + # right way for canted motors and matches the rotor's color. + forces = [] + for v, prop in zip(drone.vertices[-len(propellers):], propellers): + f = Force(v) + f.body_dir = np.array(prop["dir"][:3], dtype=float) + forces.append(f) + if motor_colors is not None: + for i, f in enumerate(forces): + f.color = motor_colors[i % len(motor_colors)] + + return drone, forces + +def set_thrust(drone, forces, T, base_len=0.0): + """ + Update force arrows to represent per-motor thrust direction and magnitude. + + Each Force uses its own body-frame direction if available, so canted motors + point correctly. ``base_len`` adds a small always-on length so the direction + stays visible even at low thrust. + + Args: + drone: Drone mesh object (for orientation) + forces: List of Force objects + T: Array of thrust magnitudes for each motor + base_len: Minimum arrow length added to every non-skipped motor + """ + R = rotation_matrix(drone.theta) + num_forces = len(forces) + num_thrusts = len(T) if hasattr(T, '__len__') else 1 + num_motors = min(num_forces, num_thrusts) + + for i in range(num_motors): + length = T[i] + base_len + if forces[i].body_dir is not None: + forces[i].F = length * (R @ forces[i].body_dir) + else: + forces[i].F = -length * R[:, 2] + + for i in range(num_motors, num_forces): + forces[i].F = np.zeros(3) + diff --git a/src/ariel/visualisation/drone/graphics_3d.py b/src/ariel/visualisation/drone/graphics_3d.py new file mode 100644 index 000000000..4420fc257 --- /dev/null +++ b/src/ariel/visualisation/drone/graphics_3d.py @@ -0,0 +1,260 @@ +""" +3D Graphics Engine for Drone Visualization + +This module provides the core 3D graphics infrastructure including camera controls, +mesh representation, and force visualization for drone simulation. + +Classes: + Camera: 3D camera with projection and mouse controls + Mesh: 3D mesh representation with drawing capabilities + Force: Force vector visualization + +Global Variables: + dragging: Mouse drag state for camera control + xi, yi: Mouse position tracking +""" + +import numpy as np +import cv2 + +# Global variables for mouse interaction +dragging = False +xi, yi = -1, -1 + +def rotation_matrix(theta): + """ + Calculate rotation matrix given euler angles. + + Args: + theta: Array of [roll, pitch, yaw] angles in radians + + Returns: + 3x3 rotation matrix + """ + R_x = np.array([[1, 0, 0], + [0, np.cos(theta[0]), -np.sin(theta[0])], + [0, np.sin(theta[0]), np.cos(theta[0])] + ]) + R_y = np.array([[np.cos(theta[1]), 0, np.sin(theta[1])], + [0, 1, 0], + [-np.sin(theta[1]), 0, np.cos(theta[1])] + ]) + R_z = np.array([[np.cos(theta[2]), -np.sin(theta[2]), 0], + [np.sin(theta[2]), np.cos(theta[2]), 0], + [0, 0, 1] + ]) + R = np.dot(R_z, np.dot(R_y, R_x)) + return R + +class Camera: + """ + 3D camera with projection and interactive mouse controls. + + Provides 3D to 2D projection, mouse-based rotation and zoom, + and camera positioning relative to a center point. + """ + + def __init__(self, pos, theta, cameraMatrix, distCoeffs): + """ + Initialize camera. + + Args: + pos: Initial camera position in world frame + theta: Initial Euler angles [roll, pitch, yaw] + cameraMatrix: OpenCV camera intrinsic matrix + distCoeffs: OpenCV distortion coefficients + """ + # pose + self.pos = pos # wrt world frame + self.theta = theta # Euler angles: roll pitch yaw + self.rMat = rotation_matrix(theta) + + self.center = np.zeros(3) # camera rotates around center + self.r = np.array([-8., 0., 0.]) + + # intrinsic camera parameters + self.cameraMatrix = cameraMatrix + self.distCoeffs = distCoeffs + + def set_center(self, vector): + """Set the center point that the camera rotates around.""" + self.center = vector + self.pos = np.dot(self.rMat, self.r) + self.center + + def rotate(self, theta): + """ + Rotate camera by given angles. + + Args: + theta: [roll, pitch, yaw] rotation increments + """ + self.theta += theta + self.rMat = rotation_matrix(self.theta) + self.pos = np.dot(self.rMat, self.r) + self.center + + def zoom(self, scl): + """ + Zoom camera by scaling distance to center. + + Args: + scl: Scale factor (>1 zoom out, <1 zoom in) + """ + self.r *= scl + self.pos = self.rMat @ self.r + self.center + + def project(self, points): + """ + Project 3D points to 2D camera image. + + Args: + points: Nx3 array of 3D points + + Returns: + tuple: (projected_points, in_frame_mask) + projected_points: Nx2 array of 2D pixel coordinates + in_frame_mask: Boolean array indicating which points are visible + """ + # points in frame (in front of the camera) given by a boolean array + in_frame = np.dot(points - self.pos, self.rMat[:, 0]) > 0.01 + + # x-axis is used as projection axis + M = np.dot(self.rMat, np.array([[0, 0, 1], [1, 0, 0], [0, 1, 0]])) + + tvec = -np.dot(np.transpose(M), self.pos) + rvec = cv2.Rodrigues(np.transpose(M))[0] + + projected_points = cv2.projectPoints(points, rvec, tvec, self.cameraMatrix, self.distCoeffs)[0].astype(np.int64) + return projected_points, in_frame + + def mouse_control(self, event, x, y, flags, params): + """ + Handle mouse events for interactive camera control. + + Args: + event: OpenCV mouse event type + x, y: Mouse coordinates + flags: Mouse event flags + params: Additional parameters (unused) + """ + global xi, yi, dragging + if event == cv2.EVENT_LBUTTONDOWN: + dragging = True + xi, yi = x, y + elif event == cv2.EVENT_MOUSEMOVE: + if dragging: + yaw = 2*np.pi * (x - xi) / 1536 + pitch = -np.pi * (y - yi) / 864 + self.rotate([0, pitch, yaw]) + xi, yi = x, y + elif event == cv2.EVENT_LBUTTONUP: + dragging = False + +class Mesh: + """ + 3D mesh representation with drawing capabilities. + + Represents a 3D object as vertices and edges that can be + transformed and rendered to a 2D image. + """ + + def __init__(self, vertices, edges): + """ + Initialize mesh. + + Args: + vertices: Nx3 array of 3D vertex positions + edges: Mx2 array of edge indices connecting vertices + """ + self.vertices = vertices + self.edges = edges + self.pos = np.array([0., 0., 0.]) + self.theta = np.array([0., 0., 0.]) + self.edge_colors = None + + def draw(self, img, cam, color=(100, 100, 100), pt=1, arrow=False): + """ + Draw mesh to image using camera projection. + + Args: + img: Image to draw on + cam: Camera object for projection + color: RGB color tuple + pt: Line thickness + arrow: Whether to draw as arrows + """ + pvertices, in_frame = cam.project(self.vertices) + edge_colors = self.edge_colors + for i, edge in enumerate(self.edges): + if in_frame[edge[0]] and in_frame[edge[1]]: + pt1 = tuple(pvertices[edge[0]][0]) + pt2 = tuple(pvertices[edge[1]][0]) + c = color + if edge_colors is not None and edge_colors[i] is not None: + c = edge_colors[i] + if arrow: + cv2.arrowedLine(img, pt1, pt2, c, pt) + else: + cv2.line(img, pt1, pt2, c, pt) + + def translate(self, vector): + """ + Translate mesh by given vector. + + Args: + vector: 3D translation vector + """ + self.pos += vector + for vertex in self.vertices: + vertex += vector + + def rotate(self, theta): + """ + Rotate mesh to given orientation. + + Args: + theta: Target Euler angles [roll, pitch, yaw] + """ + M1 = np.transpose(rotation_matrix(self.theta)) + M2 = rotation_matrix(theta) + R = np.dot(M2, M1) + for vertex in self.vertices: + delta = self.pos + np.dot(R, vertex - self.pos) - vertex + vertex += delta + self.theta = theta + +class Force: + """ + Force vector visualization. + + Represents and visualizes force vectors as arrows in 3D space. + """ + + def __init__(self, vertex): + """ + Initialize force at given position. + + Args: + vertex: 3D position where force is applied + """ + self.vertex = vertex + self.F = np.array([0., 0., 0.]) + self.body_dir = None # Unit thrust direction in drone body frame + self.color = None # BGR tuple, overrides caller's default draw color + + def draw(self, img, cam, color=(0, 0, 255), pt=1): + """ + Draw force vector as arrow. + + Args: + img: Image to draw on + cam: Camera object for projection + color: RGB color tuple + pt: Line thickness + """ + pt1, in_frame1 = cam.project(np.array([self.vertex])) + pt2, in_frame2 = cam.project(np.array([self.vertex + self.F])) + pt1 = tuple(pt1[0][0]) + pt2 = tuple(pt2[0][0]) + # check if pt1 or pt2 are in frame + if in_frame1[0] and in_frame2[0]: + cv2.arrowedLine(img, pt1, pt2, color, pt) \ No newline at end of file From 8554ef195f14fe4aab74a1fec63847274b04a0e8 Mon Sep 17 00:00:00 2001 From: A-lamo <2727043@student.vu.nl> Date: Mon, 18 May 2026 19:21:02 +0200 Subject: [PATCH 04/27] Removing redundant examples. --- .../{9_repair_demo.py => 10_repair_demo.py} | 0 examples/d_drones/1_hover_evolution.py | 193 --------- examples/d_drones/1_run_evolution.py | 226 +++++++---- examples/d_drones/2_drone_evolution.py | 210 ---------- ..._neat_evolution.py => 2_neat_evolution.py} | 0 examples/d_drones/2_simulate_lee.py | 172 -------- ...simulate_lee_ctrl.py => 3_simulate_lee.py} | 0 examples/d_drones/3_tune_lee.py | 104 ----- ...controller.py => 4_tune_lee_controller.py} | 0 examples/d_drones/4_visualize_genome.py | 105 ----- .../d_drones/5_record_best_drone_video.py | 367 ------------------ ...est_drone.py => 5_visualize_best_drone.py} | 0 .../{5_make_video.py => 7_make_video.py} | 0 ...ualize_genome.py => 8_visualize_genome.py} | 0 .../{8_generate_stl.py => 9_generate_stl.py} | 0 15 files changed, 154 insertions(+), 1223 deletions(-) rename examples/d_drones/{9_repair_demo.py => 10_repair_demo.py} (100%) delete mode 100644 examples/d_drones/1_hover_evolution.py delete mode 100644 examples/d_drones/2_drone_evolution.py rename examples/d_drones/{3_neat_evolution.py => 2_neat_evolution.py} (100%) delete mode 100644 examples/d_drones/2_simulate_lee.py rename examples/d_drones/{4_simulate_lee_ctrl.py => 3_simulate_lee.py} (100%) delete mode 100644 examples/d_drones/3_tune_lee.py rename examples/d_drones/{5_tune_lee_controller.py => 4_tune_lee_controller.py} (100%) delete mode 100644 examples/d_drones/4_visualize_genome.py delete mode 100644 examples/d_drones/5_record_best_drone_video.py rename examples/d_drones/{4_visualize_best_drone.py => 5_visualize_best_drone.py} (100%) rename examples/d_drones/{5_make_video.py => 7_make_video.py} (100%) rename examples/d_drones/{7_visualize_genome.py => 8_visualize_genome.py} (100%) rename examples/d_drones/{8_generate_stl.py => 9_generate_stl.py} (100%) diff --git a/examples/d_drones/9_repair_demo.py b/examples/d_drones/10_repair_demo.py similarity index 100% rename from examples/d_drones/9_repair_demo.py rename to examples/d_drones/10_repair_demo.py diff --git a/examples/d_drones/1_hover_evolution.py b/examples/d_drones/1_hover_evolution.py deleted file mode 100644 index fc9d53f57..000000000 --- a/examples/d_drones/1_hover_evolution.py +++ /dev/null @@ -1,193 +0,0 @@ -"""Drone morphology evolution using ARIEL's EA engine and airevolve's drone simulator. - -Evolves drone arm configurations (number, position, orientation, spin direction) -to maximise hover quality (continuous_hover_fitness ∈ [0, 3]) using a mu+lambda -strategy with NEAT-style crossover. - -The simulation backend is airevolve's custom ODE dynamics — no MuJoCo involved. -Genomes are persisted in SQLite via ARIEL's EA engine. - -Run: - python examples/d_drones/1_hover_evolution.py - python examples/d_drones/1_hover_evolution.py --pop 30 --budget 50 --workers 8 - python examples/d_drones/1_hover_evolution.py --fitness gate --workers 4 -""" - -from __future__ import annotations - -import argparse -import os -from pathlib import Path - -import numpy as np -from rich.console import Console - -# BLAS thread caps must be set before numpy/torch are imported in sub-processes. -os.environ.setdefault("OMP_NUM_THREADS", "1") -os.environ.setdefault("OPENBLAS_NUM_THREADS", "1") -os.environ.setdefault("MKL_NUM_THREADS", "1") - -from ariel.ec.drone.genome_handlers.spherical_angular_genome_handler import ( - SphericalAngularDroneGenomeHandler, -) -from ariel.body_phenotypes.drone import ( - crossover_drones, - deserialize_genome, - evaluate_drones, - initialize_drones, - mutate_drones, - parent_tag, - truncation_select, -) -from ariel.ec import EA, EASettings, Individual, Population -from ariel.ec.archive import Archive - -console = Console() - -# --------------------------------------------------------------------------- -# CLI -# --------------------------------------------------------------------------- - -parser = argparse.ArgumentParser(description="Drone hover-quality evolution") -parser.add_argument("--pop", type=int, default=50, help="Population size (mu)") -parser.add_argument("--budget", type=int, default=50, help="Number of EA generations") -parser.add_argument("--workers", type=int, default=1, help="Parallel evaluation workers") -parser.add_argument("--min-arms", type=int, default=3, help="Minimum number of rotor arms") -parser.add_argument("--max-arms", type=int, default=8, help="Maximum number of rotor arms") -parser.add_argument( - "--fitness", - choices=["pure_hover", "edit_distance", "zero"], - default="pure_hover", - help="Fitness function (pure_hover: analytical hover quality [0,3])", -) -parser.add_argument("--seed", type=int, default=42) -parser.add_argument("--viz", action="store_true", - help="Simulate best individual after evolution and save hover video") -parser.add_argument("--viz-duration", type=float, default=10.0, - help="Hover video duration in seconds (default 10)") -args = parser.parse_args() - -POP_SIZE: int = args.pop -BUDGET: int = args.budget -N_WORKERS: int = args.workers -FITNESS_MODE: str = args.fitness - -DATA = Path.cwd() / "__data__" / "drone_hover_evolution" -DATA.mkdir(parents=True, exist_ok=True) - -np.random.seed(args.seed) - -# --------------------------------------------------------------------------- -# Genome search space -# --------------------------------------------------------------------------- -# Columns: [magnitude, arm_azimuth, arm_elevation, motor_azimuth, motor_pitch, spin_dir] - -PARAMETER_LIMITS = np.array([ - [0.055, 0.17], # arm magnitude (metres from centre) - [-np.pi, np.pi], # arm azimuth (rad) - [-np.pi / 2, np.pi / 2], # arm elevation above horizontal (rad) - [-np.pi, np.pi], # motor disc azimuth (rad) - [-np.pi, np.pi], # motor disc pitch (rad) - [0, 1], # propeller spin direction (binary) -]) - -template_handler = SphericalAngularDroneGenomeHandler( - min_max_narms=(args.min_arms, args.max_arms), - parameter_limits=PARAMETER_LIMITS, - append_arm_chance=0.1, - bilateral_plane_for_symmetry=None, - repair=False, - rnd=np.random.default_rng(args.seed), -) - -# --------------------------------------------------------------------------- -# Pre-loop: build and evaluate the initial population outside the EA loop so -# that parent_tag and crossover_drones have valid fitnesses from generation 1. -# --------------------------------------------------------------------------- - -console.rule("[bold blue]Drone Hover Evolution") -console.log(f"pop={POP_SIZE} budget={BUDGET} workers={N_WORKERS} fitness={FITNESS_MODE}") -console.log(f"arms=[{args.min_arms}, {args.max_arms}] db={DATA / 'database.db'}") - -initial_pop = Population([Individual() for _ in range(POP_SIZE)]) - -init_op = initialize_drones(template_handler=template_handler) -eval_op = evaluate_drones(fitness_mode=FITNESS_MODE, n_workers=N_WORKERS) - -console.log("Initializing and evaluating initial population …") -initial_pop = init_op(initial_pop) -initial_pop = eval_op(initial_pop) - -best_init = initial_pop.best(sort="max", attribute="fitness_")[0] -console.log(f"Initial population best fitness: {best_init.fitness_:.4f}") - -# --------------------------------------------------------------------------- -# EA loop: mu+lambda strategy with NEAT crossover -# -# Each generation: -# 1. tag top-POP_SIZE alive individuals as parents -# 2. crossover: one child per parent pair (POP_SIZE // 2 offspring) -# 3. mutate: perturb all unevaluated offspring -# 4. evaluate: run drone physics for unevaluated individuals only -# 5. select: keep best POP_SIZE from parents + offspring (plus strategy) -# --------------------------------------------------------------------------- - -generation_ops = [ - parent_tag(n=POP_SIZE), - crossover_drones(template_handler=template_handler), - mutate_drones(template_handler=template_handler), - evaluate_drones(fitness_mode=FITNESS_MODE, n_workers=N_WORKERS), - truncation_select(n=POP_SIZE), -] - -ea = EA( - population=initial_pop, - operations=generation_ops, - num_steps=BUDGET, - db_file_path=DATA / "database.db", - db_handling="delete", -) - -console.rule("[bold green]Running EA") -ea.run() - -if args.viz: - import sys; sys.path.insert(0, str(Path(__file__).parent)) - from _viz_best import viz_best_from_db - viz_best_from_db(DATA / "database.db", DATA / "best_hover.mp4", duration=args.viz_duration) - -# --------------------------------------------------------------------------- -# Post-hoc analysis via Archive -# --------------------------------------------------------------------------- - -archive = Archive(DATA / "database.db") - -console.rule("[bold yellow]Results") -console.log(f"Archive size: {archive.size} evaluated individuals") -console.log(f"Generation range: {archive.generation_range}") - -stats = archive.fitness_stats() -console.log( - f"Fitness — min: {stats['min']:.4f} mean: {stats['mean']:.4f} " - f"max: {stats['max']:.4f} std: {stats['std']:.4f}" -) - -best = archive.best_individual(fitness_mode="max") -console.rule("[bold cyan]Best Individual") -console.log(f" id={best.id} fitness={best.fitness_:.4f} " - f"born={best.time_of_birth} died={best.time_of_death}") - -genome = deserialize_genome(best.genotype) -valid_mask = ~np.isnan(genome.arms[:, 0]) -valid_arms = genome.arms[valid_mask] -console.log(f" active arms: {int(valid_mask.sum())} / {genome.arms.shape[0]}") -console.log(" arm layout (magnitude | azimuth° | elevation° | motor_az° | motor_pitch° | spin):") -for i, arm in enumerate(valid_arms): - mag, az, el, maz, mpitch, spin = arm - console.log( - f" arm {i}: mag={mag:.3f}m az={np.degrees(az):.1f}° " - f"el={np.degrees(el):.1f}° motor_az={np.degrees(maz):.1f}° " - f"motor_pitch={np.degrees(mpitch):.1f}° spin={'CW' if spin > 0.5 else 'CCW'}" - ) - -console.rule("[bold]Done") diff --git a/examples/d_drones/1_run_evolution.py b/examples/d_drones/1_run_evolution.py index ff11ab8ba..5662063aa 100644 --- a/examples/d_drones/1_run_evolution.py +++ b/examples/d_drones/1_run_evolution.py @@ -1,21 +1,14 @@ -"""Drone morphology evolution using ARIEL's EA engine. +"""Drone morphology evolution — spherical genome, configurable fitness + strategy. -Evolves drone designs encoded as spherical-coordinate arm arrays, evaluated -with ``continuous_hover_fitness`` (fast, analytical) or ``UnifiedFitness`` -for gate/edit-distance modes. +Ports airevolve's run_evolution.py to ARIEL's EA engine (SQLite persistence, +Archive post-hoc analysis). Supports the spherical arm encoding and three +fitness modes via mu+lambda or mu,lambda selection. -Quick start: - # Pure-hover fitness (CPU, fast smoke test): - uv run examples/d_drones/1_run_evolution.py \\ - --fitness pure_hover --population-size 20 --generations 10 - - # Gate fitness with 4 workers: - uv run examples/d_drones/1_run_evolution.py \\ - --fitness gate --population-size 50 --generations 100 --n-workers 4 - - # Edit-distance diversity measure: - uv run examples/d_drones/1_run_evolution.py \\ - --fitness edit_distance --population-size 30 --generations 50 +Run: + python examples/d_drones/2_drone_evolution.py + python examples/d_drones/2_drone_evolution.py --fitness pure_hover --strategy plus + python examples/d_drones/2_drone_evolution.py --fitness edit_distance --workers 8 + python examples/d_drones/2_drone_evolution.py --pop 20 --budget 30 --min-arms 4 --max-arms 6 """ from __future__ import annotations @@ -24,105 +17,194 @@ import os from pathlib import Path +import numpy as np +from rich.console import Console + os.environ.setdefault("OMP_NUM_THREADS", "1") os.environ.setdefault("OPENBLAS_NUM_THREADS", "1") os.environ.setdefault("MKL_NUM_THREADS", "1") -import numpy as np - -from ariel.ec.ea import EA, EASettings -from ariel.ec.population import Population -from ariel.body_phenotypes.drone.operations import ( - initialize_drones, +from ariel.ec.drone.genome_handlers.spherical_angular_genome_handler import ( + SphericalAngularDroneGenomeHandler, +) +from ariel.body_phenotypes.drone import ( crossover_drones, - mutate_drones, + deserialize_genome, evaluate_drones, + initialize_drones, + mutate_drones, parent_tag, truncation_select, ) -from ariel.ec.drone.genome_handlers.spherical_angular_genome_handler import ( - SphericalAngularDroneGenomeHandler, -) +from ariel.ec import EA, Individual, Population +from ariel.ec.archive import Archive + +console = Console() # --------------------------------------------------------------------------- # CLI # --------------------------------------------------------------------------- -parser = argparse.ArgumentParser(description="Drone morphology evolution") -parser.add_argument("--population-size", type=int, default=50, - help="Number of individuals in the population (default 50)") -parser.add_argument("--generations", type=int, default=100, - help="Number of EA generations (default 100)") -parser.add_argument("--fitness", - choices=["pure_hover", "gate", "edit_distance", "zero"], - default="pure_hover", - help="Fitness mode (default pure_hover)") -parser.add_argument("--n-workers", type=int, default=1, - help="Parallel evaluation workers (default 1)") -parser.add_argument("--seed", type=int, default=None, - help="Random seed for reproducibility") -parser.add_argument("--save-dir", default="__data__/drone_evolution", - help="Output directory (default __data__/drone_evolution)") +parser = argparse.ArgumentParser(description="Drone morphology evolution (spherical genome)") +parser.add_argument("--pop", type=int, default=20, help="Population size (mu)") +parser.add_argument("--budget", type=int, default=50, help="Number of EA generations") +parser.add_argument("--workers", type=int, default=1, help="Parallel evaluation workers") +parser.add_argument("--min-arms", type=int, default=4, help="Minimum rotor arms") +parser.add_argument("--max-arms", type=int, default=6, help="Maximum rotor arms") +parser.add_argument("--append-arm-chance", type=float, default=0.1, + help="Probability of adding an arm during mutation (default 0.1)") +parser.add_argument( + "--fitness", + choices=["pure_hover", "edit_distance", "zero"], + default="pure_hover", + help="Fitness function: pure_hover (analytical hover quality [0,3]), " + "edit_distance (edit distance from target), zero (always 0)", +) +parser.add_argument( + "--strategy", + choices=["plus", "comma"], + default="plus", + help="Selection strategy: plus (mu+lambda, parents survive) or comma (mu,lambda)", +) +parser.add_argument("--seed", type=int, default=42) parser.add_argument("--viz", action="store_true", help="Simulate best individual after evolution and save hover video") parser.add_argument("--viz-duration", type=float, default=10.0, help="Hover video duration in seconds (default 10)") args = parser.parse_args() -if args.seed is not None: - np.random.seed(args.seed) - rng = np.random.default_rng(args.seed) -else: - rng = np.random.default_rng() +POP_SIZE: int = args.pop +BUDGET: int = args.budget +N_WORKERS: int = args.workers +FITNESS_MODE: str = args.fitness +STRATEGY: str = args.strategy -save_dir = Path(args.save_dir) -save_dir.mkdir(parents=True, exist_ok=True) +DATA = Path.cwd() / "__data__" / "drone_evolution" +DATA.mkdir(parents=True, exist_ok=True) -print(f"=== Drone Evolution ===") -print(f" fitness={args.fitness} pop={args.population_size} gens={args.generations}" - f" workers={args.n_workers} seed={args.seed}") -print(f" save_dir={save_dir}") +np.random.seed(args.seed) # --------------------------------------------------------------------------- -# Genome handler (template for all operations) +# Genome search space # --------------------------------------------------------------------------- -handler = SphericalAngularDroneGenomeHandler( - min_max_narms=(3, 8), - append_arm_chance=0.1, - rnd=rng, +PARAMETER_LIMITS = np.array([ + [0.055, 0.17], # arm magnitude (metres) + [-np.pi, np.pi], # arm azimuth (rad) + [-np.pi / 2, np.pi / 2], # arm elevation (rad) + [-np.pi, np.pi], # motor disc azimuth (rad) + [-np.pi, np.pi], # motor disc pitch (rad) + [0, 1], # propeller spin direction (binary) +]) + +template_handler = SphericalAngularDroneGenomeHandler( + min_max_narms=(args.min_arms, args.max_arms), + parameter_limits=PARAMETER_LIMITS, + append_arm_chance=args.append_arm_chance, + bilateral_plane_for_symmetry=None, + repair=False, + rnd=np.random.default_rng(args.seed), ) # --------------------------------------------------------------------------- -# EA operations +# Banner # --------------------------------------------------------------------------- -init_op = initialize_drones(template_handler=handler) -eval_op = evaluate_drones(fitness_mode=args.fitness, n_workers=args.n_workers) -tag_op = parent_tag(n=args.population_size) -xover_op = crossover_drones(template_handler=handler) -mutate_op = mutate_drones(template_handler=handler) -select_op = truncation_select(n=args.population_size) +console.rule("[bold blue]Drone Evolution") +console.log( + f"pop={POP_SIZE} budget={BUDGET} workers={N_WORKERS} " + f"fitness={FITNESS_MODE} strategy={STRATEGY}" +) +console.log(f"arms=[{args.min_arms}, {args.max_arms}] db={DATA / 'database.db'}") -from ariel.ec.individual import Individual +# --------------------------------------------------------------------------- +# Initial population +# --------------------------------------------------------------------------- -initial_pop = Population([Individual() for _ in range(args.population_size)]) +initial_pop = Population([Individual() for _ in range(POP_SIZE)]) + +init_op = initialize_drones(template_handler=template_handler) +eval_op = evaluate_drones(fitness_mode=FITNESS_MODE, n_workers=N_WORKERS) + +console.log("Initializing and evaluating initial population …") initial_pop = init_op(initial_pop) initial_pop = eval_op(initial_pop) +best_init = initial_pop.best(sort="max", attribute="fitness_")[0] +console.log(f"Initial best fitness: {best_init.fitness_:.4f}") + +# --------------------------------------------------------------------------- +# Generation ops +# --------------------------------------------------------------------------- +# For mu,lambda (comma) strategy the offspring pool size equals POP_SIZE, so +# the crossover step produces POP_SIZE//2 children and mutation adds nothing +# extra — truncation_select then picks strictly from offspring, discarding +# all parents. For mu+lambda (plus), parents survive alongside offspring. + +offspring_n = POP_SIZE if STRATEGY == "comma" else POP_SIZE // 2 + +generation_ops = [ + parent_tag(n=POP_SIZE), + crossover_drones(template_handler=template_handler), + mutate_drones(template_handler=template_handler), + evaluate_drones(fitness_mode=FITNESS_MODE, n_workers=N_WORKERS), + truncation_select(n=POP_SIZE), +] + ea = EA( population=initial_pop, - operations=[tag_op, xover_op, mutate_op, eval_op, select_op], - num_steps=args.generations, - db_file_path=save_dir / "evolution.db", + operations=generation_ops, + num_steps=BUDGET, + db_file_path=DATA / "database.db", db_handling="delete", ) -print("\nStarting evolution …") +# --------------------------------------------------------------------------- +# Run +# --------------------------------------------------------------------------- + +console.rule("[bold green]Running EA") ea.run() -print(f"\nDone. Database saved to: {save_dir / 'evolution.db'}") if args.viz: import sys; sys.path.insert(0, str(Path(__file__).parent)) from _viz_best import viz_best_from_db - viz_best_from_db(save_dir / "evolution.db", save_dir / "best_hover.mp4", duration=args.viz_duration) + viz_best_from_db(DATA / "database.db", DATA / "best_hover.mp4", duration=args.viz_duration) + +# --------------------------------------------------------------------------- +# Post-hoc analysis +# --------------------------------------------------------------------------- + +archive = Archive(DATA / "database.db") + +console.rule("[bold yellow]Results") +console.log(f"Archive size: {archive.size} evaluated individuals") +console.log(f"Generation range: {archive.generation_range}") + +stats = archive.fitness_stats() +console.log( + f"Fitness — min: {stats['min']:.4f} mean: {stats['mean']:.4f} " + f"max: {stats['max']:.4f} std: {stats['std']:.4f}" +) + +best = archive.best_individual(fitness_mode="max") +console.rule("[bold cyan]Best Individual") +console.log( + f" id={best.id} fitness={best.fitness_:.4f} " + f"born={best.time_of_birth} died={best.time_of_death}" +) + +genome = deserialize_genome(best.genotype) +valid_mask = ~np.isnan(genome.arms[:, 0]) +valid_arms = genome.arms[valid_mask] +console.log(f" active arms: {int(valid_mask.sum())} / {genome.arms.shape[0]}") +console.log(" arm layout (magnitude | azimuth° | elevation° | motor_az° | motor_pitch° | spin):") +for i, arm in enumerate(valid_arms): + mag, az, el, maz, mpitch, spin = arm + console.log( + f" arm {i}: mag={mag:.3f}m az={np.degrees(az):.1f}° " + f"el={np.degrees(el):.1f}° motor_az={np.degrees(maz):.1f}° " + f"motor_pitch={np.degrees(mpitch):.1f}° spin={'CW' if spin > 0.5 else 'CCW'}" + ) + +console.rule("[bold]Done") diff --git a/examples/d_drones/2_drone_evolution.py b/examples/d_drones/2_drone_evolution.py deleted file mode 100644 index 5662063aa..000000000 --- a/examples/d_drones/2_drone_evolution.py +++ /dev/null @@ -1,210 +0,0 @@ -"""Drone morphology evolution — spherical genome, configurable fitness + strategy. - -Ports airevolve's run_evolution.py to ARIEL's EA engine (SQLite persistence, -Archive post-hoc analysis). Supports the spherical arm encoding and three -fitness modes via mu+lambda or mu,lambda selection. - -Run: - python examples/d_drones/2_drone_evolution.py - python examples/d_drones/2_drone_evolution.py --fitness pure_hover --strategy plus - python examples/d_drones/2_drone_evolution.py --fitness edit_distance --workers 8 - python examples/d_drones/2_drone_evolution.py --pop 20 --budget 30 --min-arms 4 --max-arms 6 -""" - -from __future__ import annotations - -import argparse -import os -from pathlib import Path - -import numpy as np -from rich.console import Console - -os.environ.setdefault("OMP_NUM_THREADS", "1") -os.environ.setdefault("OPENBLAS_NUM_THREADS", "1") -os.environ.setdefault("MKL_NUM_THREADS", "1") - -from ariel.ec.drone.genome_handlers.spherical_angular_genome_handler import ( - SphericalAngularDroneGenomeHandler, -) -from ariel.body_phenotypes.drone import ( - crossover_drones, - deserialize_genome, - evaluate_drones, - initialize_drones, - mutate_drones, - parent_tag, - truncation_select, -) -from ariel.ec import EA, Individual, Population -from ariel.ec.archive import Archive - -console = Console() - -# --------------------------------------------------------------------------- -# CLI -# --------------------------------------------------------------------------- - -parser = argparse.ArgumentParser(description="Drone morphology evolution (spherical genome)") -parser.add_argument("--pop", type=int, default=20, help="Population size (mu)") -parser.add_argument("--budget", type=int, default=50, help="Number of EA generations") -parser.add_argument("--workers", type=int, default=1, help="Parallel evaluation workers") -parser.add_argument("--min-arms", type=int, default=4, help="Minimum rotor arms") -parser.add_argument("--max-arms", type=int, default=6, help="Maximum rotor arms") -parser.add_argument("--append-arm-chance", type=float, default=0.1, - help="Probability of adding an arm during mutation (default 0.1)") -parser.add_argument( - "--fitness", - choices=["pure_hover", "edit_distance", "zero"], - default="pure_hover", - help="Fitness function: pure_hover (analytical hover quality [0,3]), " - "edit_distance (edit distance from target), zero (always 0)", -) -parser.add_argument( - "--strategy", - choices=["plus", "comma"], - default="plus", - help="Selection strategy: plus (mu+lambda, parents survive) or comma (mu,lambda)", -) -parser.add_argument("--seed", type=int, default=42) -parser.add_argument("--viz", action="store_true", - help="Simulate best individual after evolution and save hover video") -parser.add_argument("--viz-duration", type=float, default=10.0, - help="Hover video duration in seconds (default 10)") -args = parser.parse_args() - -POP_SIZE: int = args.pop -BUDGET: int = args.budget -N_WORKERS: int = args.workers -FITNESS_MODE: str = args.fitness -STRATEGY: str = args.strategy - -DATA = Path.cwd() / "__data__" / "drone_evolution" -DATA.mkdir(parents=True, exist_ok=True) - -np.random.seed(args.seed) - -# --------------------------------------------------------------------------- -# Genome search space -# --------------------------------------------------------------------------- - -PARAMETER_LIMITS = np.array([ - [0.055, 0.17], # arm magnitude (metres) - [-np.pi, np.pi], # arm azimuth (rad) - [-np.pi / 2, np.pi / 2], # arm elevation (rad) - [-np.pi, np.pi], # motor disc azimuth (rad) - [-np.pi, np.pi], # motor disc pitch (rad) - [0, 1], # propeller spin direction (binary) -]) - -template_handler = SphericalAngularDroneGenomeHandler( - min_max_narms=(args.min_arms, args.max_arms), - parameter_limits=PARAMETER_LIMITS, - append_arm_chance=args.append_arm_chance, - bilateral_plane_for_symmetry=None, - repair=False, - rnd=np.random.default_rng(args.seed), -) - -# --------------------------------------------------------------------------- -# Banner -# --------------------------------------------------------------------------- - -console.rule("[bold blue]Drone Evolution") -console.log( - f"pop={POP_SIZE} budget={BUDGET} workers={N_WORKERS} " - f"fitness={FITNESS_MODE} strategy={STRATEGY}" -) -console.log(f"arms=[{args.min_arms}, {args.max_arms}] db={DATA / 'database.db'}") - -# --------------------------------------------------------------------------- -# Initial population -# --------------------------------------------------------------------------- - -initial_pop = Population([Individual() for _ in range(POP_SIZE)]) - -init_op = initialize_drones(template_handler=template_handler) -eval_op = evaluate_drones(fitness_mode=FITNESS_MODE, n_workers=N_WORKERS) - -console.log("Initializing and evaluating initial population …") -initial_pop = init_op(initial_pop) -initial_pop = eval_op(initial_pop) - -best_init = initial_pop.best(sort="max", attribute="fitness_")[0] -console.log(f"Initial best fitness: {best_init.fitness_:.4f}") - -# --------------------------------------------------------------------------- -# Generation ops -# --------------------------------------------------------------------------- -# For mu,lambda (comma) strategy the offspring pool size equals POP_SIZE, so -# the crossover step produces POP_SIZE//2 children and mutation adds nothing -# extra — truncation_select then picks strictly from offspring, discarding -# all parents. For mu+lambda (plus), parents survive alongside offspring. - -offspring_n = POP_SIZE if STRATEGY == "comma" else POP_SIZE // 2 - -generation_ops = [ - parent_tag(n=POP_SIZE), - crossover_drones(template_handler=template_handler), - mutate_drones(template_handler=template_handler), - evaluate_drones(fitness_mode=FITNESS_MODE, n_workers=N_WORKERS), - truncation_select(n=POP_SIZE), -] - -ea = EA( - population=initial_pop, - operations=generation_ops, - num_steps=BUDGET, - db_file_path=DATA / "database.db", - db_handling="delete", -) - -# --------------------------------------------------------------------------- -# Run -# --------------------------------------------------------------------------- - -console.rule("[bold green]Running EA") -ea.run() - -if args.viz: - import sys; sys.path.insert(0, str(Path(__file__).parent)) - from _viz_best import viz_best_from_db - viz_best_from_db(DATA / "database.db", DATA / "best_hover.mp4", duration=args.viz_duration) - -# --------------------------------------------------------------------------- -# Post-hoc analysis -# --------------------------------------------------------------------------- - -archive = Archive(DATA / "database.db") - -console.rule("[bold yellow]Results") -console.log(f"Archive size: {archive.size} evaluated individuals") -console.log(f"Generation range: {archive.generation_range}") - -stats = archive.fitness_stats() -console.log( - f"Fitness — min: {stats['min']:.4f} mean: {stats['mean']:.4f} " - f"max: {stats['max']:.4f} std: {stats['std']:.4f}" -) - -best = archive.best_individual(fitness_mode="max") -console.rule("[bold cyan]Best Individual") -console.log( - f" id={best.id} fitness={best.fitness_:.4f} " - f"born={best.time_of_birth} died={best.time_of_death}" -) - -genome = deserialize_genome(best.genotype) -valid_mask = ~np.isnan(genome.arms[:, 0]) -valid_arms = genome.arms[valid_mask] -console.log(f" active arms: {int(valid_mask.sum())} / {genome.arms.shape[0]}") -console.log(" arm layout (magnitude | azimuth° | elevation° | motor_az° | motor_pitch° | spin):") -for i, arm in enumerate(valid_arms): - mag, az, el, maz, mpitch, spin = arm - console.log( - f" arm {i}: mag={mag:.3f}m az={np.degrees(az):.1f}° " - f"el={np.degrees(el):.1f}° motor_az={np.degrees(maz):.1f}° " - f"motor_pitch={np.degrees(mpitch):.1f}° spin={'CW' if spin > 0.5 else 'CCW'}" - ) - -console.rule("[bold]Done") diff --git a/examples/d_drones/3_neat_evolution.py b/examples/d_drones/2_neat_evolution.py similarity index 100% rename from examples/d_drones/3_neat_evolution.py rename to examples/d_drones/2_neat_evolution.py diff --git a/examples/d_drones/2_simulate_lee.py b/examples/d_drones/2_simulate_lee.py deleted file mode 100644 index e93b27ffe..000000000 --- a/examples/d_drones/2_simulate_lee.py +++ /dev/null @@ -1,172 +0,0 @@ -"""3D simulation of a drone with Lee Geometric Controller and B-spline gate trajectory. - -Mirrors src/airevolve/examples/simulation/run_3D_simulation_lee_ctrl.py -using ARIEL imports. - -Usage: - # Visualise with figure-8 gates (interactive animation): - uv run examples/d_drones/2_simulate_lee.py --gates figure8 - - # Headless with circle gates for 20 s: - uv run examples/d_drones/2_simulate_lee.py --gates circle --time 20 --no-viz - - # Load tuned controller from JSON produced by 3_tune_lee.py: - uv run examples/d_drones/2_simulate_lee.py \\ - --gates figure8 --bspline-config __data__/tuning/tuning_results.json - -Requires: matplotlib, numpy (bundled in the project's uv environment) -""" - -from __future__ import annotations - -import argparse -import json -import os -import sys -import time - -import numpy as np - -from ariel.simulation.drone import DroneSimulator, create_standard_propeller_config -from ariel.simulation.drone.drone_interface import DroneInterface -from ariel.simulation.drone.controllers.trajectory_generation.trajectory import Trajectory -from ariel.simulation.drone.controllers.trajectory_generation.bspline_gate_trajectory import ( - BSplineGateTrajectory, -) -from ariel.simulation.drone.controllers.utils.gate_configs import GATE_CONFIGS -import ariel.simulation.drone.controllers.utils as utils - -# Lee controller lives in the controllers sub-package (unchanged from airevolve) -try: - from airevolve.controllers.lee_control.lee_controller import LeeGeometricControl - from airevolve.controllers.utils.wind_model import Wind -except ImportError: - print("WARNING: airevolve.controllers.lee_control not available; " - "Lee controller simulation will not run.") - LeeGeometricControl = None - Wind = None - -# --------------------------------------------------------------------------- -# CLI -# --------------------------------------------------------------------------- - -parser = argparse.ArgumentParser(description="Lee Controller B-Spline Simulation") -parser.add_argument("--gates", choices=["figure8", "circle", "slalom", "backandforth"], - required=True, help="Gate configuration") -parser.add_argument("--bspline-config", default=None, - help="Path to tuning_results.json (optional)") -parser.add_argument("--time", type=float, default=20.0, - help="Simulation time in seconds (default 20)") -parser.add_argument("--dt", type=float, default=0.005, - help="Time step in seconds (default 0.005)") -parser.add_argument("--arm-length", type=float, default=0.07, - help="Arm length in metres (default 0.07)") -parser.add_argument("--prop-size", type=int, default=2, - help="Propeller size in inches (default 2)") -parser.add_argument("--no-viz", action="store_true", - help="Disable matplotlib animation") -parser.add_argument("--save", action="store_true", - help="Save animation to mp4") -args = parser.parse_args() - -if LeeGeometricControl is None: - sys.exit("Lee controller not available. Aborting.") - -# --------------------------------------------------------------------------- -# Drone -# --------------------------------------------------------------------------- - -ARM_LENGTH = args.arm_length -PROP_SIZE = args.prop_size - -propellers = create_standard_propeller_config("quad", arm_length=ARM_LENGTH, prop_size=PROP_SIZE) -quad = DroneInterface(0, propellers=propellers) - -gate_config = GATE_CONFIGS[args.gates] - -# --------------------------------------------------------------------------- -# B-spline trajectory -# --------------------------------------------------------------------------- - -bspline_params = None -if args.bspline_config: - with open(args.bspline_config, "r") as f: - config = json.load(f) - if "bspline_params" in config: - bspline_params = np.array(config["bspline_params"]) - print(f"Loaded {len(bspline_params)} B-spline parameters from {args.bspline_config}") - -traj = Trajectory(quad, "xyz_pos", np.array([15, 3, 1]), gate_config=gate_config) -if bspline_params is not None: - traj.bspline_trajectory.set_parameters(bspline_params) - -# --------------------------------------------------------------------------- -# Initial drone state aligned with trajectory start -# --------------------------------------------------------------------------- - -start_pos, _, _ = traj.bspline_trajectory.evaluate(0.0) -_, vel_050, _ = traj.bspline_trajectory.evaluate(0.05) -initial_yaw = (np.arctan2(vel_050[1], vel_050[0]) - if np.linalg.norm(vel_050[:2]) > 0.001 - else gate_config.gate_yaw[0]) -initial_euler = np.array([0.0, 0.0, initial_yaw]) -quad.drone_sim.set_state(position=start_pos, velocity=np.zeros(3), - attitude=initial_euler, angular_velocity=np.zeros(3)) -quad._update_state_variables() - -print(f"Drone start: pos={np.round(start_pos, 3)} yaw={np.degrees(initial_yaw):.1f}°") - -# --------------------------------------------------------------------------- -# Lee controller -# --------------------------------------------------------------------------- - -ctrl = LeeGeometricControl(quad, yawType=3, orient="NED", auto_scale_gains=True) -wind = Wind("None", 0, "NED") -Ts = args.dt -Tf = args.time -Ti = 0.0 - -sDes = traj.desiredState(0, Ts, quad) -ctrl.controller(sDes, quad, "xyz_pos", Ts) - -# --------------------------------------------------------------------------- -# Simulation loop -# --------------------------------------------------------------------------- - -numTimeStep = int(Tf / Ts + 1) -t_all = np.zeros(numTimeStep) -pos_all = np.zeros((numTimeStep, 3)) -quat_all = np.zeros((numTimeStep, 4)) -sDes_traj_all = np.zeros((numTimeStep, len(traj.sDes))) - -t = Ti -i = 1 -start_time = time.time() - -while round(t, 3) < Tf: - t_all[i] = t - pos_all[i] = quad.pos - quat_all[i] = quad.quat - sDes_traj_all[i] = traj.sDes - - t = quad.update(t, Ts, ctrl.w_cmd, wind) - sDes = traj.desiredState(t, Ts, quad) - ctrl.controller(sDes, quad, "xyz_pos", Ts) - i += 1 - -elapsed = time.time() - start_time -print(f"Simulated {Tf}s in {elapsed:.3f}s ({Tf/elapsed:.0f}x real-time)") - -# --------------------------------------------------------------------------- -# Animation -# --------------------------------------------------------------------------- - -if not args.no_viz: - params = {"dxm": ARM_LENGTH, "dym": ARM_LENGTH, "dzm": 0.05} - utils.sameAxisAnimation( - t_all, gate_config.gate_pos, pos_all, quat_all, sDes_traj_all, - Ts, params, 15, 3, int(args.save), "NED", - gate_pos=gate_config.gate_pos, - gate_yaw=gate_config.gate_yaw, - gate_size=getattr(gate_config, "gate_size", 1.0), - ) diff --git a/examples/d_drones/4_simulate_lee_ctrl.py b/examples/d_drones/3_simulate_lee.py similarity index 100% rename from examples/d_drones/4_simulate_lee_ctrl.py rename to examples/d_drones/3_simulate_lee.py diff --git a/examples/d_drones/3_tune_lee.py b/examples/d_drones/3_tune_lee.py deleted file mode 100644 index 336ded320..000000000 --- a/examples/d_drones/3_tune_lee.py +++ /dev/null @@ -1,104 +0,0 @@ -"""Two-stage CMA-ES tuning of Lee controller gains for a drone morphology. - -Mirrors src/airevolve/examples/tuning/tune_lee_controller_gates.py using -ARIEL imports. - -Usage: - # Tune default 2-inch quad on figure-8 (100 CMA evaluations, 4 workers): - uv run examples/d_drones/3_tune_lee.py --gates figure8 - - # Tune individual loaded from a .npy file: - uv run examples/d_drones/3_tune_lee.py \\ - --genome-file __data__/drone_evolution/genome.npy \\ - --gates circle --max-evals 200 --workers 8 - -Requires: cma (uv pip install cma) -""" - -from __future__ import annotations - -import argparse -import json -import os -from pathlib import Path - -import numpy as np - -from ariel.ec.drone.evaluators.lee_tune_evaluator import ( - evaluate_individual_with_tuning, - optimize_controller_for_morphology, -) -from ariel.simulation.drone.controllers.utils.gate_configs import GATE_CONFIGS -from ariel.simulation.drone import create_standard_propeller_config - -# --------------------------------------------------------------------------- -# CLI -# --------------------------------------------------------------------------- - -parser = argparse.ArgumentParser(description="Two-stage CMA-ES Lee controller tuning") -parser.add_argument("--gates", choices=["figure8", "circle", "slalom", "backandforth"], - default="figure8", help="Gate configuration (default figure8)") -parser.add_argument("--genome-file", default=None, - help="Path to .npy genome file. If omitted, uses a default 2-inch X-quad.") -parser.add_argument("--max-evals", type=int, default=100, - help="Maximum CMA-ES evaluations (default 100)") -parser.add_argument("--workers", type=int, default=4, - help="Parallel workers for CMA-ES (default 4)") -parser.add_argument("--sim-time", type=float, default=20.0, - help="Simulation time per evaluation in seconds (default 20)") -parser.add_argument("--dt", type=float, default=0.005, - help="Simulation time step (default 0.005)") -parser.add_argument("--timeout", type=float, default=30.0, - help="Timeout per evaluation in seconds (default 30)") -parser.add_argument("--save-dir", default="__data__/tuning", - help="Output directory (default __data__/tuning)") -args = parser.parse_args() - -save_dir = Path(args.save_dir) -save_dir.mkdir(parents=True, exist_ok=True) - -# --------------------------------------------------------------------------- -# Individual -# --------------------------------------------------------------------------- - -if args.genome_file: - individual = np.load(args.genome_file, allow_pickle=True).astype(np.float32) - print(f"Loaded genome from {args.genome_file} shape={individual.shape}") -else: - # Default: 2-inch X-quad as a (4, 6) spherical genome - # [magnitude, arm_rotation, arm_pitch, motor_rotation, motor_pitch, direction] - ARM_LENGTH = 0.07 - individual = np.array([ - [ARM_LENGTH, np.pi/4, 0.0, 0.0, 0.0, 1.0], - [ARM_LENGTH, 3*np.pi/4, 0.0, 0.0, 0.0, 0.0], - [ARM_LENGTH, -3*np.pi/4, 0.0, 0.0, 0.0, 1.0], - [ARM_LENGTH, -np.pi/4, 0.0, 0.0, 0.0, 0.0], - ], dtype=np.float32) - print(f"Using default 2-inch X-quad individual shape={individual.shape}") - -# --------------------------------------------------------------------------- -# Tuning -# --------------------------------------------------------------------------- - -gate_config = GATE_CONFIGS[args.gates] -print(f"\nGate config: {args.gates} ({len(gate_config.gate_pos)} gates)") -print(f"CMA-ES: max_evals={args.max_evals} workers={args.workers}") -print(f"Output: {save_dir}\n") - -result = optimize_controller_for_morphology( - individual=individual, - gate_config=gate_config, - max_evaluations=args.max_evals, - num_workers=args.workers, - sim_time=args.sim_time, - dt=args.dt, - timeout_per_eval=args.timeout, - save_dir=str(save_dir), -) - -print("\n=== Tuning Results ===") -print(f" Gates passed : {result.get('gates_passed', 0)}") -print(f" Best gains : {result.get('best_gains')}") -print(f" Tuning time : {result.get('tuning_time_seconds', 0):.1f}s") -print(f" Success : {result.get('success', False)}") -print(f"\nResults saved to: {save_dir}") diff --git a/examples/d_drones/5_tune_lee_controller.py b/examples/d_drones/4_tune_lee_controller.py similarity index 100% rename from examples/d_drones/5_tune_lee_controller.py rename to examples/d_drones/4_tune_lee_controller.py diff --git a/examples/d_drones/4_visualize_genome.py b/examples/d_drones/4_visualize_genome.py deleted file mode 100644 index 74466b13f..000000000 --- a/examples/d_drones/4_visualize_genome.py +++ /dev/null @@ -1,105 +0,0 @@ -"""Visualise a drone genome as 3D blueprint and propeller diagrams. - -Mirrors src/airevolve/examples/visualization/genome_visualizer_demo.py and -draw_blueprint.py using ARIEL imports. - -Usage: - # Visualise a random 2-inch quad genome: - uv run examples/d_drones/4_visualize_genome.py - - # Visualise a genome saved to .npy: - uv run examples/d_drones/4_visualize_genome.py \\ - --genome-file __data__/drone_evolution/genome.npy - - # Save figures without displaying: - uv run examples/d_drones/4_visualize_genome.py --save --no-show -""" - -from __future__ import annotations - -import argparse -from pathlib import Path - -import matplotlib.pyplot as plt -import numpy as np - -from ariel.ec.drone.inspection.drone_visualizer import DroneVisualizer -from ariel.ec.drone.genome_handlers.spherical_angular_genome_handler import ( - SphericalAngularDroneGenomeHandler, -) - -# --------------------------------------------------------------------------- -# CLI -# --------------------------------------------------------------------------- - -parser = argparse.ArgumentParser(description="Drone genome visualizer") -parser.add_argument("--genome-file", default=None, - help="Path to .npy genome file (optional; uses random genome if omitted)") -parser.add_argument("--save", action="store_true", - help="Save figures to the output directory") -parser.add_argument("--no-show", action="store_true", - help="Do not display interactive figures (useful for headless runs)") -parser.add_argument("--save-dir", default="__data__/genome_viz", - help="Output directory for saved figures (default __data__/genome_viz)") -args = parser.parse_args() - -save_dir = Path(args.save_dir) -if args.save: - save_dir.mkdir(parents=True, exist_ok=True) - -# --------------------------------------------------------------------------- -# Load or generate genome -# --------------------------------------------------------------------------- - -if args.genome_file: - individual = np.load(args.genome_file, allow_pickle=True).astype(np.float64) - # Remove NaN rows to get valid arms - valid_mask = ~np.isnan(individual[:, 0]) if individual.ndim == 2 else ~np.isnan(individual) - individual = individual[valid_mask] - print(f"Loaded genome from {args.genome_file} ({len(individual)} arms)") -else: - # Generate a random 4-arm spherical genome - handler = SphericalAngularDroneGenomeHandler(min_max_narms=(4, 8)) - genome = handler._generate_random_genome() - # Extract the valid (non-NaN) arms - valid_mask = ~np.isnan(genome.arms[:, 0]) - individual = genome.arms[valid_mask] - print(f"Generated random genome ({len(individual)} arms)") - -print(f"Genome shape: {individual.shape}") -print(f"Arms (mag, arm_rot, arm_pitch, mot_rot, mot_pitch, dir):") -for i, arm in enumerate(individual): - print(f" [{i}] {np.round(arm, 3)}") - -# --------------------------------------------------------------------------- -# Blueprint visualisation -# --------------------------------------------------------------------------- - -visualizer = DroneVisualizer() - -print("\nRendering blueprint …") -fig_bp, axes_bp = visualizer.plot_blueprint(individual, title="Drone Blueprint") - -if args.save: - path = save_dir / "blueprint.png" - fig_bp.savefig(path, dpi=150, bbox_inches="tight") - print(f"Blueprint saved: {path}") - -# --------------------------------------------------------------------------- -# 3D visualisation -# --------------------------------------------------------------------------- - -print("Rendering 3D view …") -fig_3d = plt.figure(figsize=(8, 7)) -ax_3d = fig_3d.add_subplot(111, projection="3d") -visualizer.plot_3d(individual, ax=ax_3d, title="Drone 3D View") - -if args.save: - path = save_dir / "3d_view.png" - fig_3d.savefig(path, dpi=150, bbox_inches="tight") - print(f"3D view saved: {path}") - -if not args.no_show: - plt.show() -else: - plt.close("all") diff --git a/examples/d_drones/5_record_best_drone_video.py b/examples/d_drones/5_record_best_drone_video.py deleted file mode 100644 index a2db702db..000000000 --- a/examples/d_drones/5_record_best_drone_video.py +++ /dev/null @@ -1,367 +0,0 @@ -"""Record a video of the best evolved drone in 3D simulation. - -Loads the best drone individual from NEAT evolution, simulates it hovering, -and records a rotating 3D visualization as an MP4 video. - -Run: - python examples/d_drones/5_record_best_drone_video.py - python examples/d_drones/5_record_best_drone_video.py --duration 10 - python examples/d_drones/5_record_best_drone_video.py --output custom_name.mp4 -""" - -from __future__ import annotations - -import argparse -import os -from pathlib import Path - -import numpy as np -import matplotlib -import matplotlib.pyplot as plt -from matplotlib.animation import FuncAnimation, FFMpegWriter -from mpl_toolkits.mplot3d import Axes3D -from rich.console import Console - -matplotlib.use("Agg") # Headless rendering - -os.environ.setdefault("OMP_NUM_THREADS", "1") -os.environ.setdefault("OPENBLAS_NUM_THREADS", "1") -os.environ.setdefault("MKL_NUM_THREADS", "1") - -console = Console() - -# --------------------------------------------------------------------------- -# CLI -# --------------------------------------------------------------------------- - -parser = argparse.ArgumentParser( - description="Record video of the best evolved drone", -) -parser.add_argument( - "--run-dir", - type=str, - default="__data__/drone_neat_evolution", - help="Directory containing NEAT evolution results", -) -parser.add_argument( - "--generation", - type=int, - default=None, - help="Which generation to load from (default: final generation)", -) -parser.add_argument( - "--individual-id", - type=str, - default="0600", - help="Specific individual ID to visualize (default: 0600)", -) -parser.add_argument( - "--duration", - type=float, - default=5.0, - help="Video duration in seconds (default: 5.0)", -) -parser.add_argument( - "--output", - type=str, - default=None, - help="Output video filename (default: best_drone_gen{generation}_id{id}.mp4)", -) -parser.add_argument( - "--fps", - type=int, - default=30, - help="Video frames per second (default: 30)", -) -args = parser.parse_args() - -RUN_DIR = Path.cwd() / args.run_dir -OUTPUT_DIR = Path.cwd() / "__data__" / "videos" -OUTPUT_DIR.mkdir(parents=True, exist_ok=True) - -# --------------------------------------------------------------------------- -# Load drone genome -# --------------------------------------------------------------------------- - - -def load_drone_genome() -> tuple[str, str, np.ndarray]: - """Load drone genome from evolution run. - - Returns: - (generation_name, individual_id, phenotype_arms) - """ - if not RUN_DIR.exists(): - console.print(f"[red]Error: {RUN_DIR} not found[/red]") - raise FileNotFoundError(f"Run directory {RUN_DIR} not found") - - # List all generation directories - gen_dirs = sorted([d for d in RUN_DIR.iterdir() if d.is_dir() and d.name.startswith("generation_")]) - - if not gen_dirs: - raise FileNotFoundError(f"No generation directories found in {RUN_DIR}") - - # Use specified generation or last one - if args.generation is not None: - gen_name = f"generation_{args.generation:02d}" - gen_dir = RUN_DIR / gen_name - if not gen_dir.exists(): - raise FileNotFoundError(f"Generation directory {gen_dir} not found") - else: - gen_dir = gen_dirs[-1] - gen_name = gen_dir.name - - # Load the specific individual - target_ind_id = args.individual_id - target_ind_dir = gen_dir / f"individual_{target_ind_id}" - - if not target_ind_dir.exists(): - ind_dirs = sorted([d for d in gen_dir.iterdir() if d.is_dir() and d.name.startswith("individual_")]) - if not ind_dirs: - raise FileNotFoundError(f"No individuals found in {gen_dir}") - target_ind_dir = ind_dirs[0] - target_ind_id = target_ind_dir.name.split("_")[1] - - genome_path = target_ind_dir / "genome.npy" - if not genome_path.exists(): - raise FileNotFoundError(f"Genome not found at {genome_path}") - - # Load genome (allow_pickle=True needed for SphericalNeatGenome objects) - genome_obj = np.load(genome_path, allow_pickle=True) - if genome_obj.shape == (): - genome = genome_obj.item() - else: - genome = genome_obj - - # Extract phenotype (valid arms only) - if hasattr(genome, 'arms'): - arms_data = genome.arms - else: - arms_data = genome - - valid_mask = ~np.isnan(arms_data[:, 0]) - phenotype = arms_data[valid_mask] - - console.log(f"[green]Loaded drone:[/green]") - console.log(f" Generation: {gen_name}") - console.log(f" Individual ID: {target_ind_id}") - console.log(f" Arms: {phenotype.shape[0]}") - - return gen_name, target_ind_id, phenotype - - -# --------------------------------------------------------------------------- -# Animation & Video Recording -# --------------------------------------------------------------------------- - -def create_drone_animation(phenotype: np.ndarray, gen_name: str, ind_id: str) -> tuple[plt.Figure, FuncAnimation]: - """Create animated 3D visualization of drone. - - Args: - phenotype: Arm parameters (N, 6) where each row is [r, yaw, pitch, roll, yaw2, motor_ccw] - gen_name: Generation name for title - ind_id: Individual ID for title - - Returns: - (figure, animation) tuple - """ - # Create figure and 3D axis - fig = plt.figure(figsize=(10, 8)) - ax = fig.add_subplot(111, projection='3d') - - # Extract arm positions from spherical coordinates - # Parameters: [radius, yaw, pitch, roll, yaw2, motor_type] - # For visualization, we use radius, yaw, pitch to get 3D positions - - arms = [] - for arm_params in phenotype: - r = arm_params[0] # radius - yaw = arm_params[1] # yaw angle - pitch = arm_params[2] # pitch angle - - # Convert spherical to Cartesian - x = r * np.cos(yaw) * np.cos(pitch) - y = r * np.sin(yaw) * np.cos(pitch) - z = r * np.sin(pitch) - arms.append([x, y, z]) - - arms = np.array(arms) - - # Plot setup - def init(): - ax.clear() - ax.set_xlim(-0.3, 0.3) - ax.set_ylim(-0.3, 0.3) - ax.set_zlim(-0.3, 0.3) - ax.set_xlabel("X (m)") - ax.set_ylabel("Y (m)") - ax.set_zlabel("Z (m)") - ax.set_title(f"Best Drone (Gen {gen_name.split('_')[1]}, ID {ind_id}) - Hovering") - return [] - - def animate(frame): - ax.clear() - - # Rotating view based on frame - rotation_angle = (frame / 30) * 360 # Full rotation every 30 frames - - # Plot center (body) - ax.scatter([0], [0], [0], c='black', s=100, marker='o', label='Body') - - # Plot arms and motors - colors = plt.cm.viridis(np.linspace(0, 1, len(arms))) - for i, (arm, color) in enumerate(zip(arms, colors)): - # Draw line from center to motor - ax.plot([0, arm[0]], [0, arm[1]], [0, arm[2]], 'k-', alpha=0.3, linewidth=1) - - # Draw motor as a circle - motor_radius = 0.02 - u = np.linspace(0, 2 * np.pi, 20) - motor_x = motor_radius * np.cos(u) + arm[0] - motor_y = motor_radius * np.sin(u) + arm[1] - motor_z = np.full_like(u, arm[2]) - ax.plot(motor_x, motor_y, motor_z, color=color, linewidth=2, label=f'Motor {i+1}') - - ax.set_xlim(-0.3, 0.3) - ax.set_ylim(-0.3, 0.3) - ax.set_zlim(-0.3, 0.3) - ax.set_xlabel("X (m)") - ax.set_ylabel("Y (m)") - ax.set_zlabel("Z (m)") - ax.set_title( - f"Best Drone (Gen {gen_name.split('_')[1]}, ID {ind_id}) - Hovering\n" - f"Arms: {len(arms)} | View angle: {rotation_angle:.0f}°" - ) - - # Set viewing angle - ax.view_init(elev=20, azim=rotation_angle) - - if frame == 0: - ax.legend(loc='upper right', fontsize=8) - - return [] - - # Create animation - num_frames = int(args.duration * args.fps) - anim = FuncAnimation( - fig, - animate, - init_func=init, - frames=num_frames, - interval=1000 / args.fps, - blit=True, - repeat=False, - ) - - return fig, anim - - -# --------------------------------------------------------------------------- -# Main -# --------------------------------------------------------------------------- - -console.rule("[bold blue]Drone Video Recording") - -gen_name, ind_id, phenotype = load_drone_genome() - -console.log(f"\n[bold cyan]Creating animation...[/bold cyan]") - -fig, anim = create_drone_animation(phenotype, gen_name, ind_id) - -# Determine output file -output_file = args.output -if output_file is None: - gen_num = gen_name.split("_")[1] - output_file = f"best_drone_gen{gen_num}_id{ind_id}.mp4" - -output_path = OUTPUT_DIR / output_file - -console.log(f"[bold cyan]Recording video...[/bold cyan]") -console.log(f" Duration: {args.duration}s") -console.log(f" FPS: {args.fps}") -console.log(f" Frames: {int(args.duration * args.fps)}") -console.log(f" Output: {output_path}") - -# Write video -writer = FFMpegWriter(fps=args.fps, bitrate=1800) -try: - with writer.saving(fig, str(output_path), dpi=100): - num_frames = int(args.duration * args.fps) - for frame in range(num_frames): - # Manually update animation - ax = fig.axes[0] - ax.clear() - - # Rotating drone (not camera) - spin around Z axis - rotation_angle = (frame / 30) * 360 # Full rotation every 30 frames - rotation_rad = np.deg2rad(rotation_angle) - - # Create rotation matrix for Z-axis rotation - cos_r = np.cos(rotation_rad) - sin_r = np.sin(rotation_rad) - rotation_matrix = np.array([ - [cos_r, -sin_r, 0], - [sin_r, cos_r, 0], - [0, 0, 1] - ]) - - # Plot center - ax.scatter([0], [0], [0], c='black', s=100, marker='o') - - # Plot arms and motors (rotated) - colors = plt.cm.viridis(np.linspace(0, 1, len(phenotype))) - for i, (arm_params, color) in enumerate(zip(phenotype, colors)): - r = arm_params[0] - yaw = arm_params[1] - pitch = arm_params[2] - - # Original position - x = r * np.cos(yaw) * np.cos(pitch) - y = r * np.sin(yaw) * np.cos(pitch) - z = r * np.sin(pitch) - - # Rotate position around Z axis - pos = np.array([x, y, z]) - rotated_pos = rotation_matrix @ pos - x, y, z = rotated_pos - - # Draw line from center to motor - ax.plot([0, x], [0, y], [0, z], 'k-', alpha=0.3, linewidth=1) - - # Draw motor circle - motor_radius = 0.02 - u = np.linspace(0, 2 * np.pi, 20) - motor_x = motor_radius * np.cos(u) + x - motor_y = motor_radius * np.sin(u) + y - motor_z = np.full_like(u, z) - ax.plot(motor_x, motor_y, motor_z, color=color, linewidth=2) - - ax.set_xlim(-0.3, 0.3) - ax.set_ylim(-0.3, 0.3) - ax.set_zlim(-0.3, 0.3) - ax.set_xlabel("X (m)") - ax.set_ylabel("Y (m)") - ax.set_zlabel("Z (m)") - ax.set_title( - f"Best Drone (Gen {gen_name.split('_')[1]}, ID {ind_id}) - Hovering\n" - f"Arms: {len(phenotype)} | Rotation: {rotation_angle:.0f}°" - ) - # Fixed camera angle - ax.view_init(elev=20, azim=45) - - writer.grab_frame() - - # Progress indicator - if (frame + 1) % 10 == 0: - console.log(f" Frame {frame + 1}/{num_frames}") - - console.log(f"\n[green]✓ Video saved to {output_path}[/green]") - console.log(f" File size: {output_path.stat().st_size / (1024*1024):.1f} MB") - -except Exception as e: - console.log(f"[red]Error during video recording: {e}[/red]") - import traceback - traceback.print_exc() -finally: - plt.close(fig) - -console.rule("[bold]Done") diff --git a/examples/d_drones/4_visualize_best_drone.py b/examples/d_drones/5_visualize_best_drone.py similarity index 100% rename from examples/d_drones/4_visualize_best_drone.py rename to examples/d_drones/5_visualize_best_drone.py diff --git a/examples/d_drones/5_make_video.py b/examples/d_drones/7_make_video.py similarity index 100% rename from examples/d_drones/5_make_video.py rename to examples/d_drones/7_make_video.py diff --git a/examples/d_drones/7_visualize_genome.py b/examples/d_drones/8_visualize_genome.py similarity index 100% rename from examples/d_drones/7_visualize_genome.py rename to examples/d_drones/8_visualize_genome.py diff --git a/examples/d_drones/8_generate_stl.py b/examples/d_drones/9_generate_stl.py similarity index 100% rename from examples/d_drones/8_generate_stl.py rename to examples/d_drones/9_generate_stl.py From 895ac58ee17209f1fc9df883f5cdd02c35b50def Mon Sep 17 00:00:00 2001 From: A-lamo <2727043@student.vu.nl> Date: Mon, 18 May 2026 19:21:22 +0200 Subject: [PATCH 05/27] Fix video and remove redundant examples. --- examples/d_drones/10_repair_demo.py | 6 +- examples/d_drones/1_run_evolution.py | 8 +- examples/d_drones/2_neat_evolution.py | 8 +- examples/d_drones/3_simulate_lee.py | 18 +- examples/d_drones/4_tune_lee_controller.py | 26 +- examples/d_drones/5_visualize_best_drone.py | 14 +- examples/d_drones/7_make_video.py | 4 +- examples/d_drones/8_visualize_genome.py | 12 +- examples/d_drones/9_generate_stl.py | 14 +- examples/d_drones/_ctrl_helpers.py | 6 +- pyproject.toml | 3 + .../drone/phenotype_assembly/__init__.py | 62 +++ .../drone/phenotype_assembly/assembler.py | 207 ++++++++ .../drone/phenotype_assembly/config.py | 74 +++ .../drone/phenotype_assembly/generator.py | 280 ++++++++++ .../phenotype_assembly/genome_adapter.py | 355 +++++++++++++ .../drone/phenotype_assembly/models.py | 158 ++++++ src/ariel/ec/drone/inspection/utils.py | 24 +- .../drone/controllers/px4_ctrl/__init__.py | 3 + .../controllers/px4_ctrl/px4_based_ctrl.py | 499 ++++++++++++++++++ uv.lock | 285 +++++++++- 21 files changed, 1981 insertions(+), 85 deletions(-) create mode 100644 src/ariel/body_phenotypes/drone/phenotype_assembly/__init__.py create mode 100644 src/ariel/body_phenotypes/drone/phenotype_assembly/assembler.py create mode 100644 src/ariel/body_phenotypes/drone/phenotype_assembly/config.py create mode 100644 src/ariel/body_phenotypes/drone/phenotype_assembly/generator.py create mode 100644 src/ariel/body_phenotypes/drone/phenotype_assembly/genome_adapter.py create mode 100644 src/ariel/body_phenotypes/drone/phenotype_assembly/models.py create mode 100644 src/ariel/simulation/drone/controllers/px4_ctrl/__init__.py create mode 100644 src/ariel/simulation/drone/controllers/px4_ctrl/px4_based_ctrl.py diff --git a/examples/d_drones/10_repair_demo.py b/examples/d_drones/10_repair_demo.py index 6b0fffef6..5a3e291de 100644 --- a/examples/d_drones/10_repair_demo.py +++ b/examples/d_drones/10_repair_demo.py @@ -11,19 +11,19 @@ 4. Functional API (``optimization_repair_individual``) Run: - python examples/d_drones/9_repair_demo.py + python examples/d_drones/10_repair_demo.py """ from __future__ import annotations import numpy as np -from airevolve.evolution_tools.genome_handlers.operators.optimization_repair_operator import ( +from ariel.ec.drone.genome_handlers.operators.optimization_repair_operator import ( OptimizationBasedRepairOperator, OptimizationRepairConfig, optimization_repair_individual, ) -from airevolve.evolution_tools.genome_handlers.operators.repair_base import RepairConfig +from ariel.ec.drone.genome_handlers.operators.repair_base import RepairConfig # --------------------------------------------------------------------------- diff --git a/examples/d_drones/1_run_evolution.py b/examples/d_drones/1_run_evolution.py index 5662063aa..df68a598a 100644 --- a/examples/d_drones/1_run_evolution.py +++ b/examples/d_drones/1_run_evolution.py @@ -5,10 +5,10 @@ fitness modes via mu+lambda or mu,lambda selection. Run: - python examples/d_drones/2_drone_evolution.py - python examples/d_drones/2_drone_evolution.py --fitness pure_hover --strategy plus - python examples/d_drones/2_drone_evolution.py --fitness edit_distance --workers 8 - python examples/d_drones/2_drone_evolution.py --pop 20 --budget 30 --min-arms 4 --max-arms 6 + python examples/d_drones/1_run_evolution.py + python examples/d_drones/1_run_evolution.py --fitness pure_hover --strategy plus + python examples/d_drones/1_run_evolution.py --fitness edit_distance --workers 8 + python examples/d_drones/1_run_evolution.py --pop 20 --budget 30 --min-arms 4 --max-arms 6 """ from __future__ import annotations diff --git a/examples/d_drones/2_neat_evolution.py b/examples/d_drones/2_neat_evolution.py index 7e0d98895..55b1f2bb3 100644 --- a/examples/d_drones/2_neat_evolution.py +++ b/examples/d_drones/2_neat_evolution.py @@ -6,10 +6,10 @@ population and does not produce an SQLite archive. Run: - python examples/d_drones/3_neat_evolution.py - python examples/d_drones/3_neat_evolution.py --pop 20 --gens 30 - python examples/d_drones/3_neat_evolution.py --fitness pure_hover --workers 8 - python examples/d_drones/3_neat_evolution.py --compat-threshold 2.5 --target-species 4 + python examples/d_drones/2_neat_evolution.py + python examples/d_drones/2_neat_evolution.py --pop 20 --gens 30 + python examples/d_drones/2_neat_evolution.py --fitness pure_hover --workers 8 + python examples/d_drones/2_neat_evolution.py --compat-threshold 2.5 --target-species 4 """ from __future__ import annotations diff --git a/examples/d_drones/3_simulate_lee.py b/examples/d_drones/3_simulate_lee.py index b5a837c96..001ba9a89 100644 --- a/examples/d_drones/3_simulate_lee.py +++ b/examples/d_drones/3_simulate_lee.py @@ -10,15 +10,15 @@ Run: # Headless test with default B-spline parameters: - python examples/d_drones/4_simulate_lee_ctrl.py --gates figure8 --no-viz + python examples/d_drones/3_simulate_lee.py --gates figure8 --no-viz # Load a tuned config and save animation: - python examples/d_drones/4_simulate_lee_ctrl.py \\ + python examples/d_drones/3_simulate_lee.py \\ --gates figure8 \\ --bspline-config __data__/lee_tuning/stage3_best.json --save # Override position / velocity gains: - python examples/d_drones/4_simulate_lee_ctrl.py --gates circle \\ + python examples/d_drones/3_simulate_lee.py --gates circle \\ --pos-gain 12.0 --vel-gain 8.0 """ @@ -36,11 +36,11 @@ sys.path.insert(0, str(Path(__file__).parent)) from _ctrl_helpers import ARM_LENGTH, PROP_SIZE, GateChecker, create_2inch_quad -from airevolve.controllers.lee_control.lee_controller import LeeGeometricControl -from airevolve.controllers.trajectory_generation.trajectory import Trajectory -from airevolve.controllers.utils.gate_configs import GATE_CONFIGS -import airevolve.controllers.utils as ctrl_utils -from airevolve.controllers.utils.wind_model import Wind +from ariel.simulation.drone.controllers.lee_control.lee_controller import LeeGeometricControl +from ariel.simulation.drone.controllers.trajectory_generation.trajectory import Trajectory +from ariel.simulation.drone.controllers.utils.gate_configs import GATE_CONFIGS +import ariel.simulation.drone.controllers.utils as ctrl_utils +from ariel.simulation.drone.controllers.utils.wind_model import Wind # --------------------------------------------------------------------------- # CLI @@ -99,7 +99,7 @@ # --------------------------------------------------------------------------- quad = create_2inch_quad() -wind = Wind("None", args.time) +wind = Wind("None") ctrl = LeeGeometricControl( quad, diff --git a/examples/d_drones/4_tune_lee_controller.py b/examples/d_drones/4_tune_lee_controller.py index 1ed279ace..0252d2265 100644 --- a/examples/d_drones/4_tune_lee_controller.py +++ b/examples/d_drones/4_tune_lee_controller.py @@ -9,17 +9,17 @@ Run: # All three stages automatically: - python examples/d_drones/5_tune_lee_controller.py --stage all --gates figure8 + python examples/d_drones/4_tune_lee_controller.py --stage all --gates figure8 # Individual stages: - python examples/d_drones/5_tune_lee_controller.py --stage 1 --gates figure8 --max-evals 200 - python examples/d_drones/5_tune_lee_controller.py --stage 2 --gates figure8 \\ + python examples/d_drones/4_tune_lee_controller.py --stage 1 --gates figure8 --max-evals 200 + python examples/d_drones/4_tune_lee_controller.py --stage 2 --gates figure8 \\ --load-prev __data__/lee_tuning/stage1_best.json --max-evals 300 - python examples/d_drones/5_tune_lee_controller.py --stage 3 --gates figure8 \\ + python examples/d_drones/4_tune_lee_controller.py --stage 3 --gates figure8 \\ --load-prev __data__/lee_tuning/stage2_best.json --max-evals 500 After tuning, visualise with: - python examples/d_drones/4_simulate_lee_ctrl.py \\ + python examples/d_drones/3_simulate_lee.py \\ --gates figure8 --bspline-config __data__/lee_tuning/stage3_best.json """ @@ -41,13 +41,13 @@ sys.path.insert(0, str(Path(__file__).parent)) from _ctrl_helpers import ARM_LENGTH, PROP_SIZE, GateChecker, create_2inch_quad -from airevolve.controllers.lee_control.lee_controller import LeeGeometricControl -from airevolve.controllers.trajectory_generation.bspline_gate_trajectory import ( +from ariel.simulation.drone.controllers.lee_control.lee_controller import LeeGeometricControl +from ariel.simulation.drone.controllers.trajectory_generation.bspline_gate_trajectory import ( BSplineGateTrajectory, ) -from airevolve.controllers.trajectory_generation.trajectory import Trajectory -from airevolve.controllers.utils.gate_configs import GATE_CONFIGS -from airevolve.controllers.utils.wind_model import Wind +from ariel.simulation.drone.controllers.trajectory_generation.trajectory import Trajectory +from ariel.simulation.drone.controllers.utils.gate_configs import GATE_CONFIGS +from ariel.simulation.drone.controllers.utils.wind_model import Wind try: import cma @@ -129,12 +129,12 @@ def simulate_bspline( attitude=initial_euler, angular_velocity=np.zeros(3), ) - from airevolve.controllers.trajectory_generation.trajectory import Trajectory + from ariel.simulation.drone.controllers.trajectory_generation.trajectory import Trajectory traj = Trajectory(quad, "xyz_pos", np.array([15, 3, 1]), gate_config=gate_config) traj.bspline_trajectory = bspline_traj - wind = Wind("None", sim_time) + wind = Wind("None") gate_checker = GateChecker(gate_config.gate_pos, gate_config.gate_yaw, gate_config.gate_size) @@ -357,7 +357,7 @@ def _save_results(self) -> None: if self.stage < 3: print(f" To continue: --stage {self.stage + 1} --load-prev {best_path}") else: - print(f" To visualise: python examples/d_drones/4_simulate_lee_ctrl.py " + print(f" To visualise: python examples/d_drones/3_simulate_lee.py " f"--gates {args.gates} --bspline-config {best_path}") diff --git a/examples/d_drones/5_visualize_best_drone.py b/examples/d_drones/5_visualize_best_drone.py index 2e343ba00..fb3ad165f 100644 --- a/examples/d_drones/5_visualize_best_drone.py +++ b/examples/d_drones/5_visualize_best_drone.py @@ -7,9 +7,9 @@ • Interactive 3D simulator (optional) Run: - python examples/d_drones/4_visualize_best_drone.py - python examples/d_drones/4_visualize_best_drone.py --no-show - python examples/d_drones/4_visualize_best_drone.py --simulate + python examples/d_drones/5_visualize_best_drone.py + python examples/d_drones/5_visualize_best_drone.py --no-show + python examples/d_drones/5_visualize_best_drone.py --simulate """ from __future__ import annotations @@ -27,10 +27,10 @@ os.environ.setdefault("OPENBLAS_NUM_THREADS", "1") os.environ.setdefault("MKL_NUM_THREADS", "1") -from airevolve.evolution_tools.genome_handlers.spherical_angular_genome_handler import ( +from ariel.ec.drone.genome_handlers.spherical_angular_genome_handler import ( SphericalAngularDroneGenomeHandler, ) -from airevolve.evolution_tools.inspection_tools.drone_visualizer import ( +from ariel.ec.drone.inspection.drone_visualizer import ( DroneVisualizer, VisualizationConfig, ) @@ -258,7 +258,7 @@ def find_best_individual() -> tuple[str, str, str, np.ndarray]: if args.simulate: console.log("\n[bold cyan]Attempting physics simulation...[/bold cyan]") try: - from airevolve.evolution_tools.evaluators.hover_fitness import ( + from ariel.ec.drone.evaluators.hover_fitness import ( create_drone_simulator, ) import mujoco @@ -268,7 +268,7 @@ def find_best_individual() -> tuple[str, str, str, np.ndarray]: simulator = create_drone_simulator(phenotype) console.log(" [green]✓ Simulator created successfully[/green]") - console.log(" (Use 'python examples/d_drones/4_simulate_lee_ctrl.py' for interactive simulation)") + console.log(" (Use 'python examples/d_drones/3_simulate_lee.py' for interactive simulation)") except ImportError as e: console.log(f" [yellow]Simulator not available: {e}[/yellow]") diff --git a/examples/d_drones/7_make_video.py b/examples/d_drones/7_make_video.py index ae1554250..da2523ea3 100644 --- a/examples/d_drones/7_make_video.py +++ b/examples/d_drones/7_make_video.py @@ -7,11 +7,11 @@ - ``policy.zip`` — trained SB3 PPO policy Usage: - uv run examples/d_drones/5_make_video.py __data__/my_individual \\ + uv run examples/d_drones/7_make_video.py __data__/my_individual \\ --gate-cfg figure8 # With explicit device: - uv run examples/d_drones/5_make_video.py __data__/my_individual \\ + uv run examples/d_drones/7_make_video.py __data__/my_individual \\ --gate-cfg circle --device cpu """ diff --git a/examples/d_drones/8_visualize_genome.py b/examples/d_drones/8_visualize_genome.py index d7ce045b1..ff93fb698 100644 --- a/examples/d_drones/8_visualize_genome.py +++ b/examples/d_drones/8_visualize_genome.py @@ -10,8 +10,8 @@ • Multi-panel analysis dashboard Run: - python examples/d_drones/7_visualize_genome.py - python examples/d_drones/7_visualize_genome.py --no-show # headless, save only + python examples/d_drones/8_visualize_genome.py + python examples/d_drones/8_visualize_genome.py --no-show # headless, save only """ from __future__ import annotations @@ -24,17 +24,17 @@ import matplotlib import matplotlib.pyplot as plt -from airevolve.evolution_tools.genome_handlers.spherical_angular_genome_handler import ( +from ariel.ec.drone.genome_handlers.spherical_angular_genome_handler import ( SphericalAngularDroneGenomeHandler, ) -from airevolve.evolution_tools.genome_handlers.cartesian_euler_genome_handler import ( +from ariel.ec.drone.genome_handlers.cartesian_euler_genome_handler import ( CartesianEulerDroneGenomeHandler, ) -from airevolve.evolution_tools.inspection_tools.drone_visualizer import ( +from ariel.ec.drone.inspection.drone_visualizer import ( DroneVisualizer, VisualizationConfig, ) -import airevolve.evolution_tools.inspection_tools.utils as u +import ariel.ec.drone.inspection.utils as u # --------------------------------------------------------------------------- # CLI diff --git a/examples/d_drones/9_generate_stl.py b/examples/d_drones/9_generate_stl.py index ca473df9f..8592c5643 100644 --- a/examples/d_drones/9_generate_stl.py +++ b/examples/d_drones/9_generate_stl.py @@ -7,13 +7,13 @@ Run: # Randomly generated 4-arm genome: - python examples/d_drones/8_generate_stl.py + python examples/d_drones/9_generate_stl.py # Specify arm count and output directory: - python examples/d_drones/8_generate_stl.py --arms 6 --out __data__/my_drone_stl + python examples/d_drones/9_generate_stl.py --arms 6 --out __data__/my_drone_stl # Headless (no interactive matplotlib windows): - python examples/d_drones/8_generate_stl.py --no-show + python examples/d_drones/9_generate_stl.py --no-show """ from __future__ import annotations @@ -25,11 +25,11 @@ import matplotlib import matplotlib.pyplot as plt -from airevolve.evolution_tools.genome_handlers.spherical_angular_genome_handler import ( +from ariel.ec.drone.genome_handlers.spherical_angular_genome_handler import ( SphericalAngularDroneGenomeHandler, ) -from airevolve.evolution_tools.inspection_tools.drone_visualizer import DroneVisualizer -from airevolve.phenotype_assembly import generate_stl_files, AssemblyConfig +from ariel.ec.drone.inspection.drone_visualizer import DroneVisualizer +from ariel.body_phenotypes.drone.phenotype_assembly import generate_stl_files, AssemblyConfig # --------------------------------------------------------------------------- # CLI @@ -94,7 +94,7 @@ print(f"\nGenerating STL files → {output_dir}") -assembly_config = AssemblyConfig(propeller_size=args.prop_size) +assembly_config = AssemblyConfig() result = generate_stl_files( handler, output_dir=str(output_dir), diff --git a/examples/d_drones/_ctrl_helpers.py b/examples/d_drones/_ctrl_helpers.py index 1178d75dd..c398765d6 100644 --- a/examples/d_drones/_ctrl_helpers.py +++ b/examples/d_drones/_ctrl_helpers.py @@ -1,15 +1,13 @@ """Shared helpers for drone simulation and controller-tuning examples. -Extracted from airevolve's tuning example so that examples 4 (simulate) and -5 (tune) can import a common drone configuration without needing sys.path -hacks between sibling directories. +Shared helpers for examples 4 (simulate) and 5 (tune). """ from __future__ import annotations import numpy as np -from airevolve.simulator.simulation import DroneInterface +from ariel.simulation.drone.drone_interface import DroneInterface # 2-inch quadrotor constants (60 mm arm, 2-inch propellers, ~0.08 kg total) ARM_LENGTH: float = 0.06 # metres diff --git a/pyproject.toml b/pyproject.toml index 98dc6924f..d60c436f3 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -51,6 +51,9 @@ Repository = "https://github.com/ci-group/ariel" Documentation = "https://ariel.readthedocs.io" Changelog = "https://github.com/ci-group/ariel/releases" +[project.optional-dependencies] +fabrication = ["cadquery>=2.4.0"] + [dependency-groups] dev = ["mypy>=1.18.2", "pytest>=8.4.2", "pytest-modern>=0.7.4", "ruff>=0.13.3"] docs = [ diff --git a/src/ariel/body_phenotypes/drone/phenotype_assembly/__init__.py b/src/ariel/body_phenotypes/drone/phenotype_assembly/__init__.py new file mode 100644 index 000000000..9227fbc37 --- /dev/null +++ b/src/ariel/body_phenotypes/drone/phenotype_assembly/__init__.py @@ -0,0 +1,62 @@ +""" +Phenotype Assembly + +Tools for generating physical drone parts (STL / STEP files) from evolved genomes. + +Typical usage +------------- + from ariel.ec.drone.genome_handlers.spherical_angular_genome_handler import ( + SphericalAngularDroneGenomeHandler, + ) + from ariel.body_phenotypes.drone.phenotype_assembly import generate_stl_files + + handler = SphericalAngularDroneGenomeHandler(...) + # ... evolve ... + result = generate_stl_files(handler, output_dir="./my_drone") + print(result.assembly_file) + +Module layout +------------- +models.py — dataclasses: ArmCADParameters, DroneCADParameters, + AssemblyConfig, STLGenerationResult +genome_adapter.py — genome → DroneCADParameters conversion +assembler.py — positions and orients parts onto the plate +generator.py — orchestrates the full pipeline; file I/O +parts/ + core_plate.py — central hub-and-spoke plate + arm_mount.py — sphere-clamp that grips the plate rim + motor_arm.py — arm tube + motor-mounting disc +""" + +from .generator import generate_stl_files, quick_visualize_genome +from .genome_adapter import genome_to_cad_parameters +from .models import ( + ArmCADParameters, + DroneCADParameters, + AssemblyConfig, + STLGenerationResult, +) +from .assembler import place_arm_on_plate, assemble_drone +from .parts import create_core_plate, create_arm_mount, create_motor_arm + +__all__ = [ + # ── Main API ─────────────────────────────────────────────────────────── + "generate_stl_files", + "quick_visualize_genome", + # ── Data models ──────────────────────────────────────────────────────── + "ArmCADParameters", + "DroneCADParameters", + "AssemblyConfig", + "STLGenerationResult", + # ── Conversion ───────────────────────────────────────────────────────── + "genome_to_cad_parameters", + # ── Assembly helpers (advanced usage) ────────────────────────────────── + "place_arm_on_plate", + "assemble_drone", + # ── Part generators (advanced usage) ─────────────────────────────────── + "create_core_plate", + "create_arm_mount", + "create_motor_arm", +] + +__version__ = "0.2.0" diff --git a/src/ariel/body_phenotypes/drone/phenotype_assembly/assembler.py b/src/ariel/body_phenotypes/drone/phenotype_assembly/assembler.py new file mode 100644 index 000000000..1135adcd6 --- /dev/null +++ b/src/ariel/body_phenotypes/drone/phenotype_assembly/assembler.py @@ -0,0 +1,207 @@ +""" +Drone Assembler + +Places arm-mount and motor-arm parts onto the core plate at the correct +position and orientation for each arm. + +Coordinate conventions +---------------------- +Core plate + Sits at the origin. Bottom face at Z=0, top face at Z=plate_thickness. + The plate centre is at (0, 0). The outer rim is at radius = plate_radius. + +Arm mount (sphere + clamp) + Created in local space with the clamp slot pointing in the +X direction. + The slot centre (= plate rim contact) is at local X = slot_x = + sphere_radius - clamp_inset from the sphere centre. + + To place it correctly we: + 1. Rotate 180° around Z so the slot faces the *inward* direction (−X → + toward plate centre after the next rotation). + 2. Rotate by ``attachment_angle`` around Z. + 3. Translate sphere centre to (sphere_centre_r × cos, sphere_centre_r × sin, z). + + ``sphere_centre_r`` = plate_radius - clamp_inset (sphere inset from rim). + +Motor arm tube + Created in local space pointing along +Z. The tube base is at Z=0, the + motor disc centre is at Z = arm_length + sphere_offset. + + To place it correctly we: + 1. Rotate −(90° − arm_elevation)° around Y to tilt the tube from vertical + to the correct elevation angle. After this the tube points radially + outward in the XZ plane. + 2. Rotate by ``attachment_angle`` around Z to spin to the correct azimuth. + 3. Translate the tube base to the sphere surface point on the plate rim. +""" + +import math +import cadquery as cq +from typing import Dict, List, Tuple + +from .models import ArmCADParameters, AssemblyConfig +from .parts.arm_mount import create_arm_mount +from .parts.motor_arm import create_motor_arm + + +# ───────────────────────────────────────────────────────────────────────────── +# Public helpers +# ───────────────────────────────────────────────────────────────────────────── + +def arm_attach_position( + attachment_angle_deg: float, + cfg: AssemblyConfig, +) -> Tuple[float, float, float]: + """ + Return the (x, y, z) of the arm mount sphere centre for a given attachment angle. + + The sphere sits just outside the plate rim, overlapping it by ``clamp_inset`` + so the clamp jaws can grip the outer ring. The sphere centre is therefore at: + + r = plate_radius + (sphere_radius - clamp_inset) + + With defaults (plate_radius=30, sphere_radius=12, clamp_inset=10.5): + r = 30 + 1.5 = 31.5 mm + + Z is set to plate_thickness / 2 so the sphere straddles the plate mid-plane, + letting the slot cutter (in arm_mount.py) remove material for the rim to slide in. + """ + r = cfg.plate_radius + (cfg.sphere_radius - cfg.clamp_inset) + angle_rad = math.radians(attachment_angle_deg) + return ( + r * math.cos(angle_rad), + r * math.sin(angle_rad), + cfg.plate_thickness / 2.0, + ) + + +def place_arm_on_plate( + arm_params: ArmCADParameters, + cfg: AssemblyConfig, +) -> Dict[str, cq.Workplane]: + """ + Build all parts for one arm and position them relative to the core plate. + + Args: + arm_params: Parameters for this arm from ``DroneCADParameters.arms``. + cfg: Physical assembly configuration. + + Returns: + dict with keys ``'sphere'``, ``'motor_arm'``. All solids are already + in the global drone frame (origin = plate centre bottom). + """ + # mount_angle: where the sphere sits on the plate rim (discrete when snapping) + # attachment_angle: azimuth the arm tube points toward in world space + # These are equal when snap_mounts=False; they differ when the mount has + # been snapped to a discrete position. + mount_angle = arm_params.mount_angle + arm_azimuth = arm_params.attachment_angle + + # ── 1. Arm mount (sphere) ───────────────────────────────────────────────── + mount_parts = create_arm_mount( + sphere_radius=cfg.sphere_radius, + clamp_inset=cfg.clamp_inset, + arm_plate_diameter=cfg.plate_diameter, + arm_plate_thickness=cfg.plate_thickness, + arm_screw_hole_inset=cfg.arm_screw_hole_inset, + ) + + sphere_centre_x, sphere_centre_y, sphere_centre_z = arm_attach_position(mount_angle, cfg) + + placed_mount: Dict[str, cq.Workplane] = {} + for part_name, part_wp in mount_parts.items(): + solid = part_wp.val() + # Slot faces +X in local space; rotate 180° so slot now faces −X + # (toward the plate centre), then rotate to the mount azimuth on the rim. + solid = solid.rotate((0, 0, 0), (0, 0, 1), 180.0) + solid = solid.rotate((0, 0, 0), (0, 0, 1), mount_angle) + solid = solid.translate((sphere_centre_x, sphere_centre_y, sphere_centre_z)) + placed_mount[part_name] = cq.Workplane("XY").add(solid) + + # ── 2. Motor arm tube ──────────────────────────────────────────────────── + motor_arm_wp = create_motor_arm( + arm_length=arm_params.arm_length, + motor_tilt=arm_params.motor_tilt, + motor_azimuth=arm_params.motor_azimuth, + cylinder_inner_radius=cfg.cylinder_inner_radius, + wall_thickness=cfg.wall_thickness, + cylinder_extension=cfg.cylinder_extension, + sphere_offset=cfg.sphere_offset, + disc_diameter=cfg.disc_diameter, + disc_thickness=cfg.disc_thickness, + motor_screw_count=cfg.motor_screw_count, + motor_screw_start_angle=cfg.motor_screw_start_angle, + motor_screw_depth=cfg.motor_screw_depth, + center_hole_diameter=cfg.center_hole_diameter, + ) + + arm_solid = motor_arm_wp.val() + + # The tube is created along +Z. We want it to point from the mount sphere + # toward the motor tip at ``arm_elevation`` degrees above horizontal. + # + # Step 1: tilt from vertical (+Z) to the desired elevation. + # elevation = 0 → horizontal → tilt 90° around Y maps +Z→+X (outward) + # elevation = 90 → straight up → no tilt needed (stays at +Z) + # Rotation angle = 90° − elevation (positive Y rotation: +Z toward +X) + tilt_angle = 90.0 - arm_params.arm_elevation # degrees + arm_solid = arm_solid.rotate((0, 0, 0), (0, 1, 0), tilt_angle) + + # Step 2: spin to the arm's world-space azimuth (direction toward motor tip). + # This may differ from mount_angle when snap_mounts=True. + arm_solid = arm_solid.rotate((0, 0, 0), (0, 0, 1), arm_azimuth) + + # Step 3: translate so that the tube base sits at the sphere surface on + # the plate rim side. The sphere centre is at sphere_centre_{x,y,z}. + # The arm exits the sphere in the *outward* radial direction. After the + # rotations above the tube base (Z=0 in local space) maps to a point that + # is ``sphere_radius`` inward from the sphere centre along the arm axis, + # so we need to account for that offset. + # + # Rather than computing the surface intersection analytically we place the + # tube base at the sphere centre and let the sphere geometry handle the + # overlap visually. For printed parts the sphere clamp and tube are two + # separate pieces, so exact surface contact is a fitment concern, not a + # geometry error. + arm_solid = arm_solid.translate((sphere_centre_x, sphere_centre_y, sphere_centre_z)) + + placed_mount["motor_arm"] = cq.Workplane("XY").add(arm_solid) + + return placed_mount + + +def assemble_drone( + arms_params: List[ArmCADParameters], + cfg: AssemblyConfig, + core_plate_solid, +) -> Tuple[cq.Compound, Dict]: + """ + Assemble all drone parts into a single compound and a named-parts dict. + + Args: + arms_params: List of ``ArmCADParameters``, one per arm. + cfg: Assembly configuration. + core_plate_solid: The core plate CadQuery solid (from ``create_core_plate``). + + Returns: + Tuple of: + - ``cq.Compound``: All parts merged for STL export. + - ``dict``: ``{'core_plate': solid, 'arms': [{part_name: solid, …}, …]}`` + for STEP assembly export with named / coloured parts. + """ + all_solids = [core_plate_solid.val()] + named = {"core_plate": core_plate_solid, "arms": []} + + for arm_params in arms_params: + placed = place_arm_on_plate(arm_params, cfg) + arm_entry = {} + + for part_name, part_wp in placed.items(): + solid = part_wp.val() + all_solids.append(solid) + arm_entry[part_name] = part_wp + + named["arms"].append(arm_entry) + + compound = cq.Compound.makeCompound(all_solids) + return compound, named diff --git a/src/ariel/body_phenotypes/drone/phenotype_assembly/config.py b/src/ariel/body_phenotypes/drone/phenotype_assembly/config.py new file mode 100644 index 000000000..722c7f330 --- /dev/null +++ b/src/ariel/body_phenotypes/drone/phenotype_assembly/config.py @@ -0,0 +1,74 @@ + +""" +Physical constants and default dimensions for phenotype assembly. + +All measurements in millimeters unless otherwise noted. +""" + +# ══════════════════════════════════════════════════════════════════════════════ +# Screw / Fastener Parameters +# ══════════════════════════════════════════════════════════════════════════════ + +screw_size = 2.0 +screw_size_tolerance = 0.3 + +# ══════════════════════════════════════════════════════════════════════════════ +# Core Plate Parameters +# ══════════════════════════════════════════════════════════════════════════════ + +# Overall dimensions +plate_diameter = 60.0 +plate_thickness = 2.0 +plate_thickness_tolerance = 0.2 + +# Centre hub (solid disc at centre) +center_hub_radius = 20.0 +central_hole_diameter = 25.0 + +# Outer ring (annular ring at perimeter) +outer_ring_width = 6.5 +outer_ring_inner_radius = plate_diameter / 2 - outer_ring_width + +# Radial struts (connecting hub to outer ring) +strut_width = 12.0 +number_struts = 4 + +# Screw holes +screw_pattern_radius = plate_diameter / 2 - 7.5 # 7.5mm inset from edge +number_holes = 32 +screw_square_size = 25.5 + +# ══════════════════════════════════════════════════════════════════════════════ +# Arm Mount Parameters (sphere clamp on plate rim) +# ══════════════════════════════════════════════════════════════════════════════ + +# Inner cutout cylinders (above/below plate slot to reduce sphere overhang) +arm_mount_inner_cutout_height = 8.0 + +# Screw hole angles relative to slot centre (degrees) +arm_mount_screw_angles = [180.0 - 11.25, 180.0 + 11.25] + +# ══════════════════════════════════════════════════════════════════════════════ +# Motor Arm Parameters (tube + motor disc) +# ══════════════════════════════════════════════════════════════════════════════ + +# Arm tube dimensions +arm_cylinder_inner_radius = 8.0 / 2 +arm_cylinder_inner_radius_tolerance = 0.3 + +# Motor disc mounting +intermediary_outer_screw_pattern_radius = 18.0 / 2 + +# Flattening disc (removes overhang material beyond motor disc face) +motor_flattening_disc_thickness = 10.0 + +# ══════════════════════════════════════════════════════════════════════════════ +# Motor Mount Parameters (modular separate printable mount) +# ══════════════════════════════════════════════════════════════════════════════ + +# Socket cylinder dimensions +motor_mount_cylinder_height = 20.0 +motor_mount_cylinder_bottom_thickness = 20.0 + +# Mounting screw +motor_mount_screw_inset = 5.0 diff --git a/src/ariel/body_phenotypes/drone/phenotype_assembly/generator.py b/src/ariel/body_phenotypes/drone/phenotype_assembly/generator.py new file mode 100644 index 000000000..c4e57f3a2 --- /dev/null +++ b/src/ariel/body_phenotypes/drone/phenotype_assembly/generator.py @@ -0,0 +1,280 @@ +""" +STL / STEP Generator + +Top-level orchestration: converts a genome handler into physical files. + +Pipeline +-------- +genome_handler + → genome_adapter.genome_to_cad_parameters() → DroneCADParameters + → assembler.assemble_drone() → compound solid + named dict + → export (STL / STEP) + +Public API +---------- + generate_stl_files(genome_handler, ...) -> STLGenerationResult + quick_visualize_genome(genome_handler, output_file) -> Path +""" + +import cadquery as cq +from pathlib import Path +from typing import Optional + +from .models import AssemblyConfig, DroneCADParameters, STLGenerationResult +from .genome_adapter import genome_to_cad_parameters +from .assembler import assemble_drone +from .parts.core_plate import create_core_plate + +# Part colours for STEP export +_PART_COLORS = { + "sphere": cq.Color("lightblue"), + "motor_arm": cq.Color("orange"), +} + + +def generate_stl_files( + genome_handler, + output_dir: str = "./drone_stls", + include_assembly: bool = True, + include_individual_parts: bool = True, + include_motor_mounts: bool = False, + include_arm_mounts: bool = False, + include_step_files: bool = True, + include_landing_leg: bool = False, + distribute_arms_evenly: bool = False, + magnitude_to_length_scale: float = 100.0, + assembly_config: Optional[AssemblyConfig] = None, + snap_mounts: bool = False, + num_mount_positions: int = 8, +) -> STLGenerationResult: + """ + Generate STL (and optionally STEP) files for a drone from a genome handler. + + Args: + genome_handler: ``SphericalAngularDroneGenomeHandler`` with a loaded genome. + output_dir: Directory to write output files. + include_assembly: If True, write a combined ``full_drone_assembly.stl``. + include_individual_parts: If True, write ``core_plate.stl`` and one + ``arm_N.stl`` per arm (integrated tube + motor disc). + include_motor_mounts: If True, write separate ``motor_mount_N.stl`` files + (hollow socket with motor disc, for modular assembly). + include_arm_mounts: If True, write separate ``arm_mount_N.stl`` files + (sphere with arm socket hole, for modular assembly). + include_step_files: If True, also write STEP equivalents. + include_landing_leg: Reserved for future use (no-op currently). + distribute_arms_evenly: When True, arm attachment angles are evenly + spaced regardless of the genome's ``arm_rotation`` values. + magnitude_to_length_scale: Genome magnitude → arm length in mm. + assembly_config: Physical dimensions. Defaults to ``AssemblyConfig()``. + snap_mounts: When True, snap each arm mount to the nearest of + ``num_mount_positions`` discrete positions on the plate rim. + The motor tip position is preserved. Default False. + num_mount_positions: Number of discrete mount positions (default 8). + + Returns: + ``STLGenerationResult`` with paths to every generated file. + """ + output_path = Path(output_dir) + output_path.mkdir(parents=True, exist_ok=True) + + if assembly_config is None: + assembly_config = AssemblyConfig() + + result = STLGenerationResult(output_dir=output_path) + + # ── Convert genome ─────────────────────────────────────────────────────── + cad_params: DroneCADParameters = genome_to_cad_parameters( + genome_handler, + magnitude_to_length_scale=magnitude_to_length_scale, + distribute_arms_evenly=distribute_arms_evenly, + assembly_config=assembly_config, + snap_mounts=snap_mounts, + num_mount_positions=num_mount_positions, + ) + + if cad_params.num_arms == 0: + print("Warning: no valid arms in genome — skipping STL generation.") + return result + + print(f"Generating STL files for drone with {cad_params.num_arms} arms") + print(f"Output directory: {output_path}") + + # ── Core plate ─────────────────────────────────────────────────────────── + print("\nGenerating core plate…") + core_plate = create_core_plate( + plate_diameter=assembly_config.plate_diameter, + plate_thickness=assembly_config.plate_thickness, + outer_ring_width=assembly_config.outer_ring_width, + include_hollow_square=assembly_config.include_hollow_square, + hollow_square_outer_size=assembly_config.hollow_square_outer_size, + hollow_square_wall_thickness=assembly_config.hollow_square_wall_thickness, + ) + + if include_individual_parts: + core_plate_file = output_path / "core_plate.stl" + cq.exporters.export(core_plate, str(core_plate_file)) + result.core_plate_file = core_plate_file + print(f" Saved: {core_plate_file.name}") + + if include_step_files: + step_file = output_path / "core_plate.step" + core_plate.val().exportStep(str(step_file)) + result.step_files.append(step_file) + + # ── Arms (individual STLs) ─────────────────────────────────────────────── + if include_individual_parts: + from .assembler import place_arm_on_plate + + for i, arm_params in enumerate(cad_params.arms): + print(f"\nGenerating arm {i + 1}…") + print(f" Attachment angle: {arm_params.attachment_angle:.1f}° " + f"Elevation: {arm_params.arm_elevation:.1f}° " + f"Length: {arm_params.arm_length:.1f} mm") + + placed = place_arm_on_plate(arm_params, assembly_config) + arm_compound = cq.Compound.makeCompound( + [p.val() for p in placed.values()] + ) + arm_file = output_path / f"arm_{i + 1}.stl" + cq.exporters.export(arm_compound, str(arm_file)) + result.arm_files.append(arm_file) + print(f" Saved: {arm_file.name}") + + # ── Motor mounts (separate STLs for modular assembly) ──────────────────── + if include_motor_mounts: + from .parts.motor_mount import create_motor_mount + + for i, arm_params in enumerate(cad_params.arms): + print(f"\nGenerating motor mount {i + 1}…") + print(f" Motor tilt: {arm_params.motor_tilt:.1f}° " + f"Motor azimuth: {arm_params.motor_azimuth:.1f}°") + + motor_mount = create_motor_mount( + motor_tilt=arm_params.motor_tilt, + motor_azimuth=arm_params.motor_azimuth, + cylinder_inner_radius=assembly_config.cylinder_inner_radius, + pocket_thickness=assembly_config.wall_thickness, + sphere_offset=assembly_config.sphere_offset, + cylinder_extension=assembly_config.cylinder_extension, + disc_diameter=assembly_config.disc_diameter, + disc_thickness=assembly_config.disc_thickness, + motor_screw_count=assembly_config.motor_screw_count, + motor_screw_start_angle=assembly_config.motor_screw_start_angle, + motor_screw_depth=assembly_config.motor_screw_depth, + center_hole_diameter=assembly_config.center_hole_diameter, + ) + + motor_mount_file = output_path / f"motor_mount_{i + 1}.stl" + cq.exporters.export(motor_mount, str(motor_mount_file)) + result.motor_mount_files.append(motor_mount_file) + print(f" Saved: {motor_mount_file.name}") + + # ── Arm mounts (separate STLs for modular assembly) ────────────────────── + if include_arm_mounts: + from .parts.arm_mount import create_arm_mount + + for i, arm_params in enumerate(cad_params.arms): + print(f"\nGenerating arm mount {i + 1}…") + print(f" Mount angle: {arm_params.mount_angle:.1f}° " + f"Arm elevation: {arm_params.arm_elevation:.1f}° " + f"Arm azimuth: {arm_params.attachment_angle:.1f}°") + + mount_parts = create_arm_mount( + sphere_radius=assembly_config.sphere_radius, + clamp_inset=assembly_config.clamp_inset, + arm_plate_diameter=assembly_config.plate_diameter, + arm_plate_thickness=assembly_config.plate_thickness, + arm_screw_hole_inset=assembly_config.arm_screw_hole_inset, + include_arm_socket=True, # Enable socket for separate printing + arm_elevation=arm_params.arm_elevation, + arm_azimuth=arm_params.attachment_angle, + ) + + # Extract sphere from dict and export + arm_mount_file = output_path / f"arm_mount_{i + 1}.stl" + cq.exporters.export(mount_parts["sphere"], str(arm_mount_file)) + result.arm_mount_files.append(arm_mount_file) + print(f" Saved: {arm_mount_file.name}") + + # ── Full assembly ──────────────────────────────────────────────────────── + if include_assembly: + print("\nGenerating full assembly…") + compound, named = assemble_drone(cad_params.arms, assembly_config, core_plate) + + assembly_file = output_path / "full_drone_assembly.stl" + cq.exporters.export(compound, str(assembly_file)) + result.assembly_file = assembly_file + print(f" Saved: {assembly_file.name}") + + if include_step_files: + step_assembly = cq.Assembly() + step_assembly.add( + named["core_plate"], + name="core_plate", + color=cq.Color("gray"), + ) + for i, arm_parts in enumerate(named["arms"]): + for part_name, part_wp in arm_parts.items(): + step_assembly.add( + part_wp, + name=f"arm{i + 1}_{part_name}", + color=_PART_COLORS.get(part_name, cq.Color("white")), + ) + + step_file = output_path / "full_drone_assembly.step" + step_assembly.save(str(step_file)) + result.step_files.append(step_file) + print(f" Saved STEP: {step_file.name}") + + print("\n" + "=" * 70) + print("STL generation completed.") + print("=" * 70) + print(f"\nGenerated files in: {output_path}") + if result.core_plate_file: + print(f" Core plate: {result.core_plate_file.name}") + if result.arm_files: + print(f" Arms: {len(result.arm_files)} files") + if result.motor_mount_files: + print(f" Motor mounts: {len(result.motor_mount_files)} files") + if result.arm_mount_files: + print(f" Arm mounts: {len(result.arm_mount_files)} files") + if result.assembly_file: + print(f" Assembly: {result.assembly_file.name}") + if result.step_files: + print(f" STEP files: {len(result.step_files)} files") + + return result + + +def quick_visualize_genome( + genome_handler, + output_file: str = "quick_drone.stl", +) -> Optional[Path]: + """ + Quickly generate a single combined STL for visual inspection. + + Args: + genome_handler: ``SphericalAngularDroneGenomeHandler`` with a loaded genome. + output_file: Path for the output STL. + + Returns: + ``Path`` to the generated file, or ``None`` if generation failed. + """ + import os + + out_dir = os.path.dirname(output_file) or "." + result = generate_stl_files( + genome_handler, + output_dir=out_dir, + include_assembly=True, + include_individual_parts=False, + include_step_files=False, + include_landing_leg=False, + ) + + if result.assembly_file: + dest = Path(output_file) + result.assembly_file.rename(dest) + return dest + + return None diff --git a/src/ariel/body_phenotypes/drone/phenotype_assembly/genome_adapter.py b/src/ariel/body_phenotypes/drone/phenotype_assembly/genome_adapter.py new file mode 100644 index 000000000..0ec0d8684 --- /dev/null +++ b/src/ariel/body_phenotypes/drone/phenotype_assembly/genome_adapter.py @@ -0,0 +1,355 @@ +""" +Genome → CAD Parameter Adapter + +Converts a ``SphericalAngularDroneGenomeHandler`` genome into +``DroneCADParameters`` which can then be fed directly to the assembler. + +Genome column layout +-------------------- +Index Name Range Units + 0 magnitude [0.5, 2.0] (simulation scale; multiply by length_scale → mm) + 1 arm_rotation [0, 2π] radians – azimuthal angle θ in XY plane + 2 arm_pitch [−π/2, π/2] radians – elevation angle above XY plane + (0 = horizontal, π/2 = straight up) + 3 motor_rotation [0, 2π] radians – motor disc azimuth + 4 motor_pitch [−π/2, π/2] radians – motor disc elevation angle + 5 direction {0, 1} – – propeller spin (0=CCW, 1=CW) + +Mapping to ``ArmCADParameters`` +-------------------------------- +attachment_angle = degrees(arm_rotation) # azimuth directly +arm_elevation = degrees(arm_pitch) # elevation angle maps directly + # 0 → arm lies in horizontal XY plane + # π/2 → arm points straight up + # −π/2→ arm points straight down +motor_tilt = acos(n_local_z) # local-frame tilt recovered by +motor_azimuth = atan2(n_local_y, # inverting the assembler's Ry/Rz + n_local_x) # so motor_rotation/motor_pitch define + # the disc normal in **world space** +arm_length = magnitude * scale − attach_radius + # subtract the attachment radial offset so + # the motor tip lands at the same (x,y,z) + # as the simulation motor position + +snap_mounts +----------- +When ``snap_mounts=True`` the arm mount sphere is snapped to the nearest of +``num_mount_positions`` evenly-spaced discrete positions on the plate rim. +The motor tip stays at the same world-space position; the arm length, +elevation, and azimuth are recomputed from the vector between the snapped +mount centre and the motor tip. +""" + +import math +import numpy as np +from typing import List, Optional, Tuple + +from .models import ArmCADParameters, DroneCADParameters, AssemblyConfig + + +def _snap_angle(angle_rad: float, num_positions: int) -> float: + """Round ``angle_rad`` to the nearest of ``num_positions`` evenly-spaced + angles around the circle. Returns the snapped angle in radians in [0, 2π).""" + step = 2.0 * math.pi / num_positions + return round(angle_rad / step) * step % (2.0 * math.pi) + + +def _assign_mount_slots( + cont_angles_rad: List[float], + motor_tips: List[Tuple[float, float, float]], + num_positions: int, + attach_radius: float, + mount_z: float, +) -> List[float]: + """Assign each arm to a unique discrete slot on the plate rim, minimising + the total 3-D distance from each assigned slot centre to the arm's motor tip. + + When the number of arms is ≤ ``num_positions`` the assignment is globally + optimal (Hungarian algorithm via ``scipy.optimize.linear_sum_assignment``). + When there are more arms than slots a greedy nearest-neighbour with + collision avoidance is used as a fallback. + + Args: + cont_angles_rad: Continuous (genome) azimuth for each arm, in radians. + motor_tips: World-space (x, y, z) of each arm's motor tip. + num_positions: Number of equally-spaced discrete slots around the rim. + attach_radius: Radial distance from drone centre to the slot centre. + mount_z: Z coordinate of every slot centre (plate mid-plane). + + Returns: + List of assigned slot angles, one per arm, in radians, in [0, 2π). + """ + num_arms = len(cont_angles_rad) + step = 2.0 * math.pi / num_positions + slot_angles = [i * step for i in range(num_positions)] + + # Slot centre positions on the plate rim + slot_positions = [ + (attach_radius * math.cos(a), attach_radius * math.sin(a), mount_z) + for a in slot_angles + ] + + if num_arms <= num_positions: + # Build cost matrix: cost[arm_idx, slot_idx] = distance from slot to motor tip + cost = np.zeros((num_arms, num_positions)) + for ai, (mx, my, mz) in enumerate(motor_tips): + for si, (sx, sy, sz) in enumerate(slot_positions): + cost[ai, si] = math.sqrt( + (mx - sx) ** 2 + (my - sy) ** 2 + (mz - sz) ** 2 + ) + + try: + from scipy.optimize import linear_sum_assignment + _row_ind, col_ind = linear_sum_assignment(cost) + except ImportError: + # scipy not available — fall through to greedy + col_ind = None + + if col_ind is not None: + assigned = [slot_angles[col_ind[ai]] for ai in range(num_arms)] + return assigned + + # Greedy fallback: process arms in order of how far their nearest free slot + # is from their continuous angle (most-constrained first). + available = list(range(num_positions)) + # Sort arms by distance to nearest available slot (ascending), so arms + # that are close to their ideal slot get first pick. + order = sorted( + range(num_arms), + key=lambda ai: min( + abs(cont_angles_rad[ai] - slot_angles[si]) % (2.0 * math.pi) + for si in available + ), + ) + assigned_slots = [None] * num_arms + for ai in order: + mx, my, mz = motor_tips[ai] + best_si = min( + available, + key=lambda si: math.sqrt( + (mx - slot_positions[si][0]) ** 2 + + (my - slot_positions[si][1]) ** 2 + + (mz - slot_positions[si][2]) ** 2 + ), + ) + assigned_slots[ai] = slot_angles[best_si] + available.remove(best_si) + if not available: + # Ran out of unique slots — reopen all (more arms than slots) + available = list(range(num_positions)) + + return [a % (2.0 * math.pi) for a in assigned_slots] + + +def genome_to_cad_parameters( + genome_handler, + magnitude_to_length_scale: float = 100.0, + distribute_arms_evenly: bool = False, + assembly_config: Optional[AssemblyConfig] = None, + snap_mounts: bool = False, + num_mount_positions: int = 8, +) -> DroneCADParameters: + """ + Convert a SphericalAngularDroneGenomeHandler to DroneCADParameters. + + The genome stores arm positions as spherical coordinates where ``arm_pitch`` + is an **elevation** angle (degrees above the XY plane), matching the + convention used by ``utils.convert_to_cartesian`` in the visualizer. + + Because the physical arm attaches at the plate rim (not the drone centre), + the arm tube length is reduced by the attachment radial offset so that the + motor tip ends up at the same absolute position as the simulation motor. + + Args: + genome_handler: A ``SphericalAngularDroneGenomeHandler`` instance with + a valid genome loaded. + magnitude_to_length_scale: Multiplier converting genome magnitude to + the simulation-space motor distance from centre in mm. + Default 100 mm / unit. + distribute_arms_evenly: When *True*, ignore the genome's + ``arm_rotation`` and instead space arms evenly around the plate + (0°, 360/n°, …). Useful for visualisation of symmetric designs + but loses fidelity to the evolved genome. Default *False*. + assembly_config: Physical assembly dimensions used to compute the + attachment radial offset. Defaults to ``AssemblyConfig()``. + snap_mounts: When *True*, snap each arm mount to the nearest of + ``num_mount_positions`` discrete positions on the plate rim. + The motor tip position is preserved; arm length, elevation, and + azimuth are recomputed from the vector between the snapped mount + and the original motor tip. Default *False*. + num_mount_positions: Number of discrete mount positions around the + plate rim. Only used when ``snap_mounts=True``. Default 8 + (positions at 0°, 45°, 90°, …, 315°). + + Returns: + ``DroneCADParameters`` containing one ``ArmCADParameters`` per active arm. + """ + if assembly_config is None: + assembly_config = AssemblyConfig() + + # Radial distance from the drone centre to where the arm tube starts + # (the sphere centre on the plate rim). + attach_radius = assembly_config.arm_attach_radial_distance + # Z height of the sphere centre (plate mid-plane) + mount_z = assembly_config.plate_thickness / 2.0 + # Sphere offset along the arm axis (from tube end to disc centre) + sphere_offset = assembly_config.sphere_offset + + valid_arms = genome_handler.get_valid_arms() + num_arms = len(valid_arms) + + if num_arms == 0: + return DroneCADParameters(arms=[]) + + # ── Pass 1: collect continuous angles and motor tip positions ──────────── + cont_angles_rad: List[float] = [] + motor_tips: List[Tuple[float, float, float]] = [] + + for i, arm in enumerate(valid_arms): + magnitude, arm_rotation, arm_pitch, _motor_rotation, _motor_pitch, _direction = arm + + if distribute_arms_evenly: + cont_angle_rad = math.radians((360.0 / num_arms) * i) + else: + cont_angle_rad = float(arm_rotation) % (2.0 * math.pi) + + motor_distance = float(magnitude) * magnitude_to_length_scale + pitch_rad = float(arm_pitch) + motor_x = motor_distance * math.cos(pitch_rad) * math.cos(cont_angle_rad) + motor_y = motor_distance * math.cos(pitch_rad) * math.sin(cont_angle_rad) + motor_z = motor_distance * math.sin(pitch_rad) + + cont_angles_rad.append(cont_angle_rad) + motor_tips.append((motor_x, motor_y, motor_z)) + + # ── Snap mount angles: globally optimal unique-slot assignment ─────────── + if snap_mounts: + snapped_rads = _assign_mount_slots( + cont_angles_rad, motor_tips, num_mount_positions, attach_radius, mount_z + ) + else: + snapped_rads = list(cont_angles_rad) + + # ── Pass 2: build ArmCADParameters from the assigned mount angles ──────── + arms_params: List[ArmCADParameters] = [] + + for i, arm in enumerate(valid_arms): + _magnitude, _arm_rotation, _arm_pitch, motor_rotation, motor_pitch, direction = arm + + motor_x, motor_y, motor_z = motor_tips[i] + snapped_rad = snapped_rads[i] + + mount_angle = float(np.degrees(snapped_rad)) % 360.0 + + # ── Mount position on plate rim ────────────────────────────────────── + mount_x = attach_radius * math.cos(snapped_rad) + mount_y = attach_radius * math.sin(snapped_rad) + + # ── Vector from mount centre to motor tip ──────────────────────────── + vx = motor_x - mount_x + vy = motor_y - mount_y + vz = motor_z - mount_z + + # Arm tube azimuth: direction the arm points from the mount + attachment_angle = float(np.degrees(math.atan2(vy, vx))) % 360.0 + + # Arm elevation: angle above horizontal + vxy = math.sqrt(vx * vx + vy * vy) + arm_elevation = float(np.degrees(math.atan2(vz, vxy))) + + # Arm length: distance from mount sphere surface to motor tip. + # Subtract sphere_offset because the motor disc sits sphere_offset mm + # beyond the end of the arm tube (see create_motor_arm). + arm_vector_length = math.sqrt(vx * vx + vy * vy + vz * vz) + arm_length = max(arm_vector_length - sphere_offset, 1.0) + + # ── Motor orientation ───────────────────────────────────────────────── + # The genome's motor_rotation (yaw) and motor_pitch define the motor + # disc orientation in **world space**: + # + # motor_pitch = 0 → disc faces straight up (+Z in world space) + # motor_pitch = π/2 → disc faces radially outward (toward motor tip) + # motor_rotation → azimuthal rotation of the disc normal in world XY + # + # motor_arm.py builds the disc in the arm's local frame (tube = +Z), then + # the assembler applies: + # + # Step 1: Ry(β) where β = 90° − arm_elevation (tilt arm to elevation) + # Step 2: Rz(α) where α = attachment_angle (spin arm to azimuth) + # + # To produce the correct world-space normal from genome parameters, we + # must express the desired world normal in the arm's local frame by + # applying the **inverse** of the assembler's rotations: + # + # n_local = Ry(−β) @ Rz(−α) @ n_world + # + # where n_world = [sin(p)·cos(y), sin(p)·sin(y), cos(p)] + # p = motor_pitch (radians), y = motor_rotation (radians) + # + # Then (motor_tilt, motor_azimuth) are recovered by decomposing n_local: + # motor_tilt = acos(n_local_z) in [0°, 180°] + # motor_azimuth = atan2(n_local_y, n_local_x) in [0°, 360°) + + p_rad = float(motor_pitch) + y_rad = float(motor_rotation) + + # Desired world-space disc normal + nwx = math.sin(p_rad) * math.cos(y_rad) + nwy = math.sin(p_rad) * math.sin(y_rad) + nwz = math.cos(p_rad) + + # Inverse of assembler's Rz(α): apply Rz(−α) + alpha = math.radians(attachment_angle) + ca, sa = math.cos(alpha), math.sin(alpha) + nx_rz = nwx * ca + nwy * sa + ny_rz = -nwx * sa + nwy * ca + nz_rz = nwz + + # Inverse of assembler's Ry(β): apply Ry(−β) + beta = math.radians(90.0 - arm_elevation) + cb, sb = math.cos(beta), math.sin(beta) + nlx = nx_rz * cb - nz_rz * sb + nly = ny_rz + nlz = nx_rz * sb + nz_rz * cb + + # Decompose local normal into (motor_tilt, motor_azimuth) + motor_tilt = math.degrees(math.acos(max(-1.0, min(1.0, nlz)))) + motor_azimuth = math.degrees(math.atan2(nly, nlx)) % 360.0 + + # ── Motor flip detection ────────────────────────────────────────────── + # Check whether the world-space disc normal points back into the arm + # (i.e. the motor faces toward the core plate). We already have the + # world normal n_world = (nwx, nwy, nwz) from the computation above. + # + # If dot(arm_outward, n_world) < 0 the motor faces back toward the + # plate — the disc would intersect the arm tube. Flip by rotating + # 180° around the local X-axis: + # motor_tilt → 180° − motor_tilt + # motor_azimuth → motor_azimuth + 180° + # The spin direction is also inverted so thrust direction is preserved. + _FLIP_DEG = 5.0 # degrees past 90° before flip triggers + _FLIP_COS = math.cos(math.radians(90.0 + _FLIP_DEG)) # ≈ −0.087 + + arm_len = math.sqrt(vx * vx + vy * vy + vz * vz) + if arm_len > 0: + ux, uy, uz = vx / arm_len, vy / arm_len, vz / arm_len + else: + ux, uy, uz = 1.0, 0.0, 0.0 + + dot = ux * nwx + uy * nwy + uz * nwz + if dot < _FLIP_COS: + motor_tilt = 180.0 - motor_tilt + motor_azimuth = (motor_azimuth + 180.0) % 360.0 + direction = 1 - int(direction) + + arms_params.append(ArmCADParameters( + attachment_angle=attachment_angle, + mount_angle=mount_angle, + arm_elevation=arm_elevation, + arm_length=arm_length, + motor_tilt=motor_tilt, + motor_azimuth=motor_azimuth, + direction=int(direction), + )) + + return DroneCADParameters(arms=arms_params) diff --git a/src/ariel/body_phenotypes/drone/phenotype_assembly/models.py b/src/ariel/body_phenotypes/drone/phenotype_assembly/models.py new file mode 100644 index 000000000..d4044ff89 --- /dev/null +++ b/src/ariel/body_phenotypes/drone/phenotype_assembly/models.py @@ -0,0 +1,158 @@ +""" +Data models for the phenotype assembly pipeline. + +All dataclasses used across genome_adapter, assembler, and generator live here +so there is a single source of truth for each type. +""" + +from __future__ import annotations + +from dataclasses import dataclass, field +from pathlib import Path +from typing import List, Optional + +from . import config + + +# ───────────────────────────────────────────────────────────────────────────── +# Arm / drone parameters produced by genome_adapter +# ───────────────────────────────────────────────────────────────────────────── + +@dataclass +class ArmCADParameters: + """Physical parameters for one arm, ready for CAD generation. + + Angles are all in **degrees** (converted from genome radians by + ``genome_adapter``). + + Attributes: + attachment_angle: Azimuthal angle (0–360°) the arm tube points toward + in the world XY plane. 0° = +X axis, 90° = +Y axis, etc. + When ``snap_mounts=False`` this equals the genome's ``arm_rotation`` + directly. When ``snap_mounts=True`` it is the angle from the + snapped mount position toward the motor tip. + mount_angle: Azimuthal angle (0–360°) of the arm mount sphere on the + plate rim. When ``snap_mounts=False`` this equals + ``attachment_angle``. When ``snap_mounts=True`` this is snapped + to the nearest discrete mount position (e.g. multiples of 45° for + 8 positions). + arm_elevation: Elevation of the arm above horizontal (degrees). + 0° = arm lies in the XY plane, positive = arm tilts upward. + When snapping is active this is recomputed from the vector between + the snapped mount and the original motor tip. + arm_length: Length of the arm tube in mm. When snapping is active + this is recomputed as the distance from the snapped mount to the + motor tip minus ``sphere_offset``. + motor_tilt: Motor disc tilt in **local arm space** (degrees), passed + directly to ``create_motor_arm``. 0° = disc normal aligns with + +Z (arm tube axis); 90° = disc normal points radially outward. + Computed by ``genome_adapter`` by inverting the assembler's + Ry/Rz rotations so that ``motor_pitch=0`` in the genome means + the disc faces straight up in world space regardless of arm + orientation. + motor_azimuth: Motor disc azimuth in **local arm space** (degrees, + rotation around Z after tilt), chosen so that the resulting + world-space disc normal matches the genome's ``motor_rotation`` + (which is interpreted as a world-frame azimuth). + direction: Propeller spin direction. 0 = CCW, 1 = CW. + """ + attachment_angle: float # degrees, 0–360 — direction arm tube points + mount_angle: float # degrees, 0–360 — where sphere sits on plate rim + arm_elevation: float # degrees, 0 = horizontal, positive = up + arm_length: float # mm + motor_tilt: float # degrees (local arm space) + motor_azimuth: float # degrees + direction: int # 0 = CCW, 1 = CW + + +@dataclass +class DroneCADParameters: + """Complete set of per-arm CAD parameters for one drone individual.""" + arms: List[ArmCADParameters] + + @property + def num_arms(self) -> int: + return len(self.arms) + + +# ───────────────────────────────────────────────────────────────────────────── +# Assembly configuration (replaces the stringly-typed part_config dict) +# ───────────────────────────────────────────────────────────────────────────── + +@dataclass +class AssemblyConfig: + """Physical dimensions used during part generation and assembly. + + All measurements in **mm**. Defaults mirror the values previously + scattered across ``config.py`` and ``stl_generator.py``. + """ + # Core plate (must match the actual plate being used) + plate_diameter: float = config.plate_diameter + plate_thickness: float = config.plate_thickness + outer_ring_width: float = config.outer_ring_width + include_hollow_square: bool = True + hollow_square_outer_size: float = 33.0 + hollow_square_wall_thickness: float = 2.0 + + # Arm mount (sphere clamp) + sphere_radius: float = 12.0 + clamp_inset: float = 10.5 + arm_screw_hole_inset: float = config.outer_ring_width / 2 # = 3.25 mm + + # Motor arm tube + cylinder_inner_radius: float = config.arm_cylinder_inner_radius + wall_thickness: float = 1.0 + cylinder_extension: float = 13.428 + sphere_offset: float = 5.0 + + # Motor disc + disc_diameter: float = 23.0 + disc_thickness: float = 3.0 + motor_screw_count: int = 4 + motor_screw_start_angle: float = 45.0 + motor_screw_depth: float = 25.0 + center_hole_diameter: float = 0.0 + + @property + def plate_radius(self) -> float: + return self.plate_diameter / 2.0 + + @property + def outer_ring_inner_radius(self) -> float: + return self.plate_radius - self.outer_ring_width + + @property + def outer_ring_middle_radius(self) -> float: + return (self.plate_radius + self.outer_ring_inner_radius) / 2.0 + + @property + def arm_attach_radial_distance(self) -> float: + """Radial distance from drone centre to the arm mount sphere centre. + + The sphere overlaps the plate rim inward by ``clamp_inset``. Therefore: + + sphere_centre_r = plate_radius + (sphere_radius - clamp_inset) + + With defaults: 30 + (12 - 10.5) = 31.5 mm. + + Screw holes are at sphere_centre_r - arm_screw_hole_inset from centre, + i.e. 31.5 - 3.25 = 28.25 mm, landing in the middle of the outer ring. + """ + return self.plate_radius + (self.sphere_radius - self.clamp_inset) + + +# ───────────────────────────────────────────────────────────────────────────── +# Result type returned by generate_stl_files +# ───────────────────────────────────────────────────────────────────────────── + +@dataclass +class STLGenerationResult: + """Paths to every file produced by a single generate_stl_files() call.""" + output_dir: Path + core_plate_file: Optional[Path] = None + arm_files: List[Path] = field(default_factory=list) + motor_mount_files: List[Path] = field(default_factory=list) + arm_mount_files: List[Path] = field(default_factory=list) + assembly_file: Optional[Path] = None + landing_leg_file: Optional[Path] = None + step_files: List[Path] = field(default_factory=list) diff --git a/src/ariel/ec/drone/inspection/utils.py b/src/ariel/ec/drone/inspection/utils.py index 97fd5353a..206b52f3c 100644 --- a/src/ariel/ec/drone/inspection/utils.py +++ b/src/ariel/ec/drone/inspection/utils.py @@ -202,9 +202,10 @@ def extract_polar_genome_data(genome_array: npt.NDArray) -> dict: Returns: Dictionary with converted data for visualization """ - # Remove any invalid (NaN) entries - valid_mask = ~np.isnan(genome_array).any(axis=1) - valid_genome = genome_array[valid_mask] + # Cast to float so np.isnan works on integer-typed genomes (all slots filled) + genome_float = np.asarray(genome_array, dtype=float) + valid_mask = ~np.isnan(genome_float).any(axis=1) + valid_genome = genome_float[valid_mask] positions = [] orientations = [] @@ -241,9 +242,10 @@ def extract_cartesian_genome_data(genome_array: npt.NDArray) -> dict: Returns: Dictionary with converted data for visualization """ - # Remove any invalid (NaN) entries - valid_mask = ~np.isnan(genome_array).any(axis=1) - valid_genome = genome_array[valid_mask] + # Cast to float so np.isnan works on integer-typed genomes (all slots filled) + genome_float = np.asarray(genome_array, dtype=float) + valid_mask = ~np.isnan(genome_float).any(axis=1) + valid_genome = genome_float[valid_mask] positions = [] orientations = [] @@ -280,6 +282,10 @@ def auto_extract_genome_data(genome_data) -> dict: # Check if it's a genome handler with methods if hasattr(genome_data, 'get_motor_positions'): return extract_genome_data(genome_data) + + # SphericalAngularDroneGenomeHandler — use get_valid_arms() directly + if hasattr(genome_data, 'get_valid_arms'): + return extract_polar_genome_data(genome_data.get_valid_arms()) # Check if it's a numpy array (polar format) elif isinstance(genome_data, np.ndarray): @@ -293,8 +299,10 @@ def auto_extract_genome_data(genome_data) -> dict: if hasattr(genome_data, 'get_motor_positions'): return extract_cartesian_genome_data(genome_data) else: - # Assume polar format in genome attribute - return extract_polar_genome_data(genome_data.genome) + genome = genome_data.genome + # SphericalNeatGenome (or similar) stores the arm array in .arms + genome_array = genome.arms if hasattr(genome, 'arms') else genome + return extract_polar_genome_data(genome_array) else: raise ValueError(f"Unrecognized genome format: {type(genome_data)}") diff --git a/src/ariel/simulation/drone/controllers/px4_ctrl/__init__.py b/src/ariel/simulation/drone/controllers/px4_ctrl/__init__.py new file mode 100644 index 000000000..1d727f8cd --- /dev/null +++ b/src/ariel/simulation/drone/controllers/px4_ctrl/__init__.py @@ -0,0 +1,3 @@ +""" +PX4-based Control module +""" diff --git a/src/ariel/simulation/drone/controllers/px4_ctrl/px4_based_ctrl.py b/src/ariel/simulation/drone/controllers/px4_ctrl/px4_based_ctrl.py new file mode 100644 index 000000000..137069f0a --- /dev/null +++ b/src/ariel/simulation/drone/controllers/px4_ctrl/px4_based_ctrl.py @@ -0,0 +1,499 @@ +# -*- coding: utf-8 -*- +""" +Generalized Controller for Arbitrary Drone Configurations + +This controller extends the original PX4-based controller to work with any drone +configuration by using configurable allocation matrices instead of fixed mixers. + +Compatible with the existing configurable drone framework and maintains the same +interface as the original Control class. + +author: Enhanced from John Bass original controller +license: MIT +""" + +import numpy as np +from numpy import pi, sin, cos, tan, sqrt +from numpy.linalg import norm, pinv +import ariel.simulation.drone.controllers.utils as utils + +rad2deg = 180.0/pi +deg2rad = pi/180.0 + +class GeneralizedControl: + """ + Generalized Controller for Arbitrary Drone Configurations. + + This controller maintains the same interface as the original Control class + but uses configurable control allocation instead of fixed mixer matrices. + """ + + def __init__(self, quad, yawType, orient="NED", + pos_P_gain=np.array([1.0, 1.0, 3.0]), + vel_P_gain=np.array([5.0, 5.0, 5.0]), + vel_D_gain=np.array([0.5, 0.5, 1.0]), + vel_I_gain=np.array([5.0, 5.0, 5.0]), + att_P_gain=np.array([8.0, 8.0, 1.5]), + rate_P_gain=np.array([1.5, 1.5, 1.5]), + rate_D_gain=np.array([0.04, 0.04, 0.1]), + vel_max=np.array([5.0, 5.0, 5.0]), + vel_max_all=5.0, + saturate_vel_separately=False, + tilt_max=50.0*deg2rad, + rate_max=np.array([200.0*deg2rad, 200.0*deg2rad, 150.0*deg2rad]), + aggressiveness=1.0): + """ + Initialize generalized controller with configurable parameters and auto-scaling. + + Args: + quad: ConfigurableQuadcopter instance with drone configuration + yawType: Yaw control type (0 = no yaw control, 1 = yaw control enabled) + orient: Coordinate frame orientation ("NED" or "ENU") + + # Control Gains (base values, will be auto-scaled if enabled) + pos_P_gain: Position P gains [Px, Py, Pz] for X, Y, Z axes + vel_P_gain: Velocity P gains [Pxdot, Pydot, Pzdot] + vel_D_gain: Velocity D gains [Dxdot, Dydot, Dzdot] for damping + vel_I_gain: Velocity I gains [Ixdot, Iydot, Izdot] for steady-state error + att_P_gain: Attitude P gains [Pphi, Ptheta, Ppsi] for roll, pitch, yaw + rate_P_gain: Rate P gains [Pp, Pq, Pr] for roll, pitch, yaw rates + rate_D_gain: Rate D gains [Dp, Dq, Dr] for gyroscopic damping + + # Control Limits (base values, will be auto-scaled if enabled) + vel_max: Maximum velocities [uMax, vMax, wMax] in X, Y, Z axes (m/s) + vel_max_all: Maximum total velocity magnitude (m/s) + saturate_vel_separately: Whether to saturate each axis independently + tilt_max: Maximum tilt angle in radians (limits roll/pitch for safety) + rate_max: Maximum angular rates [pMax, qMax, rMax] in rad/s + + # Auto-scaling Parameters + aggressiveness: Overall scaling factor (0.5=conservative, 2.0=aggressive) + """ + # Store base control parameters + self.base_pos_P_gain = pos_P_gain.copy() + self.base_vel_P_gain = vel_P_gain.copy() + self.base_vel_D_gain = vel_D_gain.copy() + self.base_vel_I_gain = vel_I_gain.copy() + self.base_att_P_gain = att_P_gain.copy() + self.base_rate_P_gain = rate_P_gain.copy() + self.base_rate_D_gain = rate_D_gain.copy() + self.base_vel_max = vel_max.copy() + self.base_vel_max_all = vel_max_all + self.base_tilt_max = tilt_max + self.base_rate_max = rate_max.copy() + + # Store auto-scaling parameters + self.aggressiveness = aggressiveness + self.saturate_vel_separately = saturate_vel_separately + + # Store coordinate frame orientation + self.orient = orient + + # Get drone configuration first + self.drone_config = quad.drone_sim.config + self.num_motors = self.drone_config.num_motors + + # Use base values directly + self.pos_P_gain = self.base_pos_P_gain.copy() + self.vel_P_gain = self.base_vel_P_gain.copy() + self.vel_D_gain = self.base_vel_D_gain.copy() + self.vel_I_gain = self.base_vel_I_gain.copy() + self.att_P_gain = self.base_att_P_gain.copy() + self.rate_P_gain = self.base_rate_P_gain.copy() + self.rate_D_gain = self.base_rate_D_gain.copy() + self.vel_max = self.base_vel_max.copy() + self.vel_max_all = self.base_vel_max_all + self.tilt_max = self.base_tilt_max + self.rate_max = self.base_rate_max.copy() + + # Initialize state variables (same as original) + self.sDesCalc = np.zeros(16) + self.thr_int = np.zeros(3) + + # Initialize motor commands for arbitrary number of motors + self.w_cmd = np.ones(self.num_motors) * self._get_hover_speed(quad) + + # Setup yaw control + if (yawType == 0): + self.att_P_gain[2] = 0 + self.setYawWeight() + + # Initialize control variables (same as original) + self.pos_sp = np.zeros(3) + self.vel_sp = np.zeros(3) + self.acc_sp = np.zeros(3) + self.thrust_sp = np.zeros(3) + self.eul_sp = np.zeros(3) + self.pqr_sp = np.zeros(3) + self.yawFF = np.zeros(3) + + def _get_hover_speed(self, quad): + """Calculate hover speed for each motor.""" + hover_speeds = [] + hover_thrust_per_motor = (quad.params["mB"] * quad.params["g"]) / self.num_motors + + for prop in self.drone_config.propellers: + k_f, k_m = prop["constants"] + w_hover = sqrt(hover_thrust_per_motor / k_f) + hover_speeds.append(w_hover) + + return np.array(hover_speeds) + + def _get_reference_properties(self): # TODO: Not used atm but could be used in future + """ + Get reference drone properties for gain scaling baseline. + Based on actual matched configuration from run_3D_simulation_configurable.py: + 0.16m arm quadrotor with matched props - extracted from ConfigurableQuadcopter. + """ + return { + 'char_length': 0.226274, # Characteristic length from arm lengths + 'mass': 1.517882, # Total mass from matched configuration + 'inertia_trace': 0.125761, # Inertia trace from matched configuration + 'Ix': 0.031352, 'Iy': 0.031554, 'Iz': 0.062855, # Inertia components + 'num_motors': 4, # Standard quadrotor + 'thrust_to_weight': 11.137963, # Actual T/W ratio + 'max_roll_torque': 6.633960, # Actual roll authority + 'max_pitch_torque': 6.633960, # Actual pitch authority + 'max_yaw_torque': 0.620392, # Actual yaw authority + } + + def controller(self, sDes, quad, ctrl_type, Ts): + """ + Main controller function. + + Args: + sDes: Desired state vector [pos(3), vel(3), acc(3), thrust(3), eul(3), pqr(3), yawRate] + quad: ConfigurableQuadcopter instance + ctrl_type: Control type ("xyz_pos", "xyz_vel", etc.) + Ts: Time step + """ + # Extract desired state + self.pos_sp[:] = sDes[0:3] + self.vel_sp[:] = sDes[3:6] + self.acc_sp[:] = sDes[6:9] + self.thrust_sp[:] = sDes[9:12] + self.eul_sp[:] = sDes[12:15] + self.pqr_sp[:] = sDes[15:18] + self.yawFF[:] = sDes[18] + + # Select Controller based on control type + if (ctrl_type == "xyz_vel"): + self.saturateVel() + self.z_vel_control(quad, Ts) + self.xy_vel_control(quad, Ts) + self.thrustToAttitude(quad, Ts) + self.attitude_control(quad, Ts) + self.rate_control(quad, Ts) + elif (ctrl_type == "xy_vel_z_pos"): + self.z_pos_control(quad, Ts) + self.saturateVel() + self.z_vel_control(quad, Ts) + self.xy_vel_control(quad, Ts) + self.thrustToAttitude(quad, Ts) + self.attitude_control(quad, Ts) + self.rate_control(quad, Ts) + elif (ctrl_type == "xyz_pos"): + self.z_pos_control(quad, Ts) + self.xy_pos_control(quad, Ts) + self.saturateVel() + self.z_vel_control(quad, Ts) + self.xy_vel_control(quad, Ts) + self.thrustToAttitude(quad, Ts) + self.attitude_control(quad, Ts) + self.rate_control(quad, Ts) + + # THRUST DIRECTION FIX: Use Z-component instead of magnitude to preserve direction + # In NED frame: positive Z is down, motors produce upward thrust (negative Z) + # So we need to negate the Z-component to match motor thrust direction + thrust_command = -self.thrust_sp[2] # Negate to convert NED Z to upward thrust + t = np.array([thrust_command, self.rateCtrl[0], self.rateCtrl[1], self.rateCtrl[2]]) + + # Convert thrust and moment to motor speeds using configurable mixer (REVERTED TO ORIGINAL) + # DEBUG: Add detailed tracing of control values + if hasattr(self, '_debug_control') and self._debug_control: + print(f" Control pipeline debug:") + print(f" thrust_sp magnitude: {np.linalg.norm(self.thrust_sp):.3f} N") + print(f" thrust_sp vector: [{self.thrust_sp[0]:.3f}, {self.thrust_sp[1]:.3f}, {self.thrust_sp[2]:.3f}]") + print(f" thrust_sp[2] (NED Z): {self.thrust_sp[2]:.3f} N") + print(f" thrust_command (corrected): {thrust_command:.3f} N") + print(f" rateCtrl: [{self.rateCtrl[0]:.6f}, {self.rateCtrl[1]:.6f}, {self.rateCtrl[2]:.6f}] N·m") + print(f" t vector: [{t[0]:.3f}, {t[1]:.6f}, {t[2]:.6f}, {t[3]:.6f}]") + mixer_product = np.dot(quad.params["mixerFMinv"], t) + print(f" mixerFMinv @ t: [{mixer_product[0]:.1f}, {mixer_product[1]:.1f}, {mixer_product[2]:.1f}, {mixer_product[3]:.1f}]") + + # ================================================================================== + # CONTROL ALLOCATION - CONVERT CONTROL COMMANDS TO MOTOR SPEEDS + # ================================================================================== + # + # PIPELINE STEP 1: Control Commands → Normalized Motor Commands + # Input vector t = [thrust_command_N, roll_moment_Nm, pitch_moment_Nm, yaw_moment_Nm] + # The mixerFMinv matrix maps these physical commands to normalized motor speeds [0,1] + # + # WHY NORMALIZED? + # - Different motors may have different w_max values (though usually identical) + # - Allocation matrices are pre-scaled for normalized inputs + # - Allows consistent control allocation regardless of motor specifications + # + w_squared_normalized = np.dot(quad.params["mixerFMinv"], t) + + # PIPELINE STEP 2: Normalized Commands → Actual Motor Speeds Squared + # Convert from normalized range [0,1] to actual motor speed squared values + # Physical relationship: F_motor = k_f * w² where w is actual motor speed + # + # For each motor i: w²_actual[i] = w²_normalized[i] * w_max[i]² + w_max_values = np.array([prop["wmax"] for prop in quad.drone_sim.config.propellers]) + w_squared_actual = w_squared_normalized * (w_max_values**2) + + # PIPELINE STEP 3: Apply Physical Limits and Extract Motor Speeds + # Clip to ensure motor speeds stay within physical capabilities: + # - Minimum: quad.params["minWmotor"] (typically 75 rad/s for stability) + # - Maximum: quad.params["maxWmotor"] (motor/ESC limit, typically w_max) + # + # Finally take square root to get actual commanded motor speeds in rad/s + self.w_cmd = np.sqrt(np.clip(w_squared_actual, + quad.params["minWmotor"]**2, + quad.params["maxWmotor"]**2)) + # self.w_cmd = mixerFM(quad, np.linalg.norm(self.thrust_sp), self.rateCtrl) + + # Add calculated Desired States (same as original) + self.sDesCalc[0:3] = self.pos_sp + self.sDesCalc[3:6] = self.vel_sp + self.sDesCalc[6:9] = self.thrust_sp + self.sDesCalc[9:13] = self.qd + self.sDesCalc[13:16] = self.rate_sp + + # All the following methods are identical to the original controller + # (position control, velocity control, attitude control, etc.) + + def z_pos_control(self, quad, Ts): + """Z Position Control (identical to original).""" + pos_z_error = self.pos_sp[2] - quad.pos[2] + self.vel_sp[2] += self.pos_P_gain[2]*pos_z_error + + def xy_pos_control(self, quad, Ts): + """XY Position Control (identical to original).""" + pos_xy_error = (self.pos_sp[0:2] - quad.pos[0:2]) + self.vel_sp[0:2] += self.pos_P_gain[0:2]*pos_xy_error + + def saturateVel(self): + """Saturate Velocity Setpoint (identical to original).""" + if (self.saturate_vel_separately): + self.vel_sp = np.clip(self.vel_sp, -self.vel_max, self.vel_max) + else: + totalVel_sp = norm(self.vel_sp) + if (totalVel_sp > self.vel_max_all): + self.vel_sp = self.vel_sp/totalVel_sp*self.vel_max_all + + def z_vel_control(self, quad, Ts): + """Z Velocity Control (identical to original).""" + vel_z_error = self.vel_sp[2] - quad.vel[2] + if (self.orient == "NED"): + thrust_z_sp = self.vel_P_gain[2]*vel_z_error - self.vel_D_gain[2]*quad.vel_dot[2] + quad.params["mB"]*(self.acc_sp[2] - quad.params["g"]) + self.thr_int[2] + elif (self.orient == "ENU"): + thrust_z_sp = self.vel_P_gain[2]*vel_z_error - self.vel_D_gain[2]*quad.vel_dot[2] + quad.params["mB"]*(self.acc_sp[2] + quad.params["g"]) + self.thr_int[2] + + # DEBUG: Check for large Z velocity control values + if hasattr(self, '_debug_control') and self._debug_control and abs(vel_z_error) > 2.0: + print(f" Z VEL CONTROL DEBUG:") + print(f" vel_sp[2]: {self.vel_sp[2]:.3f} m/s | quad.vel[2]: {quad.vel[2]:.3f} m/s") + print(f" vel_z_error: {vel_z_error:.3f} m/s") + print(f" vel_P_gain[2]: {self.vel_P_gain[2]:.3f} | vel_D_gain[2]: {self.vel_D_gain[2]:.3f}") + print(f" thrust_z_sp: {thrust_z_sp:.3f} N") + print(f" mass*gravity: {quad.params['mB']:.3f} * {quad.params['g']:.3f} = {quad.params['mB']*quad.params['g']:.3f} N") + + # Get thrust limits + if (self.orient == "NED"): + uMax = -quad.params["minThr"] + uMin = -quad.params["maxThr"] + elif (self.orient == "ENU"): + uMax = quad.params["maxThr"] + uMin = quad.params["minThr"] + + # Apply Anti-Windup in D-direction + stop_int_D = (thrust_z_sp >= uMax and vel_z_error >= 0.0) or (thrust_z_sp <= uMin and vel_z_error <= 0.0) + + # Calculate integral part + if not (stop_int_D): + self.thr_int[2] += self.vel_I_gain[2]*vel_z_error*Ts * quad.params["useIntergral"] + self.thr_int[2] = min(abs(self.thr_int[2]), quad.params["maxThr"])*np.sign(self.thr_int[2]) + + # Saturate thrust setpoint in D-direction + self.thrust_sp[2] = np.clip(thrust_z_sp, uMin, uMax) + + def xy_vel_control(self, quad, Ts): + """XY Velocity Control (identical to original).""" + vel_xy_error = self.vel_sp[0:2] - quad.vel[0:2] + thrust_xy_sp = self.vel_P_gain[0:2]*vel_xy_error - self.vel_D_gain[0:2]*quad.vel_dot[0:2] + quad.params["mB"]*(self.acc_sp[0:2]) + self.thr_int[0:2] + + # Max allowed thrust in NE based on tilt and excess thrust + thrust_max_xy_tilt = abs(self.thrust_sp[2])*np.tan(self.tilt_max) + thrust_max_xy = sqrt(quad.params["maxThr"]**2 - self.thrust_sp[2]**2) + thrust_max_xy = min(thrust_max_xy, thrust_max_xy_tilt) + + # Saturate thrust in NE-direction + self.thrust_sp[0:2] = thrust_xy_sp + if (np.dot(self.thrust_sp[0:2].T, self.thrust_sp[0:2]) > thrust_max_xy**2): + mag = norm(self.thrust_sp[0:2]) + self.thrust_sp[0:2] = thrust_xy_sp/mag*thrust_max_xy + + # Use tracking Anti-Windup for NE-direction + arw_gain = 2.0/self.vel_P_gain[0:2] + vel_err_lim = vel_xy_error - (thrust_xy_sp - self.thrust_sp[0:2])*arw_gain + self.thr_int[0:2] += self.vel_I_gain[0:2]*vel_err_lim*Ts * quad.params["useIntergral"] + + def thrustToAttitude(self, quad, Ts): + """Thrust to Attitude (identical to original).""" + yaw_sp = self.eul_sp[2] + + # Desired body_z axis direction + body_z = -utils.vectNormalize(self.thrust_sp) + if (self.orient == "ENU"): + body_z = -body_z + + # Vector of desired Yaw direction in XY plane, rotated by pi/2 (fake body_y axis) + y_C = np.array([-sin(yaw_sp), cos(yaw_sp), 0.0]) + + # Desired body_x axis direction + body_x = np.cross(y_C, body_z) + body_x = utils.vectNormalize(body_x) + + # Desired body_y axis direction + body_y = np.cross(body_z, body_x) + + # Desired rotation matrix + R_sp = np.array([body_x, body_y, body_z]).T + + # Full desired quaternion + self.qd_full = utils.RotToQuat(R_sp) + + def attitude_control(self, quad, Ts): + """Attitude Control (identical to original).""" + # Current thrust orientation e_z and desired thrust orientation e_z_d + e_z = quad.dcm[:,2] + e_z_d = -utils.vectNormalize(self.thrust_sp) + if (self.orient == "ENU"): + e_z_d = -e_z_d + + # Quaternion error between the 2 vectors + qe_red = np.zeros(4) + qe_red[0] = np.dot(e_z, e_z_d) + sqrt(norm(e_z)**2 * norm(e_z_d)**2) + qe_red[1:4] = np.cross(e_z, e_z_d) + qe_red = utils.vectNormalize(qe_red) + + # Reduced desired quaternion + self.qd_red = utils.quatMultiply(qe_red, quad.quat) + + # Mixed desired quaternion and resulting desired quaternion qd + q_mix = utils.quatMultiply(utils.inverse(self.qd_red), self.qd_full) + q_mix = q_mix*np.sign(q_mix[0]) + q_mix[0] = np.clip(q_mix[0], -1.0, 1.0) + q_mix[3] = np.clip(q_mix[3], -1.0, 1.0) + self.qd = utils.quatMultiply(self.qd_red, np.array([cos(self.yaw_w*np.arccos(q_mix[0])), 0, 0, sin(self.yaw_w*np.arcsin(q_mix[3]))])) + + # Resulting error quaternion + self.qe = utils.quatMultiply(utils.inverse(quad.quat), self.qd) + + # Create rate setpoint from quaternion error + qe_vector = 2.0*np.sign(self.qe[0])*self.qe[1:4] + self.rate_sp = qe_vector*self.att_P_gain + + # DEBUG: Check for large attitude control values + if hasattr(self, '_debug_control') and self._debug_control: + qe_mag = np.linalg.norm(self.qe[1:4]) + rate_sp_mag = np.linalg.norm(self.rate_sp) + thrust_sp_mag = np.linalg.norm(self.thrust_sp) + if qe_mag > 0.2 or rate_sp_mag > 2.0 or thrust_sp_mag > 50.0: # Large attitude errors or commands + print(f" ATTITUDE CONTROL DEBUG:") + print(f" thrust_sp: [{self.thrust_sp[0]:.3f}, {self.thrust_sp[1]:.3f}, {self.thrust_sp[2]:.3f}] N") + print(f" thrust_sp magnitude: {thrust_sp_mag:.3f} N") + print(f" qe (quaternion error): [{self.qe[0]:.3f}, {self.qe[1]:.3f}, {self.qe[2]:.3f}, {self.qe[3]:.3f}]") + print(f" qe vector magnitude: {qe_mag:.3f}") + print(f" qe_vector (2*sign*qe[1:4]): [{qe_vector[0]:.3f}, {qe_vector[1]:.3f}, {qe_vector[2]:.3f}]") + print(f" att_P_gain: [{self.att_P_gain[0]:.3f}, {self.att_P_gain[1]:.3f}, {self.att_P_gain[2]:.3f}]") + print(f" rate_sp (before limits): [{self.rate_sp[0]:.3f}, {self.rate_sp[1]:.3f}, {self.rate_sp[2]:.3f}] rad/s") + + # Limit yawFF + self.yawFF = np.clip(self.yawFF, -self.rate_max[2], self.rate_max[2]) + + # Add Yaw rate feed-forward + self.rate_sp += utils.quat2Dcm(utils.inverse(quad.quat))[:,2]*self.yawFF + + # Limit rate setpoint + self.rate_sp = np.clip(self.rate_sp, -self.rate_max, self.rate_max) + + def rate_control(self, quad, Ts): + """Rate Control (identical to original).""" + rate_error = self.rate_sp - quad.omega + self.rateCtrl = self.rate_P_gain*rate_error - self.rate_D_gain*quad.omega_dot + + # DEBUG: Check for large rate control values + if hasattr(self, '_debug_control') and self._debug_control: + rate_error_mag = np.linalg.norm(rate_error) + rateCtrl_mag = np.linalg.norm(self.rateCtrl) + if rate_error_mag > 1.0 or rateCtrl_mag > 0.1: # Large rate errors or commands + print(f" RATE CONTROL DEBUG:") + print(f" rate_sp (setpoint): [{self.rate_sp[0]:.3f}, {self.rate_sp[1]:.3f}, {self.rate_sp[2]:.3f}] rad/s") + print(f" quad.omega (actual): [{quad.omega[0]:.3f}, {quad.omega[1]:.3f}, {quad.omega[2]:.3f}] rad/s") + print(f" rate_error: [{rate_error[0]:.3f}, {rate_error[1]:.3f}, {rate_error[2]:.3f}] rad/s") + print(f" rate_P_gain: [{self.rate_P_gain[0]:.3f}, {self.rate_P_gain[1]:.3f}, {self.rate_P_gain[2]:.3f}]") + print(f" rate_D_gain: [{self.rate_D_gain[0]:.3f}, {self.rate_D_gain[1]:.3f}, {self.rate_D_gain[2]:.3f}]") + print(f" omega_dot: [{quad.omega_dot[0]:.3f}, {quad.omega_dot[1]:.3f}, {quad.omega_dot[2]:.3f}] rad/s²") + print(f" rateCtrl output: [{self.rateCtrl[0]:.6f}, {self.rateCtrl[1]:.6f}, {self.rateCtrl[2]:.6f}] N·m") + + def setYawWeight(self): + """Set Yaw Weight (identical to original).""" + roll_pitch_gain = 0.5*(self.att_P_gain[0] + self.att_P_gain[1]) + self.yaw_w = np.clip(self.att_P_gain[2]/roll_pitch_gain, 0.0, 1.0) + self.att_P_gain[2] = roll_pitch_gain + + def get_control_info(self): + """Get comprehensive control configuration information including auto-scaling details.""" + info = { + 'num_motors': self.num_motors, + 'motor_mapping': getattr(self, 'motor_mapping_info', {'type': 'unknown'}), + 'motor_validation': getattr(self, 'motor_validation', {}), + 'control_signs_validated': getattr(self, '_control_signs_validated', False), + 'control_gains': { + 'current': { + 'pos_P_gain': self.pos_P_gain.tolist(), + 'vel_P_gain': self.vel_P_gain.tolist(), + 'vel_D_gain': self.vel_D_gain.tolist(), + 'vel_I_gain': self.vel_I_gain.tolist(), + 'att_P_gain': self.att_P_gain.tolist(), + 'rate_P_gain': self.rate_P_gain.tolist(), + 'rate_D_gain': self.rate_D_gain.tolist(), + }, + 'base': { + 'pos_P_gain': self.base_pos_P_gain.tolist(), + 'vel_P_gain': self.base_vel_P_gain.tolist(), + 'vel_D_gain': self.base_vel_D_gain.tolist(), + 'vel_I_gain': self.base_vel_I_gain.tolist(), + 'att_P_gain': self.base_att_P_gain.tolist(), + 'rate_P_gain': self.base_rate_P_gain.tolist(), + 'rate_D_gain': self.base_rate_D_gain.tolist(), + } + }, + 'control_limits': { + 'current': { + 'vel_max': self.vel_max.tolist(), + 'vel_max_all': self.vel_max_all, + 'tilt_max_deg': self.tilt_max * 180.0/pi, + 'rate_max_deg': (self.rate_max * 180.0/pi).tolist(), + }, + 'base': { + 'vel_max': self.base_vel_max.tolist(), + 'vel_max_all': self.base_vel_max_all, + 'tilt_max_deg': self.base_tilt_max * 180.0/pi, + 'rate_max_deg': (self.base_rate_max * 180.0/pi).tolist(), + } + }, + 'other_settings': { + 'saturate_vel_separately': self.saturate_vel_separately, + } + } + + return info + + +# Compatibility alias - allows drop-in replacement +Control = GeneralizedControl \ No newline at end of file diff --git a/uv.lock b/uv.lock index 2748f50d7..bdb2ff88e 100644 --- a/uv.lock +++ b/uv.lock @@ -289,6 +289,11 @@ dependencies = [ { name = "torchvision" }, ] +[package.optional-dependencies] +fabrication = [ + { name = "cadquery" }, +] + [package.dev-dependencies] dev = [ { name = "mypy" }, @@ -344,6 +349,7 @@ stubs = [ [package.metadata] requires-dist = [ { name = "attrs", specifier = ">=25.4.0" }, + { name = "cadquery", marker = "extra == 'fabrication'", specifier = ">=2.4.0" }, { name = "deap", specifier = ">=1.4.3" }, { name = "dm-control", specifier = ">=1.0.38" }, { name = "evotorch", specifier = ">=0.6.1" }, @@ -377,6 +383,7 @@ requires-dist = [ { name = "torch", specifier = ">=2.8.0" }, { name = "torchvision", specifier = ">=0.23.0" }, ] +provides-extras = ["fabrication"] [package.metadata.requires-dev] dev = [ @@ -562,6 +569,75 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/f6/a8/877f306720bc114c612579c5af36bcb359026b83d051226945499b306b1a/bokeh-3.8.2-py3-none-any.whl", hash = "sha256:5e2c0d84f75acb25d60efb9e4d2f434a791c4639b47d685534194c4e07bd0111", size = 7207131, upload-time = "2026-01-06T00:20:04.917Z" }, ] +[[package]] +name = "cadquery" +version = "2.7.0" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "cadquery-ocp" }, + { name = "casadi" }, + { name = "ezdxf" }, + { name = "multimethod" }, + { name = "nlopt" }, + { name = "path" }, + { name = "pyparsing" }, + { name = "runtype" }, + { name = "trame" }, + { name = "trame-components" }, + { name = "trame-vtk" }, + { name = "trame-vuetify" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/03/c7/23e200821c307b7765661f19494edea93aa3ae9d28fee0db72ab20448855/cadquery-2.7.0.tar.gz", hash = "sha256:224e7d861c018bedd9e77b9727bc2a86b086f630596124d13ccc8a92b2151ee6", size = 270261, upload-time = "2026-02-13T16:50:47.701Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/85/46/2544f1d16a912770ecfed25602a273ab0ad4648838decf974781a8f83b78/cadquery-2.7.0-py3-none-any.whl", hash = "sha256:13bdffe3a1c9a7b29d86d43313021173b1620f45223929d2631cf8d4c5dbe2c0", size = 182553, upload-time = "2026-02-13T16:50:46.085Z" }, +] + +[[package]] +name = "cadquery-ocp" +version = "7.8.1.1.post1" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "vtk" }, +] +wheels = [ + { url = "https://files.pythonhosted.org/packages/3a/98/7b81196dd990bfbbdeff7858db7d319dede6fef2fb6c153ede9eb409a9e9/cadquery_ocp-7.8.1.1.post1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:0022e854a3840efd5c7fc14fe933772613794777d5eb056a4754d44a86baf02a", size = 68590290, upload-time = "2025-01-29T14:34:16.804Z" }, + { url = "https://files.pythonhosted.org/packages/b4/b3/aea4e4d84916b6a26bc3635a0aeaa3737b24671ac90c117e5779554eebbb/cadquery_ocp-7.8.1.1.post1-cp312-cp312-macosx_11_0_x86_64.whl", hash = "sha256:53dc24aed402b2ae52634a29b3b17e9c01e857b8ac34bb101d4e8fa76d3cd7f7", size = 69523485, upload-time = "2025-01-29T14:34:27.338Z" }, + { url = "https://files.pythonhosted.org/packages/fa/3f/4b28aedbbb7c6cd5f1aa4e1d6e9a0f88d138941096a3d70f1878a406075f/cadquery_ocp-7.8.1.1.post1-cp312-cp312-manylinux_2_31_x86_64.whl", hash = "sha256:4882074e86722208153579baaee246be4fb10bda22dc20d101c4151f364207b9", size = 70313551, upload-time = "2025-01-29T14:34:36.484Z" }, + { url = "https://files.pythonhosted.org/packages/b9/2f/d8473c8db5f0820449819bf5ce606292ead9e2072712cbdcc5657995f6cb/cadquery_ocp-7.8.1.1.post1-cp312-cp312-win_amd64.whl", hash = "sha256:06982855db94fa0056b922276f0ca94154e5d1eb16f6cba854d704885844924a", size = 51755169, upload-time = "2025-01-29T14:34:45.096Z" }, + { url = "https://files.pythonhosted.org/packages/23/1d/f2ef5da38774f3f1d2a55f01567e81190b15f765bbfc8e97d3bfbeff3fd9/cadquery_ocp-7.8.1.1.post1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:08fdc32b79e6f974cf692584be865985161e4fd8cbf854ed64c8c1530458fce3", size = 68589505, upload-time = "2025-01-29T14:34:53.501Z" }, + { url = "https://files.pythonhosted.org/packages/54/e0/d2b4a5499af452400a49c85d98e83789acdb2b64826a95b634e9069feff6/cadquery_ocp-7.8.1.1.post1-cp313-cp313-macosx_11_0_x86_64.whl", hash = "sha256:fd5ffec5e27846fe4796db9cdc0748324e4d7c59da7c6c7d86a6eb38e823b3f5", size = 69525070, upload-time = "2025-01-29T14:35:02.585Z" }, + { url = "https://files.pythonhosted.org/packages/65/7d/873c560967fc79e4c7c850bdca6418801610acd7f7041a40b71812827588/cadquery_ocp-7.8.1.1.post1-cp313-cp313-manylinux_2_31_x86_64.whl", hash = "sha256:081017e5387debe4bf31a9dc222c2513e26d1860ca990119bfe90a6970a77104", size = 70305329, upload-time = "2025-01-29T14:35:11.799Z" }, + { url = "https://files.pythonhosted.org/packages/fe/08/edb59c820f339f7fb35b20a4580839ed91488bffcd3c7ba341f8b971d91c/cadquery_ocp-7.8.1.1.post1-cp313-cp313-win_amd64.whl", hash = "sha256:22877143d06cb52bd7d48a591510f8e72c2fc5768bafebb99e5cf077798ee939", size = 51752390, upload-time = "2025-01-29T14:35:42.303Z" }, +] + +[[package]] +name = "casadi" +version = "3.7.2" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "numpy" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/92/62/1e98662024915ecb09c6894c26a3f497f4afa66570af3f53db4651fc45f1/casadi-3.7.2.tar.gz", hash = "sha256:b4d7bd8acdc4180306903ae1c9eddaf41be2a3ae2fa7154c57174ae64acdc60d", size = 6053600, upload-time = "2025-09-10T10:05:49.521Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/65/c8/689d085447b1966f42bdb8aa4fbebef49a09697dbee32ab02a865c17ac1b/casadi-3.7.2-cp312-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:309ea41a69c9230390d349b0dd899c6a19504d1904c0756bef463e47fb5c8f9a", size = 47116756, upload-time = "2025-09-10T07:53:00.931Z" }, + { url = "https://files.pythonhosted.org/packages/1e/c0/3c4704394a6fd4dfb2123a4fd71ba64a001f340670a3eba45be7a19ac736/casadi-3.7.2-cp312-none-macosx_11_0_arm64.whl", hash = "sha256:6033381234db810b2247d16c6352e679a009ec4365d04008fc768866e011ed58", size = 42293718, upload-time = "2025-09-10T08:07:16.415Z" }, + { url = "https://files.pythonhosted.org/packages/f3/24/4cf05469ddf8544da5e92f359f96d716a97e7482999f085a632bc4ef344a/casadi-3.7.2-cp312-none-manylinux2014_aarch64.whl", hash = "sha256:732f2804d0766454bb75596339e4f2da6662ffb669621da0f630ed4af9e83d6a", size = 47276175, upload-time = "2025-09-10T08:08:09.29Z" }, + { url = "https://files.pythonhosted.org/packages/82/08/b5f57fea03128efd5c860673b6ac44776352e6c1af862b8177f4c503fffe/casadi-3.7.2-cp312-none-manylinux2014_i686.whl", hash = "sha256:cf17298ff0c162735bdf9bf72b765c636ae732130604017a3b52e26e35402857", size = 72430454, upload-time = "2025-09-10T08:09:10.781Z" }, + { url = "https://files.pythonhosted.org/packages/24/ab/d7233c915b12c005655437c6c4cf0ae46cbbb2b20d743cb5e4881ad3104a/casadi-3.7.2-cp312-none-manylinux2014_x86_64.whl", hash = "sha256:cde616930fa1440ad66f1850670399423edd37354eed9b12e74b3817b98d1187", size = 75568903, upload-time = "2025-09-10T08:10:07.108Z" }, + { url = "https://files.pythonhosted.org/packages/3e/b9/5b984124f539656efdf079f3d8f09d73667808ec8d0546e6bce6dc60ade6/casadi-3.7.2-cp312-none-win_amd64.whl", hash = "sha256:81d677d2b020c1307c1eb25eae15686e5de199bb066828c3eaabdfaaaf457ffd", size = 50991347, upload-time = "2025-09-10T08:10:46.629Z" }, + { url = "https://files.pythonhosted.org/packages/85/23/f13181cd2ba693aeabdb23e6025b2bbae856a23b2a75c57d0bf94bfb6642/casadi-3.7.2-cp313-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:b53e9cc44e9d45fd0276322e85c721977ab32fefe5147069cf57f23352253479", size = 47112576, upload-time = "2025-09-10T07:53:51.287Z" }, + { url = "https://files.pythonhosted.org/packages/09/b7/087fcbfe2a0a0b44e236c9853d7fa7c539db6b8c60ab5702fffd73be5a7c/casadi-3.7.2-cp313-none-macosx_11_0_arm64.whl", hash = "sha256:2e37806a2d6a57320da79e200398239ae432a34569afbb0268598dd3381dafb9", size = 42293771, upload-time = "2025-09-10T08:11:30.329Z" }, + { url = "https://files.pythonhosted.org/packages/69/85/0512e695a9194795ed126825a2d7781bf1f82a116aaeae9c7525bde7c1d9/casadi-3.7.2-cp313-none-manylinux2014_aarch64.whl", hash = "sha256:8c22837ff751ab22ea3333198427e0dd2aa1f3974a10867de897fe26bcb57438", size = 47276199, upload-time = "2025-09-10T08:12:12.487Z" }, + { url = "https://files.pythonhosted.org/packages/50/30/9d130b6956fb2bc9d6d154b12b6f420b1338ce0bc8d99041465ded3df1eb/casadi-3.7.2-cp313-none-manylinux2014_i686.whl", hash = "sha256:4a92b5c28abb8d00ae24ce243fed36df36c53a511449aedcdf4db54f78efaf64", size = 72430461, upload-time = "2025-09-10T08:13:06.594Z" }, + { url = "https://files.pythonhosted.org/packages/3f/5b/7120e22f6e22ca77283f4a086ab2e59d107f00bfc952116db41a015385fe/casadi-3.7.2-cp313-none-manylinux2014_x86_64.whl", hash = "sha256:63a406ead6582ddc730ea9bfcb100fc299d0793f2e6b177a967a1495846f9a72", size = 75568903, upload-time = "2025-09-10T08:14:04.404Z" }, + { url = "https://files.pythonhosted.org/packages/ba/b7/2c80912fc6655deb6a78fa2ae9aa9a4a3c59ac5daa83f2dd549547441a08/casadi-3.7.2-cp313-none-win_amd64.whl", hash = "sha256:d1a996d5904ba74ee2c0bb9991344c9b0963adc08864ddce908fe92cfdf36bf0", size = 50991336, upload-time = "2025-09-10T08:14:43.907Z" }, + { url = "https://files.pythonhosted.org/packages/19/60/76074fcbd1cc246dd542a91ca53ed638133c3fb52ebf8400ea8edffd7a98/casadi-3.7.2-cp314-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:f8faf88720477f63b48e96f443ba557931ddd3f5d7d08fc905148893b5c25917", size = 47116064, upload-time = "2025-09-11T08:15:13.381Z" }, + { url = "https://files.pythonhosted.org/packages/66/79/b1eda4d4eeefa51f3b75e51f332e3837b86d063b9b889fdbcb92081f6831/casadi-3.7.2-cp314-none-macosx_11_0_arm64.whl", hash = "sha256:08762169bd464d5a00a15bf28d2ff7deac41d24a1da842a13153a833cd247b61", size = 42295048, upload-time = "2025-09-11T08:15:20.517Z" }, + { url = "https://files.pythonhosted.org/packages/f2/06/e52fdaee135ebb5d0a004827848890d66e9e05b2148b4beb2a0150e7418d/casadi-3.7.2-cp314-none-manylinux2014_i686.whl", hash = "sha256:9b5683d06f7c5c2bc044585f2d3591d81ec0ad81de84db29765a8bca8247f9d7", size = 72430409, upload-time = "2025-09-10T14:09:48.176Z" }, + { url = "https://files.pythonhosted.org/packages/92/50/8834ae629e425802b66505c9861061439b4510d1aca1c94ea067b129e3b5/casadi-3.7.2-cp314-none-manylinux2014_x86_64.whl", hash = "sha256:8861213b7fc605a67cf9b46b29c05337b70c773c0b9615939a7c8a3361cabed1", size = 75571314, upload-time = "2025-09-10T14:10:45.54Z" }, + { url = "https://files.pythonhosted.org/packages/59/3a/aaf951d7921a7b657a3402e1e628ccd2c9dfdc6d29bf5aed209dca93073b/casadi-3.7.2-cp314-none-win_amd64.whl", hash = "sha256:62b7b1f943456447205673865e130ec9d97a6f931239968a46d9a7b40ea8c4c3", size = 50991682, upload-time = "2025-09-10T14:11:24.747Z" }, +] + [[package]] name = "certifi" version = "2025.10.5" @@ -1060,6 +1136,37 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/c1/ea/53f2148663b321f21b5a606bd5f191517cf40b7072c0497d3c92c4a13b1e/executing-2.2.1-py2.py3-none-any.whl", hash = "sha256:760643d3452b4d777d295bb167ccc74c64a81df23fb5e08eff250c425a4b2017", size = 28317, upload-time = "2025-09-01T09:48:08.5Z" }, ] +[[package]] +name = "ezdxf" +version = "1.4.4" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "fonttools" }, + { name = "numpy" }, + { name = "pyparsing" }, + { name = "typing-extensions" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/5e/d7/1b7be8db364f1c4838dfc1a40ca96577aba405deabf896a4eb3aaeb15a62/ezdxf-1.4.4.tar.gz", hash = "sha256:da5a5e0e6bdbb6656f9c017b47edc7eafceb419d61a2b5de64ffb344c168e593", size = 1866886, upload-time = "2026-05-14T09:19:19.511Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/18/3d/98648d221ffa047b5ba898c8e152010861dc71a66b531dcf15053075010e/ezdxf-1.4.4-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:d723d35d08223318c17080a32a05192a1449e544dee867c9d9c6f25998fac303", size = 3563916, upload-time = "2026-05-14T09:25:32.879Z" }, + { url = "https://files.pythonhosted.org/packages/2c/f1/84bbaa571412f840c22deeae185e54d4a67aa52f03e1728fd8425748c548/ezdxf-1.4.4-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:6b0c73b46085521bdbd4a3e7d88998da7bec5713ba89bbb502fdeffe6b42fc7e", size = 3016857, upload-time = "2026-05-14T09:25:34.607Z" }, + { url = "https://files.pythonhosted.org/packages/b0/ff/f2eb77d22d26aa98abbe0961470871d8b85ef4e73e5527f544d25f958d6e/ezdxf-1.4.4-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:ac3e83a70c1f866dd5114192a6fab6e75cc83b75e907bc08c5d94b98cce14cc0", size = 3003336, upload-time = "2026-05-14T09:25:35.947Z" }, + { url = "https://files.pythonhosted.org/packages/65/7d/2a6ddd6beef5d9a8593078619f3920a0cd76b1db4c6a974ac37045543219/ezdxf-1.4.4-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8ebe09717ab6636bf48780eabdab51e3ab2135f7963bb52452444b6d95e03d12", size = 5788485, upload-time = "2026-05-14T09:27:32.176Z" }, + { url = "https://files.pythonhosted.org/packages/e7/29/2094fd7719146ca7bb236be9751b5929d431f643cbab669aed89cf121883/ezdxf-1.4.4-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:44af248af0860fe8b1a39ca40e1cd2fa8ac37b22142b14b20c6a0caf1b50f932", size = 5816781, upload-time = "2026-05-14T09:27:13.96Z" }, + { url = "https://files.pythonhosted.org/packages/19/8d/669b8047cca162204c53b874183d73b5f6c4b1d5d48fa1e515a32d56f5ac/ezdxf-1.4.4-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:02a097794625e9fc948e637dfe07057e98167b4fe215357a59645759fef6db3f", size = 5754006, upload-time = "2026-05-14T09:27:33.858Z" }, + { url = "https://files.pythonhosted.org/packages/5b/44/b753997173327250e43ae50f11f0c69016b1e78482e0bd3857c3495236e7/ezdxf-1.4.4-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:f093bd2228f5782d483aed3bd89cdb74b672b5f90c677c4125cd236ee5649151", size = 5861860, upload-time = "2026-05-14T09:27:15.758Z" }, + { url = "https://files.pythonhosted.org/packages/0b/99/2e81cb168e0f09adfb05fb40e5f890ff87ac2c00e98079cf09837dd76330/ezdxf-1.4.4-cp312-cp312-win_amd64.whl", hash = "sha256:3e518d9ed4dcbe525d57f14c25c5e592f82660a690fdec39b03b092e6cdc4771", size = 2963238, upload-time = "2026-05-14T09:23:47.924Z" }, + { url = "https://files.pythonhosted.org/packages/be/ed/97aa3ba1ba923e4098169de5bca380ee1430e2b34d0dd85b73007e34df16/ezdxf-1.4.4-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:278a09a845d67a4f893aebe9ef8dcd8894ece9f255d7d8bb21719ffd902109b8", size = 3555283, upload-time = "2026-05-14T09:25:37.346Z" }, + { url = "https://files.pythonhosted.org/packages/4e/b1/8ca9408a2b382a806837e72d35f10931fdd9f53fe66cf208a6340358fbc5/ezdxf-1.4.4-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:b0a787f8ebcbdcb9798c6fcfe90c23afd1a0993c8d4302b6cce5d8f19ae052ae", size = 3012646, upload-time = "2026-05-14T09:25:39.01Z" }, + { url = "https://files.pythonhosted.org/packages/8b/aa/1e8d3130eaabb780c5e8adfdc1ead023bb04468779b18169d60f7ce5b291/ezdxf-1.4.4-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:c451d1c20f08b30c735ca4d650fee5b44147402f4b5662f8550053ed8a3009c2", size = 2999048, upload-time = "2026-05-14T09:25:40.348Z" }, + { url = "https://files.pythonhosted.org/packages/cd/ca/1dd390b79df9c104c2d4b5964e80db25362edf704ac742c9db9b279658a5/ezdxf-1.4.4-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3d3d9a6663993fc644751647fd7843057b51742ffac27c48ce28ea9f81239613", size = 5747890, upload-time = "2026-05-14T09:27:36.028Z" }, + { url = "https://files.pythonhosted.org/packages/8f/1e/226a6e636ae533e0bc0afe4435d1058fac173564e4af4102862f055a46d9/ezdxf-1.4.4-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:82c022cf094d21ad3db68557aa83628e4152355e8a8bef0fffd4f71a9ea325df", size = 5774707, upload-time = "2026-05-14T09:27:17.625Z" }, + { url = "https://files.pythonhosted.org/packages/24/a3/7e33c9036de944b5446982bb629d698356e48b00c4d173768f52bdeeff4b/ezdxf-1.4.4-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:3be59c2a3a93585412a2a37af29b3ad7574fa3e429e624924c3285d0573388b3", size = 5713753, upload-time = "2026-05-14T09:27:37.55Z" }, + { url = "https://files.pythonhosted.org/packages/36/9e/ac0cdc3a8623fc38aa16670f6537aa810bc1381217a51ac3481299bbc986/ezdxf-1.4.4-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:44a9716860b59dddd49a3708c04ff4580ad1e7de92ac93bb3213d85fba5ac93f", size = 5813895, upload-time = "2026-05-14T09:27:19.514Z" }, + { url = "https://files.pythonhosted.org/packages/dd/22/b511a8d9ea8f23447a67fe8977213fac5e4e69df30130a3ef31043613eaf/ezdxf-1.4.4-cp313-cp313-win_amd64.whl", hash = "sha256:207eed544417464ffaf2570880d58a792ecd2534c9c2dede45e895f3200b77e6", size = 2960937, upload-time = "2026-05-14T09:23:49.361Z" }, + { url = "https://files.pythonhosted.org/packages/a0/09/5ecb6f82d35a2f4a4334d0a608fcf764827fa69dccdf5987ce309c16b6c1/ezdxf-1.4.4-py3-none-any.whl", hash = "sha256:666edda631ba717270293b734f5d58dd97a1d1aba4787187f09d0cc584645865", size = 1331217, upload-time = "2026-05-14T09:19:26.601Z" }, +] + [[package]] name = "farama-notifications" version = "0.0.4" @@ -2396,6 +2503,15 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/ad/3f/3d42e9a78fe5edf792a83c074b13b9b770092a4fbf3462872f4303135f09/ml_dtypes-0.5.4-cp314-cp314t-win_arm64.whl", hash = "sha256:11942cbf2cf92157db91e5022633c0d9474d4dfd813a909383bd23ce828a4b7d", size = 168825, upload-time = "2025-11-17T22:32:23.766Z" }, ] +[[package]] +name = "more-itertools" +version = "11.0.2" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/a2/f7/139d22fef48ac78127d18e01d80cf1be40236ae489769d17f35c3d425293/more_itertools-11.0.2.tar.gz", hash = "sha256:392a9e1e362cbc106a2457d37cabf9b36e5e12efd4ebff1654630e76597df804", size = 144659, upload-time = "2026-04-09T15:01:33.297Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/cb/98/6af411189d9413534c3eb691182bff1f5c6d44ed2f93f2edfe52a1bbceb8/more_itertools-11.0.2-py3-none-any.whl", hash = "sha256:6e35b35f818b01f691643c6c611bc0902f2e92b46c18fffa77ae1e7c46e912e4", size = 71939, upload-time = "2026-04-09T15:01:32.21Z" }, +] + [[package]] name = "mpmath" version = "1.3.0" @@ -2601,6 +2717,15 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/b7/da/7d22601b625e241d4f23ef1ebff8acfc60da633c9e7e7922e24d10f592b3/multidict-6.7.0-py3-none-any.whl", hash = "sha256:394fc5c42a333c9ffc3e421a4c85e08580d990e08b99f6bf35b4132114c5dcb3", size = 12317, upload-time = "2025-10-06T14:52:29.272Z" }, ] +[[package]] +name = "multimethod" +version = "1.12" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/ed/f3/930a6dc1d35b2ab65faffa2a75bbcc67f12d8227857188273783df4e5134/multimethod-1.12.tar.gz", hash = "sha256:8db8ef2a8d2a247e3570cc23317680892fdf903d84c8c1053667c8e8f7671a67", size = 17423, upload-time = "2024-07-04T16:10:08.179Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/af/98/cff14d53a2f2f67d7fe8a4e235a383ee71aba6a1da12aeea24b325d0c72a/multimethod-1.12-py3-none-any.whl", hash = "sha256:fd0c473c43558908d97cc06e4d68e8f69202f167db46f7b4e4058893e7dbdf60", size = 10646, upload-time = "2024-07-04T16:10:06.482Z" }, +] + [[package]] name = "mypy" version = "1.18.2" @@ -2807,6 +2932,25 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/7e/49/bad16f65f3f933059b6eb52505c6efcc7c97d66e25681a8ecab2e1240c86/nicegui-3.0.3-py3-none-any.whl", hash = "sha256:f40c37866cedf91d75e8bdfc2730348a007dec69baf8080dfadc0ab3381ab2ab", size = 20749450, upload-time = "2025-10-06T15:14:22.858Z" }, ] +[[package]] +name = "nlopt" +version = "2.10.0" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "numpy" }, +] +wheels = [ + { url = "https://files.pythonhosted.org/packages/a4/39/76558756c758962fcf2c6f8450384e43a8e65cb8dfbb8a93d40014b09b3a/nlopt-2.10.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:19e7a5dd823eab1d167a4fb2f3da13978b997029c9b5e6164d33c747fc7ec542", size = 637168, upload-time = "2025-12-23T15:23:59.667Z" }, + { url = "https://files.pythonhosted.org/packages/2e/57/87a00a49664ae90f312cf9fd12262a3803d4f81709e01653bc2be6299b63/nlopt-2.10.0-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:939a0f3ed1710a6b9493a029744e07e8703f56aea4cfd3010d8619c4fba0df8e", size = 440214, upload-time = "2025-12-23T15:24:00.774Z" }, + { url = "https://files.pythonhosted.org/packages/a5/03/3140b6417a4cb113cd0f5d53b27ada263f81f158355ad991aaeee770e10e/nlopt-2.10.0-cp312-cp312-win_amd64.whl", hash = "sha256:8364bdd98c8265eb87779155f4ab144dd67c7990620244b629f2ebc024d727d1", size = 641684, upload-time = "2025-12-23T15:24:02.094Z" }, + { url = "https://files.pythonhosted.org/packages/99/85/9f4d06c156d6007da8594f04343c360978595b0de6c1fa41c2fa1295cb11/nlopt-2.10.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:4ff0577b4e866f5696f44d546368f5ee752a249ac73f9c45d8a29513c5f2430f", size = 636965, upload-time = "2025-12-23T15:24:03.226Z" }, + { url = "https://files.pythonhosted.org/packages/c0/eb/1dbdb4fa2ac8550870eef7f74dcd5c35f4c4df58d223e068daeac20f7c98/nlopt-2.10.0-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:c3a9697d24f3cb92b53c37cad7dc8900c7cc125dbe95da73bc92a4fed133eaf0", size = 439869, upload-time = "2025-12-23T15:24:04.598Z" }, + { url = "https://files.pythonhosted.org/packages/b6/44/20f39446c3edb9bd80e37fa0f996118170f8509eea0e118595a6c5aa3b18/nlopt-2.10.0-cp313-cp313-win_amd64.whl", hash = "sha256:98cbe9012ae641970366c9935ffcbb9cdcd6deef8521881a3e2ad7d35ed33506", size = 641822, upload-time = "2025-12-23T15:24:05.708Z" }, + { url = "https://files.pythonhosted.org/packages/60/87/6e2b468190f8a4467efb9165c94e3ab6c13e03a579fe821fae10479a5003/nlopt-2.10.0-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:404ddd3f77958d54edf8b1dbed187730fe2ab13cd6e6fb2e7b80cfac2958460f", size = 636962, upload-time = "2025-12-23T15:24:06.823Z" }, + { url = "https://files.pythonhosted.org/packages/10/92/87b81b0d149ef4439c1edd475ac62127904e63efe7aacc89f6279aba957c/nlopt-2.10.0-cp314-cp314-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:6a49ba09083bdb10c2fde31e2190a16e0e57050a2e98e37ece9b606ad2cb2a31", size = 439883, upload-time = "2025-12-23T15:24:08.233Z" }, + { url = "https://files.pythonhosted.org/packages/e8/1d/be16a2bd80f28f7cc838448950c1468ab6fced9939806b6a88396cc4028c/nlopt-2.10.0-cp314-cp314-win_amd64.whl", hash = "sha256:0b0cb9de4270b7ed2d9a299ba379ae6b24d5095b0365a2af9702ff0ccdff5235", size = 660414, upload-time = "2025-12-23T15:24:09.296Z" }, +] + [[package]] name = "notebook" version = "7.4.7" @@ -3335,6 +3479,15 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/16/32/f8e3c85d1d5250232a5d3477a2a28cc291968ff175caeadaf3cc19ce0e4a/parso-0.8.5-py2.py3-none-any.whl", hash = "sha256:646204b5ee239c396d040b90f9e272e9a8017c630092bf59980beb62fd033887", size = 106668, upload-time = "2025-08-23T15:15:25.663Z" }, ] +[[package]] +name = "path" +version = "17.1.1" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/dd/52/a7bdd5ef8488977d354b7915d1e75009bebbd04f73eff14e52372d5e9435/path-17.1.1.tar.gz", hash = "sha256:2dfcbfec8b4d960f3469c52acf133113c2a8bf12ac7b98d629fa91af87248d42", size = 50528, upload-time = "2025-07-27T20:40:23.79Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/7c/50/11c9ee1ede64b45d687fd36eb8768dafc57afc78b4d83396920cfd69ed30/path-17.1.1-py3-none-any.whl", hash = "sha256:ec7e136df29172e5030dd07e037d55f676bdb29d15bfa09b80da29d07d3b9303", size = 23936, upload-time = "2025-07-27T20:40:22.453Z" }, +] + [[package]] name = "pathspec" version = "0.12.1" @@ -6971,6 +7124,15 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/c6/2a/65880dfd0e13f7f13a775998f34703674a4554906167dce02daf7865b954/ruff-0.14.0-py3-none-win_arm64.whl", hash = "sha256:f42c9495f5c13ff841b1da4cb3c2a42075409592825dada7c5885c2c844ac730", size = 12565142, upload-time = "2025-10-07T18:21:53.577Z" }, ] +[[package]] +name = "runtype" +version = "0.5.3" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/60/76/d8a0f754c834c3d71a0896b1d40a1938244aab4bb5b4bab0b21d21525694/runtype-0.5.3.tar.gz", hash = "sha256:ccaec05c74f8d213342b9fc25e304560d114bc4d72ec117639cd1e7af9c5db1f", size = 30223, upload-time = "2025-03-03T08:39:00.081Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/80/db/879902580d720925092c86eaab2ceee7493e2fadbb5b718f54289b04d277/runtype-0.5.3-py3-none-any.whl", hash = "sha256:ea8cc6828217ebfda5c159dce969e832efd865a09d6ad1fc993f5bf5e1a627ee", size = 31944, upload-time = "2025-03-03T08:38:58.329Z" }, +] + [[package]] name = "scikit-learn" version = "1.7.2" @@ -7612,6 +7774,93 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/00/c0/8f5d070730d7836adc9c9b6408dec68c6ced86b304a9b26a14df072a6e8c/traitlets-5.14.3-py3-none-any.whl", hash = "sha256:b74e89e397b1ed28cc831db7aea759ba6640cb3de13090ca145426688ff1ac4f", size = 85359, upload-time = "2024-04-19T11:11:46.763Z" }, ] +[[package]] +name = "trame" +version = "3.13.2" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "pyyaml" }, + { name = "trame-client" }, + { name = "trame-common" }, + { name = "trame-server" }, + { name = "wslink" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/fc/c7/790a5f28d75ea166fd9ec0bc6545e42683dc59ddd0b15ed374d00fb8e187/trame-3.13.2.tar.gz", hash = "sha256:9868d1c2bce981ae2c66eb6a16d39e2a14f042eedb1047666266c753ecaf3f64", size = 26386, upload-time = "2026-05-15T03:50:50.626Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/eb/4a/1474a166fa9494162779b4145b4b82adbe482cfb776efffeff59de4ba70f/trame-3.13.2-py3-none-any.whl", hash = "sha256:23e87a65a6ea9241ce1060e9cd01426e48b3b8b72cd9f3cb974fc398649280b6", size = 31514, upload-time = "2026-05-15T03:50:49.129Z" }, +] + +[[package]] +name = "trame-client" +version = "3.12.2" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "trame-common" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/c6/90/c895a1dc56c5554105baf00e16a454028f24c94be654430d87df0ff5b788/trame_client-3.12.2.tar.gz", hash = "sha256:a9bfba0226dda4a2ff36805ebf12e649cd7eb94c40672c8495d0674a12d5d381", size = 246220, upload-time = "2026-05-11T16:36:24.677Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/ae/ba/a62b4f6dee5039074f8f92dcfe780dc68b2ca29a9882282da1750808892d/trame_client-3.12.2-py3-none-any.whl", hash = "sha256:829a59bc5e2bf9ae2adc3a254ce9b0183c0312c656b3f5b0c88be35671703c9c", size = 250679, upload-time = "2026-05-11T16:36:22.936Z" }, +] + +[[package]] +name = "trame-common" +version = "1.2.3" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/b6/8c/f9e7bcf73d888df9df6115deb8619679444d83b9e92a26604a05f0433307/trame_common-1.2.3.tar.gz", hash = "sha256:125b60d77545d7352fb8eabc0f6e0e12070aa6ada31e992862f16a49f34b73ad", size = 19998, upload-time = "2026-05-08T17:12:33.942Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/d5/80/957a3dae26c1b38a302a96bf49adc53399e5f04c0afdf750d4978216fe14/trame_common-1.2.3-py3-none-any.whl", hash = "sha256:85d13ac87e7e4db853278afc98d19d14972e1fc75394aac9800221be0829e5cd", size = 23482, upload-time = "2026-05-08T17:12:32.548Z" }, +] + +[[package]] +name = "trame-components" +version = "2.5.0" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "trame-client" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/82/47/d773f35615c22553a7547b4336af62e412548ec3607626fa3db128f30460/trame-components-2.5.0.tar.gz", hash = "sha256:df7a1d387b98c5dd71699737804f5288957ca370eb1a60bbe40e89a1f9f62b12", size = 81972, upload-time = "2025-05-30T14:21:36.718Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/02/e9/627ebbf56e00d80300940e8bbf54c6594f98fd214e3565b3abaa5450e0d4/trame_components-2.5.0-py3-none-any.whl", hash = "sha256:897a6c0ebcc72d95a461bde28d2c2e37c4bc4922013ad07df3a65e64d4884672", size = 82345, upload-time = "2025-05-30T14:21:35.526Z" }, +] + +[[package]] +name = "trame-server" +version = "3.12.3" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "more-itertools" }, + { name = "trame-common" }, + { name = "wslink" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/74/e9/86e12a8347d1a6a0ea3b755301967921cdfbb38509410eb0cef9bb7f9061/trame_server-3.12.3.tar.gz", hash = "sha256:bbf5ac5d3fb1537021db6d8f422429c7c9eb4106550138335f2aa2f2b6c7c6b6", size = 37860, upload-time = "2026-05-18T15:26:43.975Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/fd/2e/6b5dff1aeebef5dbba06d1d9b170f3762e303eeffcceb33911860802e34b/trame_server-3.12.3-py3-none-any.whl", hash = "sha256:398dcdd54e2344d2b22565a901b4babd2ab78e46c4ffcaa41cacb3f9ecdde357", size = 44360, upload-time = "2026-05-18T15:26:42.592Z" }, +] + +[[package]] +name = "trame-vtk" +version = "2.11.8" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "trame-client" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/10/de/b72ec543cf8f70ee0ef4645d04e911155db3dcba545a9cf35d6c80e849c9/trame_vtk-2.11.8.tar.gz", hash = "sha256:bef4a35d86d57bf9b4af44dda8f361f917b141e4f624c9ab7278b6c48d171e74", size = 810254, upload-time = "2026-04-24T00:28:17.494Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/ef/11/aff660ffcc0f65546da4340902cd064cafda26e0a7750f6468a27378c717/trame_vtk-2.11.8-py3-none-any.whl", hash = "sha256:31c8220f59dcc3b5f2fcfe6de8b9796e8bdb7db5dcf790ee01df83d44e79a413", size = 831787, upload-time = "2026-04-24T00:28:15.317Z" }, +] + +[[package]] +name = "trame-vuetify" +version = "3.2.2" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "trame-client" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/d7/1a/1701aaf3450def4b17cb3580d0a340361065b1d258e156861eb83a8377f2/trame_vuetify-3.2.2.tar.gz", hash = "sha256:0e111ec5fdfed31e5c189eafb306f4f25aacd75527b3a5612bb5a4cacbb18d8b", size = 5107360, upload-time = "2026-04-28T13:22:53.684Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/ac/3a/0dbff3ce4fd9cc6076fce8ef714c33796bd25d08b3d249ca78ea458a85fd/trame_vuetify-3.2.2-py3-none-any.whl", hash = "sha256:b40ecfa30a675df4ce40d5161b9b6c040cfe5445599933c478a3359afbee91d3", size = 5134630, upload-time = "2026-04-28T13:22:51.132Z" }, +] + [[package]] name = "trimesh" version = "4.11.5" @@ -7982,29 +8231,16 @@ wheels = [ [[package]] name = "vtk" -version = "9.6.1" +version = "9.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "matplotlib" }, ] wheels = [ - { url = "https://files.pythonhosted.org/packages/95/89/c274101ec7b9bf7356333fdacf5e634803fe6b40f776e82c6ce9d941e0ad/vtk-9.6.1-cp312-cp312-macosx_10_10_x86_64.whl", hash = "sha256:b8125e3e3bc3160e18853a15be98101d0efe662c16036179ab15ddf1669b32af", size = 114729308, upload-time = "2026-03-27T13:50:37.547Z" }, - { url = "https://files.pythonhosted.org/packages/9d/1a/ecbebaf31724a00f85fc4dbf95992b507328f615362ee8fa5ea1a38cf9d6/vtk-9.6.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:956d05b8c53c6a9eba569de244e9c8229815bbb3e024bb9954fafe163407e66d", size = 106814956, upload-time = "2026-03-27T13:51:24.324Z" }, - { url = "https://files.pythonhosted.org/packages/46/66/ba3c8b277cfa8058e982bfbd47875d9c6b4c06e65f98d577c69a2628f8d4/vtk-9.6.1-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:9728e8d41889a0f105b5d20a73a4da80f398b2cfe6057fa7a94cd61128c3ceb4", size = 145920093, upload-time = "2026-03-27T13:53:12.49Z" }, - { url = "https://files.pythonhosted.org/packages/f5/cb/0bbf91cd45a8d8f5453fe01cddf44c913db6316b3a2b15f41893ae0ca9ad/vtk-9.6.1-cp312-cp312-manylinux_2_28_aarch64.whl", hash = "sha256:3b5ec2e56bd6165189aa2e6e896edda29460e63040f897e1a123a1592810266d", size = 135683842, upload-time = "2026-03-27T13:52:15.218Z" }, - { url = "https://files.pythonhosted.org/packages/08/c0/653c94939498a3976157f054b830ade5c1da48ae288a23547f55fc25a262/vtk-9.6.1-cp312-cp312-win_amd64.whl", hash = "sha256:4022fda8af46636f74c3c1932c2365da13a1dc8779a6b1ea4b13dc5bbcdb729f", size = 81262921, upload-time = "2026-03-27T13:53:50.192Z" }, - { url = "https://files.pythonhosted.org/packages/a8/8d/16e597f86241772fe188bbdd86a74ce48eadd2dd9513e2410b4ea07f78aa/vtk-9.6.1-cp313-cp313-macosx_10_10_x86_64.whl", hash = "sha256:88983bce26f7665ac6e4fb7de16cf53b896140a1a6cadd942d3c13e7c74a8530", size = 114747320, upload-time = "2026-03-27T13:54:33.138Z" }, - { url = "https://files.pythonhosted.org/packages/63/ca/8f0c19bded437423479d0d3ff0b7457cf6ef68def322666df867e6dacc0f/vtk-9.6.1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:94ed369a54c6cfacea0b34f42d7d3ef41fa06c1aabfc75d93cabdc9047454293", size = 106817051, upload-time = "2026-03-27T13:55:21.903Z" }, - { url = "https://files.pythonhosted.org/packages/82/22/c1d98e6e191481af1e5c82ae3fa750798d868aa442a76db027f6a7901b95/vtk-9.6.1-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:deeb86794cd42f922ea75711b9717e45841777624203727eb84595b709af1382", size = 145920554, upload-time = "2026-03-27T13:57:14.258Z" }, - { url = "https://files.pythonhosted.org/packages/16/5d/658f60209de7b41b634178aee1f458bcad149aa2654d16bd023c09afd29c/vtk-9.6.1-cp313-cp313-manylinux_2_28_aarch64.whl", hash = "sha256:fef8abc33168ad38b2622cf29048b7d5fe48a45789bf0a0421781f5cafa1e554", size = 135686060, upload-time = "2026-03-27T13:56:23.89Z" }, - { url = "https://files.pythonhosted.org/packages/f0/31/e4eb318901a8e736c936491e759ce03a1656792f728ae912db0e20997e9a/vtk-9.6.1-cp313-cp313-win_amd64.whl", hash = "sha256:a5db7b2ff8fc3f56b547c8b9b7bc117a869c902683c86ef5cd6197c087f66183", size = 81264861, upload-time = "2026-03-27T13:57:47.164Z" }, - { url = "https://files.pythonhosted.org/packages/43/de/ad1ccb188681d51b5e5621f383afa0a1dd8711ff8f3dcba4ff950f758cbb/vtk-9.6.1-cp314-cp314-macosx_10_10_x86_64.whl", hash = "sha256:91257894723dfced8be264915d81ba418d08e5bbdb4873da0f12b02c1e21f244", size = 114382745, upload-time = "2026-03-27T13:58:30.592Z" }, - { url = "https://files.pythonhosted.org/packages/59/21/7bb2bd61b4ae05db79e2f40df452a6dbcd3bb66c259fd2043aaf60bbe5b7/vtk-9.6.1-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:e119721774418fba34e95852efaefe5ac4156a4a270362fef06894cdc1377b6e", size = 106826433, upload-time = "2026-03-27T13:59:22.109Z" }, - { url = "https://files.pythonhosted.org/packages/fc/e4/5317afdeaa4a66fe037e1fedcb6bde86b888b8227c89aba6c8ad2946e380/vtk-9.6.1-cp314-cp314-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:98df48bcd630a4ffa71ac09d6aebb69c628925902920419e3db838dc7f7ce0ed", size = 145936133, upload-time = "2026-03-27T14:01:19.29Z" }, - { url = "https://files.pythonhosted.org/packages/67/7f/f1375aa3ef1835e39b4bea978da06d4985bc1407e3e91384dfaabf5e09d0/vtk-9.6.1-cp314-cp314-manylinux_2_28_aarch64.whl", hash = "sha256:3ea3c3e466a4a9cd8fa7e5b64595215467a7936c9f0fd61ec3275954c122a79c", size = 135710278, upload-time = "2026-03-27T14:00:19.358Z" }, - { url = "https://files.pythonhosted.org/packages/91/25/7ff877a0d4f3e848d994d3a774d5a8e4495681ed26c32eb9dbb2a86b50e5/vtk-9.6.1-cp314-cp314-win_amd64.whl", hash = "sha256:a05e12ab8c82e81b225feee5ca08fda5fff814520a11c2941cc866335d990e03", size = 83197720, upload-time = "2026-03-27T14:01:53.313Z" }, - { url = "https://files.pythonhosted.org/packages/0a/ae/f621aaed0a36c99ba3c1b2f2593386094222132a8396f21c616adffacaaf/vtk-9.6.1-cp314-cp314t-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:043fb013a2669180180bd0ab667f318f2e1f14da69ae943192a7443f5ce3721a", size = 145557875, upload-time = "2026-03-27T14:03:45.531Z" }, - { url = "https://files.pythonhosted.org/packages/e1/d5/41edd3f8b38ad45b8fb30d12ef35be3d62e1221e455722a5d7d103ca2f0d/vtk-9.6.1-cp314-cp314t-manylinux_2_28_aarch64.whl", hash = "sha256:d08b3760cbd8bffdbb4551033c4c9d87afe30e9e9d4c0e5cad29cbe7107c9af7", size = 135524312, upload-time = "2026-03-27T14:02:46.035Z" }, + { url = "https://files.pythonhosted.org/packages/6f/ba/1571d61013f3f5778c11741d5de19db197b437d1a52215560f016662597b/vtk-9.3.1-cp312-cp312-macosx_10_10_x86_64.whl", hash = "sha256:05a4b6e387a906e8c8d6844441f9200116e937069fcf81f43e2600f26eb046de", size = 76832738, upload-time = "2024-06-29T03:15:26.41Z" }, + { url = "https://files.pythonhosted.org/packages/8e/75/c637c620d23ccecb8ddf58fdb80af1dc56ecdd60f3e018c55e041663398b/vtk-9.3.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:bdbefb1aef9599a0a0b8222c9582f26946732a93534e6ec37d4b8e2c524c627e", size = 70385880, upload-time = "2024-06-29T03:15:33.131Z" }, + { url = "https://files.pythonhosted.org/packages/01/ee/730d57c6d7353c1afb919ceedfac387a190ccb92e611c4b14f88e6f39066/vtk-9.3.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f728bb61f43fce850d622ced3b3d51b3116f767685ca4e4e0076f624e2d2307d", size = 92159868, upload-time = "2024-06-29T03:15:39.072Z" }, + { url = "https://files.pythonhosted.org/packages/b1/34/b9b6de4009be2fe90919c4943ae99ae3d465ada73061e928d4744683f915/vtk-9.3.1-cp312-cp312-win_amd64.whl", hash = "sha256:685988e09070e06c8605886591698fd42d8225489509b6537a5046cd034cc93e", size = 52529544, upload-time = "2024-06-29T03:15:43.967Z" }, ] [[package]] @@ -8228,6 +8464,19 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/1a/c7/8528ac2dfa2c1e6708f647df7ae144ead13f0a31146f43c7264b4942bf12/wrapt-2.1.2-py3-none-any.whl", hash = "sha256:b8fd6fa2b2c4e7621808f8c62e8317f4aae56e59721ad933bac5239d913cf0e8", size = 43993, upload-time = "2026-03-06T02:53:12.905Z" }, ] +[[package]] +name = "wslink" +version = "2.5.7" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "aiohttp" }, + { name = "msgpack" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/74/12/c23927be89cf75c24d774a8ee5bf83e368d0feb39fb361462f03ae8efd26/wslink-2.5.7.tar.gz", hash = "sha256:ed14c2b4749ea231a105a23334d2e0c7783204b2033f46104972a189ea235818", size = 29958, upload-time = "2026-05-15T02:57:36.299Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/0c/3c/571e00719a5ce5b295d6bbed62841c51222687530871d8e92a0e64e19acb/wslink-2.5.7-py3-none-any.whl", hash = "sha256:47d729f654d1ee0bb42b6f05b068c48d5fdacd3216e827c1e80ea09eca0fe287", size = 37353, upload-time = "2026-05-15T02:57:35.135Z" }, +] + [[package]] name = "wsproto" version = "1.2.0" From 01bbd631942d737721f5d78fa5a0fcd39fede5d6 Mon Sep 17 00:00:00 2001 From: A-lamo <2727043@student.vu.nl> Date: Mon, 18 May 2026 19:22:14 +0200 Subject: [PATCH 06/27] Remove wiki from global --- wiki/.obsidian/app.json | 1 - wiki/.obsidian/appearance.json | 1 - wiki/.obsidian/core-plugins.json | 33 ---- wiki/.obsidian/workspace.json | 181 -------------------- wiki/ariel_db_pandas.md | 129 --------------- wiki/ariel_individual_db.md | 37 ----- wiki/cppn_neat_genome.md | 58 ------- wiki/log.md | 16 -- wiki/neat_speciation.md | 109 ------------ wiki/robogen_lite_api.md | 273 ------------------------------- wiki/stanley_2002.md | 173 -------------------- 11 files changed, 1011 deletions(-) delete mode 100644 wiki/.obsidian/app.json delete mode 100644 wiki/.obsidian/appearance.json delete mode 100644 wiki/.obsidian/core-plugins.json delete mode 100644 wiki/.obsidian/workspace.json delete mode 100644 wiki/ariel_db_pandas.md delete mode 100644 wiki/ariel_individual_db.md delete mode 100644 wiki/cppn_neat_genome.md delete mode 100644 wiki/log.md delete mode 100644 wiki/neat_speciation.md delete mode 100644 wiki/robogen_lite_api.md delete mode 100644 wiki/stanley_2002.md diff --git a/wiki/.obsidian/app.json b/wiki/.obsidian/app.json deleted file mode 100644 index 9e26dfeeb..000000000 --- a/wiki/.obsidian/app.json +++ /dev/null @@ -1 +0,0 @@ -{} \ No newline at end of file diff --git a/wiki/.obsidian/appearance.json b/wiki/.obsidian/appearance.json deleted file mode 100644 index 9e26dfeeb..000000000 --- a/wiki/.obsidian/appearance.json +++ /dev/null @@ -1 +0,0 @@ -{} \ No newline at end of file diff --git a/wiki/.obsidian/core-plugins.json b/wiki/.obsidian/core-plugins.json deleted file mode 100644 index 639b90da7..000000000 --- a/wiki/.obsidian/core-plugins.json +++ /dev/null @@ -1,33 +0,0 @@ -{ - "file-explorer": true, - "global-search": true, - "switcher": true, - "graph": true, - "backlink": true, - "canvas": true, - "outgoing-link": true, - "tag-pane": true, - "footnotes": false, - "properties": true, - "page-preview": true, - "daily-notes": true, - "templates": true, - "note-composer": true, - "command-palette": true, - "slash-command": false, - "editor-status": true, - "bookmarks": true, - "markdown-importer": false, - "zk-prefixer": false, - "random-note": false, - "outline": true, - "word-count": true, - "slides": false, - "audio-recorder": false, - "workspaces": false, - "file-recovery": true, - "publish": false, - "sync": true, - "bases": true, - "webviewer": false -} \ No newline at end of file diff --git a/wiki/.obsidian/workspace.json b/wiki/.obsidian/workspace.json deleted file mode 100644 index 57a092d23..000000000 --- a/wiki/.obsidian/workspace.json +++ /dev/null @@ -1,181 +0,0 @@ -{ - "main": { - "id": "9627743bfab55623", - "type": "split", - "children": [ - { - "id": "19266c202a1f5048", - "type": "tabs", - "children": [ - { - "id": "18250f2a075f1126", - "type": "leaf", - "state": { - "type": "empty", - "state": {}, - "icon": "lucide-file", - "title": "New tab" - } - } - ] - } - ], - "direction": "vertical" - }, - "left": { - "id": "53f57ff569a039d5", - "type": "split", - "children": [ - { - "id": "16f861d2f5e67dab", - "type": "tabs", - "children": [ - { - "id": "dee6796142897856", - "type": "leaf", - "state": { - "type": "file-explorer", - "state": { - "sortOrder": "alphabetical", - "autoReveal": false - }, - "icon": "lucide-folder-closed", - "title": "Files" - } - }, - { - "id": "652428d5d8d462f8", - "type": "leaf", - "state": { - "type": "search", - "state": { - "query": "", - "matchingCase": false, - "explainSearch": false, - "collapseAll": false, - "extraContext": false, - "sortOrder": "alphabetical" - }, - "icon": "lucide-search", - "title": "Search" - } - }, - { - "id": "23971e86c79d2fe4", - "type": "leaf", - "state": { - "type": "bookmarks", - "state": {}, - "icon": "lucide-bookmark", - "title": "Bookmarks" - } - } - ] - } - ], - "direction": "horizontal", - "width": 300 - }, - "right": { - "id": "7f19bc721e1e9093", - "type": "split", - "children": [ - { - "id": "58edac2c5b05b075", - "type": "tabs", - "children": [ - { - "id": "ac8c62261e616062", - "type": "leaf", - "state": { - "type": "backlink", - "state": { - "collapseAll": false, - "extraContext": false, - "sortOrder": "alphabetical", - "showSearch": false, - "searchQuery": "", - "backlinkCollapsed": false, - "unlinkedCollapsed": true - }, - "icon": "links-coming-in", - "title": "Backlinks" - } - }, - { - "id": "9df05df4bcf076f7", - "type": "leaf", - "state": { - "type": "outgoing-link", - "state": { - "linksCollapsed": false, - "unlinkedCollapsed": true - }, - "icon": "links-going-out", - "title": "Outgoing links" - } - }, - { - "id": "22225ddc925c5b85", - "type": "leaf", - "state": { - "type": "tag", - "state": { - "sortOrder": "frequency", - "useHierarchy": true, - "showSearch": false, - "searchQuery": "" - }, - "icon": "lucide-tags", - "title": "Tags" - } - }, - { - "id": "75cd6a814ba04ec8", - "type": "leaf", - "state": { - "type": "all-properties", - "state": { - "sortOrder": "frequency", - "showSearch": false, - "searchQuery": "" - }, - "icon": "lucide-archive", - "title": "All properties" - } - }, - { - "id": "39a68c79b44262cf", - "type": "leaf", - "state": { - "type": "outline", - "state": { - "followCursor": false, - "showSearch": false, - "searchQuery": "" - }, - "icon": "lucide-list", - "title": "Outline" - } - } - ] - } - ], - "direction": "horizontal", - "width": 300, - "collapsed": true - }, - "left-ribbon": { - "hiddenItems": { - "switcher:Open quick switcher": false, - "graph:Open graph view": false, - "canvas:Create new canvas": false, - "daily-notes:Open today's daily note": false, - "templates:Insert template": false, - "command-palette:Open command palette": false, - "bases:Create new base": false - } - }, - "active": "18250f2a075f1126", - "lastOpenFiles": [] -} \ No newline at end of file diff --git a/wiki/ariel_db_pandas.md b/wiki/ariel_db_pandas.md deleted file mode 100644 index 079050cdb..000000000 --- a/wiki/ariel_db_pandas.md +++ /dev/null @@ -1,129 +0,0 @@ ---- -title: "Database Manipulation with Pandas" -authors: "ARIEL / ci-group" -year: 2024 -source: "https://ci-group.github.io/ariel/source/Db_examples/db_with_pandas.html" -tags: [ariel, database, pandas, sqlite, evolutionary-algorithm, analysis, visualization] ---- - -# Database Manipulation with Pandas - -One-sentence summary: Demonstrates how to read ARIEL's SQLite individual database into pandas, reconstruct per-generation populations from birth/death timestamps, compute fitness statistics, and plot progression curves. - -## Database Structure - -ARIEL stores all individuals ever created in a single SQL table (`individual`) inside `__data__/database.db` (SQLite). Unlike traditional EA implementations that store generation-based population lists, ARIEL uses a **temporal tracking** model. - -### Schema — `individual` table - -| Column | Type | Description | -|---|---|---| -| `id` | int | Individual identifier | -| `alive` | bool | Current status | -| `time_of_birth` | int | Generation when created | -| `time_of_death` | int | Generation when removed from population | -| `fitness_` | float | Fitness score | -| `genotype_` | JSON string | Genetic information | -| `tags_` | JSON string | Custom metadata | - -## Loading Data - -```python -import sqlite3 -import json5 -import pandas as pd - -data = pd.read_sql( - "SELECT * FROM individual", - sqlite3.connect("__data__/database.db"), -) -data["genotype_"] = data["genotype_"].apply(json5.loads) -``` - -Note: `genotype_` is stored as a JSON string and must be decoded with `json5.loads`. - -## Reconstructing Population per Generation - -Because individuals have birth/death times rather than a generation membership list, population snapshots must be reconstructed: - -```python -min_gen = int(data["time_of_birth"].min()) -max_gen = int(data["time_of_death"].max()) - -population_per_gen = { - gen: data.loc[ - (data["time_of_birth"] <= gen) & (data["time_of_death"] > gen), "id" - ].tolist() - for gen in range(min_gen, max_gen + 1) -} - -pop_df = pd.DataFrame({ - "generation": list(population_per_gen.keys()), - "individuals": list(population_per_gen.values()), - "pop size": [len(v) for v in population_per_gen.values()], -}) -``` - -An individual is **alive at generation `g`** if `time_of_birth <= g < time_of_death`. - -## Computing Fitness Statistics per Generation - -```python -fitness_by_id = data.set_index("id")["fitness_"] - -means, stds, maxs = [], [], [] - -for gen in pop_df["generation"]: - ids = population_per_gen.get(int(gen), []) - fits = fitness_by_id.reindex(ids).dropna().astype(float).values - if fits.size == 0: - means.append(np.nan); stds.append(np.nan); maxs.append(np.nan) - else: - means.append(float(np.mean(fits))) - stds.append(float(np.std(fits, ddof=0))) - maxs.append(float(np.min(fits))) # min = best for minimisation tasks - -pop_df["fitness_mean"] = means -pop_df["fitness_std"] = stds -pop_df["fitness_best"] = maxs -``` - -`np.min` is used for best fitness — confirms ARIEL minimises fitness by default (lower = better). - -## Visualization - -```python -import matplotlib.pyplot as plt - -df = pop_df.copy() -mask = df["fitness_mean"].notna() - -x = df.loc[mask, "generation"] -mean = df.loc[mask, "fitness_mean"] -std = df.loc[mask, "fitness_std"] -best = df.loc[mask, "fitness_best"] - -plt.figure(figsize=(10, 5)) -plt.plot(x, mean, label="Fitness mean", color="C0", linewidth=2) -plt.plot(x, best, label="Fitness best", color="C1", linestyle="--", linewidth=2) -plt.fill_between(x, mean - std, mean + std, color="C0", alpha=0.25, label="Mean ± Std") -plt.xlabel("Generation") -plt.ylabel("Fitness") -plt.title("Fitness statistics per generation") -plt.legend() -plt.grid(alpha=0.3) -plt.tight_layout() -plt.show() -``` - -## Key Design Properties - -- **Complete history**: The DB retains every individual ever created, not just survivors — enables post-hoc lineage and selection pressure analysis. -- **Generational reconstruction via temporal filter**: `time_of_birth <= g < time_of_death` is the canonical membership predicate. -- **Fitness convention**: ARIEL minimises fitness (best = `np.min`). -- **genotype_ encoding**: JSON stored as string; decode with `json5.loads` (tolerates trailing commas / single quotes). - -## Related Topics - -- [[ariel_individual_db]] — schema details and individual lifecycle -- [[ariel_ea_loop]] — how generations and selection interact diff --git a/wiki/ariel_individual_db.md b/wiki/ariel_individual_db.md deleted file mode 100644 index 8a08f02bb..000000000 --- a/wiki/ariel_individual_db.md +++ /dev/null @@ -1,37 +0,0 @@ ---- -title: "ARIEL Individual Database — Schema and Temporal Model" -tags: [ariel, database, sqlite, individual, temporal-model] ---- - -# ARIEL Individual Database - -ARIEL uses a **flat append-only SQLite database** rather than per-generation population lists. Every individual that ever existed is stored in `__data__/database.db`, table `individual`. - -## Temporal Membership Model - -Each individual carries two timestamps: - -| Field | Meaning | -|---|---| -| `time_of_birth` | Generation at which the individual was added to the population | -| `time_of_death` | Generation at which it was removed (exclusive upper bound) | - -**Alive at generation g**: `time_of_birth <= g < time_of_death` - -This lets you reconstruct any historical population snapshot with a simple pandas boolean mask — no separate population-list storage needed. - -## Fitness Convention - -ARIEL **minimises** fitness. When computing "best fitness" per generation use `np.min`, not `np.max`. - -## Genotype Encoding - -`genotype_` is stored as a JSON string (may use json5 syntax — trailing commas, single quotes). Always decode with `json5.loads`, not the stdlib `json` module. - -```python -data["genotype_"] = data["genotype_"].apply(json5.loads) -``` - -## Usage Pattern - -See [[ariel_db_pandas]] for the full pandas workflow to load, reconstruct generations, and plot fitness curves. diff --git a/wiki/cppn_neat_genome.md b/wiki/cppn_neat_genome.md deleted file mode 100644 index 699b3ecce..000000000 --- a/wiki/cppn_neat_genome.md +++ /dev/null @@ -1,58 +0,0 @@ ---- -title: "CPPN-NEAT Genome in ARIEL" -authors: "CI-Group (VU Amsterdam)" -year: 2024 -source: "https://ci-group.github.io/ariel/autoapi/ariel/body_phenotypes/robogen_lite/cppn_neat/genome/index.html" -tags: [cppn, neat, genome, evolutionary-robotics, ariel, neuroevolution] ---- - -# CPPN-NEAT Genome in ARIEL - -ARIEL uses CPPN (Compositional Pattern Producing Networks) evolved with NEAT (NeuroEvolution of Augmenting Topologies) as the genotype for robot morphologies. - -## What is CPPN-NEAT? - -- **CPPN:** A neural network whose topology encodes spatial patterns. When queried at (x, y, z, ...) coordinates, it outputs module type/rotation scores for those positions. -- **NEAT:** An evolutionary algorithm that evolves both network weights *and* topology (adding nodes/connections over generations), using innovation numbers to track gene history for crossover. - -## Genome Class API - -See [[robogen_lite_api]] for full method signatures. - -### Key operations -| Operation | Method | -|-----------|--------| -| Create random genome | `Genome.random(num_inputs, num_outputs, next_node_id, next_innov_id)` | -| Structural mutation | `genome.mutate(node_add_rate, conn_add_rate, ...)` | -| Recombination | `genome.crossover(other)` | -| Forward pass | `genome.activate(inputs) → list[float]` | -| Serialize | `genome.to_dict()` / `Genome.from_dict(data)` | -| Deep copy | `genome.copy()` | - -### Node Gene -```python -Node(_id, _typ, _activation: ActivationFunction, _bias) -``` -Node types: input, hidden, output. Supports multiple activation functions via `ActivationFunction` enum. - -### Topological Evaluation -- `get_node_ordering()` runs **Kahn's algorithm** for feed-forward networks. -- `activate()` falls back to **iterative relaxation** when cycles exist (recurrent topologies). - -## Decoding CPPN → Morphology - -The `MorphologyDecoderBestFirst` queries the genome at candidate attachment positions, applies **softmax** to raw output scores, and greedily selects the best placement until `max_modules` is reached. Result is a `nx.DiGraph`. - -See [[robogen_lite_api#decoders]] for decoder details. - -## Innovation Numbers & Speciation - -NEAT tracks structural gene identity via innovation numbers (`next_innov_id`). This enables meaningful crossover: matching genes by innovation number rather than position. ARIEL exposes this via `id_manager`. - -For the full NEAT algorithm (compatibility distance formula, speciation mechanics, fitness sharing): see [[stanley_2002]] and [[neat_speciation]]. - -## Best Practices - -- Keep `max_modules` consistent across a population (affects fitness landscape). -- Use `genome.copy()` before mutation to preserve parent for elitism. -- `from_dict` / `to_dict` enable checkpointing entire populations. diff --git a/wiki/log.md b/wiki/log.md deleted file mode 100644 index 2f3a18bef..000000000 --- a/wiki/log.md +++ /dev/null @@ -1,16 +0,0 @@ -# Wiki Ingest Log - -## [2026-04-11] Ingest | Evolving Neural Networks through Augmenting Topologies (NEAT) -- Source: https://gwern.net/doc/reinforcement-learning/exploration/2002-stanley.pdf -- Files created: stanley_2002.md, neat_speciation.md -- Updated: cppn_neat_genome.md (added cross-links) -- Covers: full NEAT algorithm — innovation numbers, crossover by historical marking, compatibility distance formula (δ = c1·E/N + c2·D/N + c3·W̄), speciation mechanics, fitness sharing, complexification from minimal topologies, double-pole balancing benchmarks - -## [2026-04-11] Ingest | robogen_lite — ARIEL Body Phenotype API -- Source: https://ci-group.github.io/ariel/autoapi/ariel/body_phenotypes/robogen_lite/index.html -- Files created: robogen_lite_api.md, cppn_neat_genome.md -- Covers: full module hierarchy (config, constructor, modules, cppn_neat, decoders, prebuilt_robots), all class/method signatures, constants, and typical usage pipeline - -## [2026-04-11] Ingest | Database Manipulation with Pandas (ARIEL docs) -- Source: https://ci-group.github.io/ariel/source/Db_examples/db_with_pandas.html -- Files created: ariel_db_pandas.md, ariel_individual_db.md diff --git a/wiki/neat_speciation.md b/wiki/neat_speciation.md deleted file mode 100644 index b54bd0c4c..000000000 --- a/wiki/neat_speciation.md +++ /dev/null @@ -1,109 +0,0 @@ ---- -title: "NEAT Speciation and Historical Markings" -authors: "Stanley, Miikkulainen" -year: 2002 -source: "https://gwern.net/doc/reinforcement-learning/exploration/2002-stanley.pdf" -tags: [neat, speciation, innovation-numbers, crossover, neuroevolution, evolutionary-computation] ---- - -# NEAT Speciation and Historical Markings - -Detailed notes on the two structural mechanisms that make NEAT's topology evolution tractable. Based on [[stanley_2002]]. - ---- - -## The Competing Conventions Problem - -When two networks encode the same function using different topologies, naive crossover produces broken offspring — genes that are functionally unrelated get swapped. This is the **competing conventions problem** that prevented earlier topology-evolving approaches from using crossover effectively. - -NEAT's innovation numbers solve this by providing a **shared historical coordinate system** across the entire population. - ---- - -## Innovation Numbers in Detail - -A global counter tracks every distinct structural mutation ever performed in a run. - -**Add-connection mutation:** -``` -new connection (A → B) → gets innovation_number = global_counter++ -``` - -**Add-node mutation** (splits connection A→B): -``` -1. Disable connection A→B -2. Add node C -3. New connection A→C → innovation_number = global_counter++ -4. New connection C→B → innovation_number = global_counter++ -``` - -**Key rule:** If the same structural mutation (same in-node, same out-node) occurs **more than once within the same generation**, all instances get the **same innovation number**. This prevents the counter from exploding and ensures convergent innovations are correctly identified as the same gene. - -Within a generation, a lookup table checks: "has this (in_node, out_node) pair already been mutated this generation?" If yes, reuse the existing innovation number. - ---- - -## Compatibility Distance - -$$\delta = \frac{c_1 \cdot E}{N} + \frac{c_2 \cdot D}{N} + c_3 \cdot \bar{W}$$ - -- **E (Excess genes):** Connection genes whose innovation numbers lie *beyond* the range of the other genome (they're newer than the other genome's most recent gene). -- **D (Disjoint genes):** Connection genes whose innovation numbers fall *within* the range of the other genome but are not present in it (innovations the other lineage missed). -- **N:** Max gene count between the two genomes — normalises so large genomes aren't automatically far from everything. -- **W̄:** Mean |weight difference| across matching genes (same innovation number in both). - -**Typical values** from the paper: c1=1.0, c2=1.0, c3=0.4 with δ_t=3.0 (problem-dependent). - -For small genomes (N < 20), the paper drops the N normalisation. - ---- - -## Species Assignment - -Each generation: -1. Pick a random **representative** from each existing species (from the previous generation). -2. For each new organism, compute δ against each representative in order. -3. If δ < δ_t for some representative, assign organism to that species. -4. If no match found, create a new species with this organism as its representative. - -Species membership is **re-evaluated every generation**. Species without offspring go extinct. - ---- - -## Adjusted Fitness and Offspring Allocation - -Within-species fitness sharing prevents a single species from dominating: - -$$f'_i = \frac{f_i}{\text{species\_size}}$$ - -(This is a simplification; the full formula sums sh(δ(i,j)) over all j, but since sh=1 within species and 0 outside, it reduces to dividing by species size.) - -**Offspring per species** = (species total adjusted fitness) / (population total adjusted fitness) × population\_size - -The **best-performing organism** in each species is copied unchanged into the next generation (**elitism within species**). - -Low-performing members of a species are culled before reproduction (e.g. bottom 20%). - ---- - -## Effect of Speciation on Search - -Without speciation, novel topologies (with unoptimised weights) are immediately outcompeted by incumbents. Speciation provides a **grace period**: - -1. A new structural mutation creates an organism in a new species (or small species). -2. That species gets offspring proportional to its (currently modest) adjusted fitness. -3. Over generations, if the topology is useful, its fitness grows and the species expands. -4. If it's not useful, the species dwindles and goes extinct. - -This is analogous to **ecological niching** in biology — different species occupy different fitness peaks without direct competition during early exploration. - ---- - -## Implementation Notes for ARIEL - -In ARIEL's `cppn_neat` module: -- Innovation numbers are tracked via `id_manager` (passed into `Genome.random()` and `genome.mutate()`). -- The `next_innov_id` counter must be **shared across the entire population** — do not instantiate per-individual. -- Species assignment logic is not built into `Genome` — it must be implemented at the population/EA level. - -See [[cppn_neat_genome]] for the genome API and [[stanley_2002]] for the full algorithmic description. diff --git a/wiki/robogen_lite_api.md b/wiki/robogen_lite_api.md deleted file mode 100644 index 74723c7b3..000000000 --- a/wiki/robogen_lite_api.md +++ /dev/null @@ -1,273 +0,0 @@ ---- -title: "robogen_lite — ARIEL Body Phenotype API" -authors: "CI-Group (VU Amsterdam)" -year: 2024 -source: "https://ci-group.github.io/ariel/autoapi/ariel/body_phenotypes/robogen_lite/index.html" -tags: [ariel, body-phenotype, modular-robot, robogen, cppn, neat, mujoco, evolutionary-robotics] ---- - -# robogen_lite — ARIEL Body Phenotype API - -Module path: `ariel.body_phenotypes.robogen_lite` - -Provides modular robot morphology generation and evolution ("ARIEL-robots") using CPPN-NEAT encoding and MuJoCo simulation. The full pipeline is: **Genome → Decoder → NetworkX DiGraph → Constructor → CoreModule (MuJoCo spec)**. - ---- - -## Module Structure - -``` -robogen_lite/ -├── config.py # Enums and constants (ModuleType, faces, rotations) -├── constructor.py # Graph → MuJoCo spec conversion -├── cppn_neat/ # NEAT-based CPPN implementation -│ ├── activations # Activation functions (ActivationFunction enum) -│ ├── connection # Connection genes -│ ├── genome # Genome class (main entry point) -│ ├── id_manager # Innovation / node ID counters -│ ├── node # Node gene -│ └── tests -├── decoders/ # CPPN genome → morphology graph -│ ├── cppn_best_first # Greedy best-first decoder -│ └── hi_prob_decoding # High-probability decoder -├── modules/ # Physical module classes -│ ├── module.py # Abstract base Module -│ ├── core.py # CoreModule -│ ├── brick.py # BrickModule -│ └── hinge.py # HingeModule -└── prebuilt_robots/ # Ready-to-use morphologies - ├── gecko - ├── spider - └── spider_with_blocks -``` - ---- - -## config — Enums & Constants - -### ModuleType (enum) -| Name | Value | -|--------|-------| -| CORE | 0 | -| BRICK | 1 | -| HINGE | 2 | -| NONE | 3 | - -### ModuleFaces (enum) — 6 attachment faces -`FRONT=0, BACK=1, RIGHT=2, LEFT=3, TOP=4, BOTTOM=5` - -### ModuleRotationsIdx / ModuleRotationsTheta (enums) -8 rotation steps in 45° increments: `DEG_0` (0°) through `DEG_315` (315°). - -### ModuleInstance (Pydantic BaseModel) -Represents one module in a genome/graph node: -- `type_: ModuleType` -- `rotation_: ModuleRotationsIdx` -- `links_: dict[ModuleFaces, int]` — maps face → child module index -- `ALLOWED_FACES_`: type-specific valid attachment faces -- `ALLOWED_ROTATIONS_`: type-specific valid rotation indices - -### Numeric constants -| Constant | Value | -|-----------------------|-------| -| `IDX_OF_CORE` | 0 | -| `NUM_OF_TYPES_OF_MODULES` | (total module types) | -| `NUM_OF_FACES` | 6 | -| `NUM_OF_ROTATIONS` | 8 | - ---- - -## Modules — Physical Components - -All module classes inherit from `Module` (abstract base). - -### CoreModule -```python -# ariel.body_phenotypes.robogen_lite.modules.core -``` -Central body; other modules attach to it. - -| Attribute / Constant | Type / Value | -|-----------------------|----------------------------| -| `index` | `int \| None = None` | -| `module_type` | `ModuleType` | -| `CORE_MASS` | `float = 1` | -| `CORE_DIMENSIONS` | `tuple = (0.1, 0.1, 0.1)` | - -**`rotate(angle: float) → None`** — raises `AttributeError` (core does not support rotation). - -### BrickModule -```python -# ariel.body_phenotypes.robogen_lite.modules.brick -``` -Passive structural block. Inherits `rotate(angle: float)`. - -### HingeModule -```python -# ariel.body_phenotypes.robogen_lite.modules.hinge -``` -Articulated joint. Constructor: `HingeModule(index: int)`. - -| Constant | Value | -|---------------------|--------------------------| -| `SHRINK` | 0.99 | -| `STATOR_MASS` | 0.02 | -| `ROTOR_MASS` | 0.04 | -| `STATOR_DIMENSIONS` | (0.025, 0.03, 0.025) | -| `ROTOR_DIMENSIONS` | (0.025, 0.02, 0.025) | - -**`rotate(angle: float) → None`** — rotates hinge by `angle` radians. - -Common properties on all modules: `sites`, `spec`, `body`. - ---- - -## constructor — Graph → MuJoCo - -```python -from ariel.body_phenotypes.robogen_lite.constructor import construct_mjspec_from_graph -``` - -### `construct_mjspec_from_graph(graph: networkx.DiGraph) → CoreModule` -Converts a NetworkX directed graph (robot structure) into a MuJoCo-simulatable `CoreModule` tree. - -- **Input:** `nx.DiGraph` where nodes encode `ModuleInstance` data and edges encode parent→child attachment. -- **Output:** `CoreModule` root object containing all sub-modules with MuJoCo specs populated. -- **Raises:** `ValueError` if the graph contains an unrecognized module type. - -This is the bridge between evolutionary genotype decoding and physical simulation. - ---- - -## cppn_neat — NEAT Genome - -### Genome -```python -from ariel.body_phenotypes.robogen_lite.cppn_neat.genome import Genome -``` - -#### Attributes -- `nodes: dict[int, Node]` -- `connections: dict[int, Connection]` -- `fitness: float` -- `serialized: dict | None` — optional cached dict - -#### Construction -```python -genome = Genome.random( - num_inputs=..., - num_outputs=..., - next_node_id=..., - next_innov_id=... -) -``` -Creates a fully-connected input→output topology. - -#### Mutation & Crossover -```python -genome.mutate( - node_add_rate=..., - conn_add_rate=..., - next_innov_id_getter=..., - next_node_id_getter=... -) -child = genome.crossover(other_genome) # → Genome -``` - -#### Network Evaluation -```python -outputs = genome.activate(inputs) # → list[float] -ordering = genome.get_node_ordering() # topological sort (Kahn's algorithm) -``` -`activate` falls back to iterative relaxation if cycles exist. - -#### Serialization -```python -d = genome.to_dict() -genome2 = Genome.from_dict(d, fitness=0.0) -copy = genome.copy() # deep copy -``` - -### Node -```python -Node(_id: int, _typ: str, _activation: ActivationFunction, _bias: float) -``` -- `typ` — node type (input / hidden / output) -- `activation` — `ActivationFunction` enum value -- `bias` — float bias -- `copy()` → new Node with identical values - ---- - -## decoders — CPPN → Morphology Graph - -### MorphologyDecoderBestFirst -```python -from ariel.body_phenotypes.robogen_lite.decoders.cppn_best_first import MorphologyDecoderBestFirst -``` - -```python -decoder = MorphologyDecoderBestFirst( - cppn_genome: Genome, - max_modules: int = 20 # hard cap on robot size -) -graph: nx.DiGraph = decoder.decode() -``` - -Greedy best-first search: iteratively selects the highest-scoring attachment position (via softmax over raw CPPN outputs) until `max_modules` is reached. - -**`softmax(raw_scores: NDArray[float32]) → NDArray[float32]`** — helper in this module. - -### hi_prob_decoding -Alternative decoder using a high-probability selection strategy (details in submodule page). - ---- - -## prebuilt_robots - -Ready-to-use `CoreModule` instances for benchmarking: - -| Submodule | Robot | -|---------------------|-------------| -| `gecko` | Gecko | -| `spider` | Spider | -| `spider_with_blocks`| Spider + blocks | - -```python -from ariel.body_phenotypes.robogen_lite.prebuilt_robots.spider import ... -``` - ---- - -## Typical Full Pipeline - -```python -from ariel.body_phenotypes.robogen_lite.cppn_neat.genome import Genome -from ariel.body_phenotypes.robogen_lite.decoders.cppn_best_first import MorphologyDecoderBestFirst -from ariel.body_phenotypes.robogen_lite.constructor import construct_mjspec_from_graph - -# 1. Create / evolve genome -genome = Genome.random(num_inputs=8, num_outputs=6, - next_node_id=id_mgr, next_innov_id=innov_mgr) - -# 2. Decode genome → morphology graph -decoder = MorphologyDecoderBestFirst(genome, max_modules=20) -graph = decoder.decode() # nx.DiGraph - -# 3. Build MuJoCo spec -robot = construct_mjspec_from_graph(graph) # CoreModule - -# 4. Simulate with MuJoCo (robot.spec etc.) -``` - ---- - -## Key Design Notes - -- **Module attachment:** each module exposes up to 6 faces (`ModuleFaces`); only type-specific `ALLOWED_FACES_` are valid attachment points. -- **Rotation:** 8 discrete orientations (45° steps); `CoreModule` does not support rotation. -- **Graph encoding:** a `nx.DiGraph` is the canonical intermediate representation between decoder and constructor. -- **CPPN outputs → module selection:** softmax over raw scores governs which face/module type is placed next. -- **max_modules=20** is the default; smaller values speed up evaluation, larger values allow more complex morphologies. - -See also: [[cppn_neat_genome]], [[mujoco_mjspec]], [[body_brain_learning]] diff --git a/wiki/stanley_2002.md b/wiki/stanley_2002.md deleted file mode 100644 index d692292d6..000000000 --- a/wiki/stanley_2002.md +++ /dev/null @@ -1,173 +0,0 @@ ---- -title: "Evolving Neural Networks through Augmenting Topologies" -authors: "Stanley, Miikkulainen" -year: 2002 -source: "https://gwern.net/doc/reinforcement-learning/exploration/2002-stanley.pdf" -tags: [neat, neuroevolution, topology, speciation, genetic-algorithms, evolutionary-computation, cppn] ---- - -# Evolving Neural Networks through Augmenting Topologies (NEAT) - -**Stanley, K.O. & Miikkulainen, R. (2002)** -*Evolutionary Computation, Vol. 10, No. 2* - -This is the foundational paper for NEAT — the algorithm underlying [[cppn_neat_genome]] in ARIEL. It introduces three key innovations that together make topology-evolving neuroevolution tractable: historical markings, speciation, and complexification from minimal initial topologies. - ---- - -## Core Problem - -Prior neuroevolution methods either (a) fixed the topology and only evolved weights (losing expressivity), or (b) evolved topology but couldn't do meaningful crossover between differently-shaped networks (the **competing conventions problem**). - -NEAT solves all three simultaneously. - ---- - -## Genome Encoding - -Every individual is a **genome** consisting of two gene lists: - -### Node genes -``` -node_id | type (input / hidden / output) -``` - -### Connection genes -``` -in_node | out_node | weight | enabled | innovation_number -``` - -The `enabled` flag allows connections to be "silenced" without deletion (important after add-node mutations). - ---- - -## Innovation Numbers (Historical Markings) - -Every structural mutation (add-node, add-connection) receives a **global innovation number** from a shared counter. This number is permanent and unique to that structural event. - -- If the same structural mutation occurs in two individuals in the same generation, both get the **same** innovation number. -- This creates a chronological historical record embedded in the genome. - -**Why it matters:** Innovation numbers enable meaningful crossover between differently-shaped topologies — align genes by innovation number rather than by position. - ---- - -## Crossover - -Given two parents A and B: - -1. **Align** connection genes by innovation number. -2. **Matching genes** (same innovation number in both): randomly inherit from either parent. -3. **Disjoint genes** (gap within the range of the other parent): inherit from the **fitter** parent. -4. **Excess genes** (beyond the range of the other parent): inherit from the **fitter** parent. - -When parents have equal fitness, disjoint/excess genes are inherited from both (randomly chosen). - -This resolves the competing conventions problem without requiring a bijective mapping between network positions. - ---- - -## Speciation - -New topological innovations start at a disadvantage (no refined weights yet). Without protection, they are eliminated before they can be optimised. - -**Solution:** Group organisms into **species** by genetic similarity. Organisms only compete within their species. - -### Compatibility distance - -$$\delta = \frac{c_1 \cdot E}{N} + \frac{c_2 \cdot D}{N} + c_3 \cdot \bar{W}$$ - -| Symbol | Meaning | -|--------|---------| -| E | Number of excess genes | -| D | Number of disjoint genes | -| N | Number of genes in the larger genome (normalises for size) | -| W̄ | Average weight difference of **matching** genes | -| c1, c2, c3 | Tunable importance coefficients | - -If δ < δ_t (threshold), two organisms belong to the same species. - -### Fitness sharing (niche pressure) - -Adjusted fitness of organism i: - -$$f'_i = \frac{f_i}{\sum_{j=1}^{n} \text{sh}(\delta(i, j))}$$ - -where sh(δ) = 1 if δ < δ_t, else 0. This divides fitness by the number of organisms in the same species, preventing any one species from taking over the population. - -Each species is **allocated offspring proportional to its total adjusted fitness**. - ---- - -## Mutation Operators - -| Mutation | Description | Structural? | -|----------|-------------|-------------| -| Weight perturbation | Add Gaussian noise to existing weights | No | -| Weight replacement | Replace weight with new random value | No | -| Add connection | New edge between two previously unconnected nodes — gets a new innovation number | Yes | -| Add node | Split an existing connection: disable it, insert a new node, add two new connections (weight-1 in, original-weight out) | Yes | - -The add-node mutation uses **two** new innovation numbers (one per new connection). - ---- - -## Complexification from Minimal Initial Topology - -All organisms start with the **same minimal topology**: input nodes connected directly to output nodes, **no hidden nodes**. Complexity emerges only through mutation. - -**Why:** Minimal starting topologies mean the search begins in a low-dimensional weight space where early fitness evaluation is cheap. Complexity is added only when it is useful. - ---- - -## Evaluation Benchmarks - -### XOR problem -- Requires non-linear separation (cannot be solved by direct I→O weights) -- NEAT reliably evolves minimal 2-hidden-node solutions - -### Double pole-balancing without velocity information -- A control task where the agent cannot directly observe velocity (must infer from history — requires recurrent connections or memory) -- NEAT solved this significantly faster than competing algorithms (SANE, ESP) -- Final networks were minimal, interpretable topologies - -### Key metrics reported -- Generations to solution (lower = better) -- Network complexity at solution (number of hidden nodes/connections) -- Success rate across multiple runs - ---- - -## Comparison to Baselines - -| Method | Double pole (no vel.) | Topology evolved? | Crossover meaningful? | -|--------|----------------------|-------------------|-----------------------| -| SANE | Often fails | No | N/A | -| ESP | Often fails | No | N/A | -| Fixed-topology NE | N/A | No | Yes | -| **NEAT** | Reliably solves | **Yes** | **Yes** | - ---- - -## Theoretical Contributions - -1. **Historical markings solve competing conventions** without requiring a topology-normalisation step before crossover. -2. **Speciation provides temporal protection** for structural innovations long enough for weight optimisation to catch up. -3. **Incremental complexification** is sufficient to discover minimal network solutions — you do not need to search over a large topology space up front. - ---- - -## Limitations - -- Speciation parameters (δ_t, c1, c2, c3) require tuning per problem. -- Scalability to very deep or very wide networks was not demonstrated. -- The population-level innovation counter can cause collisions if parallelised naively. -- Recurrent topologies complicate activation evaluation (requires iterative relaxation). - ---- - -## Relation to ARIEL / CPPN-NEAT - -ARIEL uses this exact algorithm to evolve **CPPN genomes** (where the network encodes spatial morphology patterns rather than control policies). See [[cppn_neat_genome]] for ARIEL-specific API details and [[neat_speciation]] for deeper speciation notes. - -The key adaptation: CPPN outputs are **decoded into robot morphologies** (via `MorphologyDecoderBestFirst`) rather than used as controllers. From 80469e3290be77548274b163a88e58c85f3d75da Mon Sep 17 00:00:00 2001 From: A-lamo <2727043@student.vu.nl> Date: Thu, 21 May 2026 15:35:00 +0200 Subject: [PATCH 07/27] Blueprint updates. --- DRONE_BLUEPRINT_PLAN.md | 178 ++++++++++ blueprint.txt | 28 ++ examples/d_drones/11_blueprint_demo.py | 109 ++++++ .../d_drones/12_visualize_from_blueprint.py | 217 +++++++++++ examples/d_drones/13_mujoco_blueprint_quad.py | 205 +++++++++++ examples/d_drones/14_mujoco_lee_figure8.py | 309 ++++++++++++++++ .../d_drones/15_cppn_neat_circle_to_mujoco.py | 336 ++++++++++++++++++ examples/d_drones/3_simulate_lee.py | 8 +- examples/d_drones/4_tune_lee_controller.py | 5 +- examples/d_drones/5_visualize_best_drone.py | 2 +- request_context.txt | 35 ++ src/ariel/body_phenotypes/drone/backends.py | 295 +++++++++++++++ src/ariel/body_phenotypes/drone/blueprint.py | 159 +++++++++ src/ariel/body_phenotypes/drone/decoders.py | 114 ++++++ uv.lock | 76 ++-- 15 files changed, 2035 insertions(+), 41 deletions(-) create mode 100644 DRONE_BLUEPRINT_PLAN.md create mode 100644 blueprint.txt create mode 100644 examples/d_drones/11_blueprint_demo.py create mode 100644 examples/d_drones/12_visualize_from_blueprint.py create mode 100644 examples/d_drones/13_mujoco_blueprint_quad.py create mode 100644 examples/d_drones/14_mujoco_lee_figure8.py create mode 100644 examples/d_drones/15_cppn_neat_circle_to_mujoco.py create mode 100644 request_context.txt create mode 100644 src/ariel/body_phenotypes/drone/backends.py create mode 100644 src/ariel/body_phenotypes/drone/blueprint.py create mode 100644 src/ariel/body_phenotypes/drone/decoders.py diff --git a/DRONE_BLUEPRINT_PLAN.md b/DRONE_BLUEPRINT_PLAN.md new file mode 100644 index 000000000..30050b03c --- /dev/null +++ b/DRONE_BLUEPRINT_PLAN.md @@ -0,0 +1,178 @@ +# Drone Blueprint Plan — ARIEL for the SPEAR Drone Project + +**Audience:** SPEAR pre-meeting (Friday 9:30) and consortium integration event. +**Author:** Aron (VUA), drone-evolution port in ARIEL. + +--- + +## 1. Value proposition + +ARIEL already proves a **blueprint-mediated** pipeline for modular robots: any +genotype (tree, CPPN, vector) is decoded to a common intermediate +representation, which a single phenotype builder turns into a MuJoCo robot +(`src/ariel/body_phenotypes/robogen_lite/decoders/_blueprint.py`). The same +architecture is what the drone consortium needs: many partners, many +encodings, divergent simulators (MuJoCo, Aerial Gym, Isaac Lab). A shared +**Drone Blueprint** lets each group keep their genotype and their preferred +backend while reusing the rest of the pipeline. + +## 2. Current standing + +- Jed Muff's `airevolve` is ported into ARIEL under + `src/ariel/body_phenotypes/drone/` and `src/ariel/ec/drone/`. +- Three encodings already coexist: `spherical_angular`, `cartesian_euler`, + `cppn_neat` (plus a `hybrid_cppn`). Each currently wires *directly* to a + MuJoCo phenotype — bypassing the blueprint layer that is ARIEL's actual + contribution. +- MuJoCo-only sim. No USD/Isaac Lab path yet. +- Examples in `examples/d_drones/` (evolution, NEAT, Lee controller, RL + figure-8, STL export, repair) demonstrate end-to-end runs. + +**Gap:** drone encodings can't yet share a downstream pipeline, and there +is no architectural seam for adding an Isaac Lab backend. + +## 3. Proposed Drone Blueprint + +An **ARIEL-native abstract IR**: a typed tree (NetworkX `DiGraph`, JSON +serialisable) mirroring `robogen_lite`'s blueprint, **lifted into continuous +space**. Drones aren't cubes-on-a-grid; nodes therefore carry continuous +SE(3) transforms and physical parameters rather than enum'd faces. + +### v1 node types + +| Node | Carries | +| --- | --- | +| `CorePlate` | mass, inertia tensor, mounting frame, geometry primitive (disc/box) | +| `Arm` | length, SE(3) attachment pose to parent, material/inertia | +| `Motor` | pose on parent `Arm`, thrust/torque coefficients, spin direction (CW/CCW), max rpm | +| `Rotor` | radius, pitch, blade count, drag coefficient | +| `Sensor` | type (IMU/camera/range), pose, intrinsic params | + +Edges encode parent → child attachment. The root is always a `CorePlate`. + +### Example (sketch) + +```json +{ + "nodes": [ + {"id": 0, "type": "CorePlate", "mass": 0.4, "geometry": {"shape": "disc", "r": 0.05}}, + {"id": 1, "type": "Arm", "length": 0.18, "pose": {"xyz": [0.05,0,0], "rpy": [0,0,0.785]}}, + {"id": 2, "type": "Motor", "pose": {"xyz": [0.18,0,0], "rpy": [0,0,0]}, "spin": "CW", "kf": 1.1e-5, "km": 1.9e-7}, + {"id": 3, "type": "Rotor", "radius": 0.0635, "pitch": 0.045, "blades": 2} + ], + "edges": [[0,1], [1,2], [2,3]] +} +``` + +### Decoders (genotype → blueprint) + +- **Spherical-angular → Blueprint** *(v1, must-have)* — each `(mag, az, el, + motor_az, motor_pitch, spin)` arm row becomes `Arm → Motor → Rotor`. +- **Cartesian-Euler → Blueprint** *(v1, must-have)* — proves portability: + two independent encodings producing the *same* blueprint format. +- **CPPN-NEAT → Blueprint** *(v1 stretch)* — generative mapping; sample the + CPPN over a polar grid, discretise into N arms, then emit the same tree. + Non-trivial — flag as the v1 stretch goal, with a clean v2 fallback. + +### Backends (blueprint → phenotype) + +- **MJCF / `mjSpec`** *(v1)* — replaces today's direct genome→mjSpec path + in `phenotype_assembly/generator.py`. Single source of truth for the + drone body in MuJoCo. +- **STL / STEP** *(v1, free)* — `generate_stl_files` already exists; rewire + it to consume a Blueprint instead of a `SphericalAngularDroneGenomeHandler`. +- **USD / Isaac Lab** *(designed-for, deferred)* — sketched interface: + ```python + def blueprint_to_usd(bp: Blueprint, out: Path) -> Path: ... + # → loaded by isaaclab.sim.UsdFileCfg(usd_path=...) + ``` + Each node maps to a USD `Xform` prim with appropriate `RigidBodyAPI` / + `ArticulationRootAPI`; ImplicitActuatorCfg wiring lives in a small + per-backend adapter, not the blueprint itself. Implementation deferred + pending consortium agreement on Isaac Lab adoption. + +## 4. Refactor: align drone subsystem with ARIEL conventions + +**Current layout** under `src/ariel/body_phenotypes/drone/` (shipped): + +``` +body_phenotypes/drone/ +├── blueprint.py # DroneBlueprint + Pose, *Node dataclasses, JSON I/O +├── decoders.py # spherical_angular_to_blueprint, cartesian_euler_to_blueprint +├── backends.py # blueprint_to_propellers, blueprint_to_mjspec, blueprint_to_usd (stub) +└── phenotype_assembly/ # legacy airevolve port (STL/STEP, generator.py) — not yet rewired +``` + +**Target layout** (still aspirational; matches `robogen_lite/`): + +``` +body_phenotypes/drone/ +├── blueprint.py +├── modules/ # CorePlate, Arm, Motor, Rotor, Sensor as separate modules +├── decoders/ # one file per encoding (spherical, cartesian, cppn-neat) +├── backends/ # one file per backend (mjspec, cad, usd) +└── prebuilt_drones/ # quad / hex / x8 reference blueprints +``` + +`ec/drone/` keeps the EA-side operators (mutation, crossover, evaluation, +inspection); they continue to operate on **genomes**, but downstream calls +now go through `DroneBlueprint` rather than the phenotype generator directly. + +## 5. Roadmap + +**Phase 1 — Blueprint scaffolding. ✅ Done.** +- `src/ariel/body_phenotypes/drone/blueprint.py` — `DroneBlueprint` + (NetworkX `DiGraph`, typed node dataclasses, JSON save/load, summary). +- `src/ariel/body_phenotypes/drone/decoders.py` — `spherical_angular_to_blueprint`, + `cartesian_euler_to_blueprint`. +- `src/ariel/body_phenotypes/drone/backends.py` — + - `blueprint_to_propellers(convention="z_up"|"ned")` → + `DroneSimulator` / `DroneConfiguration` (Python physics stack). + - `blueprint_to_mjspec(...)` → `mujoco.MjSpec` with one welded body per + Arm, motor cylinders + thin rotor discs, and one + `mjTRN_SITE` thrust actuator per rotor + (`ctrl ∈ [0,1] → F ∈ [0, max_thrust]` along the rotor's spin axis). + Accepts `motor_mass`, `arm_mass`, `core_mass_override` so the MuJoCo + body mass can be matched to whatever `DroneConfiguration` auto-computes. + - `blueprint_to_usd` still a stub. +- Examples: + - `examples/d_drones/11_blueprint_demo.py` — two encodings → same + blueprint format → identical `DroneConfiguration` mass/inertia. + - `examples/d_drones/12_visualize_from_blueprint.py` — blueprint flown + through a circle course with the Lee controller (Python sim) + + `sameAxisAnimation` MP4. + - `examples/d_drones/13_mujoco_blueprint_quad.py` — blueprint compiled + to MuJoCo; open-loop hover-thrust quad, MP4 or `mujoco.viewer` (`--view`). + - `examples/d_drones/14_mujoco_lee_figure8.py` — figure-8 flown by Lee + (NED Python sim, validated path), then kinematically replayed inside + MuJoCo using the blueprint's MJCF body. NED→ENU bridge: position + `z` negated, attitude `qy` negated. + +**Phase 2 — Multi-encoding portability. Partial.** +- Two decoders shipped (spherical-angular, Cartesian-Euler) and validated + through both backends. CPPN-NEAT decoder still TODO. +- STL/STEP backend not yet rewired through Blueprint (still consumes the + legacy `SphericalAngularDroneGenomeHandler` directly in + `phenotype_assembly/generator.py`). +- Open issue surfaced while building example 14: the Lee controller's + ENU motor-allocation path has a sign error + (`_wrench_to_motor_commands` applies `-self.Bf[2:3,:]` unconditionally, + which is correct for NED but inverts the relationship for ENU and + drives `w_cmd` to the motor floor). NED is validated; ENU needs the + upstream fix before closed-loop MuJoCo Lee control is possible without + the bridge. + +**Phase 3 — Isaac Lab spike. Not started.** USD backend remains stubbed; +the MJCF backend is structured so a USD compiler maps node-for-node from +the same blueprint tree. + +## 6. Asks for the meeting + +1. Confirm Isaac Lab as the simulator target the consortium will converge + on (so the USD backend is worth investing in). +2. Decide whether partners' encodings should target this Blueprint, or + whether we adopt a different community-standard IR if one is emerging. +3. Identify one partner-encoding (besides spherical/cartesian) to onboard + as a third decoder — proves the portability claim with non-VUA code. +4. Agreement that ARIEL hosts the Blueprint spec; partners contribute + decoders. diff --git a/blueprint.txt b/blueprint.txt new file mode 100644 index 000000000..2cc214848 --- /dev/null +++ b/blueprint.txt @@ -0,0 +1,28 @@ + +The blueprint is an intermediate representation that is part of the pipeline that constructs the robot. Structurally, it sits between the genotype and the phenotype. It acts as a universal common interface through which entirely different encoding schemes can be easily translated into a functioning robot body. As seen in Figure~\ref{fig:blueprint}, the process is divided into two halves: evolution and robotics. It illustrates that the blueprint is not merely a storage format, but the architectural boundary that separates evolutionary representation from embodiment, thereby allowing either side to change without forcing a redesign of the other. Figure~\ref{fig:blueprint-simvsirl} shows the transition from blueprint to instantiation in either simulation or the real world. + +\begin{figure}[htbp] +\centering +\includegraphics[width=\linewidth]{figures/ARIEL_Paper_Blueprint.pdf} +\caption{ Conceptual showcase of how the blueprint works as an intermediate step between a series of choices. Design choices feed into the genotype creation, which is then decoded into the blueprint. The blueprint is then transformed into the phenotype, and after choosing to create it in simulation or the real world, it is instantiated.} +\label{fig:blueprint} +\end{figure} +%\vspace{-7pt} + +The evolution part takes the researcher’s design decisions as input, e.g., the choice of mutation operators or parent selection. It then creates the genotype, which is transformed into a blueprint by a decoder. The blueprint is then transformed into a phenotype that matches the chosen robot platform and is equipped with a brain. The user makes their final choice, whether the output should be created in simulation or built in the real world as a physical robot. At that point, the process reaches the end of the pipeline, and the robot is instantiated and ready for evaluation. + +It can be noted that the decoder does the heavy-lifting to ensure that a genotype can be successfully instantiated; this shifts the burden of development from the traditional genotype-to-phenotype mapping to the decoder. This trade-off is worth it because as your library of decoders expands, more robot systems can reuse them for their own phenotype space. + +\begin{figure}[htbp] +\centering +\includegraphics[width=0.8\linewidth]{figures/ARIEL_blueprint_simvsirl.pdf} +\caption{Example of how the blueprint can be used for instantiation in the real world and simulation.} +\label{fig:blueprint-simvsirl} +\end{figure} + +Concretely, a blueprint may specify the arrangement of body modules, attachment relationships, actuator locations, and sensor placements in a representation that is independent of the genotype that produced it. A tree-based encoding, a CPPN-derived encoding, or another generative representation can therefore all target the same blueprint format, after which a common phenotype-construction pipeline can be reused. + +This separation provides several distinct advantages. It cleanly decouples evolutionary representation from physical construction, thereby separating research on genotypes from research on robot systems. It allows multiple different encodings to share the same downstream processing, makes validation and structural repair significantly easier, and ultimately improves the clarity of the overall pipeline. + +Conceptually, the blueprint acts as the exact meeting point between the Evolutionary Computing (EC) side and the modular robotics side of ARIEL. Practically, the blueprint acts as the foundation to support visualisation, simulation, and future physical hardware workflows. The blueprint takes the form of a tree and is agnostic to what happens on either side of it. + diff --git a/examples/d_drones/11_blueprint_demo.py b/examples/d_drones/11_blueprint_demo.py new file mode 100644 index 000000000..225595ea3 --- /dev/null +++ b/examples/d_drones/11_blueprint_demo.py @@ -0,0 +1,109 @@ +"""Demonstration of the Drone Blueprint pipeline. + +Two completely different genome encodings (spherical-angular and +cartesian-Euler) flow through the SAME downstream pipeline: + + genome → DroneBlueprint → propellers list → DroneConfiguration + +The point: ARIEL's blueprint layer decouples encoding from embodiment, +so the consortium can converge on a shared phenotype path without +forcing partners to converge on a shared genotype. + +Run: + uv run examples/d_drones/11_blueprint_demo.py +""" +from __future__ import annotations + +from pathlib import Path + +import numpy as np + +from ariel.body_phenotypes.drone.blueprint import DroneBlueprint +from ariel.body_phenotypes.drone.decoders import ( + spherical_angular_to_blueprint, + cartesian_euler_to_blueprint, +) +from ariel.body_phenotypes.drone.backends import blueprint_to_propellers +from ariel.simulation.drone.drone_configuration import DroneConfiguration + + +def banner(s: str) -> None: + print("\n" + "=" * 70 + f"\n {s}\n" + "=" * 70) + + +# ---- 1. Two encodings of (roughly) the same 4-arm drone --------------------- + +# Spherical-angular: 4 arms evenly spaced at 90°, level, motors thrust +Z, alt spins. +mag = 0.11 +spherical_genome = np.array([ + [mag, 0.00, 0.0, 0.0, 0.0, 0], # +X + [mag, np.pi / 2, 0.0, 0.0, 0.0, 1], # +Y + [mag, np.pi, 0.0, 0.0, 0.0, 0], # -X + [mag, -np.pi / 2, 0.0, 0.0, 0.0, 1], # -Y +]) + +# Cartesian-Euler: same four motors expressed directly as XYZ + thrust RPY. +cartesian_genome = np.array([ + [ mag, 0.0, 0.0, 0.0, 0.0, 0.0, 0], + [ 0.0, mag, 0.0, 0.0, 0.0, 0.0, 1], + [-mag, 0.0, 0.0, 0.0, 0.0, 0.0, 0], + [ 0.0, -mag, 0.0, 0.0, 0.0, 0.0, 1], +]) + + +# ---- 2. Decode each genome through ITS OWN decoder to a shared Blueprint ---- + +bp_a = spherical_angular_to_blueprint(spherical_genome) +bp_b = cartesian_euler_to_blueprint(cartesian_genome) + +banner("Blueprint A (from spherical-angular genome)") +print(bp_a.summary()) + +banner("Blueprint B (from cartesian-Euler genome)") +print(bp_b.summary()) + + +# ---- 3. Persist Blueprint A as JSON, round-trip it --------------------------- + +out_dir = Path("__data__") / "blueprint_demo" +out_dir.mkdir(parents=True, exist_ok=True) + +json_path = out_dir / "blueprint_A.json" +bp_a.save_json(json_path) +bp_a_roundtrip = DroneBlueprint.load_json(json_path) +banner(f"JSON round-trip → {json_path}") +print(f" nodes before: {bp_a.g.number_of_nodes()} after: " + f"{bp_a_roundtrip.g.number_of_nodes()}") +assert bp_a.g.number_of_nodes() == bp_a_roundtrip.g.number_of_nodes() + + +# ---- 4. Same backend instantiates BOTH blueprints into the SAME format ------ + +props_a = blueprint_to_propellers(bp_a) +props_b = blueprint_to_propellers(bp_b) + +banner("Propellers extracted from Blueprint A (spherical genome)") +for i, p in enumerate(props_a): + print(f" motor {i}: loc={[round(v,3) for v in p['loc']]} " + f"dir={[round(v,3) if isinstance(v,float) else v for v in p['dir']]} " + f"propsize={p['propsize']}") + +banner("Propellers extracted from Blueprint B (cartesian genome)") +for i, p in enumerate(props_b): + print(f" motor {i}: loc={[round(v,3) for v in p['loc']]} " + f"dir={[round(v,3) if isinstance(v,float) else v for v in p['dir']]} " + f"propsize={p['propsize']}") + + +# ---- 5. Both feed the existing DroneConfiguration unchanged ----------------- + +cfg_a = DroneConfiguration(props_a) +cfg_b = DroneConfiguration(props_b) + +banner("Downstream phenotype properties (same DroneConfiguration code path)") +print(f" Blueprint A → mass={cfg_a.mass:.4f} kg " + f"Ix={cfg_a.Ix:.4e} Iy={cfg_a.Iy:.4e} Iz={cfg_a.Iz:.4e}") +print(f" Blueprint B → mass={cfg_b.mass:.4f} kg " + f"Ix={cfg_b.Ix:.4e} Iy={cfg_b.Iy:.4e} Iz={cfg_b.Iz:.4e}") +print("\n → Two distinct encodings, one shared phenotype pipeline. " + "That's the blueprint.\n") diff --git a/examples/d_drones/12_visualize_from_blueprint.py b/examples/d_drones/12_visualize_from_blueprint.py new file mode 100644 index 000000000..95d535dc7 --- /dev/null +++ b/examples/d_drones/12_visualize_from_blueprint.py @@ -0,0 +1,217 @@ +"""Instantiate a drone from a DroneBlueprint and record a flight video. + +This is the natural sequel to ``11_blueprint_demo.py``. The previous demo +proved two different encodings produce identical phenotype properties; here +we close the loop by **flying** a blueprint-derived drone with the Lee +geometric controller through a gate course, and saving the rendered +animation to MP4. + +Pipeline exercised end-to-end: + + spherical_angular genome + → spherical_angular_to_blueprint (decoder) + → DroneBlueprint (saved as JSON for inspection) + → blueprint_to_propellers(convention="ned") (backend) + → DroneInterface / DroneSimulator (existing ARIEL physics) + → Lee geometric controller (existing ARIEL control) + → sameAxisAnimation -> MP4 (existing ARIEL rendering) + +Nothing downstream of the blueprint had to be modified — that's the point. + +Run: + uv run examples/d_drones/12_visualize_from_blueprint.py + uv run examples/d_drones/12_visualize_from_blueprint.py --gates figure8 --time 12 + uv run examples/d_drones/12_visualize_from_blueprint.py --no-save # show interactively +""" +from __future__ import annotations + +import argparse +import os +import time +from pathlib import Path + +import numpy as np + +os.environ.setdefault("OMP_NUM_THREADS", "1") +os.environ.setdefault("OPENBLAS_NUM_THREADS", "1") +os.environ.setdefault("MKL_NUM_THREADS", "1") + +# Blueprint layer (new in this branch) +from ariel.body_phenotypes.drone.decoders import spherical_angular_to_blueprint +from ariel.body_phenotypes.drone.backends import blueprint_to_propellers + +# Existing simulation / control stack (unchanged) +from ariel.simulation.drone.drone_interface import DroneInterface +from ariel.simulation.drone.controllers.lee_control.lee_controller import ( + LeeGeometricControl, +) +from ariel.simulation.drone.controllers.trajectory_generation.trajectory import ( + Trajectory, +) +from ariel.simulation.drone.controllers.utils.gate_configs import GATE_CONFIGS +from ariel.simulation.drone.controllers.utils.wind_model import Wind +import ariel.simulation.drone.controllers.utils as ctrl_utils + + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +parser = argparse.ArgumentParser( + description="Fly a drone instantiated from a DroneBlueprint", +) +parser.add_argument("--gates", default="circle", + choices=["figure8", "circle", "slalom", "backandforth"], + help="Gate configuration (default: circle)") +parser.add_argument("--time", type=float, default=10.0, + help="Simulation duration in seconds (default 10)") +parser.add_argument("--dt", type=float, default=0.005, + help="Simulation time-step in seconds (default 0.005)") +parser.add_argument("--arm-len", type=float, default=0.06, + help="Arm length in metres for the demo quad (default 0.06)") +parser.add_argument("--prop-size", type=int, default=2, + help="Propeller size in inches (default 2)") +parser.add_argument("--pos-gain", type=float, default=14.3) +parser.add_argument("--vel-gain", type=float, default=9.0) +parser.add_argument("--no-save", action="store_true", + help="Show interactive window instead of writing an MP4") +parser.add_argument("--out", + default="__data__/blueprint_demo/blueprint_flight.mp4", + help="Output video path") +args = parser.parse_args() + + +# --------------------------------------------------------------------------- +# 1. Build a spherical-angular genome for a 4-arm X-quad +# --------------------------------------------------------------------------- + +mag = float(args.arm_len) +genome = np.array([ + # [magnitude, arm_az, arm_pitch, motor_az, motor_pitch, direction] + [mag, np.pi / 4, 0.0, 0.0, 0.0, 0], # front-right, CCW + [mag, 3 * np.pi / 4, 0.0, 0.0, 0.0, 1], # front-left, CW + [mag, -3 * np.pi / 4, 0.0, 0.0, 0.0, 0], # rear-left, CCW + [mag, -np.pi / 4, 0.0, 0.0, 0.0, 1], # rear-right, CW +]) + + +# --------------------------------------------------------------------------- +# 2. Decode → DroneBlueprint, persist for inspection +# --------------------------------------------------------------------------- + +bp = spherical_angular_to_blueprint(genome, propsize=args.prop_size) + +out_path = Path(args.out) +out_path.parent.mkdir(parents=True, exist_ok=True) +bp_path = out_path.with_suffix(".json") +bp.save_json(bp_path) + +print("=" * 70) +print(f"DroneBlueprint built from genome ({genome.shape[0]} arms)") +print(f" saved to: {bp_path}") +print("=" * 70) +print(bp.summary()) + + +# --------------------------------------------------------------------------- +# 3. Backend: Blueprint → propellers list (NED for the Lee controller stack) +# --------------------------------------------------------------------------- + +propellers = blueprint_to_propellers(bp, convention="ned") +print("\nPropellers handed to DroneSimulator (NED convention):") +for i, p in enumerate(propellers): + print(f" motor {i}: loc={[round(v, 3) for v in p['loc']]} " + f"dir={[round(v, 3) if isinstance(v, float) else v for v in p['dir']]} " + f"propsize={p['propsize']}") + + +# --------------------------------------------------------------------------- +# 4. Instantiate DroneInterface + Lee controller + trajectory +# --------------------------------------------------------------------------- + +quad = DroneInterface(0, propellers=propellers) +wind = Wind("None") + +ctrl = LeeGeometricControl( + quad, + yawType=1, + orient="NED", + auto_scale_gains=True, + pos_P_gain=np.array([args.pos_gain] * 3), + vel_P_gain=np.array([args.vel_gain] * 3), +) + +gate_config = GATE_CONFIGS[args.gates] +traj = Trajectory(quad, "xyz_pos", np.array([15, 3, 1]), gate_config=gate_config) + +# Seed initial state to trajectory start (matches 3_simulate_lee.py) +start_pos, _, _ = traj.bspline_trajectory.evaluate(0.0) +_, vel_050, _ = traj.bspline_trajectory.evaluate(0.05) +if np.linalg.norm(vel_050[:2]) > 0.001: + initial_yaw = float(np.arctan2(vel_050[1], vel_050[0])) +else: + initial_yaw = float(gate_config.gate_yaw[0]) + +quad.drone_sim.set_state( + position=start_pos, + velocity=np.zeros(3), + attitude=np.array([0.0, 0.0, initial_yaw]), + angular_velocity=np.zeros(3), +) +quad._update_state_variables() + +sDes = traj.desiredState(0.0, args.dt, quad) +ctrl.controller(sDes, quad, traj.ctrlType, args.dt) + + +# --------------------------------------------------------------------------- +# 5. Roll the sim forward, log per-step state +# --------------------------------------------------------------------------- + +Ts = float(args.dt) +Tf = float(args.time) +num_steps = int(Tf / Ts + 1) + +t_all = np.zeros(num_steps) +pos_all = np.zeros((num_steps, 3)) +quat_all = np.zeros((num_steps, 4)) +sDes_traj_all = np.zeros((num_steps, len(traj.sDes))) + +print(f"\nRunning {Tf}s simulation @ dt={Ts}s …") +t0 = time.time() +t = 0.0 +i = 1 +while round(t, 4) < Tf and i < num_steps: + t_all[i] = t + pos_all[i] = quad.pos + quat_all[i] = quad.quat + sDes_traj_all[i] = traj.sDes + + quad.update(t, Ts, ctrl.w_cmd, wind) + t = Ts * i + sDes = traj.desiredState(t, Ts, quad) + ctrl.controller(sDes, quad, traj.ctrlType, Ts) + i += 1 +print(f" simulated {t:.2f}s in {time.time() - t0:.2f}s wall-clock") + + +# --------------------------------------------------------------------------- +# 6. Render → MP4 (or interactive) +# --------------------------------------------------------------------------- + +waypoints = np.array(gate_config.gate_pos, dtype=float) +save = not args.no_save +save_path = str(out_path) if save else None + +ctrl_utils.sameAxisAnimation( + t_all[:i], waypoints, pos_all[:i], quat_all[:i], sDes_traj_all[:i], Ts, + quad.params, 15, 3, int(save), "NED", + gate_pos=np.array(gate_config.gate_pos), + gate_yaw=np.array(gate_config.gate_yaw), + gate_size=gate_config.gate_size, + save_path=save_path, +) + +if save: + print(f"\nVideo written to: {out_path}") + print(f"Blueprint JSON : {bp_path}") diff --git a/examples/d_drones/13_mujoco_blueprint_quad.py b/examples/d_drones/13_mujoco_blueprint_quad.py new file mode 100644 index 000000000..9d3b62d7b --- /dev/null +++ b/examples/d_drones/13_mujoco_blueprint_quad.py @@ -0,0 +1,205 @@ +"""Simulate a blueprint-derived quadcopter in MuJoCo and record a video. + +Pipeline: + + spherical_angular genome + → spherical_angular_to_blueprint (decoder) + → DroneBlueprint (saved as JSON for inspection) + → blueprint_to_mjspec (NEW backend) + → mujoco.MjSpec → MjModel (compiled into ARIEL's SimpleFlatWorld) + → constant per-motor thrust (open-loop hover; no controller) + → video_renderer → MP4 + +This is the MuJoCo counterpart to example 12 (which used the Python Lee +controller stack). Same blueprint, different backend — exactly the +portability story the ARIEL blueprint architecture promises. + +Run: + uv run examples/d_drones/13_mujoco_blueprint_quad.py + uv run examples/d_drones/13_mujoco_blueprint_quad.py --duration 8 --thrust 0.55 + uv run examples/d_drones/13_mujoco_blueprint_quad.py --view # interactive viewer, no MP4 +""" +from __future__ import annotations + +import argparse +import os +from pathlib import Path + +import numpy as np +import mujoco + +os.environ.setdefault("OMP_NUM_THREADS", "1") + +from ariel.body_phenotypes.drone.decoders import spherical_angular_to_blueprint +from ariel.body_phenotypes.drone.backends import blueprint_to_mjspec +from ariel.simulation.environments import SimpleFlatWorld +from ariel.utils.video_recorder import VideoRecorder + + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +parser = argparse.ArgumentParser( + description="MuJoCo simulation of a blueprint-derived quadcopter" +) +parser.add_argument("--arm-len", type=float, default=0.12, + help="Arm length in metres (default 0.12)") +parser.add_argument("--prop-size", type=int, default=5, + help="Propeller size in inches (default 5)") +parser.add_argument("--max-thrust", type=float, default=5.0, + help="Per-motor max thrust in Newtons (default 5.0)") +parser.add_argument("--thrust", type=float, default=None, + help="Fixed per-motor ctrl ∈ [0,1]. If omitted, " + "auto-compute hover thrust = m*g / (n * max_thrust).") +parser.add_argument("--duration", type=float, default=6.0, + help="Sim duration in seconds (default 6)") +parser.add_argument("--spawn-z", type=float, default=0.5, + help="Initial spawn height in m (default 0.5)") +parser.add_argument("--out", default="__data__/blueprint_demo/mujoco_quad.mp4", + help="Output video path (ignored when --view is set)") +parser.add_argument("--view", action="store_true", + help="Launch MuJoCo passive viewer instead of writing a video") +args = parser.parse_args() + + +# --------------------------------------------------------------------------- +# 1. Build a spherical-angular genome for a 4-arm X-quad +# --------------------------------------------------------------------------- + +mag = float(args.arm_len) +genome = np.array([ + # [magnitude, arm_az, arm_pitch, motor_az, motor_pitch, direction] + [mag, np.pi / 4, 0.0, 0.0, 0.0, 0], + [mag, 3 * np.pi / 4, 0.0, 0.0, 0.0, 1], + [mag, -3 * np.pi / 4, 0.0, 0.0, 0.0, 0], + [mag, -np.pi / 4, 0.0, 0.0, 0.0, 1], +]) + + +# --------------------------------------------------------------------------- +# 2. Decode → blueprint → MuJoCo MjSpec +# --------------------------------------------------------------------------- + +bp = spherical_angular_to_blueprint(genome, propsize=args.prop_size) + +drone_spec = blueprint_to_mjspec( + bp, + max_thrust=args.max_thrust, + body_name="quad", +) + +out_path = Path(args.out) +out_path.parent.mkdir(parents=True, exist_ok=True) +bp_path = out_path.with_suffix(".json") +bp.save_json(bp_path) +print("=" * 70) +print(f"Blueprint: {bp_path}") +print(bp.summary()) + + +# --------------------------------------------------------------------------- +# 3. Spawn into a flat world and compile +# --------------------------------------------------------------------------- + +world = SimpleFlatWorld() +world.spawn( + drone_spec, + position=(0.0, 0.0, float(args.spawn_z)), + correct_collision_with_floor=False, # we *want* to start in mid-air +) + +model = world.spec.compile() +data = mujoco.MjData(model) + +print(f"\nCompiled model: nbody={model.nbody} nu={model.nu} " + f"total_mass={sum(model.body_mass):.3f} kg") +print(f"Actuators: {[mujoco.mj_id2name(model, mujoco.mjtObj.mjOBJ_ACTUATOR, i) for i in range(model.nu)]}") + + +# --------------------------------------------------------------------------- +# 4. Decide on a control level +# Hover thrust per motor = (total_mass * g) / (n_motors * max_thrust) +# --------------------------------------------------------------------------- + +total_mass = float(np.sum(model.body_mass)) +gravity_mag = abs(float(model.opt.gravity[2])) +n_motors = model.nu + +if args.thrust is None: + # Slightly above hover so the drone rises visibly during the video. + hover_ctrl = (total_mass * gravity_mag) / (n_motors * args.max_thrust) + hover_ctrl = float(np.clip(hover_ctrl * 1.08, 0.0, 1.0)) +else: + hover_ctrl = float(args.thrust) + +# Symmetric ctrl — any per-motor imbalance tilts the drone and crashes it +# under open-loop control. For tilted/asymmetric flight, plug in a Lee or +# PID controller (see example 12). +ctrl = np.full(n_motors, hover_ctrl, dtype=np.float64) +data.ctrl[:] = ctrl + +print(f"\nTotal mass: {total_mass:.4f} kg") +print(f"Gravity: {gravity_mag:.3f} m/s²") +print(f"Hover ctrl/motor (auto): {hover_ctrl:.4f}") +print(f"Final ctrl vector: {data.ctrl.tolist()}") + + +# --------------------------------------------------------------------------- +# 5. Roll the sim while writing a video +# A simple controller would loop here; for the demo we keep ctrl fixed +# and let video_renderer drive the step loop. +# --------------------------------------------------------------------------- + +# video_renderer resets data.time but not data.ctrl; we restore ctrl after +# each step by pre-seeding before render and re-applying inside the loop. +# The renderer in this repo doesn't take a step callback, so the simplest +# robust path is to inline a custom render loop: + +mujoco.mj_resetData(model, data) +data.ctrl[:] = ctrl + +if args.view: + # Interactive MuJoCo passive viewer — runs in real time, no MP4 written. + import time + import mujoco.viewer + + print("\nLaunching MuJoCo passive viewer (close window or Ctrl+C to exit) …") + with mujoco.viewer.launch_passive(model, data) as viewer: + sim_start = time.time() + while viewer.is_running() and data.time < args.duration: + step_start = time.time() + data.ctrl[:] = ctrl + mujoco.mj_step(model, data) + viewer.sync() + # Pace to wall-clock so the viewer runs at real time. + slack = model.opt.timestep - (time.time() - step_start) + if slack > 0: + time.sleep(slack) + print(f"Viewer closed at t={data.time:.2f}s " + f"(wall {time.time() - sim_start:.2f}s)") +else: + # Headless render → MP4. + recorder = VideoRecorder( + file_name=out_path.stem, + output_folder=out_path.parent, + width=640, + height=480, + fps=30, + ) + steps_per_frame = max( + 1, int(round(1.0 / (recorder.fps * model.opt.timestep))) + ) + with mujoco.Renderer(model, + width=recorder.width, + height=recorder.height) as renderer: + while data.time < args.duration: + for _ in range(steps_per_frame): + data.ctrl[:] = ctrl + mujoco.mj_step(model, data) + renderer.update_scene(data) + recorder.write(frame=renderer.render()) + recorder.release() + print(f"\nVideo: {out_path}") + +print(f"Final drone height: {data.qpos[2]:.3f} m") diff --git a/examples/d_drones/14_mujoco_lee_figure8.py b/examples/d_drones/14_mujoco_lee_figure8.py new file mode 100644 index 000000000..2eb25f973 --- /dev/null +++ b/examples/d_drones/14_mujoco_lee_figure8.py @@ -0,0 +1,309 @@ +"""Lee figure-8 flight of a blueprint drone, visualised in MuJoCo. + +Pipeline: + + spherical_angular genome + → spherical_angular_to_blueprint (decoder) + → DroneBlueprint (saved as JSON) + → blueprint_to_propellers (NED) + │ + ▼ + DroneInterface + LeeGeometricControl(orient="NED") + + Trajectory(figure8 gate config, B-spline) + │ + ▼ + record (t, pos_NED, quat_NED) over the full flight + │ + ▼ + convert NED → ENU (Z-flip) + │ + → blueprint_to_mjspec + │ + ▼ + MuJoCo: kinematic playback of the recorded flight + (mj_forward each frame; no physics integration since the + drone's pose is being driven from the recorded trajectory) + │ + ▼ + MP4 / passive viewer + +Why kinematic playback instead of closed-loop in MuJoCo? +- The validated Lee path in this repo is NED; the ENU branch in + `_wrench_to_motor_commands` has a sign error in the thrust + allocation that drives w_cmd to the motor floor. Until that's + patched upstream, the cleanest demo is to run the validated NED + controller in the Python simulator and visualise the result in + MuJoCo. The blueprint still drives both backends end-to-end — + ``blueprint_to_propellers`` feeds the Python sim, and + ``blueprint_to_mjspec`` produces the visual model. + +Run: + uv run examples/d_drones/14_mujoco_lee_figure8.py + uv run examples/d_drones/14_mujoco_lee_figure8.py --view --time 12 + uv run examples/d_drones/14_mujoco_lee_figure8.py --altitude 2 --time 20 +""" +from __future__ import annotations + +import argparse +import copy +import os +import time as _time +from pathlib import Path + +import numpy as np +import mujoco + +os.environ.setdefault("OMP_NUM_THREADS", "1") + +from ariel.body_phenotypes.drone.decoders import spherical_angular_to_blueprint +from ariel.body_phenotypes.drone.backends import ( + blueprint_to_mjspec, blueprint_to_propellers, +) +from ariel.simulation.environments import SimpleFlatWorld +from ariel.simulation.drone.drone_interface import DroneInterface +from ariel.simulation.drone.controllers.lee_control.lee_controller import ( + LeeGeometricControl, +) +from ariel.simulation.drone.controllers.trajectory_generation.trajectory import ( + Trajectory, +) +from ariel.simulation.drone.controllers.utils.gate_configs import GATE_CONFIGS +from ariel.simulation.drone.controllers.utils.wind_model import Wind +from ariel.utils.video_recorder import VideoRecorder + + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +parser = argparse.ArgumentParser( + description="Fly a blueprint-derived drone through a figure-8 in MuJoCo" +) +parser.add_argument("--arm-len", type=float, default=0.06, + help="Arm length in metres (default 0.06)") +parser.add_argument("--prop-size", type=int, default=2, + help="Propeller size in inches (default 2)") +parser.add_argument("--altitude", type=float, default=1.5, + help="Figure-8 flight altitude in metres (default 1.5)") +parser.add_argument("--time", type=float, default=15.0, + help="Simulation duration in seconds (default 15)") +parser.add_argument("--dt", type=float, default=0.005, + help="Controller dt (default 0.005, matches example 3)") +parser.add_argument("--pos-gain", type=float, default=14.3) +parser.add_argument("--vel-gain", type=float, default=9.0) +parser.add_argument("--view", action="store_true", + help="Launch passive viewer instead of writing video") +parser.add_argument("--out", + default="__data__/blueprint_demo/mujoco_figure8.mp4") +args = parser.parse_args() + + +# --------------------------------------------------------------------------- +# 1. Genome → DroneBlueprint +# --------------------------------------------------------------------------- + +mag = float(args.arm_len) +genome = np.array([ + [mag, np.pi / 4, 0.0, 0.0, 0.0, 0], + [mag, 3 * np.pi / 4, 0.0, 0.0, 0.0, 1], + [mag, -3 * np.pi / 4, 0.0, 0.0, 0.0, 0], + [mag, -np.pi / 4, 0.0, 0.0, 0.0, 1], +]) +bp = spherical_angular_to_blueprint(genome, propsize=args.prop_size) + +out_path = Path(args.out) +out_path.parent.mkdir(parents=True, exist_ok=True) +bp.save_json(out_path.with_suffix(".json")) + + +# --------------------------------------------------------------------------- +# 2. Blueprint → DroneInterface (NED) + Lee + figure-8 trajectory +# --------------------------------------------------------------------------- + +propellers = blueprint_to_propellers(bp, convention="ned") +quad = DroneInterface(0, propellers=propellers) +wind = Wind("None") + +ctrl = LeeGeometricControl( + quad, + yawType=1, + orient="NED", + auto_scale_gains=True, + pos_P_gain=np.array([args.pos_gain] * 3), + vel_P_gain=np.array([args.vel_gain] * 3), +) + +# Figure-8 gates at the chosen altitude. In NED, "up" is negative Z, so we +# flip the sign of the altitude when placing the gates. +gate_config = copy.deepcopy(GATE_CONFIGS["figure8"]) +gate_config.gate_pos = gate_config.gate_pos.copy() +gate_config.gate_pos[:, 2] = -float(args.altitude) +gate_config.starting_pos = gate_config.starting_pos.copy() +gate_config.starting_pos[2] = -float(args.altitude) + +traj = Trajectory(quad, "xyz_pos", np.array([15, 3, 1]), + gate_config=gate_config) + + +# --------------------------------------------------------------------------- +# 3. Seed initial state at the trajectory start +# --------------------------------------------------------------------------- + +start_pos, _, _ = traj.bspline_trajectory.evaluate(0.0) +_, vel_050, _ = traj.bspline_trajectory.evaluate(0.05) +initial_yaw = float(np.arctan2(vel_050[1], vel_050[0])) \ + if np.linalg.norm(vel_050[:2]) > 1e-3 else float(gate_config.gate_yaw[0]) + +quad.drone_sim.set_state( + position=np.array(start_pos), + velocity=np.zeros(3), + attitude=np.array([0.0, 0.0, initial_yaw]), + angular_velocity=np.zeros(3), +) +quad._update_state_variables() +sDes = traj.desiredState(0.0, args.dt, quad) +ctrl.controller(sDes, quad, traj.ctrlType, args.dt) + + +# --------------------------------------------------------------------------- +# 4. Run the Python simulation in NED — record (pos, quat) per step +# --------------------------------------------------------------------------- + +Ts = float(args.dt) +Tf = float(args.time) +num_steps = int(Tf / Ts) + 1 + +t_log = np.zeros(num_steps) +pos_log = np.zeros((num_steps, 3)) +quat_log = np.zeros((num_steps, 4)) # quad.quat is (w, x, y, z) here + +print(f"\nRunning Python NED sim for {Tf}s @ dt={Ts}s …") +t0 = _time.time() +i = 0 +t = 0.0 +while i < num_steps and t < Tf: + t_log[i] = t + pos_log[i] = quad.pos + quat_log[i] = quad.quat + + quad.update(t, Ts, ctrl.w_cmd, wind) + t = Ts * (i + 1) + sDes = traj.desiredState(t, Ts, quad) + ctrl.controller(sDes, quad, traj.ctrlType, Ts) + i += 1 + +t_log = t_log[:i]; pos_log = pos_log[:i]; quat_log = quat_log[:i] +print(f" recorded {i} steps in {_time.time() - t0:.2f}s wall-clock") +print(f" altitude range (NED z): " + f"min={pos_log[:, 2].min():.2f} max={pos_log[:, 2].max():.2f}") + + +# --------------------------------------------------------------------------- +# 5. NED → ENU conversion for MuJoCo playback (Z-flip on pos; rotate attitude +# 180° about the body's X axis so body +Z points up in ENU instead of +# down in NED). +# --------------------------------------------------------------------------- + +pos_enu = pos_log.copy() +pos_enu[:, 2] = -pos_enu[:, 2] + +# NED→ENU attitude: world basis change M = diag(1, 1, -1). The body's +# rotation matrix in ENU is M @ R_ned @ M (M is involutory). At the +# quaternion level this corresponds to negating the y component of the +# quaternion (q_x stays, q_y flips sign, q_z stays, q_w stays) — derived by +# direct matrix-to-quaternion algebra for this specific M. +quat_enu = quat_log.copy() +quat_enu[:, 2] = -quat_enu[:, 2] # flip the y (= qy) component + + +# --------------------------------------------------------------------------- +# 6. Build the MuJoCo model from the blueprint and prepare playback +# --------------------------------------------------------------------------- + +# Mass-match MuJoCo body to DroneInterface so the model "weighs" what Lee +# planned for (useful even in kinematic playback for any visual indicators +# that depend on inertia). +target_mass = float(quad.params["mB"]) +n_arms = sum(1 for _ in bp.children(bp.root_id)) # type: ignore[arg-type] +motor_mass_each = float(quad.drone_sim.config.propellers[0]["mass"]) +arm_mass_each = 0.034 * mag # BEAM_DENSITY × length, matches DroneConfiguration +core_mass = max(1e-4, target_mass - n_arms * (motor_mass_each + arm_mass_each)) + +drone_spec = blueprint_to_mjspec( + bp, + motor_mass=motor_mass_each, + arm_mass=arm_mass_each, + core_mass_override=core_mass, + body_name="quad", +) +world = SimpleFlatWorld() +world.spawn( + drone_spec, + position=(float(pos_enu[0, 0]), float(pos_enu[0, 1]), float(pos_enu[0, 2])), + correct_collision_with_floor=False, +) +model = world.spec.compile() +data = mujoco.MjData(model) +model.opt.timestep = Ts + + +def set_pose(idx: int) -> None: + """Write the idx-th recorded (pos, quat) into MuJoCo's freejoint qpos.""" + p = pos_enu[idx] + q = quat_enu[idx] + data.qpos[0] = float(p[0]) + data.qpos[1] = float(p[1]) + data.qpos[2] = float(p[2]) + data.qpos[3] = float(q[0]) # w + data.qpos[4] = float(q[1]) # x + data.qpos[5] = float(q[2]) # y (already sign-flipped) + data.qpos[6] = float(q[3]) # z + data.qvel[:] = 0.0 + mujoco.mj_forward(model, data) + + +# --------------------------------------------------------------------------- +# 7. Playback: viewer or MP4 +# --------------------------------------------------------------------------- + +if args.view: + import mujoco.viewer + + print("\nLaunching MuJoCo passive viewer …") + set_pose(0) + with mujoco.viewer.launch_passive(model, data) as viewer: + sim_start = _time.time() + idx = 0 + while viewer.is_running() and idx < len(t_log): + step_start = _time.time() + set_pose(idx) + viewer.sync() + slack = Ts - (_time.time() - step_start) + if slack > 0: + _time.sleep(slack) + idx += 1 + print(f"Viewer done at t={t_log[min(idx, len(t_log)-1)]:.2f}s " + f"(wall {_time.time() - sim_start:.2f}s)") +else: + recorder = VideoRecorder( + file_name=out_path.stem, + output_folder=out_path.parent, + width=720, + height=540, + fps=30, + ) + steps_per_frame = max(1, int(round(1.0 / (recorder.fps * Ts)))) + print(f"\nRendering {len(t_log)} sim steps " + f"({steps_per_frame} steps/frame) → MP4 …") + t0 = _time.time() + with mujoco.Renderer(model, width=recorder.width, + height=recorder.height) as renderer: + for idx in range(0, len(t_log), steps_per_frame): + set_pose(idx) + renderer.update_scene(data) + recorder.write(frame=renderer.render()) + recorder.release() + print(f" rendered in {_time.time() - t0:.2f}s wall-clock") + print(f"\nVideo: {out_path}") + +print(f"Final position (ENU): {pos_enu[-1].tolist()}") diff --git a/examples/d_drones/15_cppn_neat_circle_to_mujoco.py b/examples/d_drones/15_cppn_neat_circle_to_mujoco.py new file mode 100644 index 000000000..afa8eec34 --- /dev/null +++ b/examples/d_drones/15_cppn_neat_circle_to_mujoco.py @@ -0,0 +1,336 @@ +"""Evolve a drone morphology with CPPN-NEAT, then fly it through a circle in MuJoCo. + +Pipeline: + + CPPNNeatDroneGenomeHandler population + → evolve_neat (speciated NEAT with edit_distance fitness) + → best CPPN.get_phenotype() → (max_narms, 6) spherical-angular array + → spherical_angular_to_blueprint (decoder) + → DroneBlueprint (saved as JSON) + → blueprint_to_propellers + blueprint_to_mjspec (two backends) + → Python-sim Lee controller (NED) flies circle gates + → kinematic playback in MuJoCo (MP4 / passive viewer) + +The fitness for evolution is ``edit_distance`` — fast and self-contained +(``edit_distance`` would be a better proxy but pulls in the ``dronehover`` +package which isn't on PyPI). It biases toward morphologies close to the +standard hexacopter shape; the "circle task" is then exercised in the +MuJoCo rollout stage on the evolved best individual. + +Run: + uv run examples/d_drones/15_cppn_neat_circle_to_mujoco.py + uv run examples/d_drones/15_cppn_neat_circle_to_mujoco.py --pop 16 --gens 12 --view + uv run examples/d_drones/15_cppn_neat_circle_to_mujoco.py --rollout-time 10 --altitude 1.5 +""" +from __future__ import annotations + +import argparse +import copy +import os +import time as _time +from pathlib import Path + +import numpy as np +import mujoco +from rich.console import Console + +os.environ.setdefault("OMP_NUM_THREADS", "1") +os.environ.setdefault("OPENBLAS_NUM_THREADS", "1") +os.environ.setdefault("MKL_NUM_THREADS", "1") + +# Evolution side +from ariel.ec.drone.genome_handlers.cppn_neat_genome_handler import ( + CPPNNeatDroneGenomeHandler, +) +from ariel.ec.drone.evaluators.unified_fitness import UnifiedFitness +from ariel.ec.drone.selectors.tournament import tournament_selection +from ariel.ec.drone.strategies import evolve_neat + +# Blueprint side +from ariel.body_phenotypes.drone.decoders import spherical_angular_to_blueprint +from ariel.body_phenotypes.drone.backends import ( + blueprint_to_mjspec, blueprint_to_propellers, +) + +# Simulation side +from ariel.simulation.environments import SimpleFlatWorld +from ariel.simulation.drone.drone_interface import DroneInterface +from ariel.simulation.drone.controllers.lee_control.lee_controller import ( + LeeGeometricControl, +) +from ariel.simulation.drone.controllers.trajectory_generation.trajectory import ( + Trajectory, +) +from ariel.simulation.drone.controllers.utils.gate_configs import GATE_CONFIGS +from ariel.simulation.drone.controllers.utils.wind_model import Wind +from ariel.utils.video_recorder import VideoRecorder + + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +console = Console() +parser = argparse.ArgumentParser( + description="CPPN-NEAT → Blueprint → MuJoCo circle rollout" +) +# evolution params +parser.add_argument("--pop", type=int, default=12, + help="Population size (default 12, small for demo speed)") +parser.add_argument("--gens", type=int, default=8, + help="Number of NEAT generations (default 8)") +parser.add_argument("--workers", type=int, default=1) +parser.add_argument("--min-arms", type=int, default=4) +parser.add_argument("--max-arms", type=int, default=6) +parser.add_argument("--num-segments", type=int, default=8, + help="CPPN sampling resolution (max_narms = arm slots)") +parser.add_argument("--seed", type=int, default=42) +# rollout params +parser.add_argument("--altitude", type=float, default=1.5, + help="Circle altitude in metres") +parser.add_argument("--rollout-time", type=float, default=12.0, + help="MuJoCo rollout duration in seconds") +parser.add_argument("--dt", type=float, default=0.005) +parser.add_argument("--prop-size", type=int, default=2, + help="Propeller inches used by Lee + MuJoCo") +# output +parser.add_argument("--view", action="store_true", + help="Launch passive viewer instead of writing MP4") +parser.add_argument("--out-dir", default="__data__/blueprint_demo/cppn_neat_circle") +args = parser.parse_args() + +np.random.seed(args.seed) +out_dir = Path(args.out_dir) +out_dir.mkdir(parents=True, exist_ok=True) + + +# --------------------------------------------------------------------------- +# 1. Evolve a CPPN-NEAT population (fitness: edit_distance) +# --------------------------------------------------------------------------- + +PARAMETER_LIMITS = np.array([ + [0.055, 0.17], + [-np.pi, np.pi], + [-np.pi / 2, np.pi / 2], + [-np.pi, np.pi], + [-np.pi, np.pi], + [0, 1], +]) + +fitness_fn = UnifiedFitness( + brain=None, + fitness_mode="edit_distance", + hover_gradient=False, + per_individual_repair=False, + is_indirect=True, # CPPN-NEAT is indirect + handler_class=CPPNNeatDroneGenomeHandler, + handler_kwargs={ + "num_segments": args.num_segments, + "min_max_narms": (args.min_arms, args.max_arms), + "parameter_limits": PARAMETER_LIMITS, + "repair": True, + }, + coordinate_system="spherical", +) + +console.rule("[bold blue]CPPN-NEAT evolution") +console.log(f"pop={args.pop} gens={args.gens} fitness=edit_distance") + +t_evo = _time.time() +all_individuals = evolve_neat( + fitness_function=fitness_fn, + population_size=args.pop, + num_generations=args.gens, + crossover_rate=0.75, + parent_selection=tournament_selection, + genome_handler=CPPNNeatDroneGenomeHandler, + num_workers=args.workers, + compatibility_threshold=3.0, + target_species_count=3, + log_dir=str(out_dir / "logs"), + verbose=False, +) +console.log(f"Evolution done in {_time.time() - t_evo:.1f}s — " + f"{len(all_individuals)} individuals evaluated") + + +# --------------------------------------------------------------------------- +# 2. Pick the best individual (last generation, highest fitness) +# --------------------------------------------------------------------------- + +last_gen = int(all_individuals["generation"].max()) +last_df = all_individuals[all_individuals["generation"] == last_gen] +best_row = last_df.sort_values("fitness", ascending=False).iloc[0] +best_cppn = best_row["genome"] + +# Decode CPPN → spherical-angular phenotype array (max_narms, 6) +handler = CPPNNeatDroneGenomeHandler( + genome=best_cppn, + num_segments=args.num_segments, + min_max_narms=(args.min_arms, args.max_arms), + parameter_limits=PARAMETER_LIMITS, +) +phenotype = handler.get_phenotype() +n_active = int((~np.isnan(phenotype[:, 0])).sum()) +console.log(f"Best (gen {last_gen}, id={best_row['id']}): " + f"fitness={best_row['fitness']:.4f} active_arms={n_active}") +np.save(out_dir / "best_phenotype.npy", phenotype) + + +# --------------------------------------------------------------------------- +# 3. Spherical-angular array → DroneBlueprint +# --------------------------------------------------------------------------- + +bp = spherical_angular_to_blueprint(phenotype, propsize=args.prop_size) +bp_path = out_dir / "best_blueprint.json" +bp.save_json(bp_path) +console.log(f"Blueprint saved → {bp_path}") + + +# --------------------------------------------------------------------------- +# 4. Blueprint → DroneInterface (NED) + Lee + circle trajectory +# (Lee's NED path is the validated one; we replay it in MuJoCo afterwards.) +# --------------------------------------------------------------------------- + +propellers = blueprint_to_propellers(bp, convention="ned") +quad = DroneInterface(0, propellers=propellers) +wind = Wind("None") + +ctrl = LeeGeometricControl( + quad, yawType=1, orient="NED", auto_scale_gains=True, + pos_P_gain=np.array([14.3, 14.3, 14.3]), + vel_P_gain=np.array([9.0, 9.0, 9.0]), +) + +gate_config = copy.deepcopy(GATE_CONFIGS["circle"]) +gate_config.gate_pos = gate_config.gate_pos.copy() +gate_config.gate_pos[:, 2] = -float(args.altitude) # NED: up = -z +gate_config.starting_pos = gate_config.starting_pos.copy() +gate_config.starting_pos[2] = -float(args.altitude) + +traj = Trajectory(quad, "xyz_pos", np.array([15, 3, 1]), + gate_config=gate_config) + +start_pos, _, _ = traj.bspline_trajectory.evaluate(0.0) +_, vel_050, _ = traj.bspline_trajectory.evaluate(0.05) +initial_yaw = float(np.arctan2(vel_050[1], vel_050[0])) \ + if np.linalg.norm(vel_050[:2]) > 1e-3 else float(gate_config.gate_yaw[0]) + +quad.drone_sim.set_state( + position=np.array(start_pos), + velocity=np.zeros(3), + attitude=np.array([0.0, 0.0, initial_yaw]), + angular_velocity=np.zeros(3), +) +quad._update_state_variables() +sDes = traj.desiredState(0.0, args.dt, quad) +ctrl.controller(sDes, quad, traj.ctrlType, args.dt) + + +# --------------------------------------------------------------------------- +# 5. Roll out the Python NED sim, recording pose per step +# --------------------------------------------------------------------------- + +Ts = float(args.dt) +Tf = float(args.rollout_time) +N = int(Tf / Ts) + 1 +pos_log = np.zeros((N, 3)) +quat_log = np.zeros((N, 4)) + +console.rule("[bold blue]Lee circle rollout (Python NED)") +i, t = 0, 0.0 +t0 = _time.time() +while i < N and t < Tf: + pos_log[i] = quad.pos + quat_log[i] = quad.quat + quad.update(t, Ts, ctrl.w_cmd, wind) + t = Ts * (i + 1) + sDes = traj.desiredState(t, Ts, quad) + ctrl.controller(sDes, quad, traj.ctrlType, Ts) + i += 1 +pos_log = pos_log[:i]; quat_log = quat_log[:i] +console.log(f" {i} steps in {_time.time() - t0:.2f}s " + f"alt range (NED z): [{pos_log[:,2].min():.2f}, {pos_log[:,2].max():.2f}]") + +# NED→ENU +pos_enu = pos_log.copy(); pos_enu[:, 2] = -pos_enu[:, 2] +quat_enu = quat_log.copy(); quat_enu[:, 2] = -quat_enu[:, 2] + + +# --------------------------------------------------------------------------- +# 6. Build the MuJoCo body from the same blueprint, mass-matched to Lee +# --------------------------------------------------------------------------- + +target_mass = float(quad.params["mB"]) +n_arms_bp = sum(1 for _ in bp.children(bp.root_id)) # type: ignore[arg-type] +motor_mass_each = float(quad.drone_sim.config.propellers[0]["mass"]) +# Average arm length (over the active arms) — used for the beam mass. +arm_lengths = [bp.payload(a).length for a in bp.children(bp.root_id)] # type: ignore[arg-type] +mean_arm_len = float(np.mean(arm_lengths)) if arm_lengths else 0.06 +arm_mass_each = 0.034 * mean_arm_len +core_mass = max(1e-4, target_mass - n_arms_bp * (motor_mass_each + arm_mass_each)) + +drone_spec = blueprint_to_mjspec( + bp, + motor_mass=motor_mass_each, + arm_mass=arm_mass_each, + core_mass_override=core_mass, + body_name="evolved_quad", +) +world = SimpleFlatWorld() +world.spawn( + drone_spec, + position=(float(pos_enu[0, 0]), float(pos_enu[0, 1]), float(pos_enu[0, 2])), + correct_collision_with_floor=False, +) +model = world.spec.compile() +data = mujoco.MjData(model) +model.opt.timestep = Ts + + +def set_pose(idx: int) -> None: + p = pos_enu[idx]; q = quat_enu[idx] + data.qpos[0:3] = [float(p[0]), float(p[1]), float(p[2])] + data.qpos[3:7] = [float(q[0]), float(q[1]), float(q[2]), float(q[3])] + data.qvel[:] = 0.0 + mujoco.mj_forward(model, data) + + +# --------------------------------------------------------------------------- +# 7. Render (passive viewer or MP4) +# --------------------------------------------------------------------------- + +console.rule("[bold blue]MuJoCo playback") +if args.view: + import mujoco.viewer + console.log("Launching MuJoCo passive viewer …") + set_pose(0) + with mujoco.viewer.launch_passive(model, data) as viewer: + idx = 0 + sim_start = _time.time() + while viewer.is_running() and idx < len(pos_enu): + step_start = _time.time() + set_pose(idx) + viewer.sync() + slack = Ts - (_time.time() - step_start) + if slack > 0: + _time.sleep(slack) + idx += 1 + console.log(f"Viewer done (wall {_time.time() - sim_start:.2f}s)") +else: + mp4 = out_dir / "circle_flight.mp4" + recorder = VideoRecorder(file_name=mp4.stem, output_folder=mp4.parent, + width=720, height=540, fps=30) + steps_per_frame = max(1, int(round(1.0 / (recorder.fps * Ts)))) + t0 = _time.time() + with mujoco.Renderer(model, width=recorder.width, + height=recorder.height) as renderer: + for idx in range(0, len(pos_enu), steps_per_frame): + set_pose(idx) + renderer.update_scene(data) + recorder.write(frame=renderer.render()) + recorder.release() + console.log(f"Rendered in {_time.time() - t0:.2f}s") + console.log(f"[bold green]Video: {mp4}") + +console.log(f"Final pos (ENU): {pos_enu[-1].round(3).tolist()}") diff --git a/examples/d_drones/3_simulate_lee.py b/examples/d_drones/3_simulate_lee.py index 001ba9a89..7704fa9e3 100644 --- a/examples/d_drones/3_simulate_lee.py +++ b/examples/d_drones/3_simulate_lee.py @@ -227,10 +227,14 @@ # --------------------------------------------------------------------------- if not args.no_viz: + import matplotlib.pyplot as plt + waypoints = np.array(gate_config.gate_pos, dtype=float) save_path = str(Path.cwd() / "__data__" / "lee_simulation.mp4") if args.save else None - ctrl_utils.sameAxisAnimation( + # Keep a reference to the FuncAnimation — matplotlib will garbage-collect + # it otherwise and the figure renders empty. + anim = ctrl_utils.sameAxisAnimation( t_all, waypoints, pos_all, quat_all, sDes_traj_all, Ts, quad.params, 15, 3, int(args.save), "NED", gate_pos=np.array(gate_config.gate_pos), @@ -241,3 +245,5 @@ if save_path: print(f"Animation saved to: {save_path}") + else: + plt.show() diff --git a/examples/d_drones/4_tune_lee_controller.py b/examples/d_drones/4_tune_lee_controller.py index 0252d2265..ec90573d7 100644 --- a/examples/d_drones/4_tune_lee_controller.py +++ b/examples/d_drones/4_tune_lee_controller.py @@ -306,6 +306,7 @@ def run_optimization(self, max_evaluations: int = 200, ig = np.array(cfg["initial_guess"], dtype=float) bounds_lo = [b[0] for b in cfg["bounds"]] bounds_hi = [b[1] for b in cfg["bounds"]] + ig = np.clip(ig, bounds_lo, bounds_hi) options = { "maxfevals": max_evaluations, @@ -315,6 +316,7 @@ def run_optimization(self, max_evaluations: int = 200, "tolfun": 1e-4, } + es = None t0 = time.time() try: es = cma.CMAEvolutionStrategy(ig, cfg["initial_std"], options) @@ -331,8 +333,9 @@ def run_optimization(self, max_evaluations: int = 200, print("\nInterrupted — saving current best …") finally: elapsed = time.time() - t0 + evals = es.result.evaluations if es is not None else 0 print(f"\nStage {self.stage} done in {elapsed / 60:.1f} min " - f"({es.result.evaluations} evals) best={self.best_score:.3f}") + f"({evals} evals) best={self.best_score:.3f}") self._save_results() def _save_results(self) -> None: diff --git a/examples/d_drones/5_visualize_best_drone.py b/examples/d_drones/5_visualize_best_drone.py index fb3ad165f..637c0db85 100644 --- a/examples/d_drones/5_visualize_best_drone.py +++ b/examples/d_drones/5_visualize_best_drone.py @@ -59,7 +59,7 @@ parser.add_argument( "--individual-id", type=str, - default="0600", + default="5001", help="Specific individual ID to visualize (default: 0600)", ) parser.add_argument( diff --git a/request_context.txt b/request_context.txt new file mode 100644 index 000000000..41b7d18ed --- /dev/null +++ b/request_context.txt @@ -0,0 +1,35 @@ +This is the backstory and a bit of context: + + +I am a developer of the ariel codebase that was initially created for evolving modular robots with cubes attached to each other by hinges that can be actuated by the robot's controller, i.e. brain this results in a coupling of morphology and controller with both having separate genotypes and their combination being the actual moving robot that can be fitness evaluated the phenotype. This by itself is not all that new, it is a basic evolutionary robotics system that allows for multiple genotypes to be used, however what our improvement really is is that we coin the term “Blueprint” which is described in the attached paper in detail. + +New project: + +Now I’m working on a “drone morphology evolution with controllers generated by reinforcement learning” EU project that is a collaboration between multiple universities. Many research teams use different genotypes to encode their drones and they also don’t always use the same simulation software either, leading to less opportunities for collaboration and idea flow. To address this I want to propose ARIEL to be a common base for this research project. + +Current standing: + +I have integrated Jed Muff’s drone evolution code into ARIEL, however as of now it does not really follow the essential blueprint concept that is the real benefit of ARIEL. The reason is twofold, firstly I haven’t had that much time and secondly I want to create a blueprint that encodes the drones in their morphological space close enough to the simulation software that it’s universal enough to easily translate into a phenotype “out-of-the-box”. The research community would eventually like to converge on using Isaac Lab as the main simulation software for the drones. + +Email thread context: + +We have a new idea for a VUA contribution for the integration event. Aron who joined the SPEAR project recently @VUA, has been working on integrating Jed's drone evolution platform airevolve to VUA's advanced robot evolution and robot learning platform ARIEL (https://github.com/ci-group/ariel/blob/main/README.md). He is just finishing his debugging. + + +Aron is up to date with Jed's code and has been working toward porting his code to work on the MuJoCo-based simulator. ARIEL is designed to facilitate switching simulators (albeit not completely hot-swappable). It may be interesting in the meeting to have an option to try out Ariel as a potential alternative to Isaac Lab-based Aerial Gym or sharing information about Aron's work. With his availability in the meeting, we can get guidance from him directly. ARIEL has never been connected to Isaac Lab. So, this is something to be tried out in the integration meeting or later on. Let me know what you think. +—--------------------------------- +Thank you. It will be interesting to learn about Arial and see if it could be used in the integration event. + + +We could have a meeting this Friday or next Monday to learn more. I am open in the second half in these days. Please let me know your availability. +—--------------------------------- +There is a SPEAR Dissemination meeting arranged by KEMEA from 10:30-11:30 tomorrow. Some of us may be attending it. + + +How about 9:30-10:30 tomorrow, if everyone agrees with it? I will share a calendar invite, just to make an entry. Please feel free to move it, if needed. + +→ Today is Thursday so the first pre-meeting is tomorrow. + +Request: + +Parse through all the folders that have to do with modular robot evolution and drone evolution and create a plan to maximize the utility the ARIEL platform can provide for this project. \ No newline at end of file diff --git a/src/ariel/body_phenotypes/drone/backends.py b/src/ariel/body_phenotypes/drone/backends.py new file mode 100644 index 000000000..b0d4e294b --- /dev/null +++ b/src/ariel/body_phenotypes/drone/backends.py @@ -0,0 +1,295 @@ +"""DroneBlueprint → phenotype backends. + +Each backend consumes a DroneBlueprint and emits something a simulator (or +the real world) can instantiate. v1 ships: + + * ``blueprint_to_propellers`` — list[dict] consumable by + ``ariel.simulation.drone.DroneSimulator`` / ``DroneConfiguration``. + * ``blueprint_to_mjspec`` — MuJoCo ``mjSpec`` (compiles to MJCF / + ``MjModel``); the same blueprint can drive both the Python physics + stack and a full MuJoCo simulation. + +Stubs sketched for future backends: + + * ``blueprint_to_usd`` — USD prim hierarchy for Isaac Lab +""" +from __future__ import annotations + +import math +from typing import Any, TYPE_CHECKING + +import numpy as np + +from .blueprint import DroneBlueprint, ArmNode, MotorNode, RotorNode, CorePlateNode + +if TYPE_CHECKING: + import mujoco + + +def _rpy_to_R(roll: float, pitch: float, yaw: float) -> np.ndarray: + cr, sr = math.cos(roll), math.sin(roll) + cp, sp = math.cos(pitch), math.sin(pitch) + cy, sy = math.cos(yaw), math.sin(yaw) + Rz = np.array([[cy, -sy, 0], [sy, cy, 0], [0, 0, 1]]) + Ry = np.array([[cp, 0, sp], [0, 1, 0], [-sp, 0, cp]]) + Rx = np.array([[1, 0, 0], [0, cr, -sr], [0, sr, cr]]) + return Rz @ Ry @ Rx + + +def blueprint_to_propellers( + bp: DroneBlueprint, + *, + convention: str = "z_up", +) -> list[dict[str, Any]]: + """Flatten the blueprint tree to the propellers-list format consumed by + ``DroneSimulator(propellers=...)``. + + Args: + bp: the DroneBlueprint to flatten. + convention: ``"z_up"`` (default, mathematical / +Z is sky) or + ``"ned"`` (used by ``DroneSimulator`` / Lee controller, +Z is + ground). When ``"ned"``, the position Z and thrust-normal Z + components are inverted. + + Each entry: + {"loc": [x, y, z], # position of motor + "dir": [nx, ny, nz, "ccw"|"cw"], # thrust normal + spin + "propsize": int} # inches + """ + if convention not in {"z_up", "ned"}: + raise ValueError(f"convention must be 'z_up' or 'ned', got {convention!r}") + z_sign = -1.0 if convention == "ned" else 1.0 + propellers: list[dict[str, Any]] = [] + + # Core-relative pose; we descend Arm → Motor → Rotor and accumulate the + # transform of each Arm (anchored at the core), then the Motor on top. + for arm_id in bp.children(bp.root_id): # type: ignore[arg-type] + arm = bp.payload(arm_id) + if not isinstance(arm, ArmNode): + continue + R_arm = _rpy_to_R(*arm.pose.rpy) + arm_origin = np.array(arm.pose.xyz) + + for motor_id in bp.children(arm_id): + motor = bp.payload(motor_id) + if not isinstance(motor, MotorNode): + continue + # Motor offset along the arm's local +X by `length`, plus its own + # local offset; pose was authored with xyz=(length,0,0) already. + motor_world = arm_origin + R_arm @ np.array(motor.pose.xyz) + R_motor = R_arm @ _rpy_to_R(*motor.pose.rpy) + # Thrust direction = motor's local +Z in world frame. + # (NED convention used by DroneSimulator: thrust normal points in + # the rotor's spin-axis direction; sign is handled by DroneConfig.) + thrust_normal = R_motor @ np.array([0.0, 0.0, 1.0]) + + propellers.append({ + "loc": [ + float(motor_world[0]), + float(motor_world[1]), + float(motor_world[2]) * z_sign, + ], + "dir": [ + float(thrust_normal[0]), + float(thrust_normal[1]), + float(thrust_normal[2]) * z_sign, + motor.spin, + ], + "propsize": int(motor.propsize), + }) + + # (Rotor geometry is currently absorbed into propsize lookup; an + # MJCF/USD backend would consume the RotorNode separately.) + for _rotor_id in bp.children(motor_id): + rotor = bp.payload(_rotor_id) + assert isinstance(rotor, RotorNode) # type-only + + return propellers + + +# ---------- MuJoCo backend (blueprint → mjSpec) ---------- + +def blueprint_to_mjspec( + bp: DroneBlueprint, + *, + motor_mass: float = 0.05, + arm_mass: float = 0.01, + core_mass_override: float | None = None, + arm_radius: float = 0.005, + motor_radius: float = 0.015, + motor_thickness: float = 0.008, + max_thrust: float = 5.0, + body_name: str = "drone", +) -> "mujoco.MjSpec": + """Compile a DroneBlueprint into a MuJoCo ``MjSpec`` describing a + free-flying drone with one site-attached thrust actuator per motor. + + Conventions: + * Z-up (the MuJoCo default). No NED inversion is performed here — + gravity points in -Z, thrust points along each motor site's local + +Z. Use this backend when integrating with the MuJoCo-native + stack (``SimpleFlatWorld``, ``video_renderer``), not the Lee + controller pipeline (which is NED). + * The root body has a freejoint so it can fly. + * Arms attach rigidly to the core (no joint between Arm and Core); + Motors attach rigidly to Arm tips. + * One actuator per Motor; ``ctrl`` ∈ [0, 1] maps linearly to thrust + in [0, ``max_thrust``] Newtons along the rotor's spin axis. + + Args: + bp: the blueprint to compile. + motor_mass: kg per motor+rotor assembly (lumped). + arm_radius: capsule radius for arm visuals (m). + motor_radius: cylinder radius for motor visuals (m). + motor_thickness: cylinder half-length for motor visuals (m). + max_thrust: maximum thrust per motor in Newtons. + body_name: root body name. + + Returns: + A ``mujoco.MjSpec`` containing only the drone (compile it directly + with ``spec.compile()`` for a standalone model, or hand to + ``BaseWorld.spawn()`` to drop it into a world). + """ + import mujoco # local — avoid hard dependency at import time + + spec = mujoco.MjSpec() + + core = bp.payload(bp.root_id) + if not isinstance(core, CorePlateNode): + raise ValueError("Blueprint root must be a CorePlateNode.") + + # --- root body --- + # Note: no freejoint here. ``BaseWorld.spawn()`` attaches the body and + # adds the freejoint itself. For standalone use, call ``add_freejoint()`` + # on the returned spec's root body before compiling. + root = spec.worldbody.add_body(name=body_name, pos=[0.0, 0.0, 0.0]) + core_mass = core_mass_override if core_mass_override is not None else core.mass + root.add_geom( + name=f"{body_name}_core", + type=mujoco.mjtGeom.mjGEOM_CYLINDER, + size=[core.radius, core.thickness / 2.0, 0.0], + mass=core_mass, + rgba=(0.2, 0.4, 0.8, 1.0), + ) + + # --- arms + motors --- + motor_index = 0 + for arm_id in bp.children(bp.root_id): # type: ignore[arg-type] + arm = bp.payload(arm_id) + if not isinstance(arm, ArmNode): + continue + arm_yaw = arm.pose.rpy[2] + arm_pitch = arm.pose.rpy[1] + + # Compute arm tip in core-local frame: rotate (length, 0, 0) by (-pitch, yaw) + # using ZYX intrinsic order matching how the decoder authored rpy. + cy, sy = math.cos(arm_yaw), math.sin(arm_yaw) + cp, sp = math.cos(arm_pitch), math.sin(arm_pitch) + tip_local = np.array([cp * cy * arm.length, + cp * sy * arm.length, + -sp * arm.length]) + + # Arm child body (rigid offset; no joint = welded to core) + arm_body = root.add_body( + name=f"{body_name}_arm_{arm_id}", + pos=[0.0, 0.0, 0.0], + ) + arm_body.add_geom( + type=mujoco.mjtGeom.mjGEOM_CAPSULE, + fromto=[0.0, 0.0, 0.0, *tip_local.tolist()], + size=[arm_radius, 0.0, 0.0], + mass=arm_mass, + rgba=(0.3, 0.3, 0.3, 1.0), + ) + + for motor_id in bp.children(arm_id): + motor = bp.payload(motor_id) + if not isinstance(motor, MotorNode): + continue + + # The motor's site frame: thrust axis is the site's local +Z. + # The decoder authored motor pose as (xyz=(length, 0, 0), rpy) + # in the arm's local frame, where the rpy encodes the relative + # thrust orientation; we want the world-frame thrust to point + # along world +Z (motor_pitch=0, motor_az=0 → straight up), so + # we leave the site's orientation matching the parent arm tip + # for the canonical zero-pitch case. + # + # To keep things robust for tilted thrusters, we compose the + # motor's rpy on top of the arm's orientation: + mr_roll, mr_pitch, mr_yaw = motor.pose.rpy + site_quat = _rpy_to_quat(mr_roll, + mr_pitch + arm_pitch, # cancel arm tilt + mr_yaw + arm_yaw) + + motor_body = arm_body.add_body( + name=f"{body_name}_motor_{motor_id}", + pos=tip_local.tolist(), + quat=site_quat, + ) + motor_body.add_geom( + type=mujoco.mjtGeom.mjGEOM_CYLINDER, + size=[motor_radius, motor_thickness, 0.0], + mass=motor_mass, + rgba=(1.0, 0.2, 0.2, 1.0) + if motor.spin == "cw" + else (0.2, 0.8, 0.2, 1.0), + ) + + # Rotor visualisation (thin disc above motor) + rotor_radius = 0.05 # default; updated if a RotorNode is present + for rotor_id in bp.children(motor_id): + rotor = bp.payload(rotor_id) + if isinstance(rotor, RotorNode): + rotor_radius = rotor.radius + motor_body.add_geom( + type=mujoco.mjtGeom.mjGEOM_CYLINDER, + pos=[0.0, 0.0, motor_thickness + 0.002], + size=[rotor_radius, 0.001, 0.0], + mass=0.0, + rgba=(0.8, 0.8, 0.8, 0.5), + ) + + # Thrust site (force applied along local +Z) + thrust_site = motor_body.add_site( + name=f"{body_name}_thrust_{motor_index}", + pos=[0.0, 0.0, motor_thickness], + size=[0.005, 0.005, 0.005], + ) + + spec.add_actuator( + name=f"{body_name}_motor_{motor_index}", + trntype=mujoco.mjtTrn.mjTRN_SITE, + target=thrust_site.name, + gear=[0.0, 0.0, max_thrust, 0.0, 0.0, 0.0], + ctrlrange=[0.0, 1.0], + ctrllimited=True, + ) + motor_index += 1 + + return spec + + +def _rpy_to_quat(roll: float, pitch: float, yaw: float) -> list[float]: + """ZYX intrinsic Euler → (w, x, y, z) quaternion (MuJoCo order).""" + cr, sr = math.cos(roll / 2), math.sin(roll / 2) + cp, sp = math.cos(pitch / 2), math.sin(pitch / 2) + cy, sy = math.cos(yaw / 2), math.sin(yaw / 2) + return [ + cr * cp * cy + sr * sp * sy, # w + sr * cp * cy - cr * sp * sy, # x + cr * sp * cy + sr * cp * sy, # y + cr * cp * sy - sr * sp * cy, # z + ] + + +# ---------- future backends (signatures only) ---------- + +def blueprint_to_usd(bp: DroneBlueprint, out_path: str) -> str: + """Compile a DroneBlueprint into a USD file for Isaac Lab. + + Not yet implemented — would emit a USD prim hierarchy (`Xform` per node, + `RigidBodyAPI` on links, `ArticulationRootAPI` on the core), so the + file can be loaded by ``isaaclab.sim.UsdFileCfg(usd_path=...)``. + """ + raise NotImplementedError("blueprint_to_usd is the consortium-deferred backend.") diff --git a/src/ariel/body_phenotypes/drone/blueprint.py b/src/ariel/body_phenotypes/drone/blueprint.py new file mode 100644 index 000000000..4b34a3d0f --- /dev/null +++ b/src/ariel/body_phenotypes/drone/blueprint.py @@ -0,0 +1,159 @@ +"""Drone Blueprint — ARIEL-native intermediate representation for drones. + +A typed tree (NetworkX DiGraph) carrying continuous SE(3) transforms and +physical parameters. Sits between any drone genotype and any phenotype +backend (MuJoCo propellers list, MJCF, USD/Isaac Lab, CAD/STL). + +Pipeline: + genome --decoder--> DroneBlueprint --backend--> phenotype +""" +from __future__ import annotations + +import json +from dataclasses import dataclass, asdict, field +from pathlib import Path +from typing import Any, Optional + +import networkx as nx + + +# ---------- node payloads ---------- + +@dataclass +class Pose: + """SE(3) pose relative to parent node. Translation in metres, rpy in radians.""" + xyz: tuple[float, float, float] = (0.0, 0.0, 0.0) + rpy: tuple[float, float, float] = (0.0, 0.0, 0.0) + + +@dataclass +class CorePlateNode: + type: str = "CorePlate" + mass: float = 0.4 + shape: str = "disc" # "disc" | "box" + radius: float = 0.05 # disc radius (m) + thickness: float = 0.01 # disc thickness (m) + + +@dataclass +class ArmNode: + type: str = "Arm" + length: float = 0.18 # m + pose: Pose = field(default_factory=Pose) # attachment frame on parent (CorePlate) + + +@dataclass +class MotorNode: + type: str = "Motor" + pose: Pose = field(default_factory=Pose) # pose on parent Arm tip + spin: str = "ccw" # "cw" | "ccw" + propsize: int = 5 # inches; looked up in propeller_data for kf/km + + +@dataclass +class RotorNode: + type: str = "Rotor" + radius: float = 0.0635 # m (5" prop ≈ 0.127 m diameter) + pitch: float = 0.045 # m + blades: int = 2 + + +@dataclass +class SensorNode: + type: str = "Sensor" + sensor_type: str = "imu" # "imu" | "camera" | "range" + pose: Pose = field(default_factory=Pose) + + +# ---------- blueprint container ---------- + +class DroneBlueprint: + """Tree of typed drone-component nodes, JSON-serialisable. + + Internally a NetworkX DiGraph; root is the unique CorePlate node. + Each node stores its dataclass payload under the `data` attribute. + """ + + def __init__(self) -> None: + self.g: nx.DiGraph = nx.DiGraph() + self._next_id: int = 0 + self.root_id: Optional[int] = None + + # ----- construction ----- + def add(self, payload: Any, parent: Optional[int] = None) -> int: + nid = self._next_id + self._next_id += 1 + self.g.add_node(nid, data=payload) + if parent is not None: + self.g.add_edge(parent, nid) + elif self.root_id is None: + if not isinstance(payload, CorePlateNode): + raise ValueError("First node added must be a CorePlateNode (root).") + self.root_id = nid + else: + raise ValueError("Blueprint already has a root; pass parent= for further nodes.") + return nid + + # ----- traversal helpers ----- + def nodes_of_type(self, type_name: str) -> list[int]: + return [n for n, d in self.g.nodes(data=True) if d["data"].type == type_name] + + def children(self, n: int) -> list[int]: + return list(self.g.successors(n)) + + def payload(self, n: int) -> Any: + return self.g.nodes[n]["data"] + + # ----- I/O ----- + def to_dict(self) -> dict: + # NetworkX node-link with dataclass payloads serialised inline + def encode(d: Any) -> dict: + return asdict(d) if hasattr(d, "__dataclass_fields__") else d + + return { + "root": self.root_id, + "nodes": [ + {"id": n, "data": encode(d["data"])} + for n, d in self.g.nodes(data=True) + ], + "edges": list(self.g.edges()), + } + + def save_json(self, path: Path | str) -> None: + Path(path).write_text(json.dumps(self.to_dict(), indent=2)) + + @classmethod + def from_dict(cls, d: dict) -> "DroneBlueprint": + bp = cls() + bp.root_id = d["root"] + type_map = { + "CorePlate": CorePlateNode, + "Arm": ArmNode, + "Motor": MotorNode, + "Rotor": RotorNode, + "Sensor": SensorNode, + } + for entry in d["nodes"]: + data = dict(entry["data"]) + cls_ = type_map[data["type"]] + # rebuild Pose sub-dataclass where present + if "pose" in data and isinstance(data["pose"], dict): + data["pose"] = Pose(**data["pose"]) + payload = cls_(**data) + bp.g.add_node(entry["id"], data=payload) + bp._next_id = max(bp._next_id, entry["id"] + 1) + bp.g.add_edges_from(d["edges"]) + return bp + + @classmethod + def load_json(cls, path: Path | str) -> "DroneBlueprint": + return cls.from_dict(json.loads(Path(path).read_text())) + + # ----- pretty ----- + def summary(self) -> str: + lines = [f"DroneBlueprint ({self.g.number_of_nodes()} nodes)"] + for n in nx.dfs_preorder_nodes(self.g, self.root_id): + depth = int(nx.shortest_path_length(self.g, self.root_id, n)) + p = self.payload(n) + lines.append(" " * depth + f"#{n} {p}") + return "\n".join(lines) diff --git a/src/ariel/body_phenotypes/drone/decoders.py b/src/ariel/body_phenotypes/drone/decoders.py new file mode 100644 index 000000000..a162b129f --- /dev/null +++ b/src/ariel/body_phenotypes/drone/decoders.py @@ -0,0 +1,114 @@ +"""Genome → DroneBlueprint decoders. + +Each decoder takes a genome (or genome handler) and emits a DroneBlueprint. +This is the architectural seam the consortium plugs into: a new partner +adds a decoder; the rest of the pipeline is unchanged. +""" +from __future__ import annotations + +import math +import numpy as np + +from .blueprint import ( + DroneBlueprint, + CorePlateNode, + ArmNode, + MotorNode, + RotorNode, + Pose, +) + + +# ---------- decoder 1: spherical-angular ---------- + +def spherical_angular_to_blueprint( + genome: np.ndarray, + *, + core_mass: float = 0.4, + core_radius: float = 0.05, + core_thickness: float = 0.01, + propsize: int = 5, + rotor_radius: float = 0.0635, +) -> DroneBlueprint: + """Decode airevolve's spherical-angular genome → DroneBlueprint. + + Genome layout (per row): [magnitude, arm_az, arm_pitch, motor_az, motor_pitch, direction] + - magnitude : distance from core to motor (sim units; treated as metres here) + - arm_az : azimuth of arm in XY plane (rad) + - arm_pitch : elevation above XY plane (rad), 0 = horizontal + - motor_az : motor thrust-vector azimuth in world XY (rad) + - motor_pitch: motor thrust-vector pitch (rad), 0 = thrust along +Z + - direction : 0=CCW, 1=CW + NaN rows are inactive arm slots. + """ + bp = DroneBlueprint() + core_id = bp.add(CorePlateNode( + mass=core_mass, radius=core_radius, thickness=core_thickness + )) + + valid = ~np.isnan(genome[:, 0]) + for row in genome[valid]: + mag, arm_az, arm_pitch, motor_az, motor_pitch, direction = (float(x) for x in row) + + # Arm pose: position the arm's attachment frame at the core's surface + # along (arm_az, arm_pitch); the arm itself extends along its local +X. + arm_pose = Pose( + xyz=(0.0, 0.0, 0.0), # mounted at core centre frame + rpy=(0.0, -arm_pitch, arm_az), # yaw to azimuth, pitch to elevation + ) + arm_id = bp.add(ArmNode(length=mag, pose=arm_pose), parent=core_id) + + # Motor pose: at arm tip (local +X by `length`), with thrust direction + # encoded as rpy that — when composed with the arm's frame — yields the + # genome's world-frame (motor_az, motor_pitch). For the demo we store + # the relative offset literally; the backend collapses the chain. + motor_local_rpy = (0.0, motor_pitch - arm_pitch, motor_az - arm_az) + motor_pose = Pose(xyz=(mag, 0.0, 0.0), rpy=motor_local_rpy) + spin = "cw" if direction >= 0.5 else "ccw" + motor_id = bp.add( + MotorNode(pose=motor_pose, spin=spin, propsize=propsize), + parent=arm_id, + ) + + bp.add(RotorNode(radius=rotor_radius), parent=motor_id) + + return bp + + +# ---------- decoder 2: cartesian-Euler (sketched, shows portability) ---------- + +def cartesian_euler_to_blueprint( + genome: np.ndarray, + *, + core_mass: float = 0.4, + propsize: int = 5, +) -> DroneBlueprint: + """Decode a Cartesian-Euler genome → DroneBlueprint. + + Genome layout (per row): [x, y, z, roll, pitch, yaw, direction] + Each row places a motor directly at a Cartesian offset from the core, + with an Euler-angle thrust orientation. Demonstrates that an entirely + different encoding produces the same downstream blueprint shape. + """ + bp = DroneBlueprint() + core_id = bp.add(CorePlateNode(mass=core_mass)) + + valid = ~np.isnan(genome[:, 0]) + for row in genome[valid]: + x, y, z, roll, pitch, yaw, direction = (float(v) for v in row) + arm_length = math.sqrt(x * x + y * y + z * z) + arm_az = math.atan2(y, x) + arm_el = math.atan2(z, math.sqrt(x * x + y * y)) + + arm_pose = Pose(xyz=(0.0, 0.0, 0.0), rpy=(0.0, -arm_el, arm_az)) + arm_id = bp.add(ArmNode(length=arm_length, pose=arm_pose), parent=core_id) + + motor_pose = Pose(xyz=(arm_length, 0.0, 0.0), rpy=(roll, pitch, yaw)) + spin = "cw" if direction >= 0.5 else "ccw" + motor_id = bp.add( + MotorNode(pose=motor_pose, spin=spin, propsize=propsize), + parent=arm_id, + ) + bp.add(RotorNode(), parent=motor_id) + + return bp diff --git a/uv.lock b/uv.lock index bdb2ff88e..a7d8dcf7a 100644 --- a/uv.lock +++ b/uv.lock @@ -2373,7 +2373,7 @@ wheels = [ [[package]] name = "matplotlib" -version = "3.10.7" +version = "3.10.9" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "contourpy" }, @@ -2386,43 +2386,43 @@ dependencies = [ { name = "pyparsing" }, { name = "python-dateutil" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ae/e2/d2d5295be2f44c678ebaf3544ba32d20c1f9ef08c49fe47f496180e1db15/matplotlib-3.10.7.tar.gz", hash = "sha256:a06ba7e2a2ef9131c79c49e63dad355d2d878413a0376c1727c8b9335ff731c7", size = 34804865, upload-time = "2025-10-09T00:28:00.669Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/be/b3/09eb0f7796932826ec20c25b517d568627754f6c6462fca19e12c02f2e12/matplotlib-3.10.7-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:7a0edb7209e21840e8361e91ea84ea676658aa93edd5f8762793dec77a4a6748", size = 8272389, upload-time = "2025-10-09T00:26:42.474Z" }, - { url = "https://files.pythonhosted.org/packages/11/0b/1ae80ddafb8652fd8046cb5c8460ecc8d4afccb89e2c6d6bec61e04e1eaf/matplotlib-3.10.7-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:c380371d3c23e0eadf8ebff114445b9f970aff2010198d498d4ab4c3b41eea4f", size = 8128247, upload-time = "2025-10-09T00:26:44.77Z" }, - { url = "https://files.pythonhosted.org/packages/7d/18/95ae2e242d4a5c98bd6e90e36e128d71cf1c7e39b0874feaed3ef782e789/matplotlib-3.10.7-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:d5f256d49fea31f40f166a5e3131235a5d2f4b7f44520b1cf0baf1ce568ccff0", size = 8696996, upload-time = "2025-10-09T00:26:46.792Z" }, - { url = "https://files.pythonhosted.org/packages/7e/3d/5b559efc800bd05cb2033aa85f7e13af51958136a48327f7c261801ff90a/matplotlib-3.10.7-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:11ae579ac83cdf3fb72573bb89f70e0534de05266728740d478f0f818983c695", size = 9530153, upload-time = "2025-10-09T00:26:49.07Z" }, - { url = "https://files.pythonhosted.org/packages/88/57/eab4a719fd110312d3c220595d63a3c85ec2a39723f0f4e7fa7e6e3f74ba/matplotlib-3.10.7-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:4c14b6acd16cddc3569a2d515cfdd81c7a68ac5639b76548cfc1a9e48b20eb65", size = 9593093, upload-time = "2025-10-09T00:26:51.067Z" }, - { url = "https://files.pythonhosted.org/packages/31/3c/80816f027b3a4a28cd2a0a6ef7f89a2db22310e945cd886ec25bfb399221/matplotlib-3.10.7-cp312-cp312-win_amd64.whl", hash = "sha256:0d8c32b7ea6fb80b1aeff5a2ceb3fb9778e2759e899d9beff75584714afcc5ee", size = 8122771, upload-time = "2025-10-09T00:26:53.296Z" }, - { url = "https://files.pythonhosted.org/packages/de/77/ef1fc78bfe99999b2675435cc52120887191c566b25017d78beaabef7f2d/matplotlib-3.10.7-cp312-cp312-win_arm64.whl", hash = "sha256:5f3f6d315dcc176ba7ca6e74c7768fb7e4cf566c49cb143f6bc257b62e634ed8", size = 7992812, upload-time = "2025-10-09T00:26:54.882Z" }, - { url = "https://files.pythonhosted.org/packages/02/9c/207547916a02c78f6bdd83448d9b21afbc42f6379ed887ecf610984f3b4e/matplotlib-3.10.7-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:1d9d3713a237970569156cfb4de7533b7c4eacdd61789726f444f96a0d28f57f", size = 8273212, upload-time = "2025-10-09T00:26:56.752Z" }, - { url = "https://files.pythonhosted.org/packages/bc/d0/b3d3338d467d3fc937f0bb7f256711395cae6f78e22cef0656159950adf0/matplotlib-3.10.7-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:37a1fea41153dd6ee061d21ab69c9cf2cf543160b1b85d89cd3d2e2a7902ca4c", size = 8128713, upload-time = "2025-10-09T00:26:59.001Z" }, - { url = "https://files.pythonhosted.org/packages/22/ff/6425bf5c20d79aa5b959d1ce9e65f599632345391381c9a104133fe0b171/matplotlib-3.10.7-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:b3c4ea4948d93c9c29dc01c0c23eef66f2101bf75158c291b88de6525c55c3d1", size = 8698527, upload-time = "2025-10-09T00:27:00.69Z" }, - { url = "https://files.pythonhosted.org/packages/d0/7f/ccdca06f4c2e6c7989270ed7829b8679466682f4cfc0f8c9986241c023b6/matplotlib-3.10.7-cp313-cp313-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:22df30ffaa89f6643206cf13877191c63a50e8f800b038bc39bee9d2d4957632", size = 9529690, upload-time = "2025-10-09T00:27:02.664Z" }, - { url = "https://files.pythonhosted.org/packages/b8/95/b80fc2c1f269f21ff3d193ca697358e24408c33ce2b106a7438a45407b63/matplotlib-3.10.7-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:b69676845a0a66f9da30e87f48be36734d6748024b525ec4710be40194282c84", size = 9593732, upload-time = "2025-10-09T00:27:04.653Z" }, - { url = "https://files.pythonhosted.org/packages/e1/b6/23064a96308b9aeceeffa65e96bcde459a2ea4934d311dee20afde7407a0/matplotlib-3.10.7-cp313-cp313-win_amd64.whl", hash = "sha256:744991e0cc863dd669c8dc9136ca4e6e0082be2070b9d793cbd64bec872a6815", size = 8122727, upload-time = "2025-10-09T00:27:06.814Z" }, - { url = "https://files.pythonhosted.org/packages/b3/a6/2faaf48133b82cf3607759027f82b5c702aa99cdfcefb7f93d6ccf26a424/matplotlib-3.10.7-cp313-cp313-win_arm64.whl", hash = "sha256:fba2974df0bf8ce3c995fa84b79cde38326e0f7b5409e7a3a481c1141340bcf7", size = 7992958, upload-time = "2025-10-09T00:27:08.567Z" }, - { url = "https://files.pythonhosted.org/packages/4a/f0/b018fed0b599bd48d84c08794cb242227fe3341952da102ee9d9682db574/matplotlib-3.10.7-cp313-cp313t-macosx_10_13_x86_64.whl", hash = "sha256:932c55d1fa7af4423422cb6a492a31cbcbdbe68fd1a9a3f545aa5e7a143b5355", size = 8316849, upload-time = "2025-10-09T00:27:10.254Z" }, - { url = "https://files.pythonhosted.org/packages/b0/b7/bb4f23856197659f275e11a2a164e36e65e9b48ea3e93c4ec25b4f163198/matplotlib-3.10.7-cp313-cp313t-macosx_11_0_arm64.whl", hash = "sha256:5e38c2d581d62ee729a6e144c47a71b3f42fb4187508dbbf4fe71d5612c3433b", size = 8178225, upload-time = "2025-10-09T00:27:12.241Z" }, - { url = "https://files.pythonhosted.org/packages/62/56/0600609893ff277e6f3ab3c0cef4eafa6e61006c058e84286c467223d4d5/matplotlib-3.10.7-cp313-cp313t-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:786656bb13c237bbcebcd402f65f44dd61ead60ee3deb045af429d889c8dbc67", size = 8711708, upload-time = "2025-10-09T00:27:13.879Z" }, - { url = "https://files.pythonhosted.org/packages/d8/1a/6bfecb0cafe94d6658f2f1af22c43b76cf7a1c2f0dc34ef84cbb6809617e/matplotlib-3.10.7-cp313-cp313t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:09d7945a70ea43bf9248f4b6582734c2fe726723204a76eca233f24cffc7ef67", size = 9541409, upload-time = "2025-10-09T00:27:15.684Z" }, - { url = "https://files.pythonhosted.org/packages/08/50/95122a407d7f2e446fd865e2388a232a23f2b81934960ea802f3171518e4/matplotlib-3.10.7-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:d0b181e9fa8daf1d9f2d4c547527b167cb8838fc587deabca7b5c01f97199e84", size = 9594054, upload-time = "2025-10-09T00:27:17.547Z" }, - { url = "https://files.pythonhosted.org/packages/13/76/75b194a43b81583478a81e78a07da8d9ca6ddf50dd0a2ccabf258059481d/matplotlib-3.10.7-cp313-cp313t-win_amd64.whl", hash = "sha256:31963603041634ce1a96053047b40961f7a29eb8f9a62e80cc2c0427aa1d22a2", size = 8200100, upload-time = "2025-10-09T00:27:20.039Z" }, - { url = "https://files.pythonhosted.org/packages/f5/9e/6aefebdc9f8235c12bdeeda44cc0383d89c1e41da2c400caf3ee2073a3ce/matplotlib-3.10.7-cp313-cp313t-win_arm64.whl", hash = "sha256:aebed7b50aa6ac698c90f60f854b47e48cd2252b30510e7a1feddaf5a3f72cbf", size = 8042131, upload-time = "2025-10-09T00:27:21.608Z" }, - { url = "https://files.pythonhosted.org/packages/0d/4b/e5bc2c321b6a7e3a75638d937d19ea267c34bd5a90e12bee76c4d7c7a0d9/matplotlib-3.10.7-cp314-cp314-macosx_10_13_x86_64.whl", hash = "sha256:d883460c43e8c6b173fef244a2341f7f7c0e9725c7fe68306e8e44ed9c8fb100", size = 8273787, upload-time = "2025-10-09T00:27:23.27Z" }, - { url = "https://files.pythonhosted.org/packages/86/ad/6efae459c56c2fbc404da154e13e3a6039129f3c942b0152624f1c621f05/matplotlib-3.10.7-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:07124afcf7a6504eafcb8ce94091c5898bbdd351519a1beb5c45f7a38c67e77f", size = 8131348, upload-time = "2025-10-09T00:27:24.926Z" }, - { url = "https://files.pythonhosted.org/packages/a6/5a/a4284d2958dee4116359cc05d7e19c057e64ece1b4ac986ab0f2f4d52d5a/matplotlib-3.10.7-cp314-cp314-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:c17398b709a6cce3d9fdb1595c33e356d91c098cd9486cb2cc21ea2ea418e715", size = 9533949, upload-time = "2025-10-09T00:27:26.704Z" }, - { url = "https://files.pythonhosted.org/packages/de/ff/f3781b5057fa3786623ad8976fc9f7b0d02b2f28534751fd5a44240de4cf/matplotlib-3.10.7-cp314-cp314-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:7146d64f561498764561e9cd0ed64fcf582e570fc519e6f521e2d0cfd43365e1", size = 9804247, upload-time = "2025-10-09T00:27:28.514Z" }, - { url = "https://files.pythonhosted.org/packages/47/5a/993a59facb8444efb0e197bf55f545ee449902dcee86a4dfc580c3b61314/matplotlib-3.10.7-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:90ad854c0a435da3104c01e2c6f0028d7e719b690998a2333d7218db80950722", size = 9595497, upload-time = "2025-10-09T00:27:30.418Z" }, - { url = "https://files.pythonhosted.org/packages/0d/a5/77c95aaa9bb32c345cbb49626ad8eb15550cba2e6d4c88081a6c2ac7b08d/matplotlib-3.10.7-cp314-cp314-win_amd64.whl", hash = "sha256:4645fc5d9d20ffa3a39361fcdbcec731382763b623b72627806bf251b6388866", size = 8252732, upload-time = "2025-10-09T00:27:32.332Z" }, - { url = "https://files.pythonhosted.org/packages/74/04/45d269b4268d222390d7817dae77b159651909669a34ee9fdee336db5883/matplotlib-3.10.7-cp314-cp314-win_arm64.whl", hash = "sha256:9257be2f2a03415f9105c486d304a321168e61ad450f6153d77c69504ad764bb", size = 8124240, upload-time = "2025-10-09T00:27:33.94Z" }, - { url = "https://files.pythonhosted.org/packages/4b/c7/ca01c607bb827158b439208c153d6f14ddb9fb640768f06f7ca3488ae67b/matplotlib-3.10.7-cp314-cp314t-macosx_10_13_x86_64.whl", hash = "sha256:1e4bbad66c177a8fdfa53972e5ef8be72a5f27e6a607cec0d8579abd0f3102b1", size = 8316938, upload-time = "2025-10-09T00:27:35.534Z" }, - { url = "https://files.pythonhosted.org/packages/84/d2/5539e66e9f56d2fdec94bb8436f5e449683b4e199bcc897c44fbe3c99e28/matplotlib-3.10.7-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:d8eb7194b084b12feb19142262165832fc6ee879b945491d1c3d4660748020c4", size = 8178245, upload-time = "2025-10-09T00:27:37.334Z" }, - { url = "https://files.pythonhosted.org/packages/77/b5/e6ca22901fd3e4fe433a82e583436dd872f6c966fca7e63cf806b40356f8/matplotlib-3.10.7-cp314-cp314t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:b4d41379b05528091f00e1728004f9a8d7191260f3862178b88e8fd770206318", size = 9541411, upload-time = "2025-10-09T00:27:39.387Z" }, - { url = "https://files.pythonhosted.org/packages/9e/99/a4524db57cad8fee54b7237239a8f8360bfcfa3170d37c9e71c090c0f409/matplotlib-3.10.7-cp314-cp314t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:4a74f79fafb2e177f240579bc83f0b60f82cc47d2f1d260f422a0627207008ca", size = 9803664, upload-time = "2025-10-09T00:27:41.492Z" }, - { url = "https://files.pythonhosted.org/packages/e6/a5/85e2edf76ea0ad4288d174926d9454ea85f3ce5390cc4e6fab196cbf250b/matplotlib-3.10.7-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:702590829c30aada1e8cef0568ddbffa77ca747b4d6e36c6d173f66e301f89cc", size = 9594066, upload-time = "2025-10-09T00:27:43.694Z" }, - { url = "https://files.pythonhosted.org/packages/39/69/9684368a314f6d83fe5c5ad2a4121a3a8e03723d2e5c8ea17b66c1bad0e7/matplotlib-3.10.7-cp314-cp314t-win_amd64.whl", hash = "sha256:f79d5de970fc90cd5591f60053aecfce1fcd736e0303d9f0bf86be649fa68fb8", size = 8342832, upload-time = "2025-10-09T00:27:45.543Z" }, - { url = "https://files.pythonhosted.org/packages/04/5f/e22e08da14bc1a0894184640d47819d2338b792732e20d292bf86e5ab785/matplotlib-3.10.7-cp314-cp314t-win_arm64.whl", hash = "sha256:cb783436e47fcf82064baca52ce748af71725d0352e1d31564cbe9c95df92b9c", size = 8172585, upload-time = "2025-10-09T00:27:47.185Z" }, +sdist = { url = "https://files.pythonhosted.org/packages/63/1b/4be5be87d43d327a0cf4de1a56e86f7f84c89312452406cf122efe2839e6/matplotlib-3.10.9.tar.gz", hash = "sha256:fd66508e8c6877d98e586654b608a0456db8d7e8a546eb1e2600efd957302358", size = 34811233, upload-time = "2026-04-24T00:14:13.539Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/35/c6/5581e26c72233ebb2a2a6fed2d24fb7c66b4700120b813f51b0555acf0b6/matplotlib-3.10.9-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:f0c3c28d9fbcc1fe7a03be236d73430cf6409c41fb2383a7ac52fe932b072cb1", size = 8319908, upload-time = "2026-04-24T00:12:21.323Z" }, + { url = "https://files.pythonhosted.org/packages/b7/18/4880dd762e40cd360c1bf06e890c5a97b997e91cb324602b1a19950ad5ce/matplotlib-3.10.9-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:41cb28c2bd769aa3e98322c6ab09854cbcc52ab69d2759d681bba3e327b2b320", size = 8216016, upload-time = "2026-04-24T00:12:23.4Z" }, + { url = "https://files.pythonhosted.org/packages/32/91/d024616abdba99e83120e07a20658976f6a343646710760c4a51df126029/matplotlib-3.10.9-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:ae20801130378b82d647ff5047c07316295b68dc054ca6b3c13519d0ea624285", size = 8789336, upload-time = "2026-04-24T00:12:26.096Z" }, + { url = "https://files.pythonhosted.org/packages/5c/04/030a2f61ef2158f5e4c259487a92ac877732499fb33d871585d89e03c42d/matplotlib-3.10.9-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:6c63ebcd8b4b169eb2f5c200552ae6b8be8999a005b6b507ed76fb8d7d674fe2", size = 9604602, upload-time = "2026-04-24T00:12:29.052Z" }, + { url = "https://files.pythonhosted.org/packages/fc/c2/541e4d09d87bb6b5830fc28b4c887a9a8cf4e1c6cee698a8c05552ae2003/matplotlib-3.10.9-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:d75d11c949914165976c621b2324f9ef162af7ebf4b057ddf95dd1dba7e5edcf", size = 9670966, upload-time = "2026-04-24T00:12:32.131Z" }, + { url = "https://files.pythonhosted.org/packages/04/a1/4571fc46e7702de8d0c2dc54ad1b2f8e29328dea3ee90831181f7353d93c/matplotlib-3.10.9-cp312-cp312-win_amd64.whl", hash = "sha256:d091f9d758b34aaaaa6331d13574bf01891d903b3dec59bfff458ef7551de5d6", size = 8217462, upload-time = "2026-04-24T00:12:35.226Z" }, + { url = "https://files.pythonhosted.org/packages/4b/d0/2269edb12aa30c13c8bcc9382892e39943ce1d28aab4ec296e0381798e81/matplotlib-3.10.9-cp312-cp312-win_arm64.whl", hash = "sha256:10cc5ce06d10231c36f40e875f3c7e8050362a4ee8f0ee5d29a6b3277d57bb42", size = 8136688, upload-time = "2026-04-24T00:12:37.442Z" }, + { url = "https://files.pythonhosted.org/packages/aa/d3/8d4f6afbecb49fc04e060a57c0fce39ea51cc163a6bd87303ccd698e4fa6/matplotlib-3.10.9-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:b580440f1ff81a0e34122051a3dfabb7e4b7f9e380629929bde0eff9af72165f", size = 8320331, upload-time = "2026-04-24T00:12:39.688Z" }, + { url = "https://files.pythonhosted.org/packages/63/d9/9e14bc7564bf92d5ffa801ae5fac819ce74b925dfb55e3ebde61a3bbad3e/matplotlib-3.10.9-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:b1b745c489cd1a77a0dc1120a05dc87af9798faebc913601feb8c73d89bf2d1e", size = 8216461, upload-time = "2026-04-24T00:12:42.494Z" }, + { url = "https://files.pythonhosted.org/packages/8a/17/4402d0d14ccf1dfc70932600b68097fbbf9c898a4871d2cbbe79c7801a32/matplotlib-3.10.9-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:8f3bcac1ca5ed000a6f4337d47ba67dfddf37ed6a46c15fd7f014997f7bf865f", size = 8790091, upload-time = "2026-04-24T00:12:44.789Z" }, + { url = "https://files.pythonhosted.org/packages/3e/0b/322aeec06dd9b91411f92028b37d447342770a24392aa4813e317064dad5/matplotlib-3.10.9-cp313-cp313-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:7a8d66a55def891c33147ba3ba9bfcabf0b526a43764c818acbb4525e5ed0838", size = 9605027, upload-time = "2026-04-24T00:12:47.583Z" }, + { url = "https://files.pythonhosted.org/packages/74/88/5f13482f55e7b00bcfc09838b093c2456e1379978d2a146844aae05350ad/matplotlib-3.10.9-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:d843374407c4017a6403b59c6c81606773d136f3259d5b6da3131bc814542cc2", size = 9671269, upload-time = "2026-04-24T00:12:50.878Z" }, + { url = "https://files.pythonhosted.org/packages/c5/e0/0840fd2f93da988ec660b8ad1984abe9f25d2aed22a5e394ff1c68c88307/matplotlib-3.10.9-cp313-cp313-win_amd64.whl", hash = "sha256:f4399f64b3e94cd500195490972ae1ee81170df1636fa15364d157d5bdd7b921", size = 8217588, upload-time = "2026-04-24T00:12:53.784Z" }, + { url = "https://files.pythonhosted.org/packages/47/b9/d706d06dd605c49b9f83a2aed8c13e3e5db70697d7a80b7e3d7915de6b17/matplotlib-3.10.9-cp313-cp313-win_arm64.whl", hash = "sha256:ba7b3b8ef09eab7df0e86e9ae086faa433efbfbdb46afcb3aa16aabf779469a8", size = 8136913, upload-time = "2026-04-24T00:12:56.501Z" }, + { url = "https://files.pythonhosted.org/packages/9b/45/6e32d96978264c8ca8c4b1010adb955a1a49cfaf314e212bbc8908f04a61/matplotlib-3.10.9-cp313-cp313t-macosx_10_13_x86_64.whl", hash = "sha256:09218df8a93712bd6ea133e83a153c755448cf7868316c531cffcc43f69d1cc9", size = 8368019, upload-time = "2026-04-24T00:12:58.896Z" }, + { url = "https://files.pythonhosted.org/packages/86/0a/c8e3d3bba245f0f7fc424937f8ff7ef77291a36af3edb97ccd78aa93d84f/matplotlib-3.10.9-cp313-cp313t-macosx_11_0_arm64.whl", hash = "sha256:82368699727bfb7b0182e1aa13082e3c08e092fa1a25d3e1fd92405bff96f6d4", size = 8264645, upload-time = "2026-04-24T00:13:01.406Z" }, + { url = "https://files.pythonhosted.org/packages/3d/aa/5bf5a14fe4fed73a4209a155606f8096ff797aad89c6c35179026571133e/matplotlib-3.10.9-cp313-cp313t-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:3225f4e1edcb8c86c884ddf79ebe20ecd0a67d30188f279897554ccd8fded4dc", size = 8802194, upload-time = "2026-04-24T00:13:03.702Z" }, + { url = "https://files.pythonhosted.org/packages/dd/5e/b4be852d6bba6fd15893fadf91ff26ae49cb91aac789e95dde9d342e664f/matplotlib-3.10.9-cp313-cp313t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:de2445a0c6690d21b7eb6ce071cebad6d40a2e9bdf10d039074a96ba19797b99", size = 9622684, upload-time = "2026-04-24T00:13:06.647Z" }, + { url = "https://files.pythonhosted.org/packages/4c/3d/ed428c971139112ef730f62770654d609467346d09d4b62617e1afd68a5a/matplotlib-3.10.9-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:b2b9516251cb89ff618d757daec0e2ed1bf21248013844a853d87ef85ab3081d", size = 9680790, upload-time = "2026-04-24T00:13:10.009Z" }, + { url = "https://files.pythonhosted.org/packages/e7/09/052e884aaf2b985c63cb79f715f1d5b6a3eaa7de78f6a52b9dbc077d5b53/matplotlib-3.10.9-cp313-cp313t-win_amd64.whl", hash = "sha256:e9fae004b941b23ff2edcf1567a857ed77bafc8086ffa258190462328434faf8", size = 8287571, upload-time = "2026-04-24T00:13:13.087Z" }, + { url = "https://files.pythonhosted.org/packages/f4/38/ae27288e788c35a4250491422f3db7750366fc8c97d6f36fbdecfc1f5518/matplotlib-3.10.9-cp313-cp313t-win_arm64.whl", hash = "sha256:6b63d9c7c769b88ab81e10dc86e4e0607cf56817b9f9e6cf24b2a5f1693b8e38", size = 8188292, upload-time = "2026-04-24T00:13:15.546Z" }, + { url = "https://files.pythonhosted.org/packages/d6/e6/3bd8afd04949f02eabc1c17115ea5255e19cacd4d06fc5abdde4eeb0052c/matplotlib-3.10.9-cp314-cp314-macosx_10_13_x86_64.whl", hash = "sha256:172db52c9e683f5d12eaf57f0f54834190e12581fe1cc2a19595a8f5acb4e77d", size = 8321276, upload-time = "2026-04-24T00:13:18.318Z" }, + { url = "https://files.pythonhosted.org/packages/41/86/86231232fff41c9f8e4a1a7d7a597d349a02527109c3af7d618366122139/matplotlib-3.10.9-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:97e35e8d39ccc85859095e01a53847432ba9a53ddf7986f7a54a11b73d0e143f", size = 8218218, upload-time = "2026-04-24T00:13:20.974Z" }, + { url = "https://files.pythonhosted.org/packages/85/8f/becc9722cafc64f5d2eb0b7c1bf5f585271c618a45dbd8fabeb021f898b6/matplotlib-3.10.9-cp314-cp314-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:aba1615dabe83188e19d4f75a253c6a08423e04c1425e64039f800050a69de6b", size = 9608145, upload-time = "2026-04-24T00:13:23.228Z" }, + { url = "https://files.pythonhosted.org/packages/32/5d/f7e914f7d9325abff4057cee62c0fa70263683189f774473cbfb534cd13b/matplotlib-3.10.9-cp314-cp314-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:34cf8167e023ad956c15f36302911d5406bd99a9862c1a8499ea6f7c0e015dc2", size = 9885085, upload-time = "2026-04-24T00:13:25.849Z" }, + { url = "https://files.pythonhosted.org/packages/a5/fd/fa69f2221534e80cc5772ac2b7d222011a2acafc2ec7216d5dd174c864ae/matplotlib-3.10.9-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:59476c6d29d612b8e9bb6ce8c5b631be6ba8f9e3a2421f22a02b192c7dd28716", size = 9672358, upload-time = "2026-04-24T00:13:28.906Z" }, + { url = "https://files.pythonhosted.org/packages/ab/1a/5a4f747a8b271cbb024946d2dd3c913ab5032ba430626f8c3528ada96b4b/matplotlib-3.10.9-cp314-cp314-win_amd64.whl", hash = "sha256:336b9acc64d309063126edcdaca00db9373af3c476bb94388fe9c5a53ad13e6f", size = 8349970, upload-time = "2026-04-24T00:13:31.904Z" }, + { url = "https://files.pythonhosted.org/packages/64/dc/95d60ecaefe30680a154b52ea96ab4b0dab547f1fd6aa12f5fb655e89cae/matplotlib-3.10.9-cp314-cp314-win_arm64.whl", hash = "sha256:2dc9477819ffd78ad12a20df1d9d6a6bd4fec6aaa9072681465fddca052f1456", size = 8272785, upload-time = "2026-04-24T00:13:34.511Z" }, + { url = "https://files.pythonhosted.org/packages/70/a0/005d68bc8b8418300ce6591f18586910a8526806e2ab663933d9f20a41e9/matplotlib-3.10.9-cp314-cp314t-macosx_10_13_x86_64.whl", hash = "sha256:da4e09638420548f31c354032a6250e473c68e5a4e96899b4844cf39ddea23fe", size = 8367999, upload-time = "2026-04-24T00:13:36.962Z" }, + { url = "https://files.pythonhosted.org/packages/22/05/1236cc9290be70b2498af20ca348add76e3fffe7f67b477db5133a84f3ea/matplotlib-3.10.9-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:345f6f68ecc8da0ca56fad2ea08fde1a115eda530079eca185d50a7bc3e146c6", size = 8264543, upload-time = "2026-04-24T00:13:39.851Z" }, + { url = "https://files.pythonhosted.org/packages/cd/c2/071f5a5ff6c5bd63aaaf2f45c811d9bf2ced94bde188d9e1a519e21d0cba/matplotlib-3.10.9-cp314-cp314t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:4edcfbd8565339aa62f1cd4012f7180926fdbe71850f7b0d3c379c175cd6b66c", size = 9622800, upload-time = "2026-04-24T00:13:42.296Z" }, + { url = "https://files.pythonhosted.org/packages/95/57/da7d1f10a85624b9e7db68e069dd94e58dc41dbf9463c5921632ecbe3661/matplotlib-3.10.9-cp314-cp314t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:6be157fe17fc37cb95ac1d7374cf717ce9259616edec911a78d9d26dae8522d4", size = 9888561, upload-time = "2026-04-24T00:13:45.026Z" }, + { url = "https://files.pythonhosted.org/packages/67/b2/ef8d6bb59b0edb6c16c968b70f548aa13b54348972def5aa6ac85df67145/matplotlib-3.10.9-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:4e42042d54db34fda4e95a7bd3e5789c2a995d2dad3eb8850232ee534092fbbf", size = 9680884, upload-time = "2026-04-24T00:13:48.066Z" }, + { url = "https://files.pythonhosted.org/packages/61/1c/d21bfeb9931881ebe96bcfcff27c7ae4b160ae0ec291a714c42641a56d75/matplotlib-3.10.9-cp314-cp314t-win_amd64.whl", hash = "sha256:c27df8b3848f32a83d1767566595e43cfaa4460380974da06f4279a7ec143c39", size = 8432333, upload-time = "2026-04-24T00:13:51.008Z" }, + { url = "https://files.pythonhosted.org/packages/78/23/92493c3e6e1b635ccfff146f7b99e674808787915420373ac399283764c2/matplotlib-3.10.9-cp314-cp314t-win_arm64.whl", hash = "sha256:a49f1eadc84ca85fd72fa4e89e70e61bf86452df6f971af04b12c60761a0772c", size = 8324785, upload-time = "2026-04-24T00:13:53.633Z" }, ] [[package]] From 51438406f32af0aa15dfb87c8597360529e813bf Mon Sep 17 00:00:00 2001 From: A-lamo <2727043@student.vu.nl> Date: Thu, 21 May 2026 17:32:38 +0200 Subject: [PATCH 08/27] Integrated EA for drones. --- .../3_drone_evolution_spherical_ea.py | 296 ++++++++++++ .../e_drones_ec/6_drone_evolution_cppn_ea.py | 278 ++++++++++++ src/ariel/body_phenotypes/drone/__init__.py | 17 +- src/ariel/body_phenotypes/drone/genome.py | 114 ++++- src/ariel/body_phenotypes/drone/operations.py | 308 ++++++++++++- .../controllers/lee_control/mujoco_bridge.py | 424 ++++++++++++++++++ tests/unit/test_drone_ec/__init__.py | 1 + .../test_drone_ec_integration.py | 148 ++++++ .../test_drone_ec/test_lee_mujoco_bridge.py | 102 +++++ 9 files changed, 1676 insertions(+), 12 deletions(-) create mode 100644 examples/e_drones_ec/3_drone_evolution_spherical_ea.py create mode 100644 examples/e_drones_ec/6_drone_evolution_cppn_ea.py create mode 100644 src/ariel/simulation/drone/controllers/lee_control/mujoco_bridge.py create mode 100644 tests/unit/test_drone_ec/__init__.py create mode 100644 tests/unit/test_drone_ec/test_drone_ec_integration.py create mode 100644 tests/unit/test_drone_ec/test_lee_mujoco_bridge.py diff --git a/examples/e_drones_ec/3_drone_evolution_spherical_ea.py b/examples/e_drones_ec/3_drone_evolution_spherical_ea.py new file mode 100644 index 000000000..0aaa14518 --- /dev/null +++ b/examples/e_drones_ec/3_drone_evolution_spherical_ea.py @@ -0,0 +1,296 @@ +"""Drone morphology evolution with ARIEL EA + spherical-angular direct encoding. + +Mirrors the c_genotypes/3 pattern (ARIEL EA + direct genotype + MuJoCo +fitness) but for drones: + + SphericalAngularDroneGenomeHandler (direct encoding) + │ + ▼ ariel.ec EA pipeline (parent_tag → crossover → mutate → evaluate → truncate) + │ + ▼ evaluate_drones_hover_mujoco + │ + ▼ genotype → DroneBlueprint → MuJoCo (Lee→ctrl bridge) → hover fitness + +Outputs: SQLite DB, best DroneBlueprint JSON, MP4 video, optional passive +viewer behind ``--visualize``. Single-process — for parallel evaluation +see ``6_drone_evolution_cppn_ea.py``. + +Run:: + + uv run examples/e_drones_ec/3_drone_evolution_spherical_ea.py + uv run examples/e_drones_ec/3_drone_evolution_spherical_ea.py --pop 8 --budget 5 + uv run examples/e_drones_ec/3_drone_evolution_spherical_ea.py --no-visualize +""" +from __future__ import annotations + +import argparse +import os +import sys +import time +from pathlib import Path + +os.environ.setdefault("OMP_NUM_THREADS", "1") +os.environ.setdefault("OPENBLAS_NUM_THREADS", "1") +os.environ.setdefault("MKL_NUM_THREADS", "1") + +import numpy as np +from rich.console import Console + +from ariel.body_phenotypes.drone import ( + crossover_drones, + deserialize_genome, + evaluate_drones_hover_mujoco, + initialize_drones, + mutate_drones, + parent_tag, + truncation_select, +) +from ariel.body_phenotypes.drone.decoders import spherical_angular_to_blueprint +from ariel.ec import EA, Individual, Population +from ariel.ec.drone.genome_handlers.spherical_angular_genome_handler import ( + SphericalAngularDroneGenomeHandler, +) + + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +console = Console() +parser = argparse.ArgumentParser( + description="Drone morphology evolution (spherical direct encoding, ARIEL EA, MuJoCo hover)", +) +parser.add_argument("--pop", type=int, default=8, help="Population size") +parser.add_argument("--budget", type=int, default=5, help="EA generations") +parser.add_argument("--min-arms", type=int, default=4, help="Minimum rotor arms") +parser.add_argument("--max-arms", type=int, default=6, help="Maximum rotor arms") +parser.add_argument("--dur", type=float, default=1.0, help="Hover-window seconds for fitness") +parser.add_argument("--warm-up", type=float, default=0.1, help="Warm-up seconds discarded from fitness log") +parser.add_argument("--target-alt", type=float, default=1.0, help="Hover target altitude (m, ENU)") +parser.add_argument( + "--drift-weight", type=float, default=1.0, + help="Weight for lateral drift in combined fitness", +) +parser.add_argument( + "--tilt-weight", type=float, default=1.0, + help="Weight for (1 - cos θ_tilt) in combined fitness", +) +parser.add_argument( + "--ctrl-weight", type=float, default=0.05, + help="Weight for mean(ctrl²) in combined fitness", +) +parser.add_argument("--prop-size", type=int, default=2, help="Propeller size (inches)") +parser.add_argument("--seed", type=int, default=42) +parser.add_argument( + "--visualize", + action=argparse.BooleanOptionalAction, + default=True, + help="Render best individual: MP4 + passive viewer (--no-visualize to skip)", +) +parser.add_argument( + "--viewer-duration", type=float, default=5.0, + help="Seconds of hover to render in the post-evolution video / viewer", +) +args = parser.parse_args() + + +POP_SIZE = args.pop +BUDGET = args.budget +SEED = args.seed +np.random.seed(SEED) + +DATA = Path.cwd() / "__data__" / Path(__file__).stem +DATA.mkdir(parents=True, exist_ok=True) +RUN_ID = time.strftime("%Y%m%d_%H%M%S") +DB_PATH = DATA / f"database_{RUN_ID}.db" + +SPAWN_POSITION = (0.0, 0.0, float(args.target_alt)) + + +# --------------------------------------------------------------------------- +# Genome handler (direct, fixed-size spherical-angular) +# --------------------------------------------------------------------------- + +PARAMETER_LIMITS = np.array([ + [0.055, 0.17], # arm magnitude (m) + [-np.pi, np.pi], # arm azimuth + [-np.pi / 2, np.pi / 2], # arm elevation + [-np.pi, np.pi], # motor disc azimuth + [-np.pi, np.pi], # motor disc pitch + [0, 1], # propeller spin direction +]) + +template_handler = SphericalAngularDroneGenomeHandler( + min_max_narms=(args.min_arms, args.max_arms), + parameter_limits=PARAMETER_LIMITS, + append_arm_chance=0.1, + bilateral_plane_for_symmetry=None, + repair=False, + rnd=np.random.default_rng(SEED), +) + + +# --------------------------------------------------------------------------- +# Banner +# --------------------------------------------------------------------------- + +console.rule("[bold blue]Drone Spherical-Angular Evolution (ARIEL EA + MuJoCo hover)") +console.log( + f"pop={POP_SIZE} budget={BUDGET} arms=[{args.min_arms}, {args.max_arms}] " + f"dur={args.dur}s target_alt={args.target_alt}m prop_size={args.prop_size}", +) +console.log(f"DB → {DB_PATH}") + + +# --------------------------------------------------------------------------- +# Initial population (init + evaluate pre-loop) +# --------------------------------------------------------------------------- + +initial_pop = Population([Individual() for _ in range(POP_SIZE)]) + +init_op = initialize_drones(template_handler=template_handler) +eval_op = evaluate_drones_hover_mujoco( + decoder="spherical", + decoder_kwargs={"propsize": args.prop_size}, + duration=args.dur, + warm_up=args.warm_up, + target_position=SPAWN_POSITION, + n_workers=1, + drift_weight=args.drift_weight, + tilt_weight=args.tilt_weight, + ctrl_weight=args.ctrl_weight, +) + +console.log("Initializing + evaluating initial population …") +initial_pop = init_op(initial_pop) +initial_pop = eval_op(initial_pop) + +finite0 = [ind.fitness_ for ind in initial_pop if np.isfinite(ind.fitness_ or np.inf)] +if finite0: + console.log(f"Initial fitness — min={min(finite0):.4f} mean={np.mean(finite0):.4f}") + + +# --------------------------------------------------------------------------- +# Generation pipeline (lower-is-better hover fitness; survivors are top-n minimum) +# --------------------------------------------------------------------------- + +generation_ops = [ + parent_tag(n=POP_SIZE), + crossover_drones(template_handler=template_handler), + mutate_drones(template_handler=template_handler), + eval_op, + truncation_select(n=POP_SIZE), +] + +ea = EA( + population=initial_pop, + operations=generation_ops, + num_steps=BUDGET, + db_file_path=DB_PATH, + db_handling="delete", +) + +console.rule("[bold green]Evolving") +ea.run() + + +# --------------------------------------------------------------------------- +# Pick best (minimisation → smallest fitness is best) +# --------------------------------------------------------------------------- + +ea.fetch_population(only_alive=False, requires_eval=False) +all_evaluated = ea.population +finite = [ind for ind in all_evaluated if np.isfinite(ind.fitness_ or np.inf)] +if not finite: + console.log("[red]No evaluated individuals with finite fitness — aborting visualization.[/red]") + sys.exit(0) +best = sorted(finite, key=lambda i: i.fitness_)[0] + +console.rule("[bold cyan]Best individual") +console.log(f" id={best.id} fitness={best.fitness_:.4f} born={best.time_of_birth}") + +best_genome = deserialize_genome(best.genotype) +valid_mask = ~np.isnan(best_genome.arms[:, 0]) +console.log(f" active arms: {int(valid_mask.sum())} / {best_genome.arms.shape[0]}") + +best_bp = spherical_angular_to_blueprint(best_genome.arms, propsize=args.prop_size) +bp_path = DATA / f"best_blueprint_{RUN_ID}.json" +best_bp.save_json(bp_path) +console.log(f" blueprint → {bp_path}") + + +# --------------------------------------------------------------------------- +# Replay (MP4 + optional passive viewer) +# --------------------------------------------------------------------------- + +if args.visualize: + import mujoco + + from ariel.body_phenotypes.drone.backends import blueprint_to_propellers + from ariel.simulation.drone.controllers.lee_control.lee_controller import ( + LeeGeometricControl, + ) + from ariel.simulation.drone.controllers.lee_control.mujoco_bridge import ( + LeeMujocoHoverBridge, + spawn_blueprint_in_world, + ) + from ariel.simulation.drone.drone_interface import DroneInterface + from ariel.utils.video_recorder import VideoRecorder + + propellers = blueprint_to_propellers(best_bp, convention="ned") + quad = DroneInterface(0, propellers=propellers) + lee_ctrl = LeeGeometricControl( + quad, yawType=1, orient="NED", auto_scale_gains=True, + pos_P_gain=np.array([14.3, 14.3, 14.3]), + vel_P_gain=np.array([9.0, 9.0, 9.0]), + ) + spawned = spawn_blueprint_in_world( + best_bp, propellers=propellers, + target_mass=float(quad.params["mB"]), + spawn_position=SPAWN_POSITION, + ) + bridge = LeeMujocoHoverBridge( + quad=quad, lee_ctrl=lee_ctrl, + model=spawned.model, data=spawned.data, + max_thrust_per_motor=spawned.max_thrust_per_motor, + target_position_enu=SPAWN_POSITION, + ) + + # MP4 + videos_dir = DATA / "videos" + videos_dir.mkdir(parents=True, exist_ok=True) + video = VideoRecorder( + file_name=f"best_hover_{RUN_ID}", + output_folder=videos_dir, + ) + bridge.reset_pose() + steps_per_frame = max(1, int(round(1.0 / (spawned.model.opt.timestep * video.fps)))) + total_steps = int(args.viewer_duration / spawned.model.opt.timestep) + console.log(f"Recording MP4 ({args.viewer_duration}s) …") + with mujoco.Renderer(spawned.model, width=video.width, height=video.height) as renderer: + for step_i in range(total_steps): + bridge.step() + mujoco.mj_step(spawned.model, spawned.data) + if step_i % steps_per_frame == 0: + renderer.update_scene(spawned.data) + video.write(renderer.render()) + video.release() + console.log(f" MP4 → {videos_dir}") + + # Passive viewer (skip on macOS / no passive support) + if sys.platform != "darwin" and hasattr(mujoco.viewer, "launch_passive"): + bridge.reset_pose() + console.log("Launching passive viewer (close window to exit) …") + with mujoco.viewer.launch_passive(spawned.model, spawned.data) as v: + t_start = time.time() + while v.is_running() and (time.time() - t_start) < args.viewer_duration: + step_start = time.time() + bridge.step() + mujoco.mj_step(spawned.model, spawned.data) + v.sync() + slack = spawned.model.opt.timestep - (time.time() - step_start) + if slack > 0: + time.sleep(slack) + + +console.rule("[bold]Done") diff --git a/examples/e_drones_ec/6_drone_evolution_cppn_ea.py b/examples/e_drones_ec/6_drone_evolution_cppn_ea.py new file mode 100644 index 000000000..4c7148d8a --- /dev/null +++ b/examples/e_drones_ec/6_drone_evolution_cppn_ea.py @@ -0,0 +1,278 @@ +"""Drone morphology evolution with ARIEL EA + CPPN-NEAT indirect encoding. + +Mirrors the c_genotypes/6 pattern (ARIEL EA + indirect genotype + +per-individual MuJoCo fitness + multiprocessing) but for drones: + + CPPNNeatDroneGenomeHandler (CPPN-NEAT indirect encoding) + │ + ▼ ariel.ec EA pipeline (parent_tag → crossover → mutate → evaluate → truncate) + │ + ▼ evaluate_drones_hover_mujoco (multiprocessing.Pool, 'spawn' ctx) + │ + ▼ CPPN → phenotype → DroneBlueprint → MuJoCo (Lee→ctrl bridge) → hover fitness + +Outputs: SQLite DB, best CPPN JSON, best DroneBlueprint JSON, MP4 video, +optional passive viewer behind ``--visualize``. + +Run:: + + uv run examples/e_drones_ec/6_drone_evolution_cppn_ea.py + uv run examples/e_drones_ec/6_drone_evolution_cppn_ea.py --pop 8 --budget 5 --workers 4 + uv run examples/e_drones_ec/6_drone_evolution_cppn_ea.py --no-visualize +""" +from __future__ import annotations + +import argparse +import json +import os +import sys +import time +from pathlib import Path + +os.environ.setdefault("OMP_NUM_THREADS", "1") +os.environ.setdefault("OPENBLAS_NUM_THREADS", "1") +os.environ.setdefault("MKL_NUM_THREADS", "1") + +import numpy as np +from rich.console import Console + +from ariel.body_phenotypes.drone import ( + crossover_cppn_drones, + deserialize_cppn_genome, + evaluate_drones_hover_mujoco, + initialize_cppn_drones, + mutate_cppn_drones, + parent_tag, + truncation_select, +) +from ariel.body_phenotypes.drone.decoders import spherical_angular_to_blueprint +from ariel.ec import EA, Individual, Population +from ariel.ec.drone.genome_handlers.cppn_neat_genome_handler import ( + CPPNNeatDroneGenomeHandler, +) + + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +def parse_args() -> argparse.Namespace: + parser = argparse.ArgumentParser( + description="Drone morphology evolution (CPPN-NEAT indirect encoding, ARIEL EA, MuJoCo hover)", + ) + parser.add_argument("--pop", type=int, default=8, help="Population size") + parser.add_argument("--budget", type=int, default=5, help="EA generations") + parser.add_argument("--min-arms", type=int, default=4, help="Minimum rotor arms") + parser.add_argument("--max-arms", type=int, default=6, help="Maximum rotor arms") + parser.add_argument( + "--num-segments", type=int, default=8, + help="CPPN sampling resolution per arm slot", + ) + parser.add_argument("--dur", type=float, default=1.0, help="Hover-window seconds for fitness") + parser.add_argument("--warm-up", type=float, default=0.1, help="Warm-up seconds discarded from fitness log") + parser.add_argument("--target-alt", type=float, default=1.0, help="Hover target altitude (m, ENU)") + parser.add_argument("--drift-weight", type=float, default=1.0) + parser.add_argument("--tilt-weight", type=float, default=1.0) + parser.add_argument("--ctrl-weight", type=float, default=0.05) + parser.add_argument("--prop-size", type=int, default=2, help="Propeller size (inches)") + parser.add_argument( + "--workers", type=int, default=max(1, (os.cpu_count() or 1) // 2), + help="Parallel evaluation worker processes (1 = single-process)", + ) + parser.add_argument("--seed", type=int, default=42) + parser.add_argument( + "--visualize", + action=argparse.BooleanOptionalAction, + default=True, + help="Render best individual: MP4 + passive viewer (--no-visualize to skip)", + ) + parser.add_argument("--viewer-duration", type=float, default=5.0) + return parser.parse_args() + + +def main() -> None: + args = parse_args() + console = Console() + + POP_SIZE = args.pop + BUDGET = args.budget + SEED = args.seed + np.random.seed(SEED) + + DATA = Path.cwd() / "__data__" / Path(__file__).stem + DATA.mkdir(parents=True, exist_ok=True) + RUN_ID = time.strftime("%Y%m%d_%H%M%S") + DB_PATH = DATA / f"database_{RUN_ID}.db" + + SPAWN_POSITION = (0.0, 0.0, float(args.target_alt)) + + PARAMETER_LIMITS = np.array([ + [0.055, 0.17], + [-np.pi, np.pi], + [-np.pi / 2, np.pi / 2], + [-np.pi, np.pi], + [-np.pi, np.pi], + [0, 1], + ]) + + HANDLER_KWARGS = { + "num_segments": args.num_segments, + "min_max_narms": (args.min_arms, args.max_arms), + "parameter_limits": PARAMETER_LIMITS, + "repair": True, + } + + template_handler = CPPNNeatDroneGenomeHandler( + rng=np.random.default_rng(SEED), + **HANDLER_KWARGS, + ) + + console.rule("[bold blue]Drone CPPN-NEAT Evolution (ARIEL EA + MuJoCo hover)") + console.log( + f"pop={POP_SIZE} budget={BUDGET} arms=[{args.min_arms}, {args.max_arms}] " + f"segs={args.num_segments} workers={args.workers} dur={args.dur}s", + ) + console.log(f"DB → {DB_PATH}") + + initial_pop = Population([Individual() for _ in range(POP_SIZE)]) + + init_op = initialize_cppn_drones(template_handler=template_handler) + eval_op = evaluate_drones_hover_mujoco( + decoder="cppn", + decoder_kwargs={ + "propsize": args.prop_size, + "handler_kwargs": HANDLER_KWARGS, + }, + duration=args.dur, + warm_up=args.warm_up, + target_position=SPAWN_POSITION, + n_workers=args.workers, + drift_weight=args.drift_weight, + tilt_weight=args.tilt_weight, + ctrl_weight=args.ctrl_weight, + ) + + console.log("Initializing + evaluating initial population …") + initial_pop = init_op(initial_pop) + initial_pop = eval_op(initial_pop) + + finite0 = [ind.fitness_ for ind in initial_pop if np.isfinite(ind.fitness_ or np.inf)] + if finite0: + console.log(f"Initial fitness — min={min(finite0):.4f} mean={np.mean(finite0):.4f}") + + generation_ops = [ + parent_tag(n=POP_SIZE), + crossover_cppn_drones(template_handler=template_handler), + mutate_cppn_drones(template_handler=template_handler), + eval_op, + truncation_select(n=POP_SIZE), + ] + + ea = EA( + population=initial_pop, + operations=generation_ops, + num_steps=BUDGET, + db_file_path=DB_PATH, + db_handling="delete", + ) + + console.rule("[bold green]Evolving") + ea.run() + + ea.fetch_population(only_alive=False, requires_eval=False) + all_evaluated = ea.population + finite = [ind for ind in all_evaluated if np.isfinite(ind.fitness_ or np.inf)] + if not finite: + console.log("[red]No evaluated individuals with finite fitness — aborting visualization.[/red]") + return + best = sorted(finite, key=lambda i: i.fitness_)[0] + + console.rule("[bold cyan]Best individual") + console.log(f" id={best.id} fitness={best.fitness_:.4f} born={best.time_of_birth}") + + best_net = deserialize_cppn_genome(best.genotype) + best_handler = CPPNNeatDroneGenomeHandler(genome=best_net, **HANDLER_KWARGS) + best_phenotype = best_handler.get_phenotype() + n_active = int((~np.isnan(best_phenotype[:, 0])).sum()) + console.log(f" decoded active arms: {n_active} / {best_phenotype.shape[0]}") + + best_bp = spherical_angular_to_blueprint(best_phenotype, propsize=args.prop_size) + bp_path = DATA / f"best_blueprint_{RUN_ID}.json" + cppn_path = DATA / f"best_cppn_{RUN_ID}.json" + best_bp.save_json(bp_path) + cppn_path.write_text(json.dumps(best.genotype, indent=2), encoding="utf-8") + console.log(f" CPPN genome → {cppn_path}") + console.log(f" blueprint → {bp_path}") + + if args.visualize and n_active > 0: + import mujoco + + from ariel.body_phenotypes.drone.backends import blueprint_to_propellers + from ariel.simulation.drone.controllers.lee_control.lee_controller import ( + LeeGeometricControl, + ) + from ariel.simulation.drone.controllers.lee_control.mujoco_bridge import ( + LeeMujocoHoverBridge, + spawn_blueprint_in_world, + ) + from ariel.simulation.drone.drone_interface import DroneInterface + from ariel.utils.video_recorder import VideoRecorder + + propellers = blueprint_to_propellers(best_bp, convention="ned") + if not propellers: + console.log("[yellow]Best individual has no decoded propellers — skipping visualisation.[/yellow]") + return + quad = DroneInterface(0, propellers=propellers) + lee_ctrl = LeeGeometricControl( + quad, yawType=1, orient="NED", auto_scale_gains=True, + pos_P_gain=np.array([14.3, 14.3, 14.3]), + vel_P_gain=np.array([9.0, 9.0, 9.0]), + ) + spawned = spawn_blueprint_in_world( + best_bp, propellers=propellers, + target_mass=float(quad.params["mB"]), + spawn_position=SPAWN_POSITION, + ) + bridge = LeeMujocoHoverBridge( + quad=quad, lee_ctrl=lee_ctrl, + model=spawned.model, data=spawned.data, + max_thrust_per_motor=spawned.max_thrust_per_motor, + target_position_enu=SPAWN_POSITION, + ) + + videos_dir = DATA / "videos" + videos_dir.mkdir(parents=True, exist_ok=True) + video = VideoRecorder(file_name=f"best_hover_{RUN_ID}", output_folder=videos_dir) + bridge.reset_pose() + steps_per_frame = max(1, int(round(1.0 / (spawned.model.opt.timestep * video.fps)))) + total_steps = int(args.viewer_duration / spawned.model.opt.timestep) + console.log(f"Recording MP4 ({args.viewer_duration}s) …") + with mujoco.Renderer(spawned.model, width=video.width, height=video.height) as renderer: + for step_i in range(total_steps): + bridge.step() + mujoco.mj_step(spawned.model, spawned.data) + if step_i % steps_per_frame == 0: + renderer.update_scene(spawned.data) + video.write(renderer.render()) + video.release() + console.log(f" MP4 → {videos_dir}") + + if sys.platform != "darwin" and hasattr(mujoco.viewer, "launch_passive"): + bridge.reset_pose() + console.log("Launching passive viewer (close window to exit) …") + with mujoco.viewer.launch_passive(spawned.model, spawned.data) as v: + t_start = time.time() + while v.is_running() and (time.time() - t_start) < args.viewer_duration: + step_start = time.time() + bridge.step() + mujoco.mj_step(spawned.model, spawned.data) + v.sync() + slack = spawned.model.opt.timestep - (time.time() - step_start) + if slack > 0: + time.sleep(slack) + + console.rule("[bold]Done") + + +if __name__ == "__main__": + main() diff --git a/src/ariel/body_phenotypes/drone/__init__.py b/src/ariel/body_phenotypes/drone/__init__.py index 691f4298d..a4a3c0d7c 100644 --- a/src/ariel/body_phenotypes/drone/__init__.py +++ b/src/ariel/body_phenotypes/drone/__init__.py @@ -5,23 +5,38 @@ custom ODE dynamics are used for fitness evaluation. """ -from ariel.body_phenotypes.drone.genome import deserialize_genome, serialize_genome +from ariel.body_phenotypes.drone.genome import ( + deserialize_cppn_genome, + deserialize_genome, + serialize_cppn_genome, + serialize_genome, +) from ariel.body_phenotypes.drone.operations import ( + crossover_cppn_drones, crossover_drones, evaluate_drones, + evaluate_drones_hover_mujoco, + initialize_cppn_drones, initialize_drones, + mutate_cppn_drones, mutate_drones, parent_tag, truncation_select, ) __all__ = [ + "crossover_cppn_drones", "crossover_drones", + "deserialize_cppn_genome", "deserialize_genome", "evaluate_drones", + "evaluate_drones_hover_mujoco", + "initialize_cppn_drones", "initialize_drones", + "mutate_cppn_drones", "mutate_drones", "parent_tag", + "serialize_cppn_genome", "serialize_genome", "truncation_select", ] diff --git a/src/ariel/body_phenotypes/drone/genome.py b/src/ariel/body_phenotypes/drone/genome.py index 5858bca74..64964db93 100644 --- a/src/ariel/body_phenotypes/drone/genome.py +++ b/src/ariel/body_phenotypes/drone/genome.py @@ -1,14 +1,28 @@ -"""Serialization between airevolve's SphericalNeatGenome and ARIEL's JSONIterable. +"""Serialization between drone genomes and ARIEL's JSONIterable. -Genome format stored in Individual.genotype_ (SQLite JSON column): - { - "arms": [[mag, theta, phi, motor_theta, motor_phi, dir], ..., null, ...], - "innovation_ids": [0, 1, -1, ...] - } +Two formats are supported: + +1. SphericalNeatGenome (direct encoding) — fixed-size arm matrix + innovation + IDs. Empty slots are JSON null (avoids NaN-in-JSON) preserving slot + positions needed for NEAT crossover alignment:: + + { + "arms": [[mag, theta, phi, motor_theta, motor_phi, dir], ..., null, ...], + "innovation_ids": [0, 1, -1, ...] + } -Active arm slots are 6-element float lists; empty slots are JSON null (Python -None), avoiding the NaN-in-JSON problem while preserving exact slot positions -needed for NEAT crossover alignment. +2. CPPNNetwork (indirect encoding) — flat dict of nodes and connections. + Enums are stored by ``.value``:: + + { + "nodes": [{"node_id": int, "node_type": str, "activation": str, + "bias": float, "output_index": int|None, + "input_label": str|None}, ...], + "connections": [{"innovation_number": int, "source_id": int, + "target_id": int, "weight": float, + "enabled": bool}, ...], + "next_node_id": int + } """ from __future__ import annotations @@ -18,6 +32,7 @@ import numpy as np if TYPE_CHECKING: + from ariel.ec.drone.genome_handlers.cppn.network import CPPNNetwork from ariel.ec.drone.genome_handlers.spherical_angular_genome_handler import ( SphericalNeatGenome, ) @@ -60,3 +75,84 @@ def deserialize_genome(data: dict[str, Any]) -> "SphericalNeatGenome": arms[i] = arm innovation_ids = np.array(data["innovation_ids"], dtype=int) return SphericalNeatGenome(arms=arms, innovation_ids=innovation_ids) + + +def serialize_cppn_genome(genome: "CPPNNetwork") -> dict[str, Any]: + """Convert a CPPNNetwork to a JSON-serialisable dict. + + Enum-valued fields (``node_type``, ``activation``) are stored by their + ``.value`` string so the dict can be written straight into a SQLite JSON + column without custom encoders. + """ + nodes_out: list[dict[str, Any]] = [] + for node in genome.nodes.values(): + nodes_out.append( + { + "node_id": int(node.node_id), + "node_type": node.node_type.value, + "activation": node.activation.value, + "bias": float(node.bias), + "output_index": ( + int(node.output_index) if node.output_index is not None else None + ), + "input_label": node.input_label, + }, + ) + + conns_out: list[dict[str, Any]] = [] + for conn in genome.connections.values(): + conns_out.append( + { + "innovation_number": int(conn.innovation_number), + "source_id": int(conn.source_id), + "target_id": int(conn.target_id), + "weight": float(conn.weight), + "enabled": bool(conn.enabled), + }, + ) + + return { + "nodes": nodes_out, + "connections": conns_out, + "next_node_id": int(genome.next_node_id), + } + + +def deserialize_cppn_genome(data: dict[str, Any]) -> "CPPNNetwork": + """Reconstruct a CPPNNetwork from a stored dict.""" + from ariel.ec.drone.genome_handlers.cppn.network import ( + ActivationFunction, + ConnectionGene, + CPPNNetwork, + NodeGene, + NodeType, + ) + + net = CPPNNetwork() + for entry in data["nodes"]: + nid = int(entry["node_id"]) + net.nodes[nid] = NodeGene( + node_id=nid, + node_type=NodeType(entry["node_type"]), + activation=ActivationFunction(entry["activation"]), + bias=float(entry["bias"]), + output_index=( + int(entry["output_index"]) + if entry.get("output_index") is not None + else None + ), + input_label=entry.get("input_label"), + ) + + for entry in data["connections"]: + inn = int(entry["innovation_number"]) + net.connections[inn] = ConnectionGene( + innovation_number=inn, + source_id=int(entry["source_id"]), + target_id=int(entry["target_id"]), + weight=float(entry["weight"]), + enabled=bool(entry["enabled"]), + ) + + net.next_node_id = int(data.get("next_node_id", 0)) + return net diff --git a/src/ariel/body_phenotypes/drone/operations.py b/src/ariel/body_phenotypes/drone/operations.py index 70224b713..799cd2404 100644 --- a/src/ariel/body_phenotypes/drone/operations.py +++ b/src/ariel/body_phenotypes/drone/operations.py @@ -20,20 +20,31 @@ import multiprocessing as mp import os -from typing import TYPE_CHECKING, Any +import random +from typing import TYPE_CHECKING, Any, Literal import numpy as np -from ariel.body_phenotypes.drone.genome import deserialize_genome, serialize_genome +from ariel.body_phenotypes.drone.genome import ( + deserialize_cppn_genome, + deserialize_genome, + serialize_cppn_genome, + serialize_genome, +) from ariel.ec.ea import EAOperation from ariel.ec.individual import Individual from ariel.ec.population import Population if TYPE_CHECKING: + from ariel.ec.drone.genome_handlers.cppn_neat_genome_handler import ( + CPPNNeatDroneGenomeHandler, + ) from ariel.ec.drone.genome_handlers.spherical_angular_genome_handler import ( SphericalAngularDroneGenomeHandler, ) +DecoderName = Literal["spherical", "cppn"] + # --------------------------------------------------------------------------- # Multiprocessing worker — must be a module-level function for pickling @@ -207,3 +218,296 @@ def truncation_select( if i >= n: ind.alive = False return population + + +# --------------------------------------------------------------------------- +# CPPN-NEAT EAOperation factories — mirror the spherical-angular set above +# --------------------------------------------------------------------------- + + +@EAOperation +def initialize_cppn_drones( + population: Population, + template_handler: "CPPNNeatDroneGenomeHandler", +) -> Population: + """Assign random CPPN genomes to all uninitialised individuals. + + Each individual gets its own freshly generated network from the + template handler. Innovation IDs are managed by the class-level + ``_innovation_counter`` shared across all CPPN drone handlers so + that NEAT structural mutations align across generations. + """ + for ind in population: + if ind.requires_init: + child = template_handler.copy() + child.genome = template_handler._generate_random_genome() + ind.genotype = serialize_cppn_genome(child.genome) + return population + + +@EAOperation +def crossover_cppn_drones( + population: Population, + template_handler: "CPPNNeatDroneGenomeHandler", +) -> Population: + """Produce one offspring per ps-tagged pair via NEAT crossover. + + Parents must already be tagged with ``ind.tags["ps"] == True`` (use + :func:`parent_tag`). Pairs them in random order and appends one child + per pair. NEAT alignment is provided by ``CPPNNetwork`` innovation + numbers; the fitter parent's disjoint genes are inherited preferentially. + """ + parents = population.where(lambda ind: bool(ind.tags.get("ps", False))).shuffle() + for i in range(0, len(parents) - 1, 2): + pa, pb = parents[i], parents[i + 1] + + ha = template_handler.copy() + ha.genome = deserialize_cppn_genome(pa.genotype) + ha.fitness = pa.fitness_ or 0.0 + + hb = template_handler.copy() + hb.genome = deserialize_cppn_genome(pb.genotype) + hb.fitness = pb.fitness_ or 0.0 + + child_handler = ha.crossover(hb) + + child = Individual() + child.genotype = serialize_cppn_genome(child_handler.genome) + population.append(child) + return population + + +@EAOperation +def mutate_cppn_drones( + population: Population, + template_handler: "CPPNNeatDroneGenomeHandler", +) -> Population: + """Mutate every alive, unevaluated CPPN individual in place.""" + for ind in population.alive.unevaluated: + h = template_handler.copy() + h.genome = deserialize_cppn_genome(ind.genotype) + h.mutate() + ind.genotype = serialize_cppn_genome(h.genome) + return population + + +# --------------------------------------------------------------------------- +# Encoding-agnostic MuJoCo hover evaluator +# --------------------------------------------------------------------------- + + +def _decode_genotype_to_blueprint( + genotype: dict[str, Any], + decoder: DecoderName, + decoder_kwargs: dict[str, Any] | None, +): + """Worker-side dispatch: stored genotype → DroneBlueprint. + + Returns ``None`` for invalid morphologies (e.g. empty arms / failed + CPPN decode); callers translate this to a sentinel fitness. + """ + from ariel.body_phenotypes.drone.decoders import ( + spherical_angular_to_blueprint, + ) + + decoder_kwargs = dict(decoder_kwargs or {}) + + if decoder == "spherical": + genome = deserialize_genome(genotype) + valid_mask = ~np.isnan(genome.arms[:, 0]) + if not valid_mask.any(): + return None + # ``spherical_angular_to_blueprint`` ignores NaN rows itself. + propsize = int(decoder_kwargs.pop("propsize", 2)) + return spherical_angular_to_blueprint( + genome.arms, + propsize=propsize, + **decoder_kwargs, + ) + + if decoder == "cppn": + from ariel.ec.drone.genome_handlers.cppn_neat_genome_handler import ( + CPPNNeatDroneGenomeHandler, + ) + + handler_kwargs = decoder_kwargs.pop("handler_kwargs", {}) or {} + propsize = int(decoder_kwargs.pop("propsize", 2)) + net = deserialize_cppn_genome(genotype) + handler = CPPNNeatDroneGenomeHandler(genome=net, **handler_kwargs) + phenotype = handler.get_phenotype() + valid_mask = ~np.isnan(phenotype[:, 0]) + if not valid_mask.any(): + return None + return spherical_angular_to_blueprint( + phenotype, + propsize=propsize, + **decoder_kwargs, + ) + + msg = f"Unknown decoder: {decoder!r} (expected 'spherical' or 'cppn')" + raise ValueError(msg) + + +def _mujoco_hover_eval_worker( + args: tuple[ + dict[str, Any], + DecoderName, + dict[str, Any] | None, + float, + float, + tuple[float, float, float], + dict[str, float], + ], +) -> float: + """Single-individual hover evaluation. Picklable (module-level).""" + os.environ.setdefault("OMP_NUM_THREADS", "1") + os.environ.setdefault("OPENBLAS_NUM_THREADS", "1") + os.environ.setdefault("MKL_NUM_THREADS", "1") + + ( + genotype, + decoder, + decoder_kwargs, + duration, + warm_up, + target_position, + weights, + ) = args + + try: + bp = _decode_genotype_to_blueprint(genotype, decoder, decoder_kwargs) + except Exception: + return float("inf") + if bp is None: + return float("inf") + + try: + from ariel.body_phenotypes.drone.backends import blueprint_to_propellers + from ariel.simulation.drone.controllers.lee_control.lee_controller import ( + LeeGeometricControl, + ) + from ariel.simulation.drone.controllers.lee_control.mujoco_bridge import ( + LeeMujocoHoverBridge, + hover_fitness_from_log, + spawn_blueprint_in_world, + ) + from ariel.simulation.drone.drone_interface import DroneInterface + + propellers = blueprint_to_propellers(bp, convention="ned") + if not propellers: + return float("inf") + quad = DroneInterface(0, propellers=propellers) + + lee_ctrl = LeeGeometricControl( + quad, + yawType=1, + orient="NED", + auto_scale_gains=True, + pos_P_gain=np.array([14.3, 14.3, 14.3]), + vel_P_gain=np.array([9.0, 9.0, 9.0]), + ) + + spawned = spawn_blueprint_in_world( + bp, + propellers=propellers, + target_mass=float(quad.params["mB"]), + spawn_position=target_position, + ) + + bridge = LeeMujocoHoverBridge( + quad=quad, + lee_ctrl=lee_ctrl, + model=spawned.model, + data=spawned.data, + max_thrust_per_motor=spawned.max_thrust_per_motor, + target_position_enu=target_position, + ) + + log = bridge.run_hover(duration=duration, warm_up=warm_up) + return float( + hover_fitness_from_log( + log, + target_position_enu=target_position, + **weights, + ), + ) + except Exception: + return float("inf") + + +@EAOperation +def evaluate_drones_hover_mujoco( + population: Population, + decoder: DecoderName = "spherical", + decoder_kwargs: dict[str, Any] | None = None, + duration: float = 1.0, + warm_up: float = 0.1, + target_position: tuple[float, float, float] = (0.0, 0.0, 1.0), + n_workers: int = 1, + drift_weight: float = 1.0, + tilt_weight: float = 1.0, + ctrl_weight: float = 0.05, +) -> Population: + """Evaluate every alive, unevaluated individual via MuJoCo hover. + + Each genotype is decoded to a :class:`DroneBlueprint`, spawned in a + fresh ``SimpleFlatWorld``, and flown with the Lee → MuJoCo hover + bridge for ``duration`` seconds. Fitness is *lower-is-better* — set + ``is_maximisation=False`` on your :class:`EASettings`. + + Parameters + ---------- + decoder + ``"spherical"`` for ``SphericalNeatGenome`` arms, ``"cppn"`` for + :class:`CPPNNetwork` indirect encoding (decoded via + :class:`CPPNNeatDroneGenomeHandler`). + decoder_kwargs + Extra kwargs passed to the blueprint decoder. For ``"cppn"``, + must include ``handler_kwargs`` (``min_max_narms``, + ``num_segments``, ``parameter_limits``, …) so the CPPN can be + decoded back to a phenotype array. + duration, warm_up + Hover-window length and warm-up window (warm-up poses are + discarded from fitness — Lee is *active* throughout). + target_position + ENU hover setpoint. + n_workers + ``1`` runs in-process; higher values fan out across a + ``multiprocessing.Pool`` with the ``spawn`` start method. + drift_weight, tilt_weight, ctrl_weight + Forwarded to :func:`hover_fitness_from_log`. + """ + weights = { + "drift_weight": float(drift_weight), + "tilt_weight": float(tilt_weight), + "ctrl_weight": float(ctrl_weight), + } + + to_eval = [ind for ind in population.alive.unevaluated] + if not to_eval: + return population + + tasks = [ + ( + ind.genotype, + decoder, + decoder_kwargs, + float(duration), + float(warm_up), + tuple(target_position), + weights, + ) + for ind in to_eval + ] + + if n_workers == 1: + fitnesses = [_mujoco_hover_eval_worker(t) for t in tasks] + else: + ctx = mp.get_context("spawn") + with ctx.Pool(processes=int(n_workers)) as pool: + fitnesses = pool.map(_mujoco_hover_eval_worker, tasks) + + for ind, fit in zip(to_eval, fitnesses, strict=True): + ind.fitness = float(fit) + + return population diff --git a/src/ariel/simulation/drone/controllers/lee_control/mujoco_bridge.py b/src/ariel/simulation/drone/controllers/lee_control/mujoco_bridge.py new file mode 100644 index 000000000..3f75d1226 --- /dev/null +++ b/src/ariel/simulation/drone/controllers/lee_control/mujoco_bridge.py @@ -0,0 +1,424 @@ +"""Drive a MuJoCo-spawned drone with airevolve's Lee geometric controller. + +MuJoCo is the physics integrator (Z-up / ENU); Lee runs purely as a control +*policy* in NED. Each step the bridge: + +1. Reads drone state from MuJoCo (``data.qpos`` / ``data.qvel``). +2. Converts ENU → NED (flip ``z`` of position/velocity, flip ``y`` of + quaternion — same convention as example 15's NED→ENU return trip). +3. Forcibly writes the converted state into the underlying + :class:`~ariel.simulation.drone.drone_interface.DroneInterface` and + refreshes its cached state. +4. Calls :meth:`LeeGeometricControl.controller`, updating ``ctrl.w_cmd`` + (per-motor steady-state speed in rad/s). +5. Converts each ``w_cmd[i]`` to a normalised MuJoCo actuator command + ``ctrl_i = (kf * w_cmd[i]²) / max_thrust`` (clipped to ``[0, 1]``), + and writes ``data.ctrl[:]``. + +The caller drives the simulation with :func:`mujoco.mj_step`. The Lee +controller never integrates the Python NED simulator state — the state +is overwritten from MuJoCo every step, so the two never diverge. + +A helper :func:`spawn_blueprint_in_world` builds a mass-matched MuJoCo +model from a :class:`DroneBlueprint` (same mass-matching strategy as +``examples/d_drones/15_cppn_neat_circle_to_mujoco.py``). +""" +from __future__ import annotations + +from dataclasses import dataclass +from typing import TYPE_CHECKING, Optional + +import numpy as np + +if TYPE_CHECKING: + import mujoco + + from ariel.body_phenotypes.drone.blueprint import DroneBlueprint + from ariel.simulation.environments import SimpleFlatWorld + + +# --------------------------------------------------------------------------- +# Frame conversion helpers (ENU ↔ NED) +# --------------------------------------------------------------------------- + +def enu_to_ned_pos(pos_enu: np.ndarray) -> np.ndarray: + """Convert a Cartesian position vector from ENU (Z-up) to NED (Z-down).""" + return np.array( + [float(pos_enu[0]), float(pos_enu[1]), -float(pos_enu[2])], + dtype=np.float64, + ) + + +def enu_to_ned_vel(vel_enu: np.ndarray) -> np.ndarray: + """Convert a velocity vector from ENU to NED (negate the vertical).""" + return enu_to_ned_pos(vel_enu) + + +def enu_to_ned_quat(quat_enu_wxyz: np.ndarray) -> np.ndarray: + """Flip the ``y`` component of a MuJoCo (w, x, y, z) quaternion. + + Mirrors the inverse mapping used in example 15 + (``quat_enu[:, 2] = -quat_enu[:, 2]``) — the same axis flip is its + own inverse, so MuJoCo's quaternion converts to NED by negating ``q.y``. + """ + q = np.asarray(quat_enu_wxyz, dtype=np.float64).copy() + q[2] = -q[2] + return q + + +def quat_wxyz_to_euler_zyx(q: np.ndarray) -> tuple[float, float, float]: + """Convert a (w, x, y, z) quaternion to (roll, pitch, yaw) ZYX intrinsic.""" + w, x, y, z = (float(v) for v in q) + sinr_cosp = 2.0 * (w * x + y * z) + cosr_cosp = 1.0 - 2.0 * (x * x + y * y) + roll = float(np.arctan2(sinr_cosp, cosr_cosp)) + + sinp = 2.0 * (w * y - z * x) + sinp = max(-1.0, min(1.0, sinp)) + pitch = float(np.arcsin(sinp)) + + siny_cosp = 2.0 * (w * z + x * y) + cosy_cosp = 1.0 - 2.0 * (y * y + z * z) + yaw = float(np.arctan2(siny_cosp, cosy_cosp)) + return roll, pitch, yaw + + +# --------------------------------------------------------------------------- +# Mass-matched spawn helper +# --------------------------------------------------------------------------- + +@dataclass +class SpawnedDrone: + """Container for the MuJoCo model/data plus mass-matching diagnostics.""" + world: "SimpleFlatWorld" + model: "mujoco.MjModel" + data: "mujoco.MjData" + body_name: str + core_mass: float + motor_mass_each: float + arm_mass_each: float + n_motors: int + max_thrust_per_motor: float + + +def spawn_blueprint_in_world( + bp: "DroneBlueprint", + *, + propellers: list[dict], + target_mass: float, + spawn_position: tuple[float, float, float] = (0.0, 0.0, 1.0), + body_name: str = "drone", + arm_mass_per_length: float = 0.034, + safety_margin: float = 1.10, +) -> SpawnedDrone: + """Spawn a drone in a ``SimpleFlatWorld`` with masses matched to Lee's params. + + The MuJoCo body's lumped mass equals ``target_mass`` (Lee's ``mB``): + motors come from the propeller config, arms scale with their length, + and the core absorbs the remainder. Per-motor max thrust is sized to + ``safety_margin * kf * wmax²`` so the bridge's saturation matches Lee's. + + Parameters + ---------- + bp + Blueprint to compile to MJCF. + propellers + The list returned by ``blueprint_to_propellers(bp, convention='ned')``. + Used here only to fetch the prop ``mass``, ``constants`` and + ``wmax`` for actuator sizing. + target_mass + Drone total mass (Lee's ``quad.params['mB']``). + spawn_position + ENU spawn position in metres. + body_name + Root body name in the MJCF. + arm_mass_per_length + Linear-density coefficient for the arm visual mass. + safety_margin + ``max_thrust`` per actuator is scaled by this factor over + ``kf * wmax²`` to give MuJoCo a small extra ceiling. + + Returns + ------- + SpawnedDrone + """ + import mujoco + + from ariel.body_phenotypes.drone.backends import blueprint_to_mjspec + from ariel.body_phenotypes.drone.blueprint import ArmNode + from ariel.simulation.environments import SimpleFlatWorld + + if not propellers: + msg = "spawn_blueprint_in_world requires a non-empty propellers list." + raise ValueError(msg) + + arm_ids = [a for a in bp.children(bp.root_id) if isinstance(bp.payload(a), ArmNode)] + arm_lengths = [bp.payload(a).length for a in arm_ids] + mean_arm_len = float(np.mean(arm_lengths)) if arm_lengths else 0.06 + n_motors = len(propellers) + motor_mass_each = float(propellers[0]["mass"]) + arm_mass_each = arm_mass_per_length * mean_arm_len + core_mass = max(1e-4, target_mass - n_motors * (motor_mass_each + arm_mass_each)) + + kf = float(propellers[0]["constants"][0]) + wmax = float(propellers[0]["wmax"]) + max_thrust_per_motor = safety_margin * kf * wmax * wmax + + spec = blueprint_to_mjspec( + bp, + motor_mass=motor_mass_each, + arm_mass=arm_mass_each, + core_mass_override=core_mass, + max_thrust=max_thrust_per_motor, + body_name=body_name, + ) + + world = SimpleFlatWorld() + world.spawn(spec, position=spawn_position, correct_collision_with_floor=False) + model = world.spec.compile() + data = mujoco.MjData(model) + + return SpawnedDrone( + world=world, + model=model, + data=data, + body_name=body_name, + core_mass=core_mass, + motor_mass_each=motor_mass_each, + arm_mass_each=arm_mass_each, + n_motors=n_motors, + max_thrust_per_motor=max_thrust_per_motor, + ) + + +# --------------------------------------------------------------------------- +# Bridge +# --------------------------------------------------------------------------- + +class LeeMujocoHoverBridge: + """Per-step Lee → MuJoCo control bridge for a single drone. + + Build one of these once per individual, then call :meth:`step` inside + your MuJoCo simulation loop. ``data.ctrl[:]`` is updated in place; the + caller is responsible for invoking :func:`mujoco.mj_step` afterwards. + """ + + def __init__( + self, + *, + quad, # DroneInterface + lee_ctrl, # LeeGeometricControl (orient="NED") + model: "mujoco.MjModel", + data: "mujoco.MjData", + max_thrust_per_motor: float, + ctrl_type: str = "xyz_pos", + target_position_enu: np.ndarray | tuple[float, float, float] = (0.0, 0.0, 1.0), + target_yaw: float = 0.0, + timestep: Optional[float] = None, + ) -> None: + self.quad = quad + self.lee_ctrl = lee_ctrl + self.model = model + self.data = data + self.max_thrust_per_motor = float(max_thrust_per_motor) + self.ctrl_type = ctrl_type + self.target_position_enu = np.asarray(target_position_enu, dtype=np.float64) + self.target_yaw = float(target_yaw) + self.timestep = float(timestep if timestep is not None else model.opt.timestep) + + # Pre-build the desired-state vector (Lee expects 19 elements): + # [pos(3), vel(3), acc(3), thrust(3), eul(3), pqr(3), yawRate] + target_ned = enu_to_ned_pos(self.target_position_enu) + self._sDes = np.zeros(19, dtype=np.float64) + self._sDes[0:3] = target_ned + self._sDes[12:15] = (0.0, 0.0, self.target_yaw) + + # Cache thrust normalisation constants from the propeller config. + first_prop = self.quad.drone_sim.config.propellers[0] + self._kf = float(first_prop["constants"][0]) + + # ------------------------------------------------------------------ + # State conversion + # ------------------------------------------------------------------ + + def _push_mujoco_state_into_quad(self) -> None: + """Copy MuJoCo state into ``quad`` (NED frame) without round-tripping + through Euler angles. + + Lee reads ``quad.pos``, ``quad.vel``, ``quad.quat``, ``quad.omega`` + and ``quad.euler``. We populate all five from the MuJoCo state + directly so we never pass through ``DroneSimulator.set_state``'s + Euler representation (which loses precision near gimbal lock and + was the source of a slow hover divergence). + """ + pos_enu = np.asarray(self.data.qpos[0:3], dtype=np.float64).copy() + quat_enu_wxyz = np.asarray(self.data.qpos[3:7], dtype=np.float64).copy() + vel_enu = np.asarray(self.data.qvel[0:3], dtype=np.float64).copy() + # For a free joint, qvel[3:6] holds the body-frame angular velocity. + angvel_body = np.asarray(self.data.qvel[3:6], dtype=np.float64).copy() + + # Renormalise the quaternion before applying — MuJoCo integration + # can drift its norm by a small epsilon over many steps. + n = float(np.linalg.norm(quat_enu_wxyz)) + if n > 1e-9: + quat_enu_wxyz /= n + + pos_ned = enu_to_ned_pos(pos_enu) + vel_ned = enu_to_ned_vel(vel_enu) + quat_ned = enu_to_ned_quat(quat_enu_wxyz) + roll, pitch, yaw = quat_wxyz_to_euler_zyx(quat_ned) + euler = np.array([roll, pitch, yaw], dtype=np.float64) + + # Bypass DroneSimulator.set_state() (which stores Euler and rebuilds + # quat from it) — write the canonical Lee-readable fields directly. + self.quad.pos = pos_ned + self.quad.vel = vel_ned + self.quad.quat = quat_ned + self.quad.omega = angvel_body + self.quad.euler = euler + self.quad.phi, self.quad.theta, self.quad.psi = roll, pitch, yaw + + # ------------------------------------------------------------------ + # Step + # ------------------------------------------------------------------ + + def step(self) -> np.ndarray: + """Update ``data.ctrl[:]`` for one step. Returns the issued ctrl vector. + + Does NOT advance the simulation — call :func:`mujoco.mj_step` yourself. + """ + self._push_mujoco_state_into_quad() + + self.lee_ctrl.controller(self._sDes, self.quad, self.ctrl_type, self.timestep) + + w_cmd = np.asarray(self.lee_ctrl.w_cmd, dtype=np.float64) + thrust_per_motor = self._kf * w_cmd * w_cmd + ctrl = np.clip(thrust_per_motor / self.max_thrust_per_motor, 0.0, 1.0) + + n = min(ctrl.size, self.data.ctrl.size) + self.data.ctrl[:n] = ctrl[:n] + if self.data.ctrl.size > n: + self.data.ctrl[n:] = 0.0 + return self.data.ctrl.copy() + + # ------------------------------------------------------------------ + # Convenience: full hover rollout + # ------------------------------------------------------------------ + + def reset_pose( + self, + *, + position_enu: np.ndarray | tuple[float, float, float] | None = None, + quat_wxyz: np.ndarray | tuple[float, float, float, float] = (1.0, 0.0, 0.0, 0.0), + ) -> None: + """Reset the MuJoCo drone to an identity attitude (or supplied pose). + + Always zeroes ``qvel``. Useful before a hover rollout so the drone + doesn't carry over any residual velocity from the previous run. + """ + import mujoco + + mujoco.mj_resetData(self.model, self.data) + if position_enu is None: + position_enu = self.target_position_enu + self.data.qpos[0:3] = [float(v) for v in position_enu] + self.data.qpos[3:7] = [float(v) for v in quat_wxyz] + self.data.qvel[:] = 0.0 + self.data.ctrl[:] = 0.0 + mujoco.mj_forward(self.model, self.data) + + def run_hover( + self, + *, + duration: float, + warm_up: float = 0.0, + log_pose: bool = False, + reset: bool = True, + ) -> dict[str, np.ndarray]: + """Step the MuJoCo simulation for ``duration`` seconds. + + Lee is active throughout (including any ``warm_up`` window) so the + drone never free-falls. The warm-up only governs *logging*: poses + within it are discarded, so initial controller transients don't + contaminate the fitness signal. When ``reset=True`` (default) the + drone is placed at the target pose with zero velocity before stepping. + + Returns a dict with logged arrays (always 'pos', 'tilt_cos', + 'ctrl_norm'; 'quat' added when ``log_pose=True``). + """ + import mujoco + + if reset: + self.reset_pose() + + steps_total = int(round(duration / self.timestep)) + steps_warm = int(round(max(0.0, warm_up) / self.timestep)) + + n_logged = max(0, steps_total - steps_warm) + pos_log = np.zeros((n_logged, 3), dtype=np.float64) + tilt_log = np.zeros(n_logged, dtype=np.float64) + ctrl_norm_log = np.zeros(n_logged, dtype=np.float64) + quat_log = np.zeros((n_logged, 4), dtype=np.float64) if log_pose else None + + log_idx = 0 + for step_i in range(steps_total): + self.step() + mujoco.mj_step(self.model, self.data) + + if step_i >= steps_warm: + pos_log[log_idx] = self.data.qpos[0:3] + w, x, y, z = self.data.qpos[3:7] + # Tilt cosine: world-+Z projected onto body-+Z. For (w,x,y,z), + # the (3,3) entry of the rotation matrix is 1 - 2(x² + y²). + tilt_log[log_idx] = 1.0 - 2.0 * (x * x + y * y) + ctrl_norm_log[log_idx] = float(np.mean(self.data.ctrl ** 2)) + if quat_log is not None: + quat_log[log_idx] = (w, x, y, z) + log_idx += 1 + + out: dict[str, np.ndarray] = { + "pos": pos_log[:log_idx], + "tilt_cos": tilt_log[:log_idx], + "ctrl_norm": ctrl_norm_log[:log_idx], + } + if quat_log is not None: + out["quat"] = quat_log[:log_idx] + return out + + +# --------------------------------------------------------------------------- +# High-level fitness computation +# --------------------------------------------------------------------------- + +def hover_fitness_from_log( + log: dict[str, np.ndarray], + *, + target_position_enu: np.ndarray | tuple[float, float, float], + drift_weight: float = 1.0, + tilt_weight: float = 1.0, + ctrl_weight: float = 0.05, +) -> float: + """Combined hover-stability fitness (lower is better). + + :: + + fit = mean(|z - z_target|) + + drift_weight * mean(sqrt((x-xt)² + (y-yt)²)) + + tilt_weight * mean(1 - cos θ_tilt) + + ctrl_weight * mean(ctrl²) + + Spawn failures (empty log) return ``+inf``. + """ + pos = log["pos"] + if pos.size == 0: + return float("inf") + target = np.asarray(target_position_enu, dtype=np.float64) + dz = np.abs(pos[:, 2] - target[2]) + dxy = np.sqrt((pos[:, 0] - target[0]) ** 2 + (pos[:, 1] - target[1]) ** 2) + tilt_dev = 1.0 - np.clip(log["tilt_cos"], -1.0, 1.0) + return float( + np.mean(dz) + + drift_weight * np.mean(dxy) + + tilt_weight * np.mean(tilt_dev) + + ctrl_weight * float(np.mean(log["ctrl_norm"])), + ) diff --git a/tests/unit/test_drone_ec/__init__.py b/tests/unit/test_drone_ec/__init__.py new file mode 100644 index 000000000..2d299497a --- /dev/null +++ b/tests/unit/test_drone_ec/__init__.py @@ -0,0 +1 @@ +"""Tests for ARIEL-EA + drone-blueprint integration.""" diff --git a/tests/unit/test_drone_ec/test_drone_ec_integration.py b/tests/unit/test_drone_ec/test_drone_ec_integration.py new file mode 100644 index 000000000..07ce6cd5b --- /dev/null +++ b/tests/unit/test_drone_ec/test_drone_ec_integration.py @@ -0,0 +1,148 @@ +"""End-to-end smoke tests for the e_drones_ec evaluator pipeline. + +Drives one tiny generation of each encoding (spherical + CPPN-NEAT) +through ARIEL's EA pipeline using the new MuJoCo hover evaluator. The +tests don't check the *value* of fitness — only that the pipeline runs +without crashes and produces at least one individual with finite +fitness. +""" +from __future__ import annotations + +import numpy as np +import pytest + + +@pytest.mark.timeout(120) +def test_spherical_evaluator_runs_end_to_end(tmp_path) -> None: + from ariel.body_phenotypes.drone import ( + crossover_drones, + evaluate_drones_hover_mujoco, + initialize_drones, + mutate_drones, + parent_tag, + truncation_select, + ) + from ariel.ec import EA, Individual, Population + from ariel.ec.drone.genome_handlers.spherical_angular_genome_handler import ( + SphericalAngularDroneGenomeHandler, + ) + + parameter_limits = np.array([ + [0.055, 0.17], + [-np.pi, np.pi], + [-np.pi / 2, np.pi / 2], + [-np.pi, np.pi], + [-np.pi, np.pi], + [0, 1], + ]) + handler = SphericalAngularDroneGenomeHandler( + min_max_narms=(4, 6), + parameter_limits=parameter_limits, + append_arm_chance=0.1, + bilateral_plane_for_symmetry=None, + repair=False, + rnd=np.random.default_rng(0), + ) + + pop = Population([Individual() for _ in range(2)]) + init_op = initialize_drones(template_handler=handler) + eval_op = evaluate_drones_hover_mujoco( + decoder="spherical", + decoder_kwargs={"propsize": 2}, + duration=0.4, + warm_up=0.05, + target_position=(0.0, 0.0, 1.0), + n_workers=1, + ) + pop = init_op(pop) + pop = eval_op(pop) + + ops = [ + parent_tag(n=2), + crossover_drones(template_handler=handler), + mutate_drones(template_handler=handler), + eval_op, + truncation_select(n=2), + ] + ea = EA( + population=pop, + operations=ops, + num_steps=1, + db_file_path=tmp_path / "spherical.db", + db_handling="delete", + ) + ea.run() + ea.fetch_population(only_alive=False, requires_eval=False) + + fits = [ + ind.fitness_ for ind in ea.population + if ind.fitness_ is not None and np.isfinite(ind.fitness_) + ] + assert fits, "no individual produced a finite hover fitness" + + +@pytest.mark.timeout(120) +def test_cppn_evaluator_runs_end_to_end(tmp_path) -> None: + from ariel.body_phenotypes.drone import ( + crossover_cppn_drones, + evaluate_drones_hover_mujoco, + initialize_cppn_drones, + mutate_cppn_drones, + parent_tag, + truncation_select, + ) + from ariel.ec import EA, Individual, Population + from ariel.ec.drone.genome_handlers.cppn_neat_genome_handler import ( + CPPNNeatDroneGenomeHandler, + ) + + handler_kwargs = { + "num_segments": 8, + "min_max_narms": (4, 6), + "parameter_limits": np.array([ + [0.055, 0.17], + [-np.pi, np.pi], + [-np.pi / 2, np.pi / 2], + [-np.pi, np.pi], + [-np.pi, np.pi], + [0, 1], + ]), + "repair": True, + } + template = CPPNNeatDroneGenomeHandler(rng=np.random.default_rng(0), **handler_kwargs) + + pop = Population([Individual() for _ in range(2)]) + init_op = initialize_cppn_drones(template_handler=template) + eval_op = evaluate_drones_hover_mujoco( + decoder="cppn", + decoder_kwargs={"propsize": 2, "handler_kwargs": handler_kwargs}, + duration=0.4, + warm_up=0.05, + target_position=(0.0, 0.0, 1.0), + n_workers=1, + ) + pop = init_op(pop) + pop = eval_op(pop) + + ops = [ + parent_tag(n=2), + crossover_cppn_drones(template_handler=template), + mutate_cppn_drones(template_handler=template), + eval_op, + truncation_select(n=2), + ] + ea = EA( + population=pop, + operations=ops, + num_steps=1, + db_file_path=tmp_path / "cppn.db", + db_handling="delete", + ) + ea.run() + ea.fetch_population(only_alive=False, requires_eval=False) + + fits = [ + ind.fitness_ for ind in ea.population + if ind.fitness_ is not None and np.isfinite(ind.fitness_) + ] + assert fits, "no CPPN individual produced a finite hover fitness" diff --git a/tests/unit/test_drone_ec/test_lee_mujoco_bridge.py b/tests/unit/test_drone_ec/test_lee_mujoco_bridge.py new file mode 100644 index 000000000..696e89751 --- /dev/null +++ b/tests/unit/test_drone_ec/test_lee_mujoco_bridge.py @@ -0,0 +1,102 @@ +"""Sanity test: STANDARD_HEXACOPTER hovers under the Lee→MuJoCo bridge. + +De-risks the bridge before the EA examples depend on it. The test builds the +canonical hexacopter (from UnifiedFitness's edit-distance target), spawns it +in MuJoCo via blueprint_to_mjspec, drives it with the bridge for a few +seconds at a target altitude, and asserts altitude stays within a generous +tolerance and the drone has not tumbled. +""" +from __future__ import annotations + +import numpy as np +import pytest + + +@pytest.mark.timeout(60) +def test_standard_hexacopter_hovers_with_bridge() -> None: + """STANDARD_HEXACOPTER should hold altitude within ±0.5 m for 3 s of hover. + + These tolerances are intentionally loose — the goal is to catch + catastrophic regressions (motor saturation, frame conversion, mass + mismatch). If the drone holds within ±0.5 m without tumbling, the + bridge is wired up correctly enough to drive evolution. + """ + import mujoco # noqa: F401 (imported for early-fail if mujoco isn't available) + + from ariel.body_phenotypes.drone.backends import blueprint_to_propellers + from ariel.body_phenotypes.drone.decoders import spherical_angular_to_blueprint + from ariel.ec.drone.evaluators.unified_fitness import STANDARD_HEXACOPTER + from ariel.simulation.drone.controllers.lee_control.lee_controller import ( + LeeGeometricControl, + ) + from ariel.simulation.drone.controllers.lee_control.mujoco_bridge import ( + LeeMujocoHoverBridge, + hover_fitness_from_log, + spawn_blueprint_in_world, + ) + from ariel.simulation.drone.drone_interface import DroneInterface + + # --- Build the canonical hexacopter blueprint -------------------------- + bp = spherical_angular_to_blueprint(STANDARD_HEXACOPTER, propsize=2) + + # --- Build the Python NED simulator (Lee's policy needs a `quad` handle) -- + propellers = blueprint_to_propellers(bp, convention="ned") + quad = DroneInterface(0, propellers=propellers) + + lee_ctrl = LeeGeometricControl( + quad, + yawType=1, + orient="NED", + auto_scale_gains=True, + pos_P_gain=np.array([14.3, 14.3, 14.3]), + vel_P_gain=np.array([9.0, 9.0, 9.0]), + ) + + # --- Spawn in MuJoCo with mass-matched body --------------------------- + target_alt = 1.0 + spawned = spawn_blueprint_in_world( + bp, + propellers=propellers, + target_mass=float(quad.params["mB"]), + spawn_position=(0.0, 0.0, target_alt), + body_name="hex", + ) + + bridge = LeeMujocoHoverBridge( + quad=quad, + lee_ctrl=lee_ctrl, + model=spawned.model, + data=spawned.data, + max_thrust_per_motor=spawned.max_thrust_per_motor, + target_position_enu=(0.0, 0.0, target_alt), + ) + + # --- Hover ------------------------------------------------------------ + # 1.0 s window matches the duration used by the EA evaluator. Long-horizon + # (>~1.5 s) Lee→MuJoCo hover stability is a known follow-up issue. + log = bridge.run_hover(duration=1.0, warm_up=0.1) + assert log["pos"].shape[0] > 0, "hover loop produced no logged poses" + + z = log["pos"][:, 2] + xy = np.linalg.norm(log["pos"][:, :2], axis=1) + tilt_cos = np.clip(log["tilt_cos"], -1.0, 1.0) + + assert np.all(np.isfinite(z)), "altitude went non-finite during hover" + + z_err = float(np.max(np.abs(z - target_alt))) + xy_drift = float(np.max(xy)) + min_tilt_cos = float(np.min(tilt_cos)) + + # Generous tolerances — the goal is to catch catastrophic regressions + # (motor saturation, frame conversion, mass mismatch), not require + # millimetre hover precision. + assert z_err < 0.3, f"altitude error too large: max|z - target| = {z_err:.3f} m" + assert xy_drift < 0.3, f"lateral drift too large: max |xy| = {xy_drift:.3f} m" + # cos(45°) ≈ 0.707; anything below this means the drone has rolled / + # pitched far past sane hover orientations. + assert min_tilt_cos > 0.7, f"drone tumbled: min cos(tilt) = {min_tilt_cos:.3f}" + + # Sanity: the high-level fitness helper should give a finite, sensible score. + fit = hover_fitness_from_log(log, target_position_enu=(0.0, 0.0, target_alt)) + assert np.isfinite(fit), "hover_fitness_from_log returned non-finite score" + assert fit < 0.3, f"hover fitness is implausibly high: {fit:.3f}" From 23267de9334ce44095d9d8bfbfdcb0ae4fa48b56 Mon Sep 17 00:00:00 2001 From: Keiichi Ito Date: Sun, 24 May 2026 15:51:34 +0200 Subject: [PATCH 09/27] Add blueprint_to_urdf stub. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Sketches the planned URDF backend (Isaac Lab UrdfConverter as the URDF→USD half) alongside the existing blueprint_to_usd stub. Co-Authored-By: Claude Opus 4.7 --- src/ariel/body_phenotypes/drone/backends.py | 46 +++++++++++++++++++++ 1 file changed, 46 insertions(+) diff --git a/src/ariel/body_phenotypes/drone/backends.py b/src/ariel/body_phenotypes/drone/backends.py index b0d4e294b..11d2141ea 100644 --- a/src/ariel/body_phenotypes/drone/backends.py +++ b/src/ariel/body_phenotypes/drone/backends.py @@ -11,7 +11,10 @@ Stubs sketched for future backends: + * ``blueprint_to_urdf`` — URDF file; can be fed to Isaac Lab's + ``UrdfConverter`` to produce a USD asset. * ``blueprint_to_usd`` — USD prim hierarchy for Isaac Lab + (direct, no URDF intermediate). """ from __future__ import annotations @@ -285,6 +288,49 @@ def _rpy_to_quat(roll: float, pitch: float, yaw: float) -> list[float]: # ---------- future backends (signatures only) ---------- +def blueprint_to_urdf( + bp: DroneBlueprint, + out_path: str, + *, + motor_mass: float = 0.05, + arm_mass: float = 0.01, + core_mass_override: float | None = None, + arm_radius: float = 0.005, + motor_radius: float = 0.015, + motor_thickness: float = 0.008, + robot_name: str = "drone", +) -> str: + """Compile a DroneBlueprint into a URDF file. + + Intended as the intermediate step for Isaac Lab / Isaac Sim: the + emitted ``.urdf`` is consumed by + ``isaaclab.sim.converters.UrdfConverter`` to produce a USD asset + (see ``soft_airframe_optimization/scripts/convert_xconfig_urdf.py`` + for the conversion call pattern). + + Planned mapping (mirrors ``blueprint_to_mjspec``): + * One ```` per blueprint node (CorePlate, Arm, Motor) with + an analytically-computed ```` block for the primitive + shape. + * One ```` per parent-child edge. Default is + ``type="fixed"`` (rigid drone). A future ``CompliantJoint`` + annotation on ``ArmNode`` would emit ``type="revolute"`` with + ````; the non-linear ``τ(θ)`` law is + stashed as sidecar attributes for a runtime controller to apply + (same two-layer pattern soft_airframe uses with ``morphy:*`` + USD attributes). + * Capsule arms are approximated as cylinders — URDF has no + capsule primitive. + + Not yet implemented. + """ + raise NotImplementedError( + "blueprint_to_urdf is not yet implemented. " + "Use blueprint_to_mjspec for MuJoCo, or blueprint_to_propellers " + "for the Python physics stack." + ) + + def blueprint_to_usd(bp: DroneBlueprint, out_path: str) -> str: """Compile a DroneBlueprint into a USD file for Isaac Lab. From 8a0f1de3e7672a9189c72f01b586b88497ebcf1a Mon Sep 17 00:00:00 2001 From: Keiichi Ito Date: Sun, 24 May 2026 18:35:24 +0200 Subject: [PATCH 10/27] Derive arm and motor physical params from blueprint nodes. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Schema refactor preparing for blueprint_to_urdf. Mass and inertia are now read off the Blueprint nodes themselves rather than passed as backend kwargs, so MJCF / URDF / future USD backends share one source of truth. - blueprint.py: add CylindricalCrossSection / HollowTubeCrossSection / RectangularCrossSection sub-objects, each with `area` and `principal_inertia(length, mass)`. Extend ArmNode with `density` + `cross_section` + derived `mass` / `inertia_diag` properties. Extend MotorNode with derived `mass` / `radius` / `thickness` / `inertia_diag` via PROPELLER_LIBRARY lookup. Default cross-section is HollowTube (4mm OD / 3mm ID) which with density=1500 kg/m³ reproduces existing BEAM_DENSITY = 0.034 kg/m. Extend from_dict to rebuild cross_section sub-dataclasses on load. - propeller_data.py: add motor_radius / motor_thickness per prop entry, values from the APC propeller-motor pairing table — outer-can radius plateaus at ~14mm for prop5+ (all use 22mm-class stators), only thickness grows. - backends.py: blueprint_to_mjspec drops motor_mass / arm_mass / arm_radius / motor_radius / motor_thickness kwargs, reads from node properties, dispatches arm geometry on isinstance(cross_section, …) (capsule for circular, box for rectangular). blueprint_to_urdf stub signature trimmed to match. - DRONE_BLUEPRINT_PLAN.md: Phase 3 marked in-progress, blueprint_to_mjspec description refreshed, new §6 Design decisions captures the 11 choices made on this branch (URDF-first vs direct USD, hybrid mass model, cross-section sub-object, compliant-joint two-layer pattern, etc.). Co-Authored-By: Claude Opus 4.7 --- DRONE_BLUEPRINT_PLAN.md | 121 ++++++++++++++++-- src/ariel/body_phenotypes/drone/backends.py | 87 ++++++++----- src/ariel/body_phenotypes/drone/blueprint.py | 122 ++++++++++++++++++- src/ariel/simulation/drone/propeller_data.py | 24 ++++ 4 files changed, 315 insertions(+), 39 deletions(-) diff --git a/DRONE_BLUEPRINT_PLAN.md b/DRONE_BLUEPRINT_PLAN.md index 30050b03c..71f25d3fe 100644 --- a/DRONE_BLUEPRINT_PLAN.md +++ b/DRONE_BLUEPRINT_PLAN.md @@ -132,9 +132,12 @@ now go through `DroneBlueprint` rather than the phenotype generator directly. Arm, motor cylinders + thin rotor discs, and one `mjTRN_SITE` thrust actuator per rotor (`ctrl ∈ [0,1] → F ∈ [0, max_thrust]` along the rotor's spin axis). - Accepts `motor_mass`, `arm_mass`, `core_mass_override` so the MuJoCo - body mass can be matched to whatever `DroneConfiguration` auto-computes. - - `blueprint_to_usd` still a stub. + Physical parameters (`arm.mass`, `arm.inertia_diag`, `motor.mass`, + `motor.radius`, `motor.thickness`) are read from the blueprint nodes + themselves; only `core_mass_override` survives as a tuning kwarg. + - `blueprint_to_urdf` stub on `blueprint-to-urdf` branch; intermediate + for the Isaac Lab path via `isaaclab.sim.converters.UrdfConverter`. + - `blueprint_to_usd` still a stub (direct-USD path deferred behind URDF). - Examples: - `examples/d_drones/11_blueprint_demo.py` — two encodings → same blueprint format → identical `DroneConfiguration` mass/inertia. @@ -162,11 +165,115 @@ now go through `DroneBlueprint` rather than the phenotype generator directly. upstream fix before closed-loop MuJoCo Lee control is possible without the bridge. -**Phase 3 — Isaac Lab spike. Not started.** USD backend remains stubbed; -the MJCF backend is structured so a USD compiler maps node-for-node from -the same blueprint tree. +**Phase 3 — Isaac Lab spike. In progress (branch `blueprint-to-urdf`).** +Approach: Blueprint → URDF → USD via Isaac Lab's `UrdfConverter`, not a +direct `blueprint_to_usd`. Schema refactor landed on the branch so +backends read physical parameters from the Blueprint nodes themselves +(see §6). `blueprint_to_urdf` body is the next step. Direct +`blueprint_to_usd` remains stubbed and now sits *behind* URDF in the +roadmap. -## 6. Asks for the meeting +## 6. Design decisions (Phase 3 — URDF / USD backends) + +Each entry: **decision** — *why*; alternatives considered. + +1. **URDF as the intermediate to USD, not direct `pxr`.** URDF is plain + XML, no new dependency, and verifiable without an Isaac Sim install; + the Blueprint tree maps 1:1 to URDF ``/``. The + soft_airframe project already exercises the URDF→USD half via + `isaaclab.sim.converters.UrdfConverter` (see + `soft_airframe_optimization/scripts/convert_xconfig_urdf.py`). Direct + USD emission with `pxr` is feasible but harder to author and verify + from outside an Isaac Lab environment; deferred behind the URDF route. + +2. **Hybrid mass model: density-volumetric for arms, propsize lookup for + motors, inertia always derived.** Arms have homogeneous geometry the + EA can evolve (length, radius/width), so `mass = density × area × + length` is the right physical model. Motors are catalog parts whose + mass correlates with `propsize`, not arbitrary cylinder volume, so a + `propsize → mass` lookup matches reality and the existing + `propeller_data.PROPELLER_LIBRARY` pattern (which already keys `k_f`, + `k_m`, `wmax` on propsize). Inertia tensors are always derived from + shape + mass — nobody hand-authors `Ixx/Iyy/Izz` on a genotype. + Alternatives: store `mass` directly on every node (no shape↔mass + coupling, lets EA evolve impossibly heavy 1m arms); density-only for + motors (meaningless — motor isn't a homogeneous cylinder). + +3. **Derived properties live on the Blueprint node dataclasses, not in + backends.** `@property mass`, `@property inertia_diag` on `ArmNode` / + `MotorNode`. Backends (MJCF, URDF, USD) just call `arm.mass`. Single + source of truth; formulas tested once; backends can't drift. + Alternatives: a helper module (extra indirection, no enforcement); + per-backend duplication (drift risk). + +4. **`CorePlateNode.mass` stays a primary field.** The core is a lumped + controller + battery mass (cf. `propeller_data.CONTROLLER_MASS + + BATTERY_MASS = 0.0568 kg` baseline; ariel's default `0.4 kg` is the + larger ref build), not a homogeneous geometric solid. Deriving it + from `density × disc volume` would be physically meaningless. Also + keeps existing `decoders.py` `CorePlateNode(mass=core_mass)` call + working unchanged. + +5. **Cross-section is a tagged sub-object on `ArmNode`, not flat + fields.** Three classes: `CylindricalCrossSection`, + `HollowTubeCrossSection`, `RectangularCrossSection`. Each exposes + `area` (property) and `principal_inertia(length, mass)` (method). + `arm.mass` and `arm.inertia_diag` work uniformly regardless of shape. + Adding a new section (e.g. hollow box, I-beam) is one new dataclass, + no backend changes for mass/inertia. Alternatives: flat fields with + a `shape` discriminator (half-empty fields are footguns); subclasses + of `ArmNode` (forces backends to dispatch on more types). + +6. **Default cross-section is `HollowTubeCrossSection(outer=0.004, + inner=0.003)` with `density=1500 kg/m³`.** With these defaults, + `mass per metre ≈ 0.033 kg/m`, matching ariel's existing + `propeller_data.BEAM_DENSITY = 0.034 kg/m` (8mm OD / 6mm ID + carbon-fiber tube). Switching to the volumetric model is + behavior-preserving for the canonical small-drone build. + Alternatives considered: solid cylinder with a hand-tuned tiny radius + (awkward defaults); solid cylinder at 5 mm radius (~2× mass change + on existing builds, rejected). + +7. **Backends dispatch geometry emission on `isinstance(cross_section, + …)`. The Blueprint module has no MuJoCo / URDF / `pxr` imports.** + Cross-section classes carry physics formulas (area, inertia) but no + backend-specific emission code. Each backend knows how to render + each section type. Alternatives: cross-section classes carry + `urdf_geometry()` / `mjcf_kwargs()` methods (couples Blueprint to + every backend it'll ever serve; rejected). + +8. **Motor visual dimensions (`motor_radius`, `motor_thickness`) added to + `PROPELLER_LIBRARY`, sourced from the APC propeller-motor pairing + table.** Outer-can radius plateaus at ≈ 14 mm for prop5+ (all use + 22mm-class stators — `2204`–`2212`); only motor *height* grows with + propsize beyond that. EA-evolved `propsize` automatically picks the + matching visual size. Alternatives: keep dims as `blueprint_to_mjspec` + defaults (single propsize only); heuristic radius ∝ propsize (wrong + physics — was the v1 rough estimate, replaced). + +9. **MJCF arm visuals: capsule for cylindrical/hollow, box for + rectangular. URDF will use cylinder/box (URDF has no capsule).** + Visual proxies only — true inertia comes from + `arm.inertia_diag`, not the geom-derived MuJoCo formula. Capsule is + MuJoCo's `fromto` primitive for "rounded cylinder along an arbitrary + axis" and is already the existing behavior for cylindrical arms. + +10. **Compliant joints (deferred for v1) will use a two-layer pattern.** + Emit a `revolute` joint with zero physics stiffness in URDF / MJCF / + USD; store the non-linear `τ(θ)` law as sidecar custom attributes + (proposed `ariel:*` namespace, mirroring soft_airframe's `morphy:*` + on USD root prims); a runtime controller reads the params and + applies the torque each step. Rationale: URDF / MJCF / USD only + support linear torsional springs natively. The soft_airframe X-config + drone already uses this exact pattern and it is proven. + +11. **No actuators in URDF.** URDF has no first-class actuator + primitive equivalent to MuJoCo's `mjTRN_SITE`. Isaac Lab applies + thrust at runtime via Python by force-on-link; the URDF only needs + to expose named motor link prims. This is simpler than MJCF's + actuator-per-motor wiring, not harder. + +## 7. Asks for the meeting 1. Confirm Isaac Lab as the simulator target the consortium will converge on (so the USD backend is worth investing in). diff --git a/src/ariel/body_phenotypes/drone/backends.py b/src/ariel/body_phenotypes/drone/backends.py index 11d2141ea..0437b15c6 100644 --- a/src/ariel/body_phenotypes/drone/backends.py +++ b/src/ariel/body_phenotypes/drone/backends.py @@ -23,7 +23,16 @@ import numpy as np -from .blueprint import DroneBlueprint, ArmNode, MotorNode, RotorNode, CorePlateNode +from .blueprint import ( + DroneBlueprint, + ArmNode, + MotorNode, + RotorNode, + CorePlateNode, + CylindricalCrossSection, + HollowTubeCrossSection, + RectangularCrossSection, +) if TYPE_CHECKING: import mujoco @@ -115,12 +124,7 @@ def blueprint_to_propellers( def blueprint_to_mjspec( bp: DroneBlueprint, *, - motor_mass: float = 0.05, - arm_mass: float = 0.01, core_mass_override: float | None = None, - arm_radius: float = 0.005, - motor_radius: float = 0.015, - motor_thickness: float = 0.008, max_thrust: float = 5.0, body_name: str = "drone", ) -> "mujoco.MjSpec": @@ -139,12 +143,15 @@ def blueprint_to_mjspec( * One actuator per Motor; ``ctrl`` ∈ [0, 1] maps linearly to thrust in [0, ``max_thrust``] Newtons along the rotor's spin axis. + Physical parameters are read from the blueprint nodes themselves: + arm mass / inertia from ``arm.mass`` / ``arm.cross_section``; motor + mass and visual dimensions from ``motor.mass`` / ``motor.radius`` / + ``motor.thickness`` (sourced from ``propeller_data.PROPELLER_LIBRARY`` + via ``motor.propsize``). + Args: bp: the blueprint to compile. - motor_mass: kg per motor+rotor assembly (lumped). - arm_radius: capsule radius for arm visuals (m). - motor_radius: cylinder radius for motor visuals (m). - motor_thickness: cylinder half-length for motor visuals (m). + core_mass_override: if given, overrides ``core.mass`` for testing. max_thrust: maximum thrust per motor in Newtons. body_name: root body name. @@ -197,13 +204,32 @@ def blueprint_to_mjspec( name=f"{body_name}_arm_{arm_id}", pos=[0.0, 0.0, 0.0], ) - arm_body.add_geom( - type=mujoco.mjtGeom.mjGEOM_CAPSULE, - fromto=[0.0, 0.0, 0.0, *tip_local.tolist()], - size=[arm_radius, 0.0, 0.0], - mass=arm_mass, - rgba=(0.3, 0.3, 0.3, 1.0), - ) + # Geometry dispatch on cross-section type. Mass and inertia + # come from arm.mass / arm.cross_section.principal_inertia. + cs = arm.cross_section + if isinstance(cs, RectangularCrossSection): + # Box geom centered along the arm, oriented to match tip_local. + arm_body.add_geom( + pos=(tip_local / 2.0).tolist(), + quat=_rpy_to_quat(0.0, arm_pitch, arm_yaw), + type=mujoco.mjtGeom.mjGEOM_BOX, + size=[arm.length / 2.0, cs.width / 2.0, cs.thickness / 2.0], + mass=arm.mass, + rgba=(0.3, 0.3, 0.3, 1.0), + ) + else: + # CylindricalCrossSection (solid) or HollowTubeCrossSection + # — visualised as a capsule. Outer radius drives the visual. + visual_radius = ( + cs.outer_radius if isinstance(cs, HollowTubeCrossSection) else cs.radius + ) + arm_body.add_geom( + type=mujoco.mjtGeom.mjGEOM_CAPSULE, + fromto=[0.0, 0.0, 0.0, *tip_local.tolist()], + size=[visual_radius, 0.0, 0.0], + mass=arm.mass, + rgba=(0.3, 0.3, 0.3, 1.0), + ) for motor_id in bp.children(arm_id): motor = bp.payload(motor_id) @@ -232,8 +258,8 @@ def blueprint_to_mjspec( ) motor_body.add_geom( type=mujoco.mjtGeom.mjGEOM_CYLINDER, - size=[motor_radius, motor_thickness, 0.0], - mass=motor_mass, + size=[motor.radius, motor.thickness, 0.0], + mass=motor.mass, rgba=(1.0, 0.2, 0.2, 1.0) if motor.spin == "cw" else (0.2, 0.8, 0.2, 1.0), @@ -247,7 +273,7 @@ def blueprint_to_mjspec( rotor_radius = rotor.radius motor_body.add_geom( type=mujoco.mjtGeom.mjGEOM_CYLINDER, - pos=[0.0, 0.0, motor_thickness + 0.002], + pos=[0.0, 0.0, motor.thickness + 0.002], size=[rotor_radius, 0.001, 0.0], mass=0.0, rgba=(0.8, 0.8, 0.8, 0.5), @@ -256,7 +282,7 @@ def blueprint_to_mjspec( # Thrust site (force applied along local +Z) thrust_site = motor_body.add_site( name=f"{body_name}_thrust_{motor_index}", - pos=[0.0, 0.0, motor_thickness], + pos=[0.0, 0.0, motor.thickness], size=[0.005, 0.005, 0.005], ) @@ -292,12 +318,7 @@ def blueprint_to_urdf( bp: DroneBlueprint, out_path: str, *, - motor_mass: float = 0.05, - arm_mass: float = 0.01, core_mass_override: float | None = None, - arm_radius: float = 0.005, - motor_radius: float = 0.015, - motor_thickness: float = 0.008, robot_name: str = "drone", ) -> str: """Compile a DroneBlueprint into a URDF file. @@ -308,10 +329,18 @@ def blueprint_to_urdf( (see ``soft_airframe_optimization/scripts/convert_xconfig_urdf.py`` for the conversion call pattern). + Physical parameters are read from the blueprint nodes themselves + (``arm.mass``, ``arm.inertia_diag``, ``motor.mass``, ``motor.radius``, + ``motor.thickness``), so this signature only needs URDF-mechanical + options. + Planned mapping (mirrors ``blueprint_to_mjspec``): * One ```` per blueprint node (CorePlate, Arm, Motor) with - an analytically-computed ```` block for the primitive - shape. + an ```` block populated from the node's derived + ``mass`` and ``inertia_diag``. + * Arm ```` dispatches on ``arm.cross_section``: + ```` for solid / hollow-tube cross sections, + ```` for rectangular. * One ```` per parent-child edge. Default is ``type="fixed"`` (rigid drone). A future ``CompliantJoint`` annotation on ``ArmNode`` would emit ``type="revolute"`` with @@ -319,8 +348,6 @@ def blueprint_to_urdf( stashed as sidecar attributes for a runtime controller to apply (same two-layer pattern soft_airframe uses with ``morphy:*`` USD attributes). - * Capsule arms are approximated as cylinders — URDF has no - capsule primitive. Not yet implemented. """ diff --git a/src/ariel/body_phenotypes/drone/blueprint.py b/src/ariel/body_phenotypes/drone/blueprint.py index 4b34a3d0f..9dacdf8c3 100644 --- a/src/ariel/body_phenotypes/drone/blueprint.py +++ b/src/ariel/body_phenotypes/drone/blueprint.py @@ -10,12 +10,15 @@ from __future__ import annotations import json +import math from dataclasses import dataclass, asdict, field from pathlib import Path -from typing import Any, Optional +from typing import Any, Optional, Union import networkx as nx +from ariel.simulation.drone.propeller_data import get_propeller_specs + # ---------- node payloads ---------- @@ -35,19 +38,124 @@ class CorePlateNode: thickness: float = 0.01 # disc thickness (m) +# ---------- arm cross sections ---------- +# +# Each cross-section class describes the *shape* of an arm's cross-section +# (perpendicular to the arm's local +X axis). They expose a uniform +# interface used by ArmNode (mass / inertia derivation) and by backends +# (geometry emission, via isinstance dispatch). + +@dataclass +class CylindricalCrossSection: + """Solid circular cross-section.""" + type: str = "Cylindrical" # discriminator for from_dict + radius: float = 0.005 # m + + @property + def area(self) -> float: + return math.pi * self.radius ** 2 + + def principal_inertia(self, length: float, mass: float) -> tuple[float, float, float]: + # Solid cylinder along local +X. Ixx is the axial moment. + Ixx = 0.5 * mass * self.radius ** 2 + Iyy = Izz = mass * (3 * self.radius ** 2 + length ** 2) / 12 + return (Ixx, Iyy, Izz) + + +@dataclass +class HollowTubeCrossSection: + """Hollow circular cross-section (tube). Default = 8mm OD / 6mm ID, + matching propeller_data.BEAM_DENSITY when density = 1500 kg/m³.""" + type: str = "HollowTube" + outer_radius: float = 0.004 # m + inner_radius: float = 0.003 # m + + @property + def area(self) -> float: + return math.pi * (self.outer_radius ** 2 - self.inner_radius ** 2) + + def principal_inertia(self, length: float, mass: float) -> tuple[float, float, float]: + # Hollow cylinder along local +X. + sum_sq = self.outer_radius ** 2 + self.inner_radius ** 2 + Ixx = 0.5 * mass * sum_sq + Iyy = Izz = mass * (3 * sum_sq + length ** 2) / 12 + return (Ixx, Iyy, Izz) + + +@dataclass +class RectangularCrossSection: + """Solid rectangular (box) cross-section.""" + type: str = "Rectangular" + width: float = 0.01 # m (along arm's local +Y) + thickness: float = 0.005 # m (along arm's local +Z) + + @property + def area(self) -> float: + return self.width * self.thickness + + def principal_inertia(self, length: float, mass: float) -> tuple[float, float, float]: + # Box (length × width × thickness) along local +X. + Ixx = mass * (self.width ** 2 + self.thickness ** 2) / 12 + Iyy = mass * (length ** 2 + self.thickness ** 2) / 12 + Izz = mass * (length ** 2 + self.width ** 2) / 12 + return (Ixx, Iyy, Izz) + + +CrossSection = Union[ + CylindricalCrossSection, + HollowTubeCrossSection, + RectangularCrossSection, +] + + @dataclass class ArmNode: type: str = "Arm" length: float = 0.18 # m + density: float = 1500.0 # kg/m³ — carbon-fiber-ish + cross_section: CrossSection = field(default_factory=HollowTubeCrossSection) pose: Pose = field(default_factory=Pose) # attachment frame on parent (CorePlate) + @property + def mass(self) -> float: + """Derived: density × cross-section area × length.""" + return self.density * self.cross_section.area * self.length + + @property + def inertia_diag(self) -> tuple[float, float, float]: + """Principal moments (Ixx, Iyy, Izz) about COM, arm along local +X.""" + return self.cross_section.principal_inertia(self.length, self.mass) + @dataclass class MotorNode: type: str = "Motor" pose: Pose = field(default_factory=Pose) # pose on parent Arm tip spin: str = "ccw" # "cw" | "ccw" - propsize: int = 5 # inches; looked up in propeller_data for kf/km + propsize: int = 5 # inches; PROPELLER_LIBRARY key + + @property + def mass(self) -> float: + """Lumped motor + propeller mass from PROPELLER_LIBRARY.""" + return get_propeller_specs(self.propsize)["mass"] + + @property + def radius(self) -> float: + """Visual / collision cylinder radius from PROPELLER_LIBRARY.""" + return get_propeller_specs(self.propsize)["motor_radius"] + + @property + def thickness(self) -> float: + """Visual / collision cylinder half-length from PROPELLER_LIBRARY.""" + return get_propeller_specs(self.propsize)["motor_thickness"] + + @property + def inertia_diag(self) -> tuple[float, float, float]: + """Solid-cylinder principal moments. Spin axis = local +Z.""" + m, r, h = self.mass, self.radius, 2 * self.thickness + Ixx = Iyy = m * (3 * r ** 2 + h ** 2) / 12 + Izz = 0.5 * m * r ** 2 + return (Ixx, Iyy, Izz) @dataclass @@ -133,12 +241,22 @@ def from_dict(cls, d: dict) -> "DroneBlueprint": "Rotor": RotorNode, "Sensor": SensorNode, } + cross_section_map = { + "Cylindrical": CylindricalCrossSection, + "HollowTube": HollowTubeCrossSection, + "Rectangular": RectangularCrossSection, + } for entry in d["nodes"]: data = dict(entry["data"]) cls_ = type_map[data["type"]] # rebuild Pose sub-dataclass where present if "pose" in data and isinstance(data["pose"], dict): data["pose"] = Pose(**data["pose"]) + # rebuild cross_section sub-dataclass where present + if "cross_section" in data and isinstance(data["cross_section"], dict): + cs_data = dict(data["cross_section"]) + cs_cls = cross_section_map[cs_data["type"]] + data["cross_section"] = cs_cls(**cs_data) payload = cls_(**data) bp.g.add_node(entry["id"], data=payload) bp._next_id = max(bp._next_id, entry["id"] + 1) diff --git a/src/ariel/simulation/drone/propeller_data.py b/src/ariel/simulation/drone/propeller_data.py index 9ea0006e6..89bf5ed34 100644 --- a/src/ariel/simulation/drone/propeller_data.py +++ b/src/ariel/simulation/drone/propeller_data.py @@ -24,6 +24,9 @@ "constants": [8.12e-08, 6.40e-10], # [k_f, k_m] force and moment constants "wmax": 5000, # Maximum angular velocity (rad/s) "mass": 0.0046, # Propeller + motor mass (kg) + # Motor visuals — sub-1306 brushless motor (outer can radius + half-height). + "motor_radius": 0.007, + "motor_thickness": 0.005, # Borrowed from params_3inch (closest sysid set; prop2 has no real sysid). "w_min": 305.40, "k": 0.84, @@ -42,6 +45,9 @@ "constants": [1.80e-07, 2.89e-09], # [k_f, k_m] (k_f = k_w·m_canonical, rough) "wmax": 4887, "mass": 0.012, + # Motor visuals — 1306-class (13mm stator + bell). + "motor_radius": 0.009, + "motor_thickness": 0.006, "w_min": 305.40, "k": 0.84, "k_r_react": 1.14e-03, @@ -53,6 +59,9 @@ "constants": [7.24e-07, 8.20e-09], # [k_f, k_m] force and moment constants "wmax": 3927, # Maximum angular velocity (rad/s) "mass": 0.018, # Propeller + motor mass (kg) + # Motor visuals — APC 4x45E pairs with 1806-class (18mm stator). + "motor_radius": 0.012, + "motor_thickness": 0.007, # Borrowed from params_3inch (closest sysid set). "w_min": 305.40, "k": 0.84, @@ -65,6 +74,9 @@ "constants": [1.08e-06, 1.22e-08], "wmax": 3142, "mass": 0.0196, + # Motor visuals — APC 5x5E pairs with 2204-2206 (22mm stator + bell). + "motor_radius": 0.014, + "motor_thickness": 0.008, # Sysid: params_5inch from optimal_quad_control_RL/randomization.py:5-10. "w_min": 238.49, "k": 0.95, @@ -77,6 +89,9 @@ "constants": [2.21e-06, 2.74e-08], "wmax": 2618, "mass": 0.0252, + # Motor visuals — APC 6x55E pairs with 2204-2208 (same 22mm stator, taller). + "motor_radius": 0.014, + "motor_thickness": 0.009, # Borrowed from params_5inch (closest sysid set). "w_min": 238.49, "k": 0.95, @@ -89,6 +104,9 @@ "constants": [4.65e-06, 6.62e-08], "wmax": 2244, "mass": 0.046, + # Motor visuals — APC 7x6E pairs with 2208 (22mm stator, 8mm stack). + "motor_radius": 0.014, + "motor_thickness": 0.010, # Borrowed from params_5inch (closest sysid set). "w_min": 238.49, "k": 0.95, @@ -101,6 +119,9 @@ "constants": [7.60e-06, 1.14e-07], "wmax": 1963, "mass": 0.056, + # Motor visuals — APC 8x6E pairs with 2212-or-larger (22mm stator, 12mm stack). + "motor_radius": 0.014, + "motor_thickness": 0.013, # Borrowed from params_5inch (closest sysid set). "w_min": 238.49, "k": 0.95, @@ -113,6 +134,9 @@ "constants": [1.076e-05, 1.61e-07], # Matched to original framework (kTh = 1.076e-5) "wmax": 1963, "mass": 0.300, # Increased to match original 1.2kg total mass exactly + # Motor visuals — large hobby motor (22mm-class outer can). + "motor_radius": 0.014, + "motor_thickness": 0.012, # Borrowed from params_5inch (closest sysid set). "w_min": 238.49, "k": 0.95, From 3a7c1a34eb40a78bbd5300f6fa8e1adeef9bb422 Mon Sep 17 00:00:00 2001 From: Keiichi Ito Date: Sun, 24 May 2026 18:46:27 +0200 Subject: [PATCH 11/27] Implement blueprint_to_urdf for rigid-drone Isaac Lab path. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Walks the blueprint tree and emits a URDF file: one per CorePlate / Arm / Motor node (with diagonal sourced from the node's derived mass + inertia_diag) and one per parent-child edge. Arm geometry dispatches on cross-section type: for solid / hollow-tube, for rectangular. Rotor visuals are folded into the parent motor link (no separate rotor link; rotor mass is already lumped into motor.mass). No actuators emitted — Isaac Lab applies thrust at runtime via force on the motor link's local +Z. This is the URDF half of the Blueprint → URDF → USD path; the soft_ airframe_optimization repo already has the URDF → USD half via isaaclab.sim.converters.UrdfConverter, so the two combine into a full Isaac Lab asset pipeline. Compliant joints (a future ArmNode.CompliantJoint annotation) will swap the joint type to "revolute" with zero physics stiffness and stash the non-linear τ(θ) law as sidecar ariel:* attributes, mirroring soft_ airframe's morphy:* USD two-layer pattern. Smoke test: decoder-built quad emits 9 links + 8 joints; mixed-cross- section drone correctly dispatches box vs cylinder per arm; output is well-formed XML that MuJoCo's URDF parser accepts without error. Co-Authored-By: Claude Opus 4.7 --- src/ariel/body_phenotypes/drone/backends.py | 300 ++++++++++++++++++-- 1 file changed, 272 insertions(+), 28 deletions(-) diff --git a/src/ariel/body_phenotypes/drone/backends.py b/src/ariel/body_phenotypes/drone/backends.py index 0437b15c6..5e0637a27 100644 --- a/src/ariel/body_phenotypes/drone/backends.py +++ b/src/ariel/body_phenotypes/drone/backends.py @@ -1,25 +1,30 @@ """DroneBlueprint → phenotype backends. Each backend consumes a DroneBlueprint and emits something a simulator (or -the real world) can instantiate. v1 ships: +the real world) can instantiate: * ``blueprint_to_propellers`` — list[dict] consumable by ``ariel.simulation.drone.DroneSimulator`` / ``DroneConfiguration``. * ``blueprint_to_mjspec`` — MuJoCo ``mjSpec`` (compiles to MJCF / ``MjModel``); the same blueprint can drive both the Python physics stack and a full MuJoCo simulation. + * ``blueprint_to_urdf`` — URDF file (rigid drone, fixed joints). + Intermediate for Isaac Lab via ``isaaclab.sim.converters.UrdfConverter``. Stubs sketched for future backends: - * ``blueprint_to_urdf`` — URDF file; can be fed to Isaac Lab's - ``UrdfConverter`` to produce a USD asset. * ``blueprint_to_usd`` — USD prim hierarchy for Isaac Lab (direct, no URDF intermediate). """ from __future__ import annotations +import copy import math +import xml.etree.ElementTree as ET +from collections.abc import Sequence +from pathlib import Path from typing import Any, TYPE_CHECKING +from xml.dom import minidom import numpy as np @@ -312,7 +317,188 @@ def _rpy_to_quat(roll: float, pitch: float, yaw: float) -> list[float]: ] -# ---------- future backends (signatures only) ---------- +# ---------- URDF backend (blueprint → .urdf) ---------- + +def _urdf_fmt(x: float) -> str: + return f"{float(x):.6g}" + + +def _urdf_fmt_vec(v: Sequence[float]) -> str: + return " ".join(_urdf_fmt(c) for c in v) + + +def _urdf_add_origin(parent: ET.Element, xyz: Sequence[float], rpy: Sequence[float]) -> None: + ET.SubElement(parent, "origin", attrib={ + "xyz": _urdf_fmt_vec(xyz), + "rpy": _urdf_fmt_vec(rpy), + }) + + +def _urdf_add_inertial( + link: ET.Element, + *, + com_xyz: Sequence[float], + mass: float, + inertia_diag: Sequence[float], +) -> None: + """Append an ```` block with diagonal inertia tensor. + ``inertia_diag`` is ``(Ixx, Iyy, Izz)`` about the COM.""" + inertial = ET.SubElement(link, "inertial") + _urdf_add_origin(inertial, com_xyz, (0.0, 0.0, 0.0)) + ET.SubElement(inertial, "mass", attrib={"value": _urdf_fmt(mass)}) + Ixx, Iyy, Izz = inertia_diag + ET.SubElement(inertial, "inertia", attrib={ + "ixx": _urdf_fmt(Ixx), "ixy": "0", "ixz": "0", + "iyy": _urdf_fmt(Iyy), "iyz": "0", + "izz": _urdf_fmt(Izz), + }) + + +def _urdf_add_visual_collision( + link: ET.Element, + *, + xyz: Sequence[float], + rpy: Sequence[float], + geometry: ET.Element, + rgba: Sequence[float] | None = None, + include_collision: bool = True, +) -> None: + """Append matching ```` (+ optional ````) blocks + with the given geometry. ``geometry`` is a freshly-built ```` + element; we deep-copy it so visual and collision are independent.""" + visual = ET.SubElement(link, "visual") + _urdf_add_origin(visual, xyz, rpy) + visual.append(copy.deepcopy(geometry)) + if rgba is not None: + mat = ET.SubElement(visual, "material", attrib={"name": ""}) + ET.SubElement(mat, "color", attrib={"rgba": _urdf_fmt_vec(rgba)}) + if include_collision: + collision = ET.SubElement(link, "collision") + _urdf_add_origin(collision, xyz, rpy) + collision.append(copy.deepcopy(geometry)) + + +def _urdf_cylinder_geom(radius: float, length: float) -> ET.Element: + geom = ET.Element("geometry") + ET.SubElement(geom, "cylinder", attrib={ + "radius": _urdf_fmt(radius), + "length": _urdf_fmt(length), + }) + return geom + + +def _urdf_box_geom(size: Sequence[float]) -> ET.Element: + geom = ET.Element("geometry") + ET.SubElement(geom, "box", attrib={"size": _urdf_fmt_vec(size)}) + return geom + + +def _urdf_add_fixed_joint( + robot: ET.Element, + *, + name: str, + parent: str, + child: str, + xyz: Sequence[float], + rpy: Sequence[float], +) -> None: + joint = ET.SubElement(robot, "joint", attrib={"name": name, "type": "fixed"}) + _urdf_add_origin(joint, xyz, rpy) + ET.SubElement(joint, "parent", attrib={"link": parent}) + ET.SubElement(joint, "child", attrib={"link": child}) + + +def _urdf_core_inertia_diag(core: CorePlateNode, mass: float) -> tuple[float, float, float]: + """Solid-cylinder inertia about COM, disc axis = link's local +Z.""" + r, h = core.radius, core.thickness + Ixx = Iyy = mass * (3.0 * r * r + h * h) / 12.0 + Izz = 0.5 * mass * r * r + return (Ixx, Iyy, Izz) + + +def _urdf_add_core_link(robot: ET.Element, name: str, core: CorePlateNode, mass: float) -> None: + link = ET.SubElement(robot, "link", attrib={"name": name}) + _urdf_add_inertial( + link, + com_xyz=(0.0, 0.0, 0.0), + mass=mass, + inertia_diag=_urdf_core_inertia_diag(core, mass), + ) + _urdf_add_visual_collision( + link, + xyz=(0.0, 0.0, 0.0), + rpy=(0.0, 0.0, 0.0), + geometry=_urdf_cylinder_geom(core.radius, core.thickness), + rgba=(0.2, 0.4, 0.8, 1.0), + ) + + +def _urdf_add_arm_link(robot: ET.Element, name: str, arm: ArmNode) -> None: + """Arm link frame is at the joint-to-parent; arm extends along local +X. + Visual / collision geometry is centered at midpoint along the arm.""" + link = ET.SubElement(robot, "link", attrib={"name": name}) + com_xyz = (arm.length / 2.0, 0.0, 0.0) + _urdf_add_inertial(link, com_xyz=com_xyz, mass=arm.mass, inertia_diag=arm.inertia_diag) + + cs = arm.cross_section + if isinstance(cs, RectangularCrossSection): + _urdf_add_visual_collision( + link, + xyz=com_xyz, + rpy=(0.0, 0.0, 0.0), + geometry=_urdf_box_geom((arm.length, cs.width, cs.thickness)), + rgba=(0.3, 0.3, 0.3, 1.0), + ) + else: + # Cylindrical (solid) or HollowTube — URDF has no hollow cylinder, + # render solid using outer radius. URDF cylinders point along the + # link's local +Z; rotate by π/2 about +Y so the cylinder axis + # aligns with the arm's local +X. + visual_radius = ( + cs.outer_radius if isinstance(cs, HollowTubeCrossSection) else cs.radius + ) + _urdf_add_visual_collision( + link, + xyz=com_xyz, + rpy=(0.0, math.pi / 2.0, 0.0), + geometry=_urdf_cylinder_geom(visual_radius, arm.length), + rgba=(0.3, 0.3, 0.3, 1.0), + ) + + +def _urdf_add_motor_link( + robot: ET.Element, + name: str, + motor: MotorNode, + rotor: RotorNode | None, +) -> None: + """Motor link: cylinder along local +Z (the thrust axis), centered at + the link origin. An optional rotor visual disc sits above it.""" + link = ET.SubElement(robot, "link", attrib={"name": name}) + full_height = 2.0 * motor.thickness + rgba = (1.0, 0.2, 0.2, 1.0) if motor.spin == "cw" else (0.2, 0.8, 0.2, 1.0) + _urdf_add_inertial( + link, + com_xyz=(0.0, 0.0, 0.0), + mass=motor.mass, + inertia_diag=motor.inertia_diag, + ) + _urdf_add_visual_collision( + link, + xyz=(0.0, 0.0, 0.0), + rpy=(0.0, 0.0, 0.0), + geometry=_urdf_cylinder_geom(motor.radius, full_height), + rgba=rgba, + ) + if rotor is not None: + # Visual-only thin disc above the motor; no collision, no mass + # (motor.mass already lumps motor + propeller). + visual = ET.SubElement(link, "visual") + _urdf_add_origin(visual, (0.0, 0.0, motor.thickness + 0.002), (0.0, 0.0, 0.0)) + visual.append(_urdf_cylinder_geom(rotor.radius, 0.002)) + mat = ET.SubElement(visual, "material", attrib={"name": ""}) + ET.SubElement(mat, "color", attrib={"rgba": "0.8 0.8 0.8 0.5"}) + def blueprint_to_urdf( bp: DroneBlueprint, @@ -321,7 +507,7 @@ def blueprint_to_urdf( core_mass_override: float | None = None, robot_name: str = "drone", ) -> str: - """Compile a DroneBlueprint into a URDF file. + """Compile a DroneBlueprint into a URDF file (rigid drone, fixed joints). Intended as the intermediate step for Isaac Lab / Isaac Sim: the emitted ``.urdf`` is consumed by @@ -329,34 +515,92 @@ def blueprint_to_urdf( (see ``soft_airframe_optimization/scripts/convert_xconfig_urdf.py`` for the conversion call pattern). - Physical parameters are read from the blueprint nodes themselves - (``arm.mass``, ``arm.inertia_diag``, ``motor.mass``, ``motor.radius``, - ``motor.thickness``), so this signature only needs URDF-mechanical - options. - - Planned mapping (mirrors ``blueprint_to_mjspec``): - * One ```` per blueprint node (CorePlate, Arm, Motor) with - an ```` block populated from the node's derived - ``mass`` and ``inertia_diag``. + Mapping (mirrors ``blueprint_to_mjspec``): + * One ```` per CorePlate / Arm / Motor node, with an + ```` block populated from the node's derived ``mass`` + and ``inertia_diag``. Visual + collision geometry per link. + Rotor visuals are folded into the parent motor link (no separate + rotor link; rotor mass is already lumped into ``motor.mass``). + * One ```` per parent-child edge. Drone is + rigid in v1; compliant-joint support is planned (zero-stiffness + revolute + sidecar ``ariel:*`` torque attributes, mirroring + soft_airframe's two-layer pattern). * Arm ```` dispatches on ``arm.cross_section``: ```` for solid / hollow-tube cross sections, ```` for rectangular. - * One ```` per parent-child edge. Default is - ``type="fixed"`` (rigid drone). A future ``CompliantJoint`` - annotation on ``ArmNode`` would emit ``type="revolute"`` with - ````; the non-linear ``τ(θ)`` law is - stashed as sidecar attributes for a runtime controller to apply - (same two-layer pattern soft_airframe uses with ``morphy:*`` - USD attributes). - - Not yet implemented. + * No actuators: Isaac Lab applies thrust at runtime by force on + the motor link's local +Z axis. + + Conventions: + * Z-up, metres, radians. URDF cylinders are along link-local +Z; + arm cylinders are rotated 90° about +Y so the cylinder axis + matches the arm's local +X. + * Each link's frame is at the joint to its parent; joint + ```` carries the child frame's pose in the parent. + + Args: + bp: blueprint to compile. + out_path: destination ``.urdf`` path. + core_mass_override: if given, replaces ``core.mass`` (matches + ``blueprint_to_mjspec`` semantics). + robot_name: ```` attribute. + + Returns: + Absolute path to the written URDF, as a string. """ - raise NotImplementedError( - "blueprint_to_urdf is not yet implemented. " - "Use blueprint_to_mjspec for MuJoCo, or blueprint_to_propellers " - "for the Python physics stack." - ) + core = bp.payload(bp.root_id) + if not isinstance(core, CorePlateNode): + raise ValueError("Blueprint root must be a CorePlateNode.") + core_mass = core_mass_override if core_mass_override is not None else core.mass + + robot = ET.Element("robot", attrib={"name": robot_name}) + + core_link = "base_link" + _urdf_add_core_link(robot, core_link, core, core_mass) + + for arm_id in bp.children(bp.root_id): # type: ignore[arg-type] + arm = bp.payload(arm_id) + if not isinstance(arm, ArmNode): + continue + arm_link = f"arm_{arm_id}" + _urdf_add_arm_link(robot, arm_link, arm) + _urdf_add_fixed_joint( + robot, + name=f"core_to_arm_{arm_id}", + parent=core_link, + child=arm_link, + xyz=arm.pose.xyz, + rpy=arm.pose.rpy, + ) + for motor_id in bp.children(arm_id): + motor = bp.payload(motor_id) + if not isinstance(motor, MotorNode): + continue + rotor: RotorNode | None = None + for rotor_id in bp.children(motor_id): + cand = bp.payload(rotor_id) + if isinstance(cand, RotorNode): + rotor = cand + break + motor_link = f"motor_{motor_id}" + _urdf_add_motor_link(robot, motor_link, motor, rotor) + _urdf_add_fixed_joint( + robot, + name=f"arm_{arm_id}_to_motor_{motor_id}", + parent=arm_link, + child=motor_link, + xyz=motor.pose.xyz, + rpy=motor.pose.rpy, + ) + raw = ET.tostring(robot, encoding="unicode") + pretty = minidom.parseString(raw).toprettyxml(indent=" ") + out = Path(out_path).resolve() + out.write_text(pretty) + return str(out) + + +# ---------- future backends (signatures only) ---------- def blueprint_to_usd(bp: DroneBlueprint, out_path: str) -> str: """Compile a DroneBlueprint into a USD file for Isaac Lab. From 1c1fc1b4313391a3a670f31782839b776d61ccfc Mon Sep 17 00:00:00 2001 From: Keiichi Ito Date: Mon, 25 May 2026 14:50:22 +0200 Subject: [PATCH 12/27] =?UTF-8?q?Add=20Blueprint=20=E2=86=92=20URDF=20?= =?UTF-8?q?=E2=86=92=20USD=20pipeline=20scripts.?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit The conversion is split across two scripts because ariel requires Python 3.12 (PEP 695 type-statement syntax) while the local isaaclab conda env runs Python 3.11. The URDF file is the boundary between the two envs. * scripts/blueprint_to_urdf.py — runs in the ariel env. Builds a DroneBlueprint (either a preset or from a saved JSON), calls blueprint_to_urdf, writes the .urdf to --out. * scripts/urdf_to_usd.py — runs in the isaaclab env. Takes a URDF path and writes a USD via isaaclab.sim.converters.UrdfConverter. All joints in the v1 URDF are fixed, so joint_drive is configured with target_type="none" and zero PD gains (just satisfies the required-field validator). Progress messages go to stderr to survive Isaac Sim's stdout capture. End-to-end smoke test passed: blueprint_to_urdf produces a 4-arm quad URDF; urdf_to_usd produces the standard Isaac Lab layered USD output (quad.usd + configuration/{quad_base, quad_physics, quad_robot, quad_sensor}.usd, ~10 KB total). Sample run: python scripts/blueprint_to_urdf.py --preset quad --out /tmp/quad.urdf /home/keiichi-ito/miniconda3/envs/isaaclab/bin/python \ scripts/urdf_to_usd.py --headless \ --input /tmp/quad.urdf --output_dir /tmp/quad_usd # (the second invocation needs ${ISAAC_SIM}/setup_conda_env.sh sourced) Co-Authored-By: Claude Opus 4.7 --- scripts/blueprint_to_urdf.py | 78 ++++++++++++++++++++++++ scripts/urdf_to_usd.py | 113 +++++++++++++++++++++++++++++++++++ 2 files changed, 191 insertions(+) create mode 100644 scripts/blueprint_to_urdf.py create mode 100644 scripts/urdf_to_usd.py diff --git a/scripts/blueprint_to_urdf.py b/scripts/blueprint_to_urdf.py new file mode 100644 index 000000000..3e2d322c8 --- /dev/null +++ b/scripts/blueprint_to_urdf.py @@ -0,0 +1,78 @@ +#!/usr/bin/env python3 +"""Build a DroneBlueprint and emit a URDF file. + +Ariel-env side of the two-step Blueprint → URDF → USD pipeline. The +emitted ``.urdf`` is consumed by ``scripts/urdf_to_usd.py`` in an Isaac +Lab environment (the two envs are separated because ariel requires +Python 3.12 PEP 695 syntax and the local isaaclab env runs 3.11). + +Examples: + + # Quad with default propsize=5 + python scripts/blueprint_to_urdf.py --preset quad --out /tmp/quad.urdf + + # Load a saved blueprint + python scripts/blueprint_to_urdf.py --blueprint_json bp.json --out drone.urdf +""" +from __future__ import annotations + +import argparse +import sys +from pathlib import Path + +import numpy as np + +# Make ariel importable when run from a checkout without `pip install -e .`. +_REPO_ROOT = Path(__file__).resolve().parent.parent +sys.path.insert(0, str(_REPO_ROOT / "src")) + +from ariel.body_phenotypes.drone.backends import blueprint_to_urdf # noqa: E402 +from ariel.body_phenotypes.drone.blueprint import DroneBlueprint # noqa: E402 +from ariel.body_phenotypes.drone.decoders import spherical_angular_to_blueprint # noqa: E402 + + +# (mag, az, pitch, motor_az, motor_pitch, direction) per arm. +PRESETS: dict[str, np.ndarray] = { + "quad": np.array([ + [0.18, 0.0, 0.0, 0.0, 0.0, 1.0], + [0.18, np.pi / 2.0, 0.0, 0.0, 0.0, 0.0], + [0.18, np.pi, 0.0, 0.0, 0.0, 1.0], + [0.18, 3 * np.pi / 2, 0.0, 0.0, 0.0, 0.0], + ]), + "hex": np.array([ + [0.18, i * np.pi / 3.0, 0.0, 0.0, 0.0, float(i % 2)] + for i in range(6) + ]), +} + + +def _build_blueprint(args: argparse.Namespace) -> DroneBlueprint: + if args.blueprint_json: + bp = DroneBlueprint.load_json(args.blueprint_json) + print(f"[blueprint_to_urdf] Loaded blueprint from {args.blueprint_json}") + return bp + genome = PRESETS[args.preset] + bp = spherical_angular_to_blueprint(genome, propsize=args.propsize) + print(f"[blueprint_to_urdf] Built '{args.preset}' preset (propsize={args.propsize})") + return bp + + +def main() -> None: + parser = argparse.ArgumentParser(description=__doc__.splitlines()[0]) + parser.add_argument("--preset", choices=list(PRESETS), default="quad") + parser.add_argument("--blueprint_json", type=str, default=None, + help="Optional: load a saved DroneBlueprint JSON instead of a preset.") + parser.add_argument("--propsize", type=int, default=5, + help="Propeller size for the preset (ignored if --blueprint_json given).") + parser.add_argument("--out", type=str, required=True, + help="Destination .urdf path.") + parser.add_argument("--robot_name", type=str, default="drone") + args = parser.parse_args() + + bp = _build_blueprint(args) + urdf_path = blueprint_to_urdf(bp, args.out, robot_name=args.robot_name) + print(f"[blueprint_to_urdf] URDF written: {urdf_path}") + + +if __name__ == "__main__": + main() diff --git a/scripts/urdf_to_usd.py b/scripts/urdf_to_usd.py new file mode 100644 index 000000000..efd59d0d8 --- /dev/null +++ b/scripts/urdf_to_usd.py @@ -0,0 +1,113 @@ +#!/usr/bin/env python3 +"""Convert a URDF file to USD via Isaac Lab's UrdfConverter. + +Isaac-Lab-env side of the two-step Blueprint → URDF → USD pipeline. +Pairs with ``scripts/blueprint_to_urdf.py`` (run in the ariel env). +Pure stdlib + Isaac Lab — no ariel dependency. + +Examples: + + # Default conda-env path + /home/keiichi-ito/miniconda3/envs/isaaclab/bin/python \\ + scripts/urdf_to_usd.py --headless \\ + --input /tmp/quad.urdf --output_dir /tmp/quad_usd +""" +from __future__ import annotations + +import argparse +import sys +import traceback +from pathlib import Path + + +def _log(msg: str) -> None: + """Print to stderr (Isaac Sim captures stdout but leaves stderr alone).""" + sys.stderr.write(f"[urdf_to_usd] {msg}\n") + sys.stderr.flush() + + +def _build_parser() -> argparse.ArgumentParser: + parser = argparse.ArgumentParser(description=__doc__.splitlines()[0]) + parser.add_argument("--input", type=str, required=True, + help="Path to source .urdf file.") + parser.add_argument("--output_dir", type=str, required=True, + help="Directory to write the .usd into (created if missing).") + parser.add_argument("--usd_name", type=str, default=None, + help="Output USD filename (default: .usd).") + parser.add_argument("--merge_fixed_joints", action="store_true", + help="Collapse fixed-joint chains into a single rigid body. " + "Off by default so each motor stays a separate link " + "(needed for per-motor thrust application in Isaac Lab).") + parser.add_argument("--fix_base", action="store_true", + help="Treat the URDF root as a fixed base. Off by default " + "(drones are floating-base; Isaac Lab adds the freejoint).") + return parser + + +def main() -> None: + _log("starting") + parser = _build_parser() + + # Isaac Lab adds --headless, --device, etc. + _log("importing isaaclab.app.AppLauncher") + from isaaclab.app import AppLauncher # noqa: PLC0415 + AppLauncher.add_app_launcher_args(parser) + args = parser.parse_args() + + urdf_path = Path(args.input).resolve() + if not urdf_path.is_file(): + raise FileNotFoundError(f"URDF not found: {urdf_path}") + + output_dir = Path(args.output_dir).resolve() + output_dir.mkdir(parents=True, exist_ok=True) + usd_name = args.usd_name or f"{urdf_path.stem}.usd" + expected_out = output_dir / usd_name + + _log(f"input : {urdf_path}") + _log(f"output: {expected_out}") + + _log("launching Isaac Sim app...") + app_launcher = AppLauncher(args, multi_gpu=False) + simulation_app = app_launcher.app + _log("Isaac Sim app launched") + + try: + from isaaclab.sim.converters import UrdfConverter, UrdfConverterCfg # noqa: PLC0415 + + _log("building UrdfConverterCfg") + # All joints in our v1 URDF are fixed, so stiffness is unused; we set + # it to 0 just to satisfy the configclass validator (the field is + # MISSING by default). + cfg = UrdfConverterCfg( + asset_path=str(urdf_path), + usd_dir=str(output_dir), + usd_file_name=usd_name, + force_usd_conversion=True, + merge_fixed_joints=args.merge_fixed_joints, + fix_base=args.fix_base, + joint_drive=UrdfConverterCfg.JointDriveCfg( + target_type="none", + gains=UrdfConverterCfg.JointDriveCfg.PDGainsCfg( + stiffness=0.0, + damping=0.0, + ), + ), + ) + _log("invoking UrdfConverter") + converter = UrdfConverter(cfg) + result_path = Path(converter.usd_path) + if result_path.exists(): + _log(f"USD written: {result_path} (size={result_path.stat().st_size} bytes)") + else: + _log(f"WARNING: converter returned path {result_path} but file does not exist") + except Exception as e: + _log(f"ERROR: {type(e).__name__}: {e}") + traceback.print_exc(file=sys.stderr) + raise + finally: + _log("closing simulation app") + simulation_app.close() + + +if __name__ == "__main__": + main() From c2823e1737885e31f5c9253246e6d1585be2984c Mon Sep 17 00:00:00 2001 From: Keiichi Ito Date: Mon, 25 May 2026 14:55:19 +0200 Subject: [PATCH 13/27] Add example 16: blueprint_to_urdf demo with cross-section dispatch. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Builds an X-quad blueprint, calls blueprint_to_urdf, parses the result back and reports link/joint counts, total mass, and which geometry tags ended up in the URDF — verifying the arm cross-section dispatch ( for default HollowTube vs for --rect-arms). End-to-end smoke check: both the default and --rect-arms outputs round- tripped cleanly through scripts/urdf_to_usd.py to USD (1453 bytes, standard Isaac Lab layered layout). Co-Authored-By: Claude Opus 4.7 --- examples/d_drones/16_blueprint_to_urdf.py | 127 ++++++++++++++++++++++ 1 file changed, 127 insertions(+) create mode 100644 examples/d_drones/16_blueprint_to_urdf.py diff --git a/examples/d_drones/16_blueprint_to_urdf.py b/examples/d_drones/16_blueprint_to_urdf.py new file mode 100644 index 000000000..32f0ddeca --- /dev/null +++ b/examples/d_drones/16_blueprint_to_urdf.py @@ -0,0 +1,127 @@ +"""Emit a URDF file from a DroneBlueprint and inspect the result. + +Pipeline: + + spherical_angular genome + → spherical_angular_to_blueprint (decoder) + → DroneBlueprint (saved as JSON for inspection) + → blueprint_to_urdf (NEW backend — this example) + → quad.urdf (rigid drone, fixed joints) + +The emitted URDF is the intermediate for the Isaac Lab pipeline. Hand +it to ``scripts/urdf_to_usd.py`` in an Isaac Lab env to produce a USD: + + /path/to/isaaclab/python scripts/urdf_to_usd.py --headless \\ + --input examples/d_drones/__data__/blueprint_demo/quad.urdf \\ + --output_dir examples/d_drones/__data__/blueprint_demo/usd + +Cross-section dispatch: ``--rect-arms`` swaps the default hollow-tube +arms (8mm OD / 6mm ID, matching ariel's ``BEAM_DENSITY``) for solid +rectangular box arms, which exercises ``blueprint_to_urdf``'s +``isinstance(arm.cross_section, RectangularCrossSection)`` branch. + +Run: + uv run examples/d_drones/16_blueprint_to_urdf.py + uv run examples/d_drones/16_blueprint_to_urdf.py --arm-len 0.18 --prop-size 4 + uv run examples/d_drones/16_blueprint_to_urdf.py --rect-arms +""" +from __future__ import annotations + +import argparse +import xml.etree.ElementTree as ET +from pathlib import Path + +import numpy as np + +from ariel.body_phenotypes.drone.backends import blueprint_to_urdf +from ariel.body_phenotypes.drone.blueprint import ( + ArmNode, + RectangularCrossSection, +) +from ariel.body_phenotypes.drone.decoders import spherical_angular_to_blueprint + + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +parser = argparse.ArgumentParser(description=__doc__.splitlines()[0]) +parser.add_argument("--arm-len", type=float, default=0.12, + help="Arm length in metres (default 0.12).") +parser.add_argument("--prop-size", type=int, default=5, + help="Propeller size in inches (default 5).") +parser.add_argument("--rect-arms", action="store_true", + help="Swap default HollowTube arms for solid rectangular " + "(10 mm wide × 5 mm thick) — exercises the URDF box " + "geometry path.") +parser.add_argument("--robot-name", type=str, default="quad") +parser.add_argument("--out", type=Path, + default=Path("examples/d_drones/__data__/blueprint_demo/quad.urdf"), + help="Destination URDF path.") +args = parser.parse_args() + + +# --------------------------------------------------------------------------- +# 1. Build an X-quad spherical-angular genome and decode to a blueprint +# --------------------------------------------------------------------------- + +mag = float(args.arm_len) +genome = np.array([ + [mag, np.pi / 4, 0.0, 0.0, 0.0, 0], + [mag, 3 * np.pi / 4, 0.0, 0.0, 0.0, 1], + [mag, -3 * np.pi / 4, 0.0, 0.0, 0.0, 0], + [mag, -np.pi / 4, 0.0, 0.0, 0.0, 1], +]) + +bp = spherical_angular_to_blueprint(genome, propsize=args.prop_size) + +if args.rect_arms: + # Re-author each ArmNode's cross_section in place. + for arm_id in bp.children(bp.root_id): # type: ignore[arg-type] + arm = bp.payload(arm_id) + if isinstance(arm, ArmNode): + arm.cross_section = RectangularCrossSection(width=0.010, thickness=0.005) + + +# --------------------------------------------------------------------------- +# 2. Emit URDF +# --------------------------------------------------------------------------- + +args.out.parent.mkdir(parents=True, exist_ok=True) +bp.save_json(args.out.with_suffix(".json")) +urdf_path = blueprint_to_urdf(bp, str(args.out), robot_name=args.robot_name) + +print("=" * 70) +print(bp.summary()) +print(f"\nBlueprint JSON: {args.out.with_suffix('.json')}") +print(f"URDF: {urdf_path}") + + +# --------------------------------------------------------------------------- +# 3. Quick structural inspection — parse the URDF back and tally +# --------------------------------------------------------------------------- + +tree = ET.parse(urdf_path) +robot = tree.getroot() +links = robot.findall("link") +joints = robot.findall("joint") + +print("\nURDF structure:") +print(f" links : {len(links)} (expect 1 core + N arms + N motors)") +print(f" joints : {len(joints)} (all fixed in v1)") + +total_mass = 0.0 +for link in links: + mass_el = link.find("inertial/mass") + if mass_el is not None: + total_mass += float(mass_el.attrib["value"]) +print(f" Σ mass : {total_mass:.4f} kg") + +geom_tags = sorted({ + g.tag for L in links for g in L.findall("visual/geometry/*") +}) +print(f" arm/motor geometry types in URDF: {geom_tags}") + +print("\nNext step (Isaac Lab env):") +print(f" $ISAAC_PYTHON scripts/urdf_to_usd.py --headless \\") +print(f" --input {urdf_path} --output_dir {args.out.parent}/usd") From b6b88451ae1062bb300b0ceb9d5717ce2db952c2 Mon Sep 17 00:00:00 2001 From: Keiichi Ito Date: Mon, 25 May 2026 15:01:29 +0200 Subject: [PATCH 14/27] Record Phase 3 progress and end-of-session state. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Updated Phase 3 in §5 from "In progress" to "Largely landed for rigid drones," with a numbered list of the 5 commits that landed today and what each does. Calls out what's still pending: compliant joints (schema + URDF revolute + USD ariel:* attrs + example), the optional wrapper script, and pytest integration coverage. * Added §6 entries 12–14 capturing decisions made during the pipeline bring-up: two-env split with URDF as the boundary, stderr-based logging in urdf_to_usd.py to survive Isaac Sim's stdout capture, and the joint_drive workaround for the all-fixed-joints case. Co-Authored-By: Claude Opus 4.7 --- DRONE_BLUEPRINT_PLAN.md | 89 ++++++++++++++++++++++++++++++++++++++--- 1 file changed, 83 insertions(+), 6 deletions(-) diff --git a/DRONE_BLUEPRINT_PLAN.md b/DRONE_BLUEPRINT_PLAN.md index 71f25d3fe..3287ef93c 100644 --- a/DRONE_BLUEPRINT_PLAN.md +++ b/DRONE_BLUEPRINT_PLAN.md @@ -165,13 +165,61 @@ now go through `DroneBlueprint` rather than the phenotype generator directly. upstream fix before closed-loop MuJoCo Lee control is possible without the bridge. -**Phase 3 — Isaac Lab spike. In progress (branch `blueprint-to-urdf`).** +**Phase 3 — Isaac Lab spike. Largely landed for rigid drones (branch `blueprint-to-urdf`).** Approach: Blueprint → URDF → USD via Isaac Lab's `UrdfConverter`, not a -direct `blueprint_to_usd`. Schema refactor landed on the branch so -backends read physical parameters from the Blueprint nodes themselves -(see §6). `blueprint_to_urdf` body is the next step. Direct -`blueprint_to_usd` remains stubbed and now sits *behind* URDF in the -roadmap. +direct `blueprint_to_usd`. Direct `blueprint_to_usd` remains stubbed and +now sits *behind* URDF in the roadmap. + +What's landed (in order of commit): + +1. `Add blueprint_to_urdf stub.` (also on `drones`) — sketches the + planned URDF backend alongside the existing `blueprint_to_usd` stub. +2. `Derive arm and motor physical params from blueprint nodes.` — + schema refactor: cross-section sub-objects (`CylindricalCrossSection` + / `HollowTubeCrossSection` / `RectangularCrossSection`) and derived + `mass` / `inertia_diag` properties on `ArmNode` and `MotorNode`, + sourced from a `propsize`-keyed lookup in `PROPELLER_LIBRARY` + (extended with `motor_radius` / `motor_thickness` per entry, values + from the APC propeller-motor pairing table). Default arm cross- + section is `HollowTube(outer=4mm, inner=3mm)` which with + `density=1500 kg/m³` reproduces existing `BEAM_DENSITY = 0.034 kg/m`. +3. `Implement blueprint_to_urdf for rigid-drone Isaac Lab path.` — + walks the Blueprint tree, emits one `` per CorePlate/Arm/Motor + (diagonal `` from node-derived properties), one + `` per parent-child edge, dispatches arm + geometry on cross-section type (`` for solid/hollow-tube, + `` for rectangular). No actuators emitted (Isaac Lab applies + thrust at runtime via force on the motor link's local +Z). +4. `Add Blueprint → URDF → USD pipeline scripts.` — split across two + envs because ariel needs Python 3.12 (PEP 695 `type` statements, + 25+ files) and the local isaaclab conda env runs Python 3.11. URDF + file is the boundary: + * `scripts/blueprint_to_urdf.py` — ariel env, builds blueprint, + writes URDF. + * `scripts/urdf_to_usd.py` — isaaclab env, takes URDF, writes USD + via `isaaclab.sim.converters.UrdfConverter` (with `target_type= + "none"` + zero PD gains for the all-fixed-joints case). + End-to-end smoke test: quad URDF → USD via the standard Isaac Lab + layered layout (`quad.usd` + `configuration/{quad_base, + quad_physics, quad_robot, quad_sensor}.usd`). +5. `Add example 16: blueprint_to_urdf demo with cross-section + dispatch.` — `examples/d_drones/16_blueprint_to_urdf.py`. Default + produces a HollowTube X-quad URDF; `--rect-arms` flips arms to + solid boxes and verifies the URDF box-geometry path (both variants + round-trip cleanly to USD via the converter). + +**Still pending on this branch — to pick up next session:** + +* **Compliant joints (URDF revolute + sidecar stiffness + USD + `ariel:*` attrs).** The two-layer pattern is documented in §6 entry + 10 — zero-stiffness `revolute` joint in URDF, non-linear `τ(θ)` law + stashed as sidecar attrs for a runtime controller. Schema, emission + in both backends, USD post-processing, and a compliant-arm example + are all not yet written. +* Optional `scripts/blueprint_to_usd.py` wrapper that subprocess- + chains the two halves so users don't have to invoke them manually. +* Pytest integration test (currently skips end-to-end because the + isaaclab env isn't directly invokable from ariel's pytest). ## 6. Design decisions (Phase 3 — URDF / USD backends) @@ -273,6 +321,35 @@ Each entry: **decision** — *why*; alternatives considered. to expose named motor link prims. This is simpler than MJCF's actuator-per-motor wiring, not harder. +12. **Pipeline split into two scripts across two Python envs; URDF file + is the boundary.** ariel uses PEP 695 `type X = …` syntax (25+ + files) which requires Python 3.12, while the local isaaclab conda + env runs Python 3.11. We can't make ariel importable from the + isaaclab env without a non-trivial rewrite. So + `scripts/blueprint_to_urdf.py` runs in the ariel env (produces + URDF) and `scripts/urdf_to_usd.py` runs in the isaaclab env (URDF → + USD via `UrdfConverter`). Alternatives considered: (a) rewrite + ariel to 3.11-compatible syntax (large mechanical change, kicks + the can on type-statement adoption); (b) one wrapper that + subprocess-chains both envs (still possible as a follow-up; + deferred because the manual two-step is fine for now and easier + to debug). + +13. **`scripts/urdf_to_usd.py` logs progress to stderr, not stdout.** + Isaac Sim's launcher captures stdout (probably for its Carb + logger), so `print(...)` from inside the script can be lost. We + use a small `_log(msg)` that writes to `sys.stderr` and flushes, + so the only "where did my prints go?" question is answered up + front. Discovered by burning a debug cycle on it. + +14. **`UrdfConverterCfg.joint_drive` is required even for all-fixed + drones.** The configclass validator treats + `joint_drive.gains.stiffness` as a required field. For our v1 + rigid drone we don't have any actuated joints, so we set + `target_type="none"` with zero PD gains — the values are unused + but the field has to be present to pass validation. (Same dance + soft_airframe does in `convert_xconfig_urdf.py`.) + ## 7. Asks for the meeting 1. Confirm Isaac Lab as the simulator target the consortium will converge From 7f678f39c34bf530e3c3a758f8228a47e63e92c3 Mon Sep 17 00:00:00 2001 From: Keiichi Ito Date: Tue, 26 May 2026 18:07:26 +0200 Subject: [PATCH 15/27] Make ariel importable on Python 3.11. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Replaces PEP 695 type-statement syntax (Python 3.12+) with PEP 613 TypeAlias, so ariel can run in the Python 3.11 conda env that Isaac Sim 5.1 requires. Goal: one unified env in which ariel and Isaac Lab both work, eliminating the two-script subprocess split documented in DRONE_BLUEPRINT_PLAN.md §6 entry 12. Changes: * 31 `type X = ...` statements rewritten to `X: TypeAlias = ...` across 14 files in src/ariel/{ec,parameters,utils,body_phenotypes} and examples/{re_book,z_ec_course}. Each file adds `TypeAlias` to its existing typing import (or adds a new import where there was none). * src/ariel/ec/ea.py: `class EAOperation[**P]:` (PEP 695 generic class syntax) → `class EAOperation(Generic[P]):` using the module-level `P = ParamSpec("P")` that already existed at line 26. * src/ariel/ec/individual.py: dropped the self-referential typing of JSONType / JSONIterable. PEP 695 `type X = ...` evaluates the body lazily, so recursive aliases worked transparently; PEP 613 evaluates eagerly, and forward-ref strings then break at runtime when SQLModel introspects `JSONIterable | None` field annotations. Nested values fall through to `Any` — same approach pydantic.JsonValue takes for runtime use. * pyproject.toml: `requires-python` from `>=3.12` to `>=3.11`. Validation: * Python 3.12 (current dev env): full import chain works, blueprint decoder + URDF + MJCF backends all functional. No regression. * Python 3.11 (isaaclab conda env): syntax is now clean — what was `SyntaxError: invalid syntax (archive.py, line 14)` is now just `ModuleNotFoundError: No module named 'sqlmodel'` (an env-setup issue, not a code issue). The migration is complete; remaining work is installing ariel's runtime deps into the isaaclab env. Co-Authored-By: Claude Opus 4.7 --- examples/re_book/2_body_brain_evolution.py | 4 ++-- examples/re_book/3_body_brain_lr.py | 6 +++--- examples/z_ec_course/A3_template.py | 4 ++-- examples/z_ec_course/A3_template_jack.py | 6 +++--- pyproject.toml | 2 +- .../body_phenotypes/robogen_lite/modules/core.py | 7 +++++-- .../body_phenotypes/robogen_lite/modules/hinge.py | 7 +++++-- src/ariel/ec/archive.py | 8 ++++---- src/ariel/ec/ea.py | 6 +++--- src/ariel/ec/generators copy.py | 6 +++--- src/ariel/ec/generators.py | 6 +++--- src/ariel/ec/individual.py | 14 +++++++++++--- src/ariel/parameters/ariel_modules.py | 5 +++-- src/ariel/parameters/ariel_types.py | 12 +++++++----- src/ariel/parameters/mujoco_params.py | 5 +++-- src/ariel/utils/noise_gen.py | 4 ++-- 16 files changed, 60 insertions(+), 42 deletions(-) diff --git a/examples/re_book/2_body_brain_evolution.py b/examples/re_book/2_body_brain_evolution.py index cd55a063b..2aec4aca1 100644 --- a/examples/re_book/2_body_brain_evolution.py +++ b/examples/re_book/2_body_brain_evolution.py @@ -11,7 +11,7 @@ import argparse import random from pathlib import Path -from typing import Literal +from typing import Literal, TypeAlias import mujoco @@ -92,7 +92,7 @@ NUM_CPPN_OUTPUTS = 1 + T + R # Type Aliases -type ViewerTypes = Literal["launcher", "video", "simple"] +ViewerTypes: TypeAlias = Literal["launcher", "video", "simple"] # Determinism SEED = 42 diff --git a/examples/re_book/3_body_brain_lr.py b/examples/re_book/3_body_brain_lr.py index 67801d03e..8e486dc8d 100644 --- a/examples/re_book/3_body_brain_lr.py +++ b/examples/re_book/3_body_brain_lr.py @@ -11,7 +11,7 @@ import shutil from collections.abc import Callable from pathlib import Path -from typing import Any, Literal +from typing import Any, Literal, TypeAlias # Third-party libraries import mujoco as mj @@ -50,10 +50,10 @@ from ariel.utils.video_recorder import VideoRecorder # Type Checking -type ViewerTypes = Literal["launcher", "video", "simple", "no_control", "frame"] +ViewerTypes: TypeAlias = Literal["launcher", "video", "simple", "no_control", "frame"] # Type Aliases -type PopulationFunc = Callable[[Population], Population] +PopulationFunc: TypeAlias = Callable[[Population], Population] # --- DATA SETUP --- # SCRIPT_NAME = __file__.split("/")[-1][:-3] diff --git a/examples/z_ec_course/A3_template.py b/examples/z_ec_course/A3_template.py index 38757e95a..d5b17b183 100644 --- a/examples/z_ec_course/A3_template.py +++ b/examples/z_ec_course/A3_template.py @@ -2,7 +2,7 @@ # Standard library from pathlib import Path -from typing import TYPE_CHECKING, Any, Literal +from typing import TYPE_CHECKING, Any, Literal, TypeAlias # Third-party libraries import mujoco as mj @@ -32,7 +32,7 @@ from networkx import DiGraph # Type Aliases -type ViewerTypes = Literal["launcher", "video", "simple", "no_control", "frame"] +ViewerTypes: TypeAlias = Literal["launcher", "video", "simple", "no_control", "frame"] # --- RANDOM GENERATOR SETUP --- # SEED = 42 diff --git a/examples/z_ec_course/A3_template_jack.py b/examples/z_ec_course/A3_template_jack.py index 1fd6b0e8d..651ef1687 100644 --- a/examples/z_ec_course/A3_template_jack.py +++ b/examples/z_ec_course/A3_template_jack.py @@ -2,7 +2,7 @@ # Standard library from pathlib import Path -from typing import TYPE_CHECKING, Any, Literal, cast +from typing import TYPE_CHECKING, Any, Literal, TypeAlias, cast import matplotlib.pyplot as plt import mujoco as mj @@ -38,7 +38,7 @@ from networkx import DiGraph # Type Aliases -type ViewerTypes = Literal[ +ViewerTypes: TypeAlias = Literal[ "launcher", "video", "simple", @@ -46,7 +46,7 @@ "no_control", "frame", ] -type Vector = npt.NDArray[np.float64] +Vector: TypeAlias = npt.NDArray[np.float64] # --- RANDOM GENERATOR SETUP --- # SEED = 42 diff --git a/pyproject.toml b/pyproject.toml index d60c436f3..dff402192 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -3,7 +3,7 @@ name = "ariel" version = "0.0.0" description = "ARIEL" readme = "README.md" -requires-python = ">=3.12" +requires-python = ">=3.11" license = { text = "GPL-3.0" } authors = [{ name = "jmdm", email = "jmdm.880@gmail.com" }] classifiers = ["Development Status :: 2 - Pre-Alpha"] diff --git a/src/ariel/body_phenotypes/robogen_lite/modules/core.py b/src/ariel/body_phenotypes/robogen_lite/modules/core.py index 0af7d23bb..ffd815af6 100644 --- a/src/ariel/body_phenotypes/robogen_lite/modules/core.py +++ b/src/ariel/body_phenotypes/robogen_lite/modules/core.py @@ -1,5 +1,8 @@ """TODO(jmdm): description of script.""" +# Standard library +from typing import TypeAlias + # Third-party libraries import mujoco import numpy as np @@ -14,8 +17,8 @@ from ariel.body_phenotypes.robogen_lite.modules.module import Module # Type Aliases -type WeightType = float -type DimensionType = tuple[float, float, float] +WeightType: TypeAlias = float +DimensionType: TypeAlias = tuple[float, float, float] # --- Robogen Configuration --- # # Module weights (kg) diff --git a/src/ariel/body_phenotypes/robogen_lite/modules/hinge.py b/src/ariel/body_phenotypes/robogen_lite/modules/hinge.py index 635f9c74f..2a8759b1a 100644 --- a/src/ariel/body_phenotypes/robogen_lite/modules/hinge.py +++ b/src/ariel/body_phenotypes/robogen_lite/modules/hinge.py @@ -5,6 +5,9 @@ [ ] ".rotate" as superclass method? """ +# Standard library +from typing import TypeAlias + # Third-party libraries import mujoco import numpy as np @@ -18,8 +21,8 @@ SHRINK = 0.99 # Type Aliases -type WeightType = float -type DimensionType = tuple[float, float, float] +WeightType: TypeAlias = float +DimensionType: TypeAlias = tuple[float, float, float] # --- Robogen Configuration --- # # Module weights (kg) diff --git a/src/ariel/ec/archive.py b/src/ariel/ec/archive.py index cc8cee4ab..fb17be53b 100644 --- a/src/ariel/ec/archive.py +++ b/src/ariel/ec/archive.py @@ -2,7 +2,7 @@ import random from pathlib import Path -from typing import Literal +from typing import Literal, TypeAlias import numpy as np from sqlalchemy import Engine, Select, create_engine, func @@ -11,9 +11,9 @@ from ariel.ec.individual import Individual from ariel.ec.population import Population -type FitnessMode = Literal["min", "max"] -type AgeRange = tuple[int, int] | None -type FitnessRange = tuple[float, float] | None +FitnessMode: TypeAlias = Literal["min", "max"] +AgeRange: TypeAlias = tuple[int, int] | None +FitnessRange: TypeAlias = tuple[float, float] | None class Archive: diff --git a/src/ariel/ec/ea.py b/src/ariel/ec/ea.py index 7e168a34b..a0795df15 100644 --- a/src/ariel/ec/ea.py +++ b/src/ariel/ec/ea.py @@ -3,7 +3,7 @@ import inspect from collections.abc import Callable from pathlib import Path -from typing import Concatenate, Literal, ParamSpec +from typing import Concatenate, Generic, Literal, ParamSpec, TypeAlias from pydantic import computed_field from pydantic_settings import BaseSettings @@ -25,7 +25,7 @@ install() P = ParamSpec("P") -type DBHandlingMode = Literal["delete", "halt"] +DBHandlingMode: TypeAlias = Literal["delete", "halt"] # -- Settings ------------------------------------------------------------------ @@ -99,7 +99,7 @@ def db_file_path(self) -> Path: # -- Step wrapper -------------------------------------------------------------- -class EAOperation[**P]: +class EAOperation(Generic[P]): """EAOperation class. Decorating a function with ``@EAOperation`` validates its signature and diff --git a/src/ariel/ec/generators copy.py b/src/ariel/ec/generators copy.py index e49f14ebb..588ae028b 100644 --- a/src/ariel/ec/generators copy.py +++ b/src/ariel/ec/generators copy.py @@ -1,7 +1,7 @@ """ "Generators and mutations for the EC module.""" from collections.abc import Sequence -from typing import TYPE_CHECKING, cast +from typing import TYPE_CHECKING, TypeAlias, cast import numpy as np from numpy.random import Generator @@ -14,8 +14,8 @@ SEED: int = 42 _rng: Generator = np.random.default_rng(SEED) -type Integers = Sequence[int] -type Floats = Sequence[float] +Integers: TypeAlias = Sequence[int] +Floats: TypeAlias = Sequence[float] # ── Settings ────────────────────────────────────────────────────────────────── diff --git a/src/ariel/ec/generators.py b/src/ariel/ec/generators.py index bbebd0c52..5df040ee3 100644 --- a/src/ariel/ec/generators.py +++ b/src/ariel/ec/generators.py @@ -1,7 +1,7 @@ """Generators and mutations for the EC module.""" from collections.abc import Sequence -from typing import TYPE_CHECKING, cast +from typing import TYPE_CHECKING, TypeAlias, cast import numpy as np from numpy.random import Generator @@ -14,8 +14,8 @@ SEED: int = 42 _rng: Generator = np.random.default_rng(SEED) -type Integers = Sequence[int] -type Floats = Sequence[float] +Integers: TypeAlias = Sequence[int] +Floats: TypeAlias = Sequence[float] # -- Settings ------------------------------------------------------------------ diff --git a/src/ariel/ec/individual.py b/src/ariel/ec/individual.py index 4d2ce8051..608b03233 100644 --- a/src/ariel/ec/individual.py +++ b/src/ariel/ec/individual.py @@ -1,12 +1,20 @@ """ARIEL Individual.""" from collections.abc import Hashable, Sequence +from typing import Any, TypeAlias from sqlalchemy import JSON, Column from sqlmodel import Field, SQLModel -type JSONPrimitive = str | int | float | bool -type JSONType = JSONPrimitive | Sequence[JSONType] | dict[Hashable, JSONType] -type JSONIterable = Sequence[JSONType] | dict[Hashable, JSONType] +# Nested JSON values fall through to `Any` because PEP 613 TypeAlias is +# evaluated eagerly and self-referential aliases would need forward-ref +# strings, which then fail at runtime when SQLModel introspects +# `JSONIterable | None` field annotations. PEP 695's lazy `type X = ...` +# handled this transparently; the `Any` fallback is the standard +# pre-3.12 workaround (matches how pydantic.JsonValue and friends model +# the nested case for runtime use). +JSONPrimitive: TypeAlias = str | int | float | bool +JSONType: TypeAlias = JSONPrimitive | Sequence[Any] | dict[Hashable, Any] +JSONIterable: TypeAlias = Sequence[Any] | dict[Hashable, Any] class Individual(SQLModel, table=True): diff --git a/src/ariel/parameters/ariel_modules.py b/src/ariel/parameters/ariel_modules.py index 1eac2d132..dfcd3f6ad 100644 --- a/src/ariel/parameters/ariel_modules.py +++ b/src/ariel/parameters/ariel_modules.py @@ -16,6 +16,7 @@ # Standard library from pathlib import Path +from typing import TypeAlias # Third-party libraries import numpy as np @@ -28,8 +29,8 @@ # Type Checking # Type Aliases # Type Aliases -type WeightType = float -type DimensionType = tuple[float, float, float] +WeightType: TypeAlias = float +DimensionType: TypeAlias = tuple[float, float, float] # --- DATA SETUP --- # SCRIPT_NAME = __file__.split("/")[-1][:-3] diff --git a/src/ariel/parameters/ariel_types.py b/src/ariel/parameters/ariel_types.py index ebcada139..8aba9d0a5 100644 --- a/src/ariel/parameters/ariel_types.py +++ b/src/ariel/parameters/ariel_types.py @@ -1,6 +1,8 @@ """ARIEL Types.""" # Standard library +from typing import TypeAlias + # Third-party libraries import numpy as np import numpy.typing as npt @@ -16,10 +18,10 @@ # Type Aliases # --- NUMERICAL TYPES --- # -type Dimension = tuple[float, float, float] # length, width, height -type Position = tuple[float, float, float] # x-pos, y-pos, z-pos -type Rotation = tuple[float, float, float] # x-axis, y-axis, z-axis +Dimension: TypeAlias = tuple[float, float, float] # length, width, height +Position: TypeAlias = tuple[float, float, float] # x-pos, y-pos, z-pos +Rotation: TypeAlias = tuple[float, float, float] # x-axis, y-axis, z-axis # --- NUMPY DERIVED TYPES --- # -type FloatArray = npt.NDArray[ND_FLOAT_PRECISION] -type IntArray = npt.NDArray[ND_INT_PRECISION] +FloatArray: TypeAlias = npt.NDArray[ND_FLOAT_PRECISION] +IntArray: TypeAlias = npt.NDArray[ND_INT_PRECISION] diff --git a/src/ariel/parameters/mujoco_params.py b/src/ariel/parameters/mujoco_params.py index f3b141970..e44584fa7 100644 --- a/src/ariel/parameters/mujoco_params.py +++ b/src/ariel/parameters/mujoco_params.py @@ -16,6 +16,7 @@ # Standard library from pathlib import Path +from typing import TypeAlias # Third-party libraries import mujoco @@ -29,8 +30,8 @@ # Type Checking # Type Aliases # Type Aliases -type WeightType = float -type DimensionType = tuple[float, float, float] +WeightType: TypeAlias = float +DimensionType: TypeAlias = tuple[float, float, float] # --- DATA SETUP --- # SCRIPT_NAME = __file__.split("/")[-1][:-3] diff --git a/src/ariel/utils/noise_gen.py b/src/ariel/utils/noise_gen.py index 34f7f6bf2..393b5e051 100644 --- a/src/ariel/utils/noise_gen.py +++ b/src/ariel/utils/noise_gen.py @@ -2,7 +2,7 @@ # Standard library from dataclasses import dataclass -from typing import Literal +from typing import Literal, TypeAlias # Third-party libraries import numpy as np @@ -16,7 +16,7 @@ ) # Type Aliases -type NormMethod = Literal["linear", "clip", "none"] +NormMethod: TypeAlias = Literal["linear", "clip", "none"] @dataclass From 784ca13c83727ce83d5614f15f869f53eb44f226 Mon Sep 17 00:00:00 2001 From: Keiichi Ito Date: Tue, 26 May 2026 18:18:48 +0200 Subject: [PATCH 16/27] Record unified-env achievement on python-311-compat. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Phase 3 follow-on commit list extended with the 3.11 migration; the "Still pending" section drops the obsoleted wrapper-script item (single env makes it unnecessary) and adds the dep-pin item as a deferred stretch. * §6 entry 12 (the two-env split rationale) marked superseded with a forward pointer to the new entry. * §6 entry 15 added documenting the migration: scope, the self-referential-alias subtlety, and validation status (URDF→USD pipeline runs end-to-end in one isaaclab env despite the pip resolver's warnings about numpy 2 / gymnasium 1.3 / torch CUDA build swaps). Co-Authored-By: Claude Opus 4.7 --- DRONE_BLUEPRINT_PLAN.md | 68 ++++++++++++++++++++++++++++++----------- 1 file changed, 50 insertions(+), 18 deletions(-) diff --git a/DRONE_BLUEPRINT_PLAN.md b/DRONE_BLUEPRINT_PLAN.md index 3287ef93c..5ccca6724 100644 --- a/DRONE_BLUEPRINT_PLAN.md +++ b/DRONE_BLUEPRINT_PLAN.md @@ -208,7 +208,17 @@ What's landed (in order of commit): solid boxes and verifies the URDF box-geometry path (both variants round-trip cleanly to USD via the converter). -**Still pending on this branch — to pick up next session:** +**Follow-on branch `python-311-compat` (off `blueprint-to-urdf`):** + +6. `Make ariel importable on Python 3.11.` — dropped all PEP 695 + syntax (31 type-alias statements + one generic class) and + downgraded `requires-python` to `>=3.11`. Motivation: unify ariel + and Isaac Lab into one conda env (Isaac Sim 5.1 pins Python 3.11). + After `pip install -e ariel` into the existing `isaaclab` conda + env, the full Blueprint → URDF → USD pipeline runs in one + process. See §6 entry 15 for details. + +**Still pending — to pick up next session:** * **Compliant joints (URDF revolute + sidecar stiffness + USD `ariel:*` attrs).** The two-layer pattern is documented in §6 entry @@ -216,10 +226,12 @@ What's landed (in order of commit): stashed as sidecar attrs for a runtime controller. Schema, emission in both backends, USD post-processing, and a compliant-arm example are all not yet written. -* Optional `scripts/blueprint_to_usd.py` wrapper that subprocess- - chains the two halves so users don't have to invoke them manually. -* Pytest integration test (currently skips end-to-end because the - isaaclab env isn't directly invokable from ariel's pytest). +* Pytest integration test for the Blueprint → URDF → USD pipeline + (now feasible in-process under the unified env; just needs a + `pytest.mark.isaaclab` skip-if-not-available guard). +* (Stretch) Targeted dep pins in pyproject.toml to keep numpy < 2 + and gymnasium == 1.2.1 so isaaclab's pins aren't violated. Defer + until a downstream isaaclab feature actually breaks. ## 6. Design decisions (Phase 3 — URDF / USD backends) @@ -321,19 +333,16 @@ Each entry: **decision** — *why*; alternatives considered. to expose named motor link prims. This is simpler than MJCF's actuator-per-motor wiring, not harder. -12. **Pipeline split into two scripts across two Python envs; URDF file - is the boundary.** ariel uses PEP 695 `type X = …` syntax (25+ - files) which requires Python 3.12, while the local isaaclab conda - env runs Python 3.11. We can't make ariel importable from the - isaaclab env without a non-trivial rewrite. So - `scripts/blueprint_to_urdf.py` runs in the ariel env (produces - URDF) and `scripts/urdf_to_usd.py` runs in the isaaclab env (URDF → - USD via `UrdfConverter`). Alternatives considered: (a) rewrite - ariel to 3.11-compatible syntax (large mechanical change, kicks - the can on type-statement adoption); (b) one wrapper that - subprocess-chains both envs (still possible as a follow-up; - deferred because the manual two-step is fine for now and easier - to debug). +12. **~~Pipeline split into two scripts across two Python envs~~ — superseded by entry 15.** + Originally documented: ariel used PEP 695 `type X = …` syntax (25+ + files) requiring Python 3.12, while the local isaaclab conda env + runs Python 3.11, so `scripts/blueprint_to_urdf.py` ran in the + ariel env and `scripts/urdf_to_usd.py` in the isaaclab env with + the URDF file as the boundary. **As of branch `python-311-compat` + (commit `7f678f3`), this constraint is gone** — ariel is now 3.11- + compatible and pip-installable into the isaaclab env. The two + scripts still exist and are useful as separable building blocks, + but they can both run in the single unified env. 13. **`scripts/urdf_to_usd.py` logs progress to stderr, not stdout.** Isaac Sim's launcher captures stdout (probably for its Carb @@ -350,6 +359,29 @@ Each entry: **decision** — *why*; alternatives considered. but the field has to be present to pass validation. (Same dance soft_airframe does in `convert_xconfig_urdf.py`.) +15. **ariel is now Python 3.11-compatible (branch `python-311-compat`).** + Motivation: ARIEL needs to be simulator-agnostic, and the only + practical way to host Isaac Lab inside the same conda env as ariel + was to drop ariel's Python 3.12-only constructs (Isaac Sim 5.1 + ships its own Python 3.11 in `_isaac_sim/kit/python/`; NVIDIA + pins it). Audit found ~31 PEP 695 `type X = ...` statements + across 14 files plus one PEP 695 generic class + (`class EAOperation[**P]:`); no 3.12-only stdlib calls. Each + `type X = ...` became `X: TypeAlias = ...` (PEP 613); the generic + class became `class EAOperation(Generic[P]):` using the existing + module-level `P = ParamSpec("P")`. One subtlety: + `src/ariel/ec/individual.py` had self-referential aliases + (`JSONType` referring to itself); PEP 695's lazy evaluation made + this transparent, but PEP 613 is eager, so we dropped the + recursion (nested values now `Any`, matching `pydantic.JsonValue` + practice). pyproject.toml dropped from `>=3.12` to `>=3.11`. End- + to-end validation: blueprint_to_urdf + urdf_to_usd both run in + one `isaaclab` conda env after `pip install -e ariel`. The pip + resolver reports conflicts (numpy 2 vs `isaaclab`'s `<2`, + gymnasium 1.3 vs 1.2.1, torch CUDA build swap) but the URDF→USD + pipeline still works; if those conflicts bite elsewhere (RL + training, dex_retargeting, etc.) they'll need targeted pins. + ## 7. Asks for the meeting 1. Confirm Isaac Lab as the simulator target the consortium will converge From fb6c94ed4116e00a103dc300197cbd9a111ca571 Mon Sep 17 00:00:00 2001 From: Keiichi Ito Date: Tue, 26 May 2026 18:26:29 +0200 Subject: [PATCH 17/27] =?UTF-8?q?Expand=20=C2=A76=20entry=2015=20with=20th?= =?UTF-8?q?e=20EA-inner-loop=20motivation.?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit The previous version said the migration was for "simulator-agnostic" without naming the use case that actually forced it: EA objective functions that simulate each morphology, where the two-env subprocess split would pay ~60–90 s of Isaac Sim launch overhead per individual. Also lists alternatives we considered (Isaac→3.12, long-running worker, MuJoCo-only EA loop) and why we picked the migration. Co-Authored-By: Claude Opus 4.7 --- DRONE_BLUEPRINT_PLAN.md | 55 ++++++++++++++++++++++++++++------------- 1 file changed, 38 insertions(+), 17 deletions(-) diff --git a/DRONE_BLUEPRINT_PLAN.md b/DRONE_BLUEPRINT_PLAN.md index 5ccca6724..7e408af76 100644 --- a/DRONE_BLUEPRINT_PLAN.md +++ b/DRONE_BLUEPRINT_PLAN.md @@ -360,27 +360,48 @@ Each entry: **decision** — *why*; alternatives considered. soft_airframe does in `convert_xconfig_urdf.py`.) 15. **ariel is now Python 3.11-compatible (branch `python-311-compat`).** - Motivation: ARIEL needs to be simulator-agnostic, and the only - practical way to host Isaac Lab inside the same conda env as ariel - was to drop ariel's Python 3.12-only constructs (Isaac Sim 5.1 - ships its own Python 3.11 in `_isaac_sim/kit/python/`; NVIDIA - pins it). Audit found ~31 PEP 695 `type X = ...` statements - across 14 files plus one PEP 695 generic class - (`class EAOperation[**P]:`); no 3.12-only stdlib calls. Each - `type X = ...` became `X: TypeAlias = ...` (PEP 613); the generic - class became `class EAOperation(Generic[P]):` using the existing - module-level `P = ParamSpec("P")`. One subtlety: + + **Motivation:** ARIEL must be simulator-agnostic, and the use case + that forced this was *EA objective functions that simulate each + morphology* (e.g., fitness = gates passed in N seconds). With + thousands of individuals per evolution, the previous two-env + subprocess split paid the Isaac Sim launch cost (~60–90 s) once + per evaluation — catastrophic. The only practical way to host + Isaac Lab inside the same conda env as ariel was to drop ariel's + Python 3.12-only constructs, because Isaac Sim 5.1 ships its own + Python 3.11 in `_isaac_sim/kit/python/` and NVIDIA pins it (we + can't bring Isaac to 3.12, so ariel comes down to 3.11). With + both in one process, EA workers can convert + simulate + in-memory; per-individual launch overhead disappears. + + **Audit:** 31 PEP 695 `type X = ...` statements across 14 files + plus one PEP 695 generic class (`class EAOperation[**P]:`); no + 3.12-only stdlib calls. Alternatives considered: (a) rewrite + Isaac to support 3.12 — not actually controllable by us; (b) + long-running Isaac Lab worker process talking to ariel over IPC + — viable but ~hundreds of lines of plumbing and harder to debug; + (c) keep MuJoCo as the only EA-loop simulator and use Isaac Lab + only for top-K validation — a fine v1 default but doesn't give + us GPU-parallel envs. + + **Rewrite:** each `type X = ...` → `X: TypeAlias = ...` (PEP 613); + the generic class → `class EAOperation(Generic[P]):` using the + existing module-level `P = ParamSpec("P")`. One subtlety: `src/ariel/ec/individual.py` had self-referential aliases - (`JSONType` referring to itself); PEP 695's lazy evaluation made + (`JSONType` refers to itself); PEP 695's lazy evaluation made this transparent, but PEP 613 is eager, so we dropped the recursion (nested values now `Any`, matching `pydantic.JsonValue` - practice). pyproject.toml dropped from `>=3.12` to `>=3.11`. End- - to-end validation: blueprint_to_urdf + urdf_to_usd both run in - one `isaaclab` conda env after `pip install -e ariel`. The pip + practice for runtime use). pyproject.toml dropped from `>=3.12` + to `>=3.11`. + + **Validation:** blueprint_to_urdf + urdf_to_usd both run in one + `isaaclab` conda env after `pip install -e ariel`. The pip resolver reports conflicts (numpy 2 vs `isaaclab`'s `<2`, - gymnasium 1.3 vs 1.2.1, torch CUDA build swap) but the URDF→USD - pipeline still works; if those conflicts bite elsewhere (RL - training, dex_retargeting, etc.) they'll need targeted pins. + gymnasium 1.3 vs 1.2.1, torch CUDA build swap from `+cu128` to + `+cu130`) but the URDF→USD pipeline still works. If those + conflicts bite elsewhere (RL training, dex_retargeting, etc.) + they'll need targeted pins in ariel's pyproject.toml; deferred + until something actually breaks. ## 7. Asks for the meeting From 57592d4cfba69956dc546036cbb4abe79cd9f690 Mon Sep 17 00:00:00 2001 From: Keiichi Ito Date: Tue, 26 May 2026 23:32:07 +0200 Subject: [PATCH 18/27] Add pluggable simulator backend Protocol + tutorial. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Defines the BlueprintGateEnv Protocol — ariel's contract for a simulator-backend-agnostic gymnasium VecEnv constructed from a DroneBlueprint. The PPO trainer (and any other consumer) accepts any implementation; collaborators can plug in their own simulator while keeping ariel's EA + learning infrastructure. This is the architectural payoff of the unified-env work in §6 entry 15. Phase 1 ships: * src/ariel/simulation/tasks/blueprint_gate_env.py — the @runtime_checkable BlueprintGateEnv Protocol, plus NumpyBlueprintGateEnv: a thin subclass of the existing DroneGateEnv that adds a Blueprint → propellers-list adapter at the constructor. Inherits all VecEnv methods, gate definitions, reward shaping, and observation/action spaces unchanged. * src/ariel/simulation/tasks/isaaclab_gate_env.py — IsaacLabBlueprintGateEnv stub with the planned constructor signature and NotImplementedError. Pins the API so the tutorial's --simulator isaaclab path compiles against the intended shape; body is Phase 2 work. * tutorials/pluggable_simulator/{README.md, train.py} — README walks through the architecture, the Protocol contract, and a five-step "add your own backend" recipe. train.py is the unified entry point with --simulator {numpy,isaaclab} dispatch, demonstrating that the PPO loop is identical across backends. Bug fix bundled in: * src/ariel/simulation/tasks/drone_gate_env.py: renamed self.seed → self._seed. DroneGateEnv stored its seed as an int attribute shadowing the inherited VecEnv.seed() method that stable-baselines3 PPO calls in set_random_seed. Anyone passing seed= to PPO would have hit "TypeError: 'int' object is not callable". Surfaced because the new tutorial passes a seed through the entire pipeline; fix is targeted (3 lines across __init__ and reset_seed). Validation: * Smoke test (ariel 3.12 venv): PPO 2000 timesteps, num_envs=4, quad preset → completes in 4.7 s at ~6600 env-steps/sec. ep_rew_mean ~-21 (expected for a from-scratch policy). Protocol isinstance assert passes. * Smoke test (unified isaaclab 3.11 conda env): hits a segfault during PPO startup, likely numpy 2 ABI conflict with stable- baselines3 compiled deps. This is exactly the "if pip conflicts bite elsewhere" risk we flagged in §6 entry 15; promoted to a blocking item in the "Still pending" list. Doc updates (DRONE_BLUEPRINT_PLAN.md): * Phase 3 follow-on commit list extended with the pluggable- simulator branch and entry 7. * "Still pending" rewritten: Phase 2 (Isaac Lab implementation) is the next item; numpy<2 pinning promoted from stretch since the segfault means it now blocks RL training in the unified env. * §6 entry 17 added documenting the design decisions: why the seam is a Protocol (not ABC, not gymnasium-only duck typing), why NumpyBlueprintGateEnv is a subclass rather than composition, and the seed-attribute bug we found and fixed in passing. Co-Authored-By: Claude Opus 4.7 --- DRONE_BLUEPRINT_PLAN.md | 82 +++++++- .../simulation/tasks/blueprint_gate_env.py | 118 +++++++++++ src/ariel/simulation/tasks/drone_gate_env.py | 19 +- .../simulation/tasks/isaaclab_gate_env.py | 91 ++++++++ tutorials/pluggable_simulator/README.md | 195 ++++++++++++++++++ tutorials/pluggable_simulator/train.py | 125 +++++++++++ 6 files changed, 614 insertions(+), 16 deletions(-) create mode 100644 src/ariel/simulation/tasks/blueprint_gate_env.py create mode 100644 src/ariel/simulation/tasks/isaaclab_gate_env.py create mode 100644 tutorials/pluggable_simulator/README.md create mode 100644 tutorials/pluggable_simulator/train.py diff --git a/DRONE_BLUEPRINT_PLAN.md b/DRONE_BLUEPRINT_PLAN.md index 7e408af76..46cf11646 100644 --- a/DRONE_BLUEPRINT_PLAN.md +++ b/DRONE_BLUEPRINT_PLAN.md @@ -218,20 +218,43 @@ What's landed (in order of commit): env, the full Blueprint → URDF → USD pipeline runs in one process. See §6 entry 15 for details. +**Follow-on branch `pluggable-simulator` (off `python-311-compat`):** + +7. `Add pluggable simulator backend Protocol + tutorial.` — defines + the `BlueprintGateEnv` Protocol so ariel's EA+PPO loop is + simulator-backend-agnostic. Ships `NumpyBlueprintGateEnv` (thin + shim over the existing `DroneGateEnv` declared as a Protocol + implementation) and an `IsaacLabBlueprintGateEnv` stub showing + the next plug-in target. Tutorial at + `tutorials/pluggable_simulator/` walks a collaborator through the + architecture and the "add your own simulator" recipe. Includes a + fix to a pre-existing `DroneGateEnv` bug where `self.seed` + shadowed the inherited `VecEnv.seed()` method (broke + stable-baselines3's `set_random_seed`). See §6 entry 17. + **Still pending — to pick up next session:** +* **Phase 2 of pluggable simulator** — implement + `IsaacLabBlueprintGateEnv` for real (URDF→USD in-process, parallel + envs, per-motor thrust model lifted from soft_airframe). The + Protocol contract is now stable, so this is purely simulator-side + work. * **Compliant joints (URDF revolute + sidecar stiffness + USD - `ariel:*` attrs).** The two-layer pattern is documented in §6 entry - 10 — zero-stiffness `revolute` joint in URDF, non-linear `τ(θ)` law - stashed as sidecar attrs for a runtime controller. Schema, emission - in both backends, USD post-processing, and a compliant-arm example - are all not yet written. + `ariel:*` attrs).** Schema landed on `compliant-joint-schema`; + the emission half is what's still pending. The two-layer pattern + is documented in §6 entry 10 — zero-stiffness `revolute` joint in + URDF, non-linear `τ(θ)` law stashed as sidecar attrs for a + runtime controller. * Pytest integration test for the Blueprint → URDF → USD pipeline (now feasible in-process under the unified env; just needs a `pytest.mark.isaaclab` skip-if-not-available guard). -* (Stretch) Targeted dep pins in pyproject.toml to keep numpy < 2 - and gymnasium == 1.2.1 so isaaclab's pins aren't violated. Defer - until a downstream isaaclab feature actually breaks. +* Targeted dep pins in pyproject.toml to keep numpy < 2 and + gymnasium == 1.2.1 so isaaclab's pins aren't violated. **Promoted + from stretch:** the smoke test for `pluggable-simulator` segfaulted + in the unified isaaclab env on PPO startup (likely a numpy 2 ABI + conflict with stable-baselines3's compiled deps). Same smoke test + passed cleanly in the ariel 3.12 venv where numpy 1.x is intact, + confirming the seam itself is correct. ## 6. Design decisions (Phase 3 — URDF / USD backends) @@ -403,6 +426,49 @@ Each entry: **decision** — *why*; alternatives considered. they'll need targeted pins in ariel's pyproject.toml; deferred until something actually breaks. +17. **Simulator backends are a plug point, not a hard-coded choice; + the contract is the `BlueprintGateEnv` Protocol.** + + **Motivation:** the ARIEL consortium has collaborators using + divergent simulators (MuJoCo, Aerial Gym, Isaac Lab, IsaacGym, + in-house stacks). ARIEL's contribution to those groups is the + *evolutionary + learning loop* — decoders, EA operators, repair, + inspection, PPO training. If the simulator is hard-coded, every + collaborator either swaps to ariel's simulator (won't happen) or + re-implements the loop themselves (defeats the point). The + seam has to be deliberate. + + **Contract:** a `BlueprintGateEnv` is a `gymnasium.VecEnv` (stable- + baselines3 style) constructed from a `DroneBlueprint`, exposing + `.blueprint` and `.num_envs` attributes. Implemented as + `typing.Protocol` with `@runtime_checkable` (per the + pluggable-backend question we deliberated): no inheritance + forced on collaborators, but `isinstance(env, BlueprintGateEnv)` + works for runtime sanity-checks. Concrete VecEnv methods come + via the standard `stable_baselines3.common.vec_env.VecEnv` base + class. + + **What ships in v1:** + - `NumpyBlueprintGateEnv` — declares the existing `DroneGateEnv` + (NumPy + SymPy physics) as a Protocol implementation by + subclassing it and adding a Blueprint → propellers-list + adapter at the constructor. Smoke-tested with PPO 2k steps in + 4.7 s. + - `IsaacLabBlueprintGateEnv` — stub with the planned constructor + signature and a `NotImplementedError` body. Phase 2 work. + - `tutorials/pluggable_simulator/{README.md, train.py}` — + walks a collaborator through the architecture, the + `--simulator {numpy,isaaclab}` dispatch, and the five-step + "add your own backend" recipe. + + **Pre-existing bug fixed in passing:** `DroneGateEnv.__init__` + stored `self.seed = seed` (an int), shadowing the inherited + `VecEnv.seed()` method that stable-baselines3's `PPO` calls in + `set_random_seed`. Renamed to `self._seed` and updated the one + other internal reader (`reset_seed`). Any PPO user of + `DroneGateEnv` would have hit this; nothing in the existing + examples exercised it because they didn't pass `seed=` to PPO. + ## 7. Asks for the meeting 1. Confirm Isaac Lab as the simulator target the consortium will converge diff --git a/src/ariel/simulation/tasks/blueprint_gate_env.py b/src/ariel/simulation/tasks/blueprint_gate_env.py new file mode 100644 index 000000000..6578201e9 --- /dev/null +++ b/src/ariel/simulation/tasks/blueprint_gate_env.py @@ -0,0 +1,118 @@ +"""Pluggable simulator backends for the drone-gate-passing task. + +This module exposes the ``BlueprintGateEnv`` *Protocol* — ariel's +contract for a simulator-backend-agnostic gymnasium ``VecEnv`` that +runs the gate-racing task on a drone described by a +:class:`~ariel.body_phenotypes.drone.blueprint.DroneBlueprint`. + +The PPO trainer (and any other consumer) accepts *any* implementation +of this Protocol; collaborators can plug in their own simulator by +satisfying the contract. v1 ships: + +* :class:`NumpyBlueprintGateEnv` — wraps the existing + :class:`~ariel.simulation.tasks.drone_gate_env.DroneGateEnv`, which + drives the pure-NumPy ``DroneSimulator``. +* :class:`~ariel.simulation.tasks.isaaclab_gate_env.IsaacLabBlueprintGateEnv` + — stub (next phase). Will wrap Isaac Lab parallel envs spawned from + a USD generated via ``blueprint_to_urdf``. + +Usage: + + from ariel.body_phenotypes.drone.decoders import spherical_angular_to_blueprint + from ariel.simulation.tasks.blueprint_gate_env import NumpyBlueprintGateEnv + + bp = spherical_angular_to_blueprint(genome, propsize=5) + env = NumpyBlueprintGateEnv(blueprint=bp, num_envs=64) + # env is a gymnasium VecEnv — hand to PPO unchanged. +""" +from __future__ import annotations + +from typing import Any, Protocol, runtime_checkable + +from stable_baselines3.common.vec_env import VecEnv + +from ariel.body_phenotypes.drone.backends import blueprint_to_propellers +from ariel.body_phenotypes.drone.blueprint import DroneBlueprint +from ariel.simulation.tasks.drone_gate_env import DroneGateEnv + + +# ---------- Protocol ---------- + +@runtime_checkable +class BlueprintGateEnv(Protocol): + """Construction contract for simulator-backend-agnostic gate-racing envs. + + Implementations are gymnasium VecEnvs (stable-baselines3 style) + constructed from a :class:`DroneBlueprint`. A PPO trainer treats + any conforming instance as an opaque ``VecEnv`` — it never has to + know which simulator backend produced it. + + A conforming implementation must: + + 1. Accept a ``blueprint: DroneBlueprint`` argument at construction + (alongside ``num_envs`` and any backend-specific kwargs). + 2. Expose ``self.blueprint`` and ``self.num_envs`` as public + attributes. + 3. Implement the standard ``VecEnv`` methods (``reset``, + ``step_async``, ``step_wait``, ``close``, ``get_attr``, + ``set_attr``, ``env_method``, ``env_is_wrapped``) — most + implementations inherit these from + ``stable_baselines3.common.vec_env.VecEnv``. + + To add a new simulator backend, write a class that satisfies this + Protocol; ariel's EA + PPO pipeline will accept it directly. + """ + + blueprint: DroneBlueprint + num_envs: int + + +# ---------- v1 backend: NumPy DroneSimulator via existing DroneGateEnv ---------- + +class NumpyBlueprintGateEnv(DroneGateEnv): + """Pluggable-Protocol wrapper around the existing NumPy-physics env. + + Composes ``blueprint_to_propellers`` (Blueprint → propellers list) + with the existing :class:`DroneGateEnv` (propellers → VecEnv). + Inheriting from ``DroneGateEnv`` is a deliberate choice: every + VecEnv method, the gate definitions, the reward shaping, and the + observation/action space are reused unchanged. The wrapper's only + job is to be the Protocol-conforming entry point and stash + ``self.blueprint``. + + Subclassing instead of composition means consumers can isinstance- + check either ``NumpyBlueprintGateEnv`` or ``DroneGateEnv``, and + ``VecEnv`` introspection (``env.num_envs``, ``env.observation_space``) + works without forwarding boilerplate. + """ + + def __init__( + self, + *, + blueprint: DroneBlueprint, + num_envs: int, + convention: str = "ned", + **drone_gate_env_kwargs: Any, + ) -> None: + # `DroneSimulator` (the NumPy backend underneath DroneGateEnv) is + # NED — z-down, Lee-controller convention. blueprint_to_propellers + # supports both "z_up" (default) and "ned"; we ask for NED here so + # the propellers list matches DroneSimulator's frame without an + # extra inversion in the env layer. + propellers = blueprint_to_propellers(blueprint, convention=convention) + super().__init__( + num_envs=num_envs, + propellers=propellers, + **drone_gate_env_kwargs, + ) + self.blueprint = blueprint + # Protocol also requires `num_envs`; DroneGateEnv -> VecEnv already + # sets that, but reassigning makes the contract visible at this + # class's source. + self.num_envs = num_envs + + +__all__ = [ + "BlueprintGateEnv", + "NumpyBlueprintGateEnv", +] diff --git a/src/ariel/simulation/tasks/drone_gate_env.py b/src/ariel/simulation/tasks/drone_gate_env.py index 27deee1f7..033644033 100644 --- a/src/ariel/simulation/tasks/drone_gate_env.py +++ b/src/ariel/simulation/tasks/drone_gate_env.py @@ -74,11 +74,14 @@ def __init__(self, self.y_bounds = y_bounds self.z_bounds = z_bounds - # set seed - self.seed = seed - if self.seed is not None: - np.random.seed(self.seed) - torch.manual_seed(self.seed) + # set seed. + # NOTE: stored as `self._seed`, not `self.seed`, to avoid shadowing + # the inherited `VecEnv.seed()` method that stable-baselines3's + # `set_random_seed` calls. + self._seed = seed + if self._seed is not None: + np.random.seed(self._seed) + torch.manual_seed(self._seed) # Initialize drone simulator if propellers is not None: @@ -256,9 +259,9 @@ def _convert_individual_to_propellers(self, individual): return propellers, mounting_points def reset_seed(self): - if self.seed is not None: - np.random.seed(self.seed) - torch.manual_seed(self.seed) + if self._seed is not None: + np.random.seed(self._seed) + torch.manual_seed(self._seed) def update_states_gate(self): # Transform pos and vel in gate frame diff --git a/src/ariel/simulation/tasks/isaaclab_gate_env.py b/src/ariel/simulation/tasks/isaaclab_gate_env.py new file mode 100644 index 000000000..d2dd5caf1 --- /dev/null +++ b/src/ariel/simulation/tasks/isaaclab_gate_env.py @@ -0,0 +1,91 @@ +"""Isaac Lab backend for the drone-gate-passing task — *stub*. + +Implementation deferred to Phase 2 of the pluggable-simulator effort. +The Protocol contract lives in +:mod:`ariel.simulation.tasks.blueprint_gate_env`; this module reserves +the import path and pins the planned API so collaborators can see the +shape from both sides of the seam. + +Phase 2 will: + +1. Convert the blueprint to URDF in-process via + ``ariel.body_phenotypes.drone.backends.blueprint_to_urdf``. +2. Run ``isaaclab.sim.converters.UrdfConverter`` to produce a USD + (no subprocess — both halves live in the unified ariel/isaaclab + conda env now; see DRONE_BLUEPRINT_PLAN.md §6 entry 15). +3. Spawn ``num_envs`` parallel articulation instances in Isaac Sim. +4. Apply per-motor thrust each step using a first-order motor model + lifted from + ``soft_airframe_optimization/src/morphy_simulator.py`` + (matched to the NumPy backend's reference dynamics so trained + policies have a chance at sim-to-sim transfer). +5. Spawn gate prims at the same positions as the NumPy env so the + task reward shaping is identical. +6. Return observations / rewards / dones in the standard VecEnv + format, satisfying the + :class:`~ariel.simulation.tasks.blueprint_gate_env.BlueprintGateEnv` + Protocol. +""" +from __future__ import annotations + +from typing import Any + +from stable_baselines3.common.vec_env import VecEnv + +from ariel.body_phenotypes.drone.blueprint import DroneBlueprint + + +class IsaacLabBlueprintGateEnv(VecEnv): + """Isaac Lab gate-passing env — *not yet implemented*. + + Carries the planned constructor signature so the call site in the + tutorial (and any future production callers) compiles against the + intended API. Calling it raises ``NotImplementedError`` until + Phase 2 lands. + """ + + blueprint: DroneBlueprint + num_envs: int + + def __init__( + self, + *, + blueprint: DroneBlueprint, + num_envs: int, + headless: bool = True, + device: str = "cuda:0", + **kwargs: Any, + ) -> None: + raise NotImplementedError( + "IsaacLabBlueprintGateEnv is the Phase 2 deliverable of the " + "pluggable-simulator effort. Use NumpyBlueprintGateEnv for now." + ) + + # The abstract VecEnv methods would be implemented in Phase 2; we + # leave them as stubs so the class can at least be imported. + def reset(self): # type: ignore[override] + raise NotImplementedError + + def step_async(self, actions): # type: ignore[override] + raise NotImplementedError + + def step_wait(self): # type: ignore[override] + raise NotImplementedError + + def close(self) -> None: # type: ignore[override] + raise NotImplementedError + + def get_attr(self, attr_name, indices=None): # type: ignore[override] + raise NotImplementedError + + def set_attr(self, attr_name, value, indices=None): # type: ignore[override] + raise NotImplementedError + + def env_method(self, method_name, *method_args, indices=None, **method_kwargs): # type: ignore[override] + raise NotImplementedError + + def env_is_wrapped(self, wrapper_class, indices=None): # type: ignore[override] + raise NotImplementedError + + +__all__ = ["IsaacLabBlueprintGateEnv"] diff --git a/tutorials/pluggable_simulator/README.md b/tutorials/pluggable_simulator/README.md new file mode 100644 index 000000000..9db9908f9 --- /dev/null +++ b/tutorials/pluggable_simulator/README.md @@ -0,0 +1,195 @@ +# Pluggable simulator backends for drone evolution + RL + +This tutorial demonstrates how ariel decouples the **EA + PPO learning loop** +from the **physics simulator** so that collaborators can plug in their own +simulators while reusing ariel's evolutionary and learning infrastructure. + +The same PPO trainer drives any backend that implements the +`BlueprintGateEnv` Protocol; today two backends ship (NumPy and a stub for +Isaac Lab), and a third — yours — can be added without changing the trainer. + +--- + +## 1. The architecture + +``` +ariel offers: EA loop + PPO trainer + DroneBlueprint IR +───────────────────────────────────────────────────────── + genome handlers │ EA operators │ gate-train PPO + │ + ▼ + ─── Plug point: BlueprintGateEnv Protocol ─── + │ + ┌──────────────────────────┼──────────────────────────┐ + ▼ ▼ ▼ + NumpyBlueprint IsaacLabBlueprint + GateEnv GateEnv (stub) GateEnv + │ │ │ + ▼ ▼ ▼ +blueprint_to_propellers blueprint_to_urdf → whatever conversion + │ UrdfConverter → your backend + ▼ parallel envs needs +DroneSimulator +(pure NumPy) +``` + +**What ariel provides** (above the plug point): +- `DroneBlueprint` — the morphology IR every backend consumes. +- The PPO loop in `gate_train.py` / this tutorial's `train.py`. +- EA operators, genome handlers, repair, inspection — all simulator-agnostic. + +**What a simulator backend provides** (below the plug point): +- A gymnasium `VecEnv` constructed from a `DroneBlueprint`. +- Per-step physics, reward, termination, and observation packaging. +- That's it. + +--- + +## 2. The contract: `BlueprintGateEnv` + +The Protocol lives in +[`src/ariel/simulation/tasks/blueprint_gate_env.py`](../../src/ariel/simulation/tasks/blueprint_gate_env.py) +and is intentionally minimal: + +```python +@runtime_checkable +class BlueprintGateEnv(Protocol): + blueprint: DroneBlueprint + num_envs: int + # ...plus the standard VecEnv methods inherited from + # stable_baselines3.common.vec_env.VecEnv. +``` + +A conforming class: + +1. Accepts a `DroneBlueprint` at construction. +2. Exposes `.blueprint` and `.num_envs`. +3. Implements the standard `VecEnv` interface (`reset`, `step_async`, + `step_wait`, `close`, `get_attr`, `set_attr`, `env_method`, + `env_is_wrapped`) — usually by inheriting from + `stable_baselines3.common.vec_env.VecEnv` and doing the obvious thing. + +Because the Protocol is `@runtime_checkable`, `isinstance(env, BlueprintGateEnv)` +works as a sanity assertion (`train.py` does this before handing the env to PPO). + +--- + +## 3. Running the shipped backends + +### NumPy backend (works today) + +```bash +python tutorials/pluggable_simulator/train.py \ + --simulator numpy \ + --preset quad \ + --num-envs 8 \ + --total-timesteps 5000 +``` + +This wraps the existing `DroneSimulator` (pure NumPy + SymPy) via +`NumpyBlueprintGateEnv` — a thin shim that calls `blueprint_to_propellers` +and forwards to the established `DroneGateEnv`. >100× real-time on CPU. + +### Isaac Lab backend (stub; Phase 2) + +```bash +python tutorials/pluggable_simulator/train.py \ + --simulator isaaclab \ + --preset quad \ + --num-envs 64 \ + --total-timesteps 50000 +``` + +Currently raises `NotImplementedError` with a pointer to the Phase 2 plan. +When implemented, it will: + +1. Run `blueprint_to_urdf` in-process to produce a URDF. +2. Call Isaac Lab's `UrdfConverter` to produce a USD. +3. Spawn N parallel articulation instances in Isaac Sim. +4. Apply per-motor thrust each step via a first-order motor model + (lifted from soft_airframe's `morphy_simulator.py`). + +This is unblocked because ariel and Isaac Lab now share one conda env +(see [DRONE_BLUEPRINT_PLAN.md §6 entry 15](../../DRONE_BLUEPRINT_PLAN.md)). + +--- + +## 4. Adding your own simulator + +Five steps: + +**1. Create `src/ariel/simulation/tasks/_gate_env.py`.** + +```python +from stable_baselines3.common.vec_env import VecEnv +from ariel.body_phenotypes.drone.blueprint import DroneBlueprint + +class YourBackendBlueprintGateEnv(VecEnv): + def __init__(self, *, blueprint: DroneBlueprint, num_envs: int, **kwargs): + # Convert the Blueprint into whatever your simulator needs. + # Available helpers in ariel.body_phenotypes.drone.backends: + # - blueprint_to_propellers(bp) → list[dict] (motor positions/dirs) + # - blueprint_to_mjspec(bp) → mujoco.MjSpec + # - blueprint_to_urdf(bp, path) → URDF file + ... + self.blueprint = blueprint + self.num_envs = num_envs + super().__init__(num_envs=num_envs, + observation_space=..., + action_space=...) + + # Implement the VecEnv abstract methods: + def reset(self): ... + def step_async(self, actions): ... + def step_wait(self): ... + def close(self): ... + def get_attr(self, attr_name, indices=None): ... + def set_attr(self, attr_name, value, indices=None): ... + def env_method(self, method_name, *args, indices=None, **kwargs): ... + def env_is_wrapped(self, wrapper_class, indices=None): ... +``` + +**2. Define the gate-passing task** in your env — gate positions, reward +shaping, observation/action spaces. The shipped envs use the gate layout in +[`src/ariel/simulation/tasks/drone_gate_env.py:22-34`](../../src/ariel/simulation/tasks/drone_gate_env.py) +as the reference; matching that layout means trained policies can be +compared backend-to-backend. + +**3. Register your backend in `train.py`** by adding one branch to +`make_env()`: + +```python +if simulator == "your_backend": + from ariel.simulation.tasks.your_backend_gate_env import YourBackendBlueprintGateEnv + return YourBackendBlueprintGateEnv(blueprint=blueprint, num_envs=num_envs, **kwargs) +``` + +**4. Verify Protocol conformance** by running: + +```bash +python tutorials/pluggable_simulator/train.py --simulator your_backend \ + --total-timesteps 1000 --num-envs 2 +``` + +If the assert at the top of `main()` fires, the env doesn't satisfy the +Protocol — typically because `self.blueprint` or `self.num_envs` wasn't +set, or one of the VecEnv methods is missing. + +**5. Plug into the EA evaluator.** Once the env trains a policy, point +`ariel.ec.drone.evaluators.gate_evaluator.GateEvaluator` (or your own +evaluator) at the new backend. The EA loop never sees the simulator +choice — it just gets fitness numbers back per individual. + +--- + +## 5. Why this matters + +The ARIEL consortium's collaborators bring their own simulators: MuJoCo, +Aerial Gym, Isaac Lab, IsaacGym, custom in-house stacks. The Protocol +seam means each group keeps their preferred simulator while sharing +ariel's evolutionary and learning infrastructure — decoders, EA +operators, repair, descriptors, training boilerplate. One IR +(`DroneBlueprint`), one EA loop, many backends. + +See [DRONE_BLUEPRINT_PLAN.md](../../DRONE_BLUEPRINT_PLAN.md) §1 ("Value +proposition") and §6 entry 17 for the broader rationale. diff --git a/tutorials/pluggable_simulator/train.py b/tutorials/pluggable_simulator/train.py new file mode 100644 index 000000000..6b810253e --- /dev/null +++ b/tutorials/pluggable_simulator/train.py @@ -0,0 +1,125 @@ +"""Train a PPO gate-passing policy through a pluggable simulator backend. + +Demonstrates ariel's backend-agnostic EA+PPO loop: the same trainer +runs against any backend that satisfies the +:class:`~ariel.simulation.tasks.blueprint_gate_env.BlueprintGateEnv` +Protocol. Today there are two backends: + + --simulator numpy → NumpyBlueprintGateEnv (shipped) + --simulator isaaclab → IsaacLabBlueprintGateEnv (stub; Phase 2) + +The morphology is built from a small set of presets via +``spherical_angular_to_blueprint``; the PPO training loop is identical +across backends. + +Examples: + + # Short smoke run on the NumPy backend (a few thousand steps). + python tutorials/pluggable_simulator/train.py --simulator numpy \\ + --total-timesteps 5000 --num-envs 4 + + # Full Isaac Lab path (not yet implemented). + python tutorials/pluggable_simulator/train.py --simulator isaaclab \\ + --total-timesteps 50000 --num-envs 64 +""" +from __future__ import annotations + +import argparse +import time + +import numpy as np +from stable_baselines3 import PPO +from stable_baselines3.common.vec_env import VecMonitor + +from ariel.body_phenotypes.drone.decoders import spherical_angular_to_blueprint +from ariel.simulation.tasks.blueprint_gate_env import ( + BlueprintGateEnv, + NumpyBlueprintGateEnv, +) + + +# ---------- preset morphologies ------------------------------------------------- + +PRESETS = { + "quad": np.array([ + [0.18, 0.0, 0.0, 0.0, 0.0, 1.0], + [0.18, np.pi / 2.0, 0.0, 0.0, 0.0, 0.0], + [0.18, np.pi, 0.0, 0.0, 0.0, 1.0], + [0.18, 3 * np.pi / 2, 0.0, 0.0, 0.0, 0.0], + ]), + "hex": np.array([ + [0.18, i * np.pi / 3.0, 0.0, 0.0, 0.0, float(i % 2)] + for i in range(6) + ]), +} + + +# ---------- backend dispatch ---------------------------------------------------- + +def make_env(simulator: str, blueprint, num_envs: int, **kwargs) -> BlueprintGateEnv: + """Return a BlueprintGateEnv for the requested backend. + + Adding a new simulator means adding one branch here and one + implementation file under ``ariel.simulation.tasks`` that + satisfies the BlueprintGateEnv Protocol. + """ + if simulator == "numpy": + return NumpyBlueprintGateEnv(blueprint=blueprint, num_envs=num_envs, **kwargs) + if simulator == "isaaclab": + from ariel.simulation.tasks.isaaclab_gate_env import IsaacLabBlueprintGateEnv + return IsaacLabBlueprintGateEnv(blueprint=blueprint, num_envs=num_envs, **kwargs) + raise ValueError( + f"Unknown simulator {simulator!r}. Known: 'numpy', 'isaaclab'." + ) + + +# ---------- main ---------------------------------------------------------------- + +def main() -> None: + parser = argparse.ArgumentParser(description=__doc__.splitlines()[0]) + parser.add_argument("--simulator", choices=["numpy", "isaaclab"], default="numpy", + help="Which simulator backend to plug behind the PPO loop.") + parser.add_argument("--preset", choices=list(PRESETS), default="quad", + help="Built-in morphology to evolve a policy on.") + parser.add_argument("--propsize", type=int, default=5) + parser.add_argument("--num-envs", type=int, default=8, + help="Vectorized parallel envs.") + parser.add_argument("--total-timesteps", type=int, default=10_000, + help="PPO total environment steps (a few thousand for " + "a smoke test; tens of millions for actual training).") + parser.add_argument("--seed", type=int, default=42) + args = parser.parse_args() + + print(f"=== pluggable-simulator demo ===") + print(f" simulator : {args.simulator}") + print(f" preset / propsize: {args.preset} / {args.propsize}") + print(f" num_envs : {args.num_envs}") + print(f" total_timesteps : {args.total_timesteps}") + + blueprint = spherical_angular_to_blueprint( + PRESETS[args.preset], propsize=args.propsize, + ) + print(f" blueprint : {blueprint.g.number_of_nodes()} nodes") + + env = make_env( + args.simulator, blueprint=blueprint, num_envs=args.num_envs, seed=args.seed, + ) + # Sanity check the Protocol — runtime_checkable lets us assert here. + assert isinstance(env, BlueprintGateEnv), ( + f"{type(env).__name__} does not satisfy BlueprintGateEnv Protocol" + ) + env = VecMonitor(env) + + model = PPO("MlpPolicy", env, verbose=1, seed=args.seed, device="cpu") + t0 = time.time() + model.learn(total_timesteps=args.total_timesteps) + dt = time.time() - t0 + + print(f"\n=== training complete ===") + print(f" wall time : {dt:.1f} s") + print(f" steps : {args.total_timesteps}") + print(f" steps/sec : {args.total_timesteps / dt:.0f}") + + +if __name__ == "__main__": + main() From 47a1af7d8a0c5c132909866c1117c445601551bc Mon Sep 17 00:00:00 2001 From: Keiichi Ito Date: Wed, 27 May 2026 07:12:20 +0200 Subject: [PATCH 19/27] Phase 2: Isaac Lab backend env constructs and runs end-to-end. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Lands the Isaac-Lab-side env construction for the pluggable-simulator architecture. The full Blueprint → URDF → USD → DirectRLEnv → N parallel drones pipeline runs in-process. Trains via random-action stepping for v1; rl_games PPO wiring is in place but blocked by a layered env-stack issue (see §6 entry 17). Architecture pivot from Phase 1: the Isaac Lab backend follows the DirectRLEnv shape rather than the gymnasium VecEnv Protocol, accepting that different simulator ecosystems use different RL libraries. Renamed (preserves git history): * src/ariel/simulation/tasks/isaaclab_gate_env.py → src/ariel/simulation/tasks/isaaclab_hover_env.py Implementation (isaaclab_hover_env.py): * `make_blueprint_usd(blueprint, output_dir)` — in-process URDF→USD conversion via blueprint_to_urdf + UrdfConverter. Requires Isaac Sim app to already be running. * `IsaacLabBlueprintHoverEnvCfg` (@configclass extending DirectRLEnvCfg) with a `.from_blueprint(bp, num_envs=...)` classmethod that generates the USD as a side effect and slots its path into `robot.spawn.usd_path`. Overrides default `joint_pos`/`joint_vel` `{".*": 0.0}` regexes to empty dicts, since our rigid-drone articulations have zero movable joints (otherwise: "Not all regular expressions are matched!"). * `IsaacLabBlueprintHoverEnv(DirectRLEnv)` — modeled on Isaac Lab's reference QuadcopterEnv. 4-action thrust+moment wrench at root body; 12-D observation (root_lin_vel_b, root_ang_vel_b, projected_gravity_b, desired_pos_b); reward = -distance_to_goal × step_dt (numerically stable for all distance values, per the project lead's design note); done on episode length or z bounds. * `make_rl_games_agent_cfg(...)` — returns an rl_games PPO config dict matched to Isaac Lab's reference quadcopter `rl_games_ppo_cfg.yaml`. Defined as a function (not @configclass) because rl_games is dict- configured. Ready to plug into Phase 2.5 once the env-stack issue is resolved. train.py: * New `main_isaaclab` that launches AppLauncher, generates USD, constructs env, then runs a random-action stepping loop for `max_iterations × 24` steps (the rl_games horizon shape). Verifies end-to-end correctness of obs/reward/done plumbing. * Per-step progress + final stats logged to stderr (stdout is captured by Isaac Sim's launcher; same trick we used in urdf_to_usd.py). * Peek-parser dispatch on `--simulator` so the numpy path doesn't pay the Isaac Lab import cost. Verified: * `--simulator numpy --total-timesteps 2000` in the ariel 3.12 venv: PPO trains in 3.8 s at ~525 steps/sec. * `--simulator isaaclab --headless --num-envs 16 --max-iterations 3` in the unified isaaclab conda env: env constructs + spawns 16 drones + steps 72 times in 1.6 s. Mean reward ~ -0.03 (consistent with -distance × dt for small distances and short episodes). Env-stack issues encountered (documented in §6 entry 17's "Phase 2.5 deferred" subsection): * sb3 + numpy 2 ABI segfault → avoided by NOT routing Isaac Lab via sb3 / `isaaclab_rl.sb3` adapter. * `isaaclab_rl.rsl_rl` adapter vs `rsl-rl-lib`: tried 3.0.1 and 5.3.0; both fail on different config-shape mismatches (`optimizer`, `share_cnn_encoders`, `class_name`). Shim `handle_deprecated_rsl_rl_cfg` didn't catch the relevant fields. * `rl_games` + Isaac Sim bundled torch: tensorboard import pulls in bundled pip_prebundle torch which transitively imports older tensorflow → jax → tries `numpy.dtypes.StringDType` on a bundled older numpy. v1 ships with a random-action stepping loop instead; PPO wiring is reachable in `make_rl_games_agent_cfg` and ready to plug in once the env-stack is resolved (Phase 2.5). Doc updates: * tutorials/pluggable_simulator/README.md: rewrote the architecture section as a 2-row table (numpy / isaaclab) with honest Phase 2 status. Updated the "Adding your own simulator" recipe to cover both contracts (gymnasium VecEnv path AND Isaac Lab DirectRLEnv path). * DRONE_BLUEPRINT_PLAN.md: added Phase 3 follow-on commit 8; rewrote §6 entry 17 to capture the architectural pivot (one Protocol → two contracts) and the layered env-stack issues that informed it. Promoted Phase 2.5 to the "Still pending" headline item. Co-Authored-By: Claude Opus 4.7 --- DRONE_BLUEPRINT_PLAN.md | 132 ++++-- .../simulation/tasks/isaaclab_gate_env.py | 91 ---- .../simulation/tasks/isaaclab_hover_env.py | 426 ++++++++++++++++++ tutorials/pluggable_simulator/README.md | 260 +++++++---- tutorials/pluggable_simulator/train.py | 226 +++++++--- 5 files changed, 866 insertions(+), 269 deletions(-) delete mode 100644 src/ariel/simulation/tasks/isaaclab_gate_env.py create mode 100644 src/ariel/simulation/tasks/isaaclab_hover_env.py diff --git a/DRONE_BLUEPRINT_PLAN.md b/DRONE_BLUEPRINT_PLAN.md index 46cf11646..8c45afedc 100644 --- a/DRONE_BLUEPRINT_PLAN.md +++ b/DRONE_BLUEPRINT_PLAN.md @@ -232,13 +232,39 @@ What's landed (in order of commit): shadowed the inherited `VecEnv.seed()` method (broke stable-baselines3's `set_random_seed`). See §6 entry 17. +8. `Implement IsaacLabBlueprintHoverEnv (Phase 2).` — + `src/ariel/simulation/tasks/isaaclab_hover_env.py` adapted from + Isaac Lab's reference `QuadcopterEnv`; spawns N parallel drones + from a Blueprint-derived USD, applies a thrust+moment wrench at + the root body each step, computes `-distance × step_dt` rewards. + `train.py --simulator isaaclab` exercises the full path + end-to-end via a random-action stepping loop (72 steps in 1.6 s + on 16 envs). Real PPO training via `rl_games.torch_runner.Runner` + is wired through `make_rl_games_agent_cfg` but currently calls a + random-action loop instead, gated on Phase 2.5. Architectural + choice change from Phase 1: the Isaac Lab backend follows the + `DirectRLEnv` shape rather than the `BlueprintGateEnv` Protocol — + "two-Protocols-one-trainer" as picked during planning. See §6 + entry 17. + **Still pending — to pick up next session:** -* **Phase 2 of pluggable simulator** — implement - `IsaacLabBlueprintGateEnv` for real (URDF→USD in-process, parallel - envs, per-motor thrust model lifted from soft_airframe). The - Protocol contract is now stable, so this is purely simulator-side - work. +* **Phase 2.5 of pluggable simulator: actually train.** The + `rl_games` Runner trips on a transitive import chain (Isaac Sim's + bundled `torch.utils.tensorboard.writer` → lazy `tensorflow` → + `jax` → `numpy.dtypes.StringDType`) because Isaac Sim's + `pip_prebundle/` ships an older numpy than the conda env's + numpy 2.4.6. Options: (a) install a clean conda env with pinned + versions matched to Isaac Sim's bundle, (b) shadow the bundled + torch with the conda env's torch on `PYTHONPATH`, (c) downgrade + jax + tensorboard to versions tolerant of numpy 2. Independent of + this, `rsl_rl` integration via `isaaclab_rl.rsl_rl` was a + separate dead end during Phase 2 — the adapter sends kwargs + (`optimizer`, `share_cnn_encoders`) that don't match the + installed `rsl-rl-lib` 3.0.1 PPO signature (and 5.x has its own + config shape mismatch). `rl_games` is the path we picked + forward; `make_rl_games_agent_cfg` in + `isaaclab_hover_env.py` is the matching config helper. * **Compliant joints (URDF revolute + sidecar stiffness + USD `ariel:*` attrs).** Schema landed on `compliant-joint-schema`; the emission half is what's still pending. The two-layer pattern @@ -427,39 +453,81 @@ Each entry: **decision** — *why*; alternatives considered. until something actually breaks. 17. **Simulator backends are a plug point, not a hard-coded choice; - the contract is the `BlueprintGateEnv` Protocol.** + the contract is two complementary shapes — one per ecosystem.** **Motivation:** the ARIEL consortium has collaborators using divergent simulators (MuJoCo, Aerial Gym, Isaac Lab, IsaacGym, - in-house stacks). ARIEL's contribution to those groups is the - *evolutionary + learning loop* — decoders, EA operators, repair, - inspection, PPO training. If the simulator is hard-coded, every + in-house stacks). ARIEL's contribution is the *evolutionary + + learning loop* — decoders, EA operators, repair, inspection, + training boilerplate. If the simulator is hard-coded, every collaborator either swaps to ariel's simulator (won't happen) or - re-implements the loop themselves (defeats the point). The - seam has to be deliberate. - - **Contract:** a `BlueprintGateEnv` is a `gymnasium.VecEnv` (stable- - baselines3 style) constructed from a `DroneBlueprint`, exposing - `.blueprint` and `.num_envs` attributes. Implemented as - `typing.Protocol` with `@runtime_checkable` (per the - pluggable-backend question we deliberated): no inheritance - forced on collaborators, but `isinstance(env, BlueprintGateEnv)` - works for runtime sanity-checks. Concrete VecEnv methods come - via the standard `stable_baselines3.common.vec_env.VecEnv` base - class. + re-implements the loop themselves (defeats the point). The seam + has to be deliberate. + + **Architecture (revised in Phase 2): two Protocols, one trainer + per backend.** Initially we tried a single `BlueprintGateEnv` + Protocol (gymnasium VecEnv). The Phase 2 attempt to wrap Isaac + Lab's `DirectRLEnv` to that shape via `isaaclab_rl.sb3` collided + with the numpy-2 ABI issues that sb3's compiled deps have in the + unified env. The honest fix is to accept heterogeneity: numpy + backend exposes a gymnasium VecEnv and pairs with sb3 PPO; + Isaac Lab backend exposes a `DirectRLEnv` and pairs with one of + Isaac Lab's native RL libraries (`rl_games` is the v1 target). + Each backend brings its own simulator AND its own trainer — same + as how heterogeneous simulator ecosystems work in the wild. + + **Contract 1 (gymnasium-VecEnv path):** `BlueprintGateEnv` is a + `typing.Protocol` declaring `.blueprint`, `.num_envs`, plus the + standard VecEnv methods (inherited from + `stable_baselines3.common.vec_env.VecEnv`). `@runtime_checkable`, + so `isinstance(env, BlueprintGateEnv)` works for sanity checks. + `NumpyBlueprintGateEnv` is the v1 reference implementation. + + **Contract 2 (Isaac Lab DirectRLEnv path):** subclass + `isaaclab.envs.DirectRLEnv` with a config built from a + `DroneBlueprint` (Blueprint → URDF → USD generated at construction + time via the helpers in `isaaclab_hover_env.py`). The standard + `_setup_scene` / `_pre_physics_step` / `_apply_action` / + `_get_observations` / `_get_rewards` / `_get_dones` / `_reset_idx` + methods implement the task. **What ships in v1:** - - `NumpyBlueprintGateEnv` — declares the existing `DroneGateEnv` - (NumPy + SymPy physics) as a Protocol implementation by - subclassing it and adding a Blueprint → propellers-list - adapter at the constructor. Smoke-tested with PPO 2k steps in - 4.7 s. - - `IsaacLabBlueprintGateEnv` — stub with the planned constructor - signature and a `NotImplementedError` body. Phase 2 work. - - `tutorials/pluggable_simulator/{README.md, train.py}` — - walks a collaborator through the architecture, the - `--simulator {numpy,isaaclab}` dispatch, and the five-step - "add your own backend" recipe. + - **NumPy backend (Phase 1):** `NumpyBlueprintGateEnv` — + Protocol-conforming subclass of existing `DroneGateEnv` with a + Blueprint→propellers adapter. Trains a gate-passing policy + with sb3 PPO end-to-end. Smoke-tested with PPO 2k steps in + 4.7 s (3.12 venv); also works in the unified 3.11 env. + - **Isaac Lab backend (Phase 2):** `IsaacLabBlueprintHoverEnv` — + adapted from Isaac Lab's reference `QuadcopterEnv`; the + articulation USD is generated at runtime from a Blueprint via + `blueprint_to_urdf` + `UrdfConverter`. Spawns N parallel drones, + computes `-distance × step_dt` rewards. v1 smoke-tests via a + random-action stepping loop (PPO training deferred to + Phase 2.5; see below). 72 steps in 1.6 s on 16 envs through + Isaac Sim PhysX. + - `tutorials/pluggable_simulator/{README.md, train.py}` — the + tutorial doc + a unified entry point with `--simulator + {numpy,isaaclab}` dispatch and the five-step "add your own + backend" recipe. + + **Phase 2.5 deferred — three layered env-stack issues + encountered:** + 1. `sb3 + numpy 2`: sb3's compiled deps segfault in the unified + isaaclab env (numpy ABI mismatch with bundled torch). Avoided + by NOT routing Isaac Lab through sb3. + 2. `isaaclab_rl.rsl_rl` adapter ↔ `rsl-rl-lib`: the adapter + sends config keys (`optimizer`, `share_cnn_encoders`) that + don't match the installed PPO signature on either 3.0.1 or + 5.3.0. Tried both; both fail differently. The + `handle_deprecated_rsl_rl_cfg` shim doesn't catch the + relevant fields on these versions. + 3. `rl_games` (the v1 target): the runner's tensorboard import + transitively pulls in Isaac Sim's bundled `pip_prebundle/torch`, + which imports an older `tensorflow` → `jax` → + `numpy.dtypes.StringDType`. Bundle ships older numpy than the + conda env's 2.4.6, so the attribute lookup fails. Architectural + fix likely requires either a clean conda env with pinned-to- + bundle versions, or shadowing the bundle's torch. **Pre-existing bug fixed in passing:** `DroneGateEnv.__init__` stored `self.seed = seed` (an int), shadowing the inherited diff --git a/src/ariel/simulation/tasks/isaaclab_gate_env.py b/src/ariel/simulation/tasks/isaaclab_gate_env.py deleted file mode 100644 index d2dd5caf1..000000000 --- a/src/ariel/simulation/tasks/isaaclab_gate_env.py +++ /dev/null @@ -1,91 +0,0 @@ -"""Isaac Lab backend for the drone-gate-passing task — *stub*. - -Implementation deferred to Phase 2 of the pluggable-simulator effort. -The Protocol contract lives in -:mod:`ariel.simulation.tasks.blueprint_gate_env`; this module reserves -the import path and pins the planned API so collaborators can see the -shape from both sides of the seam. - -Phase 2 will: - -1. Convert the blueprint to URDF in-process via - ``ariel.body_phenotypes.drone.backends.blueprint_to_urdf``. -2. Run ``isaaclab.sim.converters.UrdfConverter`` to produce a USD - (no subprocess — both halves live in the unified ariel/isaaclab - conda env now; see DRONE_BLUEPRINT_PLAN.md §6 entry 15). -3. Spawn ``num_envs`` parallel articulation instances in Isaac Sim. -4. Apply per-motor thrust each step using a first-order motor model - lifted from - ``soft_airframe_optimization/src/morphy_simulator.py`` - (matched to the NumPy backend's reference dynamics so trained - policies have a chance at sim-to-sim transfer). -5. Spawn gate prims at the same positions as the NumPy env so the - task reward shaping is identical. -6. Return observations / rewards / dones in the standard VecEnv - format, satisfying the - :class:`~ariel.simulation.tasks.blueprint_gate_env.BlueprintGateEnv` - Protocol. -""" -from __future__ import annotations - -from typing import Any - -from stable_baselines3.common.vec_env import VecEnv - -from ariel.body_phenotypes.drone.blueprint import DroneBlueprint - - -class IsaacLabBlueprintGateEnv(VecEnv): - """Isaac Lab gate-passing env — *not yet implemented*. - - Carries the planned constructor signature so the call site in the - tutorial (and any future production callers) compiles against the - intended API. Calling it raises ``NotImplementedError`` until - Phase 2 lands. - """ - - blueprint: DroneBlueprint - num_envs: int - - def __init__( - self, - *, - blueprint: DroneBlueprint, - num_envs: int, - headless: bool = True, - device: str = "cuda:0", - **kwargs: Any, - ) -> None: - raise NotImplementedError( - "IsaacLabBlueprintGateEnv is the Phase 2 deliverable of the " - "pluggable-simulator effort. Use NumpyBlueprintGateEnv for now." - ) - - # The abstract VecEnv methods would be implemented in Phase 2; we - # leave them as stubs so the class can at least be imported. - def reset(self): # type: ignore[override] - raise NotImplementedError - - def step_async(self, actions): # type: ignore[override] - raise NotImplementedError - - def step_wait(self): # type: ignore[override] - raise NotImplementedError - - def close(self) -> None: # type: ignore[override] - raise NotImplementedError - - def get_attr(self, attr_name, indices=None): # type: ignore[override] - raise NotImplementedError - - def set_attr(self, attr_name, value, indices=None): # type: ignore[override] - raise NotImplementedError - - def env_method(self, method_name, *method_args, indices=None, **method_kwargs): # type: ignore[override] - raise NotImplementedError - - def env_is_wrapped(self, wrapper_class, indices=None): # type: ignore[override] - raise NotImplementedError - - -__all__ = ["IsaacLabBlueprintGateEnv"] diff --git a/src/ariel/simulation/tasks/isaaclab_hover_env.py b/src/ariel/simulation/tasks/isaaclab_hover_env.py new file mode 100644 index 000000000..724e70175 --- /dev/null +++ b/src/ariel/simulation/tasks/isaaclab_hover_env.py @@ -0,0 +1,426 @@ +"""Isaac Lab hover-to-goal task driven by a DroneBlueprint. + +Phase 2 of the pluggable-simulator effort. Adapts Isaac Lab's reference +``QuadcopterEnv`` (``isaaclab_tasks/direct/quadcopter/quadcopter_env.py``) +with one substitution: the articulation USD is generated at runtime +from a :class:`DroneBlueprint` (via ``blueprint_to_urdf`` + +``UrdfConverter``) instead of being a hard-coded Crazyflie asset. + +Architecture (see DRONE_BLUEPRINT_PLAN.md §6 entry 17): + +* Trained with ``rl_games`` PPO (Isaac Lab's most-stable native RL + library on the current install), not stable-baselines3. The + two-Protocols-one-trainer-per-backend decision means each backend + brings its own RL library; we use rl_games here because (a) it's + native to Isaac Lab's DirectRLEnv shape, (b) it avoids the numpy-2 + ABI issues that stable-baselines3 has in the unified isaaclab + conda env, and (c) it's stable on the actual installed library + version while ``isaaclab_rl.rsl_rl`` was caught between rsl-rl-lib + 3.x and 5.x API drift in our smoke tests. +* Action space (4D): total thrust + 3 moment components. Morphology- + independent. Per-rotor thrust modeling is deferred to a follow-up; + the wrench-at-root abstraction works for any roughly-balanced + drone. +* Reward: ``-distance_to_goal`` per step (cumulates to + ``-Σ distance × step_dt`` over the episode). Numerically stable + for all distance values including very near zero, per the project + lead's design note. + +Note: this module imports ``isaaclab.*`` at the top of the file; it +should only be imported after ``AppLauncher`` has launched Isaac Sim. +The tutorial's ``train.py`` does this dispatch correctly. +""" +from __future__ import annotations + +from pathlib import Path +from typing import Optional + +import torch + +import isaaclab.sim as sim_utils +from isaaclab.assets import Articulation, ArticulationCfg +from isaaclab.envs import DirectRLEnv, DirectRLEnvCfg +from isaaclab.scene import InteractiveSceneCfg +from isaaclab.sim import SimulationCfg +from isaaclab.terrains import TerrainImporterCfg +from isaaclab.utils import configclass +from isaaclab.utils.math import subtract_frame_transforms + +from ariel.body_phenotypes.drone.backends import blueprint_to_urdf +from ariel.body_phenotypes.drone.blueprint import DroneBlueprint + + +# ---------- Blueprint → USD helper --------------------------------------------- + +def make_blueprint_usd( + blueprint: DroneBlueprint, + *, + output_dir: str | Path, + robot_name: str = "drone", +) -> str: + """Convert a ``DroneBlueprint`` to USD via the URDF intermediate. + + Requires Isaac Sim to already be running (so ``UrdfConverter`` can + import). The tutorial's ``train.py`` launches the app before + importing this module. + + Returns the absolute path to the produced ``.usd`` file. + """ + from isaaclab.sim.converters import UrdfConverter, UrdfConverterCfg # noqa: PLC0415 + + output_dir = Path(output_dir).resolve() + output_dir.mkdir(parents=True, exist_ok=True) + + urdf_path = output_dir / f"{robot_name}.urdf" + blueprint_to_urdf(blueprint, str(urdf_path), robot_name=robot_name) + + cfg = UrdfConverterCfg( + asset_path=str(urdf_path), + usd_dir=str(output_dir), + usd_file_name=f"{robot_name}.usd", + force_usd_conversion=True, + merge_fixed_joints=False, + fix_base=False, + joint_drive=UrdfConverterCfg.JointDriveCfg( + target_type="none", + gains=UrdfConverterCfg.JointDriveCfg.PDGainsCfg( + stiffness=0.0, damping=0.0, + ), + ), + ) + return UrdfConverter(cfg).usd_path + + +# ---------- env config ---------------------------------------------------------- + +@configclass +class IsaacLabBlueprintHoverEnvCfg(DirectRLEnvCfg): + """Config for the Blueprint-driven hover-to-goal task. + + Use :meth:`from_blueprint` to build a fully-populated config from a + ``DroneBlueprint`` (generates the USD as a side effect). + """ + + # env + episode_length_s: float = 5.0 + decimation: int = 2 + action_space: int = 4 # thrust + 3 moments + observation_space: int = 12 + state_space: int = 0 + + # simulation + sim: SimulationCfg = SimulationCfg(dt=1.0 / 100.0, render_interval=decimation) + + # ground plane + terrain: TerrainImporterCfg = TerrainImporterCfg( + prim_path="/World/ground", + terrain_type="plane", + collision_group=-1, + debug_vis=False, + ) + + # scene + scene: InteractiveSceneCfg = InteractiveSceneCfg( + num_envs=64, env_spacing=3.0, replicate_physics=True, + ) + + # robot — usd_path filled in by `from_blueprint()`; left empty in default + # so constructing the bare cfg without a blueprint raises an obvious + # error from UsdFileCfg rather than silently spawning nothing. + robot: ArticulationCfg = ArticulationCfg( + prim_path="/World/envs/env_.*/Robot", + spawn=sim_utils.UsdFileCfg( + usd_path="", + rigid_props=sim_utils.RigidBodyPropertiesCfg( + disable_gravity=False, + max_depenetration_velocity=10.0, + enable_gyroscopic_forces=True, + ), + articulation_props=sim_utils.ArticulationRootPropertiesCfg( + enabled_self_collisions=False, + solver_position_iteration_count=4, + solver_velocity_iteration_count=0, + ), + copy_from_source=False, + ), + init_state=ArticulationCfg.InitialStateCfg( + pos=(0.0, 0.0, 1.0), + # Blueprint-generated drones have all-fixed joints, so the + # articulation has zero movable joints. Override the default + # `{".*": 0.0}` joint_pos/vel regexes that otherwise raise + # "Not all regular expressions are matched!" against an empty + # joint list. + joint_pos={}, + joint_vel={}, + ), + # Rigid drone: all blueprint joints are fixed, so no actuated joints. + actuators={}, + ) + + # control allocation + thrust_to_weight: float = 2.0 + moment_scale: float = 0.05 + + # reward shaping + distance_reward_scale: float = 1.0 + + # termination + z_lower: float = 0.1 + z_upper: float = 3.0 + + @classmethod + def from_blueprint( + cls, + blueprint: DroneBlueprint, + *, + num_envs: int = 64, + usd_output_dir: Optional[str | Path] = None, + **overrides, + ) -> "IsaacLabBlueprintHoverEnvCfg": + """Build a config from a ``DroneBlueprint`` by generating a USD asset. + + Generates the USD into ``usd_output_dir`` (a fresh temp dir if + not provided), then slots the path into ``robot.spawn.usd_path``. + """ + import tempfile # noqa: PLC0415 + if usd_output_dir is None: + usd_output_dir = tempfile.mkdtemp(prefix="ariel_blueprint_usd_") + usd_path = make_blueprint_usd(blueprint, output_dir=usd_output_dir) + cfg = cls(**overrides) + cfg.scene.num_envs = num_envs + cfg.robot.spawn.usd_path = usd_path + return cfg + + +# ---------- env class ----------------------------------------------------------- + +class IsaacLabBlueprintHoverEnv(DirectRLEnv): + """Direct RL env: a drone (built from a ``DroneBlueprint`` USD) + learns to hover at a randomly-sampled goal in body-frame coords. + + Modeled on Isaac Lab's reference ``QuadcopterEnv``. + """ + + cfg: IsaacLabBlueprintHoverEnvCfg + + def __init__( + self, + cfg: IsaacLabBlueprintHoverEnvCfg, + render_mode: Optional[str] = None, + **kwargs, + ) -> None: + super().__init__(cfg, render_mode, **kwargs) + + self._actions = torch.zeros(self.num_envs, self.cfg.action_space, device=self.device) + self._thrust = torch.zeros(self.num_envs, 1, 3, device=self.device) + self._moment = torch.zeros(self.num_envs, 1, 3, device=self.device) + self._desired_pos_w = torch.zeros(self.num_envs, 3, device=self.device) + + # Resolve the root body index. `blueprint_to_urdf` emits a "base_link" + # link for the CorePlate; that's the body we apply the wrench to. + body_ids, _ = self._robot.find_bodies("base_link") + if not body_ids: + raise RuntimeError( + "Could not find 'base_link' on the blueprint-generated articulation. " + "Was the URDF emitted by blueprint_to_urdf?" + ) + self._body_id = body_ids + + # Mass / weight for thrust scaling. + self._robot_mass = self._robot.root_physx_view.get_masses()[0].sum() + self._gravity_magnitude = torch.tensor(self.sim.cfg.gravity, device=self.device).norm() + self._robot_weight = float((self._robot_mass * self._gravity_magnitude).item()) + + # -- scene ----------------------------------------------------------- + + def _setup_scene(self) -> None: + self._robot = Articulation(self.cfg.robot) + self.scene.articulations["robot"] = self._robot + + self.cfg.terrain.num_envs = self.scene.cfg.num_envs + self.cfg.terrain.env_spacing = self.scene.cfg.env_spacing + self._terrain = self.cfg.terrain.class_type(self.cfg.terrain) + + self.scene.clone_environments(copy_from_source=False) + if self.device == "cpu": + self.scene.filter_collisions(global_prim_paths=[self.cfg.terrain.prim_path]) + + light_cfg = sim_utils.DomeLightCfg(intensity=2000.0, color=(0.75, 0.75, 0.75)) + light_cfg.func("/World/Light", light_cfg) + + # -- per-step dynamics ----------------------------------------------- + + def _pre_physics_step(self, actions: torch.Tensor) -> None: + self._actions = actions.clone().clamp(-1.0, 1.0) + # action[0] ∈ [-1, 1] → thrust along body +Z in [0, thrust_to_weight * weight]. + self._thrust[:, 0, 2] = ( + self.cfg.thrust_to_weight * self._robot_weight * (self._actions[:, 0] + 1.0) / 2.0 + ) + self._moment[:, 0, :] = self.cfg.moment_scale * self._actions[:, 1:] + + def _apply_action(self) -> None: + self._robot.permanent_wrench_composer.set_forces_and_torques( + body_ids=self._body_id, + forces=self._thrust, + torques=self._moment, + ) + + # -- obs / reward / done --------------------------------------------- + + def _get_observations(self) -> dict: + desired_pos_b, _ = subtract_frame_transforms( + self._robot.data.root_pos_w, + self._robot.data.root_quat_w, + self._desired_pos_w, + ) + obs = torch.cat( + [ + self._robot.data.root_lin_vel_b, + self._robot.data.root_ang_vel_b, + self._robot.data.projected_gravity_b, + desired_pos_b, + ], + dim=-1, + ) + return {"policy": obs} + + def _get_rewards(self) -> torch.Tensor: + # Negative distance, summed across the episode → minimizes total + # excursion from the goal. Numerically stable for all distance + # values; never blows up near zero. + distance_to_goal = torch.linalg.norm( + self._desired_pos_w - self._robot.data.root_pos_w, dim=1 + ) + return -distance_to_goal * self.cfg.distance_reward_scale * self.step_dt + + def _get_dones(self) -> tuple[torch.Tensor, torch.Tensor]: + time_out = self.episode_length_buf >= self.max_episode_length - 1 + z = self._robot.data.root_pos_w[:, 2] + died = (z < self.cfg.z_lower) | (z > self.cfg.z_upper) + return died, time_out + + # -- reset ----------------------------------------------------------- + + def _reset_idx(self, env_ids: Optional[torch.Tensor]) -> None: + if env_ids is None or len(env_ids) == self.num_envs: + env_ids = self._robot._ALL_INDICES + + self._robot.reset(env_ids) + super()._reset_idx(env_ids) + + self._actions[env_ids] = 0.0 + + # Random goal in [-1.5, 1.5]² XY, [0.6, 1.5] Z, around the env origin. + self._desired_pos_w[env_ids, :2] = torch.zeros_like( + self._desired_pos_w[env_ids, :2] + ).uniform_(-1.5, 1.5) + self._desired_pos_w[env_ids, :2] += self._terrain.env_origins[env_ids, :2] + self._desired_pos_w[env_ids, 2] = torch.zeros_like( + self._desired_pos_w[env_ids, 2] + ).uniform_(0.6, 1.5) + + # Reset robot pose/velocity from defaults. + default_root_state = self._robot.data.default_root_state[env_ids] + default_root_state[:, :3] += self._terrain.env_origins[env_ids] + self._robot.write_root_pose_to_sim(default_root_state[:, :7], env_ids) + self._robot.write_root_velocity_to_sim(default_root_state[:, 7:], env_ids) + + +# ---------- rl_games PPO config helper ----------------------------------------- + +def make_rl_games_agent_cfg( + *, + max_epochs: int = 200, + horizon_length: int = 24, + minibatch_size: int = 24 * 64, # horizon_length × default num_envs + device: str = "cuda:0", + experiment_name: str = "ariel_blueprint_hover", +) -> dict: + """Return an rl_games agent-config dict matched to Isaac Lab's + reference quadcopter PPO config (``rl_games_ppo_cfg.yaml``). + + rl_games is configured by nested dicts (the standard YAML pattern), + so this helper returns a plain ``dict`` rather than a dataclass. + Mutate the returned dict if you need to override anything. + + We use rl_games (rather than rsl_rl) because Isaac Lab's + ``isaaclab_rl.rl_games`` adapter is stable on the actual installed + rl_games version, while ``isaaclab_rl.rsl_rl`` was caught between + rsl-rl-lib 3.x and 5.x API drift when we tried it. + """ + return { + "params": { + "seed": 42, + "env": { + "clip_actions": 1.0, + }, + "algo": {"name": "a2c_continuous"}, + "model": {"name": "continuous_a2c_logstd"}, + "network": { + "name": "actor_critic", + "separate": False, + "space": { + "continuous": { + "mu_activation": "None", + "sigma_activation": "None", + "mu_init": {"name": "default"}, + "sigma_init": {"name": "const_initializer", "val": 0}, + "fixed_sigma": True, + }, + }, + "mlp": { + "units": [64, 64], + "activation": "elu", + "d2rl": False, + "initializer": {"name": "default"}, + "regularizer": {"name": "None"}, + }, + }, + "load_checkpoint": False, + "load_path": "", + "config": { + "name": experiment_name, + "env_name": "rlgpu", + "device": device, + "device_name": device, + "multi_gpu": False, + "ppo": True, + "mixed_precision": False, + "normalize_input": True, + "normalize_value": True, + "value_bootstrap": True, + "num_actors": -1, # filled in by the train script + "reward_shaper": {"scale_value": 0.01}, + "normalize_advantage": True, + "gamma": 0.99, + "tau": 0.95, + "learning_rate": 5e-4, + "lr_schedule": "adaptive", + "schedule_type": "legacy", + "kl_threshold": 0.016, + "score_to_win": 20000, + "max_epochs": max_epochs, + "save_best_after": 100, + "save_frequency": 25, + "grad_norm": 1.0, + "entropy_coef": 0.0, + "truncate_grads": True, + "e_clip": 0.2, + "horizon_length": horizon_length, + "minibatch_size": minibatch_size, + "mini_epochs": 5, + "critic_coef": 2, + "clip_value": True, + "seq_length": 4, + "bounds_loss_coef": 0.0001, + }, + }, + } + + +__all__ = [ + "make_blueprint_usd", + "IsaacLabBlueprintHoverEnvCfg", + "IsaacLabBlueprintHoverEnv", + "make_rl_games_agent_cfg", +] diff --git a/tutorials/pluggable_simulator/README.md b/tutorials/pluggable_simulator/README.md index 9db9908f9..2c3654fdd 100644 --- a/tutorials/pluggable_simulator/README.md +++ b/tutorials/pluggable_simulator/README.md @@ -1,55 +1,92 @@ # Pluggable simulator backends for drone evolution + RL -This tutorial demonstrates how ariel decouples the **EA + PPO learning loop** -from the **physics simulator** so that collaborators can plug in their own -simulators while reusing ariel's evolutionary and learning infrastructure. - -The same PPO trainer drives any backend that implements the -`BlueprintGateEnv` Protocol; today two backends ship (NumPy and a stub for -Isaac Lab), and a third — yours — can be added without changing the trainer. +This tutorial demonstrates how ariel decouples the **EA + RL learning loop** +from the **physics simulator** so that collaborators can plug in their +own simulators while reusing ariel's evolutionary and morphology-IR +infrastructure. + +Two backends ship today: + +| `--simulator` | Simulator (physics) | RL library / loop | Task | +|---------------|---------------------|---------------|----------------| +| `numpy` | `DroneSimulator` (pure NumPy + SymPy) | **stable-baselines3 PPO** (trains end-to-end) | gate-passing | +| `isaaclab` | Isaac Lab / Isaac Sim PhysX | random-action env stepping (rl_games PPO wiring is Phase 2.5) | hover-to-goal | + +Each backend brings its own simulator **and** its own RL library, because +that matches how real heterogeneous simulator ecosystems work — Isaac +Lab ships rsl_rl/rl_games/skrl as native trainers, the NumPy stack pairs +naturally with sb3, etc. The EA loop above never sees the simulator +choice; it just gets a fitness scalar back per individual. + +**Phase 2 status:** the architectural seam is demonstrated for both +backends. The NumPy backend trains a policy with sb3 PPO end-to-end. +The Isaac Lab backend constructs the env, spawns N parallel drones, +and steps them with random actions to validate observations / rewards / +dones. Actual PPO training via `rl_games` is wired in +[`make_rl_games_agent_cfg()`](../../src/ariel/simulation/tasks/isaaclab_hover_env.py) +but currently blocked on an env-stack issue (Isaac Sim's bundled torch +tensorboard transitively imports an older TF/jax/numpy stack that +conflicts with the conda env's numpy 2). See +[DRONE_BLUEPRINT_PLAN.md §6 entry 17](../../DRONE_BLUEPRINT_PLAN.md) for +the full story and the Phase 2.5 path forward. --- ## 1. The architecture ``` -ariel offers: EA loop + PPO trainer + DroneBlueprint IR -───────────────────────────────────────────────────────── - genome handlers │ EA operators │ gate-train PPO +ariel offers: EA loop + RL trainers + DroneBlueprint IR +───────────────────────────────────────────────────────────── + genome handlers │ EA operators │ scripts/train.py dispatch │ ▼ - ─── Plug point: BlueprintGateEnv Protocol ─── + ─── Plug point: simulator+trainer pair ─── │ ┌──────────────────────────┼──────────────────────────┐ ▼ ▼ ▼ - NumpyBlueprint IsaacLabBlueprint - GateEnv GateEnv (stub) GateEnv - │ │ │ - ▼ ▼ ▼ -blueprint_to_propellers blueprint_to_urdf → whatever conversion - │ UrdfConverter → your backend - ▼ parallel envs needs +NumpyBlueprintGateEnv IsaacLabBlueprintHoverEnv + (gymnasium VecEnv) (DirectRLEnv) (whatever shape + + + your simulator +sb3 PPO rsl_rl PPO needs) + │ │ │ + ▼ ▼ ▼ +blueprint_to_propellers blueprint_to_urdf → whatever conversion + │ UrdfConverter → your backend + ▼ Isaac Sim spawn needs DroneSimulator (pure NumPy) ``` **What ariel provides** (above the plug point): - `DroneBlueprint` — the morphology IR every backend consumes. -- The PPO loop in `gate_train.py` / this tutorial's `train.py`. -- EA operators, genome handlers, repair, inspection — all simulator-agnostic. +- EA operators, genome handlers, repair, inspection, descriptors — + all simulator-agnostic. +- A unified `train.py` dispatch that routes to backend-specific RL + glue without exposing the choice to the EA. **What a simulator backend provides** (below the plug point): -- A gymnasium `VecEnv` constructed from a `DroneBlueprint`. -- Per-step physics, reward, termination, and observation packaging. -- That's it. +- A learning-ready env constructed from a `DroneBlueprint`. +- Hooks into its preferred RL library (sb3, rsl_rl, rl_games, skrl, + or anything else). +- A task definition (reward, termination, observation/action spaces). + +The seam is **deliberate**: the EA evolves the same morphology +variables either way; only the fitness function and the trained +policy are backend-specific. --- -## 2. The contract: `BlueprintGateEnv` +## 2. The two contracts -The Protocol lives in -[`src/ariel/simulation/tasks/blueprint_gate_env.py`](../../src/ariel/simulation/tasks/blueprint_gate_env.py) -and is intentionally minimal: +ariel ships two complementary contracts, each matched to its +backend's native shape: + +### 2a. `BlueprintGateEnv` Protocol (gymnasium VecEnv) + +Lives in +[`src/ariel/simulation/tasks/blueprint_gate_env.py`](../../src/ariel/simulation/tasks/blueprint_gate_env.py). +Used by backends that train with **stable-baselines3** or any other +gymnasium-VecEnv-compatible RL library. ```python @runtime_checkable @@ -60,23 +97,43 @@ class BlueprintGateEnv(Protocol): # stable_baselines3.common.vec_env.VecEnv. ``` -A conforming class: +Conformance: subclass `stable_baselines3.common.vec_env.VecEnv` and +take a `DroneBlueprint` at construction. `NumpyBlueprintGateEnv` is +the shipped reference implementation. + +### 2b. Isaac Lab's `DirectRLEnv` shape (lives in `isaaclab.envs`) -1. Accepts a `DroneBlueprint` at construction. -2. Exposes `.blueprint` and `.num_envs`. -3. Implements the standard `VecEnv` interface (`reset`, `step_async`, - `step_wait`, `close`, `get_attr`, `set_attr`, `env_method`, - `env_is_wrapped`) — usually by inheriting from - `stable_baselines3.common.vec_env.VecEnv` and doing the obvious thing. +Used by backends that train with **Isaac Lab's native RL libraries** +(rsl_rl, rl_games, skrl). Isaac Lab provides this class hierarchy; +our `IsaacLabBlueprintHoverEnv` extends it and slots in a +Blueprint-derived USD at scene-setup time. -Because the Protocol is `@runtime_checkable`, `isinstance(env, BlueprintGateEnv)` -works as a sanity assertion (`train.py` does this before handing the env to PPO). +```python +class IsaacLabBlueprintHoverEnv(DirectRLEnv): + cfg: IsaacLabBlueprintHoverEnvCfg + def __init__(self, cfg, render_mode=None, **kwargs): ... + def _setup_scene(self): ... + def _pre_physics_step(self, actions): ... + def _apply_action(self): ... + def _get_observations(self): ... + def _get_rewards(self): ... + def _get_dones(self): ... + def _reset_idx(self, env_ids): ... +``` + +Why two contracts and not one universal? Trying to force both +simulator ecosystems through a single shape (e.g., wrapping Isaac +Lab to gymnasium VecEnv via `isaaclab_rl.sb3`) drags in +stable-baselines3, which collides with the numpy-2 ABI in the +unified isaaclab conda env. Honest heterogeneity is cheaper than +forced uniformity. See [DRONE_BLUEPRINT_PLAN.md §6 entry 17](../../DRONE_BLUEPRINT_PLAN.md) +for the full rationale. --- ## 3. Running the shipped backends -### NumPy backend (works today) +### NumPy backend (gate task, sb3 PPO) ```bash python tutorials/pluggable_simulator/train.py \ @@ -86,37 +143,48 @@ python tutorials/pluggable_simulator/train.py \ --total-timesteps 5000 ``` -This wraps the existing `DroneSimulator` (pure NumPy + SymPy) via -`NumpyBlueprintGateEnv` — a thin shim that calls `blueprint_to_propellers` -and forwards to the established `DroneGateEnv`. >100× real-time on CPU. +Uses `DroneSimulator` (pure NumPy + SymPy) via `NumpyBlueprintGateEnv` +— a thin shim that calls `blueprint_to_propellers` and forwards to +the established `DroneGateEnv`. >100× real-time on CPU. ~6600 env- +steps/sec on 8 parallel envs. -### Isaac Lab backend (stub; Phase 2) +### Isaac Lab backend (hover task, env-stepping smoke for v1) ```bash python tutorials/pluggable_simulator/train.py \ --simulator isaaclab \ - --preset quad \ - --num-envs 64 \ - --total-timesteps 50000 + --headless \ + --num-envs 16 \ + --max-iterations 3 ``` -Currently raises `NotImplementedError` with a pointer to the Phase 2 plan. -When implemented, it will: - -1. Run `blueprint_to_urdf` in-process to produce a URDF. -2. Call Isaac Lab's `UrdfConverter` to produce a USD. -3. Spawn N parallel articulation instances in Isaac Sim. -4. Apply per-motor thrust each step via a first-order motor model - (lifted from soft_airframe's `morphy_simulator.py`). - -This is unblocked because ariel and Isaac Lab now share one conda env -(see [DRONE_BLUEPRINT_PLAN.md §6 entry 15](../../DRONE_BLUEPRINT_PLAN.md)). +Requires the unified ariel+IsaacLab conda env (see +[DRONE_BLUEPRINT_PLAN.md §6 entry 15](../../DRONE_BLUEPRINT_PLAN.md)). +What v1 does: + +1. Launches Isaac Sim via `AppLauncher`. +2. Runs `blueprint_to_urdf` to produce a URDF. +3. Calls `UrdfConverter` to produce a USD. +4. Spawns N parallel articulation instances in Isaac Sim. +5. Steps the env with random actions for `max_iterations × 24` steps, + computing observations + rewards (`-distance_to_goal × step_dt`) + + done flags per step. Verifies the whole physics + reward pipeline. + +Phase 2.5 will replace step 5 with a real PPO training run via +`rl_games.torch_runner.Runner` — the config helper +[`make_rl_games_agent_cfg`](../../src/ariel/simulation/tasks/isaaclab_hover_env.py) +already returns a working agent config; wiring it through is gated on +resolving the bundled-package-vs-conda-env stack issue described +above. --- ## 4. Adding your own simulator -Five steps: +Five steps. The exact contract you implement depends on your RL +library of choice: + +### If you're using stable-baselines3 (gymnasium VecEnv) **1. Create `src/ariel/simulation/tasks/_gate_env.py`.** @@ -127,8 +195,8 @@ from ariel.body_phenotypes.drone.blueprint import DroneBlueprint class YourBackendBlueprintGateEnv(VecEnv): def __init__(self, *, blueprint: DroneBlueprint, num_envs: int, **kwargs): # Convert the Blueprint into whatever your simulator needs. - # Available helpers in ariel.body_phenotypes.drone.backends: - # - blueprint_to_propellers(bp) → list[dict] (motor positions/dirs) + # Helpers available in ariel.body_phenotypes.drone.backends: + # - blueprint_to_propellers(bp) → list[dict] motor positions/dirs # - blueprint_to_mjspec(bp) → mujoco.MjSpec # - blueprint_to_urdf(bp, path) → URDF file ... @@ -149,33 +217,53 @@ class YourBackendBlueprintGateEnv(VecEnv): def env_is_wrapped(self, wrapper_class, indices=None): ... ``` -**2. Define the gate-passing task** in your env — gate positions, reward -shaping, observation/action spaces. The shipped envs use the gate layout in -[`src/ariel/simulation/tasks/drone_gate_env.py:22-34`](../../src/ariel/simulation/tasks/drone_gate_env.py) -as the reference; matching that layout means trained policies can be -compared backend-to-backend. +### If you're using Isaac Lab's native RL (rsl_rl, rl_games, skrl) -**3. Register your backend in `train.py`** by adding one branch to -`make_env()`: +**1. Create `src/ariel/simulation/tasks/__env.py`.** ```python -if simulator == "your_backend": - from ariel.simulation.tasks.your_backend_gate_env import YourBackendBlueprintGateEnv - return YourBackendBlueprintGateEnv(blueprint=blueprint, num_envs=num_envs, **kwargs) +from isaaclab.envs import DirectRLEnv, DirectRLEnvCfg +from isaaclab.utils import configclass +from ariel.body_phenotypes.drone.blueprint import DroneBlueprint + +@configclass +class YourBackendEnvCfg(DirectRLEnvCfg): + # episode_length_s, decimation, action_space, observation_space, scene, robot ... + @classmethod + def from_blueprint(cls, blueprint: DroneBlueprint, **kwargs): + # Generate a USD asset from the Blueprint, slot path into self.robot.spawn. + ... + +class YourBackendEnv(DirectRLEnv): + cfg: YourBackendEnvCfg + def __init__(self, cfg, render_mode=None, **kwargs): + super().__init__(cfg, render_mode, **kwargs) + ... + def _setup_scene(self): ... + def _pre_physics_step(self, actions): ... + def _apply_action(self): ... + def _get_observations(self): ... + def _get_rewards(self): ... + def _get_dones(self): ... + def _reset_idx(self, env_ids): ... ``` -**4. Verify Protocol conformance** by running: +### Both paths: register your backend in `train.py` + +**2. Add a dispatch branch in `train.py`** (a `main_` +function that imports your env + your RL library and runs training). + +**3. Add `--simulator ` to the choices list** so the +peek-parser routes correctly. + +**4. Verify it runs:** ```bash -python tutorials/pluggable_simulator/train.py --simulator your_backend \ - --total-timesteps 1000 --num-envs 2 +python tutorials/pluggable_simulator/train.py --simulator \ + --num-envs 2 --total-timesteps 1000 # or --max-iterations 2 ``` -If the assert at the top of `main()` fires, the env doesn't satisfy the -Protocol — typically because `self.blueprint` or `self.num_envs` wasn't -set, or one of the VecEnv methods is missing. - -**5. Plug into the EA evaluator.** Once the env trains a policy, point +**5. Plug into the EA evaluator.** Once training works, point `ariel.ec.drone.evaluators.gate_evaluator.GateEvaluator` (or your own evaluator) at the new backend. The EA loop never sees the simulator choice — it just gets fitness numbers back per individual. @@ -184,12 +272,14 @@ choice — it just gets fitness numbers back per individual. ## 5. Why this matters -The ARIEL consortium's collaborators bring their own simulators: MuJoCo, -Aerial Gym, Isaac Lab, IsaacGym, custom in-house stacks. The Protocol -seam means each group keeps their preferred simulator while sharing -ariel's evolutionary and learning infrastructure — decoders, EA -operators, repair, descriptors, training boilerplate. One IR -(`DroneBlueprint`), one EA loop, many backends. - -See [DRONE_BLUEPRINT_PLAN.md](../../DRONE_BLUEPRINT_PLAN.md) §1 ("Value -proposition") and §6 entry 17 for the broader rationale. +The ARIEL consortium's collaborators bring their own simulators: +MuJoCo, Aerial Gym, Isaac Lab, IsaacGym, custom in-house stacks. +Each group has a preferred RL library too. The two-contract seam +means each can keep their preferred simulator and trainer while +sharing ariel's evolutionary and morphology infrastructure — +decoders, EA operators, repair, descriptors, the morphology IR. +One IR (`DroneBlueprint`), one EA loop, many backends, many +trainers. + +See [DRONE_BLUEPRINT_PLAN.md](../../DRONE_BLUEPRINT_PLAN.md) §1 +("Value proposition") and §6 entry 17 for the broader rationale. diff --git a/tutorials/pluggable_simulator/train.py b/tutorials/pluggable_simulator/train.py index 6b810253e..7b666b140 100644 --- a/tutorials/pluggable_simulator/train.py +++ b/tutorials/pluggable_simulator/train.py @@ -1,41 +1,47 @@ -"""Train a PPO gate-passing policy through a pluggable simulator backend. +"""Train a PPO policy through a pluggable simulator backend. -Demonstrates ariel's backend-agnostic EA+PPO loop: the same trainer -runs against any backend that satisfies the -:class:`~ariel.simulation.tasks.blueprint_gate_env.BlueprintGateEnv` -Protocol. Today there are two backends: +Demonstrates ariel's backend-agnostic EA + PPO loop: the same outer +training script accepts any backend that satisfies its plug point. +Each backend brings its own simulator AND its own RL library, because +that matches how real heterogeneous simulator ecosystems work: - --simulator numpy → NumpyBlueprintGateEnv (shipped) - --simulator isaaclab → IsaacLabBlueprintGateEnv (stub; Phase 2) + --simulator numpy → NumpyBlueprintGateEnv (gymnasium VecEnv) + + stable-baselines3 PPO (gate-passing task) + + --simulator isaaclab → IsaacLabBlueprintHoverEnv (DirectRLEnv) + + random-action env stepping (hover-to-goal task; + rl_games PPO wiring + pending Phase 2.5) The morphology is built from a small set of presets via -``spherical_angular_to_blueprint``; the PPO training loop is identical -across backends. +``spherical_angular_to_blueprint``; the EA above this script never +sees the simulator choice — it just gets a fitness scalar back. Examples: - # Short smoke run on the NumPy backend (a few thousand steps). + # NumPy backend, gate task, sb3 PPO (short smoke run). python tutorials/pluggable_simulator/train.py --simulator numpy \\ --total-timesteps 5000 --num-envs 4 - # Full Isaac Lab path (not yet implemented). + # Isaac Lab backend, hover task, rsl_rl PPO (headless, short run). python tutorials/pluggable_simulator/train.py --simulator isaaclab \\ - --total-timesteps 50000 --num-envs 64 + --headless --max-iterations 20 --num-envs 64 """ from __future__ import annotations import argparse +import sys import time import numpy as np -from stable_baselines3 import PPO -from stable_baselines3.common.vec_env import VecMonitor from ariel.body_phenotypes.drone.decoders import spherical_angular_to_blueprint -from ariel.simulation.tasks.blueprint_gate_env import ( - BlueprintGateEnv, - NumpyBlueprintGateEnv, -) + + +def _log(msg: str) -> None: + """stderr-flushed progress messages (Isaac Sim sometimes swallows stdout).""" + sys.stderr.write(f"[train] {msg}\n") + sys.stderr.flush() # ---------- preset morphologies ------------------------------------------------- @@ -54,60 +60,45 @@ } -# ---------- backend dispatch ---------------------------------------------------- +# ---------- shared base parser -------------------------------------------------- -def make_env(simulator: str, blueprint, num_envs: int, **kwargs) -> BlueprintGateEnv: - """Return a BlueprintGateEnv for the requested backend. - - Adding a new simulator means adding one branch here and one - implementation file under ``ariel.simulation.tasks`` that - satisfies the BlueprintGateEnv Protocol. - """ - if simulator == "numpy": - return NumpyBlueprintGateEnv(blueprint=blueprint, num_envs=num_envs, **kwargs) - if simulator == "isaaclab": - from ariel.simulation.tasks.isaaclab_gate_env import IsaacLabBlueprintGateEnv - return IsaacLabBlueprintGateEnv(blueprint=blueprint, num_envs=num_envs, **kwargs) - raise ValueError( - f"Unknown simulator {simulator!r}. Known: 'numpy', 'isaaclab'." - ) +def _base_parser() -> argparse.ArgumentParser: + p = argparse.ArgumentParser(description=__doc__.splitlines()[0]) + p.add_argument("--simulator", choices=["numpy", "isaaclab"], default="numpy", + help="Which simulator backend (and matching RL library) to use.") + p.add_argument("--preset", choices=list(PRESETS), default="quad") + p.add_argument("--propsize", type=int, default=5) + p.add_argument("--num-envs", type=int, default=8) + p.add_argument("--seed", type=int, default=42) + return p -# ---------- main ---------------------------------------------------------------- +# ---------- numpy backend: sb3 PPO + NumpyBlueprintGateEnv ---------------------- -def main() -> None: - parser = argparse.ArgumentParser(description=__doc__.splitlines()[0]) - parser.add_argument("--simulator", choices=["numpy", "isaaclab"], default="numpy", - help="Which simulator backend to plug behind the PPO loop.") - parser.add_argument("--preset", choices=list(PRESETS), default="quad", - help="Built-in morphology to evolve a policy on.") - parser.add_argument("--propsize", type=int, default=5) - parser.add_argument("--num-envs", type=int, default=8, - help="Vectorized parallel envs.") +def main_numpy(parser: argparse.ArgumentParser) -> None: parser.add_argument("--total-timesteps", type=int, default=10_000, - help="PPO total environment steps (a few thousand for " - "a smoke test; tens of millions for actual training).") - parser.add_argument("--seed", type=int, default=42) + help="sb3 PPO total environment steps.") args = parser.parse_args() - print(f"=== pluggable-simulator demo ===") - print(f" simulator : {args.simulator}") - print(f" preset / propsize: {args.preset} / {args.propsize}") - print(f" num_envs : {args.num_envs}") - print(f" total_timesteps : {args.total_timesteps}") + from ariel.simulation.tasks.blueprint_gate_env import ( + BlueprintGateEnv, + NumpyBlueprintGateEnv, + ) + from stable_baselines3 import PPO + from stable_baselines3.common.vec_env import VecMonitor + + print(f"=== pluggable-simulator demo: numpy + stable-baselines3 PPO ===") + print(f" preset / propsize : {args.preset} / {args.propsize}") + print(f" num_envs : {args.num_envs}") + print(f" total_timesteps : {args.total_timesteps}") blueprint = spherical_angular_to_blueprint( PRESETS[args.preset], propsize=args.propsize, ) - print(f" blueprint : {blueprint.g.number_of_nodes()} nodes") - - env = make_env( - args.simulator, blueprint=blueprint, num_envs=args.num_envs, seed=args.seed, - ) - # Sanity check the Protocol — runtime_checkable lets us assert here. - assert isinstance(env, BlueprintGateEnv), ( - f"{type(env).__name__} does not satisfy BlueprintGateEnv Protocol" + env = NumpyBlueprintGateEnv( + blueprint=blueprint, num_envs=args.num_envs, seed=args.seed, ) + assert isinstance(env, BlueprintGateEnv), "Protocol mismatch" env = VecMonitor(env) model = PPO("MlpPolicy", env, verbose=1, seed=args.seed, device="cpu") @@ -117,9 +108,122 @@ def main() -> None: print(f"\n=== training complete ===") print(f" wall time : {dt:.1f} s") - print(f" steps : {args.total_timesteps}") print(f" steps/sec : {args.total_timesteps / dt:.0f}") +# ---------- isaaclab backend: rsl_rl PPO + DirectRLEnv -------------------------- + +def main_isaaclab(parser: argparse.ArgumentParser) -> None: + # Add Isaac-Lab-specific args + AppLauncher args, then parse. + parser.add_argument("--max-iterations", type=int, default=20, + help="rl_games PPO max_epochs.") + parser.add_argument("--device-override", type=str, default=None, + help="Override the auto-selected device " + "(e.g., 'cpu' or 'cuda:0').") + + # AppLauncher must be imported early so its args can be added to the + # parser. Importing it triggers Isaac Sim's launcher setup; this is + # the cost of going down the isaaclab path. + from isaaclab.app import AppLauncher # noqa: PLC0415 + AppLauncher.add_app_launcher_args(parser) + args = parser.parse_args() + + if args.device_override is not None: + args.device = args.device_override + + _log(f"=== pluggable-simulator demo: isaaclab + env-stepping smoke " + f"(rl_games PPO wiring deferred to Phase 2.5; see DRONE_BLUEPRINT_PLAN.md §6 entry 17) ===") + _log(f" preset / propsize : {args.preset} / {args.propsize}") + _log(f" num_envs : {args.num_envs}") + _log(f" max_iterations : {args.max_iterations}") + + # Launch Isaac Sim. The env module imports isaaclab.* at module level, + # so we delay the import until *after* the launcher is running. + _log("launching Isaac Sim...") + app_launcher = AppLauncher(args, multi_gpu=False) + simulation_app = app_launcher.app + _log("Isaac Sim launched") + + import traceback # noqa: PLC0415 + try: + _log("importing IsaacLabBlueprintHoverEnv...") + from ariel.simulation.tasks.isaaclab_hover_env import ( # noqa: PLC0415 + IsaacLabBlueprintHoverEnv, + IsaacLabBlueprintHoverEnvCfg, + ) + import torch # noqa: PLC0415 + + _log("building blueprint...") + blueprint = spherical_angular_to_blueprint( + PRESETS[args.preset], propsize=args.propsize, + ) + + _log("building cfg from blueprint (generates URDF + USD)...") + env_cfg = IsaacLabBlueprintHoverEnvCfg.from_blueprint( + blueprint, num_envs=args.num_envs, + ) + env_cfg.seed = args.seed + env_cfg.sim.device = args.device + + _log(f"constructing env (num_envs={args.num_envs}, device={args.device})...") + env = IsaacLabBlueprintHoverEnv(cfg=env_cfg) + + # Phase 2 demonstrates env construction + scene spawn + per-step + # physics via a random-action stepping loop. Real PPO training + # via `rl_games.torch_runner.Runner` is structurally wired (see + # IsaacLabBlueprintHoverEnv's `make_rl_games_agent_cfg`) but + # blocked on a Phase 2.5 follow-up: Isaac Sim's bundled torch + # tensorboard transitively imports an older TF/jax/numpy stack + # that conflicts with the conda env's numpy 2. See + # DRONE_BLUEPRINT_PLAN.md §6 entry 17 for the full story. + n_steps = max(1, args.max_iterations) * 24 # iterations × horizon + _log(f"stepping env with random actions for {n_steps} steps " + f"(env-construction smoke; PPO is Phase 2.5)...") + + env.reset() + action_dim = env.cfg.action_space + rewards_seen: list[float] = [] + t0 = time.time() + for step in range(n_steps): + actions = (torch.rand(args.num_envs, action_dim, device=args.device) * 2.0 - 1.0) + _obs_dict, reward, _terminated, _truncated, _info = env.step(actions) + rewards_seen.append(float(reward.mean().item())) + if (step + 1) % 24 == 0: + _log(f" step {step+1:4d} | mean reward (last 24): " + f"{sum(rewards_seen[-24:])/24:.4f}") + dt = time.time() - t0 + + _log(f"=== env-stepping smoke complete ===") + _log(f" wall time : {dt:.1f} s") + _log(f" steps : {n_steps}") + _log(f" steps/sec : {n_steps / dt:.0f}") + _log(f" mean reward : {sum(rewards_seen) / len(rewards_seen):.4f}") + except Exception as exc: + _log(f"ERROR: {type(exc).__name__}: {exc}") + traceback.print_exc(file=sys.stderr) + raise + finally: + _log("closing simulation app") + simulation_app.close() + + +# ---------- entry point --------------------------------------------------------- + +def main() -> None: + # Peek at --simulator without committing to a fully-parsed namespace yet. + # This lets us avoid importing isaaclab when the user only wants numpy. + peek_parser = argparse.ArgumentParser(add_help=False) + peek_parser.add_argument("--simulator", choices=["numpy", "isaaclab"], default="numpy") + peek_args, _ = peek_parser.parse_known_args(sys.argv[1:]) + + parser = _base_parser() + if peek_args.simulator == "numpy": + main_numpy(parser) + elif peek_args.simulator == "isaaclab": + main_isaaclab(parser) + else: + raise SystemExit(f"Unknown simulator: {peek_args.simulator!r}") + + if __name__ == "__main__": main() From 53d5fb0a42ed98990eb5efe7b8dc31f9f023ba8b Mon Sep 17 00:00:00 2001 From: Keiichi Ito Date: Wed, 27 May 2026 13:22:15 +0200 Subject: [PATCH 20/27] Phase 2.5: dependency-ownership split + lazy imports + parts/ pkg. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Stops ariel's base package from owning Isaac-Lab-sensitive binary deps (numpy 2, torch, gymnasium), and unblocks two import chains that were dragging optional heavy deps into common code paths. This is the architectural prerequisite to actually running rl_games PPO on the Isaac Lab backend — the Phase 2.5 plan documented in §6 entry 15 / Phase 3 "Still pending" of DRONE_BLUEPRINT_PLAN.md. pyproject.toml — dependency ownership split: * `[project.dependencies]` trimmed to simulator-agnostic essentials. Base `numpy` is now pinned conservatively to `>=1.26,<2` (was `>=2.0.2`) so installing ariel into an Isaac Lab env doesn't drag in numpy 2's ABI and segfault sb3. * New optional extras: `rl-sb3` (gymnasium==1.2.1 + sb3>=2.7.0), `torch` (torch + torchvision), `viz` (opencv/pillow/panel/plotly/ kaleido), `fabrication` (cadquery), `experimental` (the long tail of attrs/deap/dm-control/ipykernel/jupyter/keyboard/manifold3d/ nevergrad/nicegui/omegaconf/polars/pyserial/pyvista). torch and gymnasium leave [project.dependencies] entirely — Isaac Lab's env owns those. README.md — installation matrix: * Documents `uv sync --extra rl-sb3 --extra torch` for the sb3 path, and crucially `pip install -e . --no-deps` for installing ariel into an Isaac Lab env without replacing simulator-owned binaries. src/ariel/ec/drone/genome_handlers/__init__.py — lazy imports: * Replaced eager handler imports with `__getattr__`-based lazy resolution. Importing `genome_handlers` no longer pulls in `fcl` (or any other optional heavy dep) just because something under the package is touched. Verified: `from ariel.ec.drone. genome_handlers import GenomeHandler` succeeds with fcl absent from sys.modules. src/ariel/body_phenotypes/drone/phenotype_assembly/parts/ — new fabrication package (added by user): * 4 CAD-part factories: `create_core_plate`, `create_arm_mount`, `create_motor_arm`, `create_motor_mount`. Imported by the assembly code; previously missing, so `fabrication` extra imports failed even with cadquery installed. .gitignore — source-tree `parts/` exception: * The pre-existing `parts/` rule at line 33 is the standard Python/buildout block; it was silently swallowing the new source-tree `parts/` package above. Added `!src/**/parts/` exception so source `parts/` packages are tracked normally; the buildout-style ignore still applies to output directories elsewhere. DRONE_BLUEPRINT_PLAN.md — extensive doc updates: * Phase 2.5 in "Still pending" rewritten with a concrete Option A execution recipe (clean conda env from Isaac Lab's environment.yml + `pip install -e . --no-deps` for ariel) and an acceptance checklist. Options B and C demoted to diagnostic-only fallbacks with their own minimal runbooks. * The old "Targeted dep pins" pending item replaced with a summary of what was implemented this session. * §6 entry 15 (the unified-env entry) expanded with the dependency-ownership split rationale. * New §6 entry 18 documenting the lazy-imports + parts/ fixes and the clean-env smoke validation across `rl-sb3`, `torch`, `viz`, `fabrication`, `experimental` extras. uv.lock — regenerated to match pyproject.toml's new dependency shape. Co-Authored-By: Keiichi Ito (Phase 2.5 architectural changes) Co-Authored-By: Claude Opus 4.7 --- .gitignore | 4 + DRONE_BLUEPRINT_PLAN.md | 220 +- README.md | 21 +- pyproject.toml | 53 +- .../phenotype_assembly/parts/__init__.py | 13 + .../phenotype_assembly/parts/arm_mount.py | 44 + .../phenotype_assembly/parts/core_plate.py | 36 + .../phenotype_assembly/parts/motor_arm.py | 63 + .../phenotype_assembly/parts/motor_mount.py | 51 + .../ec/drone/genome_handlers/__init__.py | 58 +- uv.lock | 2210 +++++++++++------ 11 files changed, 1881 insertions(+), 892 deletions(-) create mode 100644 src/ariel/body_phenotypes/drone/phenotype_assembly/parts/__init__.py create mode 100644 src/ariel/body_phenotypes/drone/phenotype_assembly/parts/arm_mount.py create mode 100644 src/ariel/body_phenotypes/drone/phenotype_assembly/parts/core_plate.py create mode 100644 src/ariel/body_phenotypes/drone/phenotype_assembly/parts/motor_arm.py create mode 100644 src/ariel/body_phenotypes/drone/phenotype_assembly/parts/motor_mount.py diff --git a/.gitignore b/.gitignore index 4f5e76e6e..d20844a72 100644 --- a/.gitignore +++ b/.gitignore @@ -31,6 +31,10 @@ eggs/ lib/ lib64/ parts/ +# Don't let the buildout-style `parts/` rule above silently swallow +# source-tree `parts/` packages (e.g. +# src/ariel/body_phenotypes/drone/phenotype_assembly/parts/). +!src/**/parts/ sdist/ var/ wheels/ diff --git a/DRONE_BLUEPRINT_PLAN.md b/DRONE_BLUEPRINT_PLAN.md index 8c45afedc..74e75bc27 100644 --- a/DRONE_BLUEPRINT_PLAN.md +++ b/DRONE_BLUEPRINT_PLAN.md @@ -249,21 +249,147 @@ What's landed (in order of commit): **Still pending — to pick up next session:** -* **Phase 2.5 of pluggable simulator: actually train.** The - `rl_games` Runner trips on a transitive import chain (Isaac Sim's - bundled `torch.utils.tensorboard.writer` → lazy `tensorflow` → - `jax` → `numpy.dtypes.StringDType`) because Isaac Sim's - `pip_prebundle/` ships an older numpy than the conda env's - numpy 2.4.6. Options: (a) install a clean conda env with pinned - versions matched to Isaac Sim's bundle, (b) shadow the bundled - torch with the conda env's torch on `PYTHONPATH`, (c) downgrade - jax + tensorboard to versions tolerant of numpy 2. Independent of - this, `rsl_rl` integration via `isaaclab_rl.rsl_rl` was a - separate dead end during Phase 2 — the adapter sends kwargs - (`optimizer`, `share_cnn_encoders`) that don't match the - installed `rsl-rl-lib` 3.0.1 PPO signature (and 5.x has its own - config shape mismatch). `rl_games` is the path we picked - forward; `make_rl_games_agent_cfg` in +* **Phase 2.5 of pluggable simulator: stabilize the Isaac Lab + training stack, then run PPO.** The `rl_games` Runner trips on a + transitive import chain (Isaac Sim's bundled + `torch.utils.tensorboard.writer` → lazy `tensorflow` → `jax` → + `numpy.dtypes.StringDType`) because Isaac Sim's `pip_prebundle/` + ships an older numpy than the conda env's numpy 2.4.6. We should + stop treating the three remediations as peers; the recommended + path is a dedicated Isaac-Lab-specific training env pinned to the + Isaac Sim / Isaac Lab stack, with ariel installed into it without + upgrading the simulator-owned binaries. + + **Concrete packaging / env plan:** + 1. Create a clean `ariel-isaaclab-train` conda env from Isaac + Lab's published env / bundled versions first, not from + ariel's top-level `pyproject.toml`. + 2. Install Isaac Lab / Isaac Sim into that env, verify the stock + `rl_games` examples run, then install ariel editable with + `pip install -e . --no-deps` so pip does not replace the + simulator-owned torch / gymnasium / numpy stack. + 3. Trim ariel's top-level dependencies down to simulator-agnostic + requirements. In particular, move `torch`, `torchvision`, and + `gymnasium` out of `[project.dependencies]`; do not let the + base package force versions of libraries Isaac Lab already owns. + 4. Pin shared binary deps conservatively in the base package: + `numpy>=1.26,<2` is the target unless a code path is proven to + require a numpy-2-only API. The current `numpy>=2.0.2` default + is the wrong bias for this integration. + 5. If we keep an optional `isaaclab` extra, it should be a + glue-only extra, not a second owner of the low-level runtime. + That means: no `torch`, no `torchvision`, no `gymnasium`, and + no attempt to pip-install Isaac Lab itself from ariel. At most, + it carries tiny compatibility pins that are not already owned by + Isaac Lab's env. + 6. Treat shadowing torch on `PYTHONPATH` as a diagnostic hack, not + a supported solution. Treat `jax` / `tensorboard` downgrades as + a probe to confirm the import chain, not the primary fix. + 7. Phase-2.5 exit criterion: one reproducible env-creation recipe, + one documented install command, and one short `rl_games` PPO + smoke run from `tutorials/pluggable_simulator/train.py`. + + **Option A execution recipe (copy/paste):** + + ```bash + # 0) Paths (adjust if your checkout differs) + export ARIEL_ROOT="$HOME/Documents/sandbox/ariel" + export ISAACLAB_ROOT="$HOME/Documents/sandbox/IsaacLab" + export ENV_NAME="ariel-isaaclab-train" + + # 1) Create a clean env from Isaac Lab's pinned stack + conda env remove -n "$ENV_NAME" -y || true + conda env create -n "$ENV_NAME" -f "$ISAACLAB_ROOT/environment.yml" + conda activate "$ENV_NAME" + + # 2) Install Isaac Lab into that env (owns torch/gymnasium/numpy ABI layer) + cd "$ISAACLAB_ROOT" + ./isaaclab.sh -i + + # 3) Sanity-check Isaac Lab python path first + ./isaaclab.sh -p -c "import isaaclab; print('isaaclab import OK')" + + # 4) Install ariel WITHOUT dependency resolution side effects + cd "$ARIEL_ROOT" + pip install -e . --no-deps + + # 5) Quick import smoke for ariel + sb3/numpy backend path + python -c "from ariel.simulation.tasks.drone_gate_env import DroneGateEnv; print('DroneGateEnv import OK')" + + # 6) Isaac Lab backend smoke (env stepping; PPO training still Phase 2.5 gate) + python tutorials/pluggable_simulator/train.py \ + --simulator isaaclab \ + --headless \ + --num-envs 16 \ + --max-iterations 3 + ``` + + **Option A acceptance checklist (mark done when all true):** + - [ ] New clean env is created from Isaac Lab's `environment.yml` with no manual pin surgery. + - [ ] Isaac Lab import sanity check passes before ariel is installed. + - [ ] `pip install -e . --no-deps` completes and does not replace simulator-owned torch/gymnasium/numpy. + - [ ] `DroneGateEnv` import smoke passes in the Option A env. + - [ ] `train.py --simulator isaaclab --headless --max-iterations 3` completes successfully. + - [ ] One short `rl_games` PPO smoke run completes in this env (single command recorded in the notes). + - [ ] Re-running the same commands in a fresh env reproduces the same result. + + **Option B (diagnostic only): shadow bundled torch with env torch** + + **Purpose:** quickly test whether the `rl_games` failure is mainly an + import-precedence issue (`pip_prebundle/torch` winning over the env's + torch). + + **Why this is NOT a primary fix:** this changes import order rather than + making the environment reproducible. It is sensitive to launch scripts, + shell state, and path ordering. + + **Minimal runbook (for diagnosis):** + 1. Start from a known-good Option A env. + 2. Export `PYTHONPATH` so the env's site-packages come before Isaac Sim's + bundled paths. + 3. Run the shortest failing `rl_games` smoke command. + 4. Capture `sys.path`, `torch.__file__`, and `numpy.__version__` in logs. + + **Stop criteria:** + - If this makes PPO smoke pass once but the result is not reproducible in + a fresh shell, treat as a confirmed diagnostic only. + - If this still fails on the same tensorboard/jax path, abandon Option B + and return to Option A. + + **Rollback:** unset `PYTHONPATH`, reopen shell, and re-run baseline Option A + smoke to verify environment behavior is unchanged. + + **Option C (diagnostic fallback): targeted jax/tensorboard downgrade** + + **Purpose:** test whether the `numpy.dtypes.StringDType` failure is caused by + a specific transitive version edge in `jax` / `tensorboard`. + + **Why this is NOT a primary fix:** package surgery in this subtree can hide + deeper ABI mismatches and often drifts over time. + + **Minimal runbook (for diagnosis):** + 1. Clone Option A env to an isolated test env. + 2. Apply only the smallest jax/tensorboard version change needed for the + failing import path. + 3. Re-run the same short `rl_games` smoke command. + 4. Record before/after versions for `jax`, `tensorboard`, `tensorflow`, + `numpy`, and `torch`. + + **Stop criteria:** + - If PPO smoke passes, treat this as evidence about the failure mechanism, + not production config, until reproduced from a locked env spec. + - If additional downgrades cascade beyond this subtree, stop and revert; + this is no longer a targeted probe. + + **Rollback:** discard the test env and recreate from Option A recipe rather + than attempting in-place undo. + + Independent of this, `rsl_rl` integration via + `isaaclab_rl.rsl_rl` was a separate dead end during Phase 2 — the + adapter sends kwargs (`optimizer`, `share_cnn_encoders`) that do + not match the installed `rsl-rl-lib` 3.0.1 PPO signature (and 5.x + has its own config shape mismatch). `rl_games` is the path we + picked forward; `make_rl_games_agent_cfg` in `isaaclab_hover_env.py` is the matching config helper. * **Compliant joints (URDF revolute + sidecar stiffness + USD `ariel:*` attrs).** Schema landed on `compliant-joint-schema`; @@ -274,13 +400,16 @@ What's landed (in order of commit): * Pytest integration test for the Blueprint → URDF → USD pipeline (now feasible in-process under the unified env; just needs a `pytest.mark.isaaclab` skip-if-not-available guard). -* Targeted dep pins in pyproject.toml to keep numpy < 2 and - gymnasium == 1.2.1 so isaaclab's pins aren't violated. **Promoted - from stretch:** the smoke test for `pluggable-simulator` segfaulted - in the unified isaaclab env on PPO startup (likely a numpy 2 ABI - conflict with stable-baselines3's compiled deps). Same smoke test - passed cleanly in the ariel 3.12 venv where numpy 1.x is intact, - confirming the seam itself is correct. +* **~~Targeted dep pins in pyproject.toml~~ — implemented this + session as a dependency-ownership split.** + `pyproject.toml` now keeps simulator-agnostic requirements in + `[project.dependencies]` and moves simulator-/workflow-specific + stacks to extras (`rl-sb3`, `torch`, `viz`, `fabrication`, + `experimental`). Base `numpy` is pinned conservatively + (`>=1.26,<2`) and `rl-sb3` pins `gymnasium==1.2.1` to match + Isaac Lab expectations. `README.md` now documents the + extra-specific install commands and the Isaac-Lab-safe + `pip install -e . --no-deps` path. ## 6. Design decisions (Phase 3 — URDF / USD backends) @@ -447,10 +576,19 @@ Each entry: **decision** — *why*; alternatives considered. `isaaclab` conda env after `pip install -e ariel`. The pip resolver reports conflicts (numpy 2 vs `isaaclab`'s `<2`, gymnasium 1.3 vs 1.2.1, torch CUDA build swap from `+cu128` to - `+cu130`) but the URDF→USD pipeline still works. If those - conflicts bite elsewhere (RL training, dex_retargeting, etc.) - they'll need targeted pins in ariel's pyproject.toml; deferred - until something actually breaks. + `+cu130`) but the URDF→USD pipeline still works. Phase 2.5 makes + this no longer a vague future cleanup item: ariel's base package + should stop owning Isaac-Lab-sensitive binary deps. The concrete + split is: + + * keep simulator-agnostic deps in `[project.dependencies]`; + * pin base `numpy` conservatively (`>=1.26,<2` unless proven + otherwise); + * move `torch`, `torchvision`, and `gymnasium` out of top-level + deps; + * keep any future `isaaclab` extra glue-only, so the env created + by Isaac Lab remains the sole owner of torch / gymnasium / + low-level CUDA-coupled packages. 17. **Simulator backends are a plug point, not a hard-coded choice; the contract is two complementary shapes — one per ecosystem.** @@ -537,6 +675,36 @@ Each entry: **decision** — *why*; alternatives considered. `DroneGateEnv` would have hit this; nothing in the existing examples exercised it because they didn't pass `seed=` to PPO. +18. **Session update (dependency split + smoke validation): + two import-chain blockers were fixed to make the new extras + usable in clean envs.** + + **Why:** after moving dependencies behind extras, clean-env smoke + tests surfaced two failures that made the split incomplete: + (a) importing `DroneGateEnv` through the `rl-sb3` path + transitively imported `fcl` from an unrelated operator module; + (b) `fabrication` imports failed because + `phenotype_assembly/parts/` did not exist even though the + assembly code imported it. + + **What was changed this session:** + - `src/ariel/ec/drone/genome_handlers/__init__.py` was converted + from eager imports to lazy `__getattr__`-based imports. This + prevents optional heavy deps from being imported just by touching + helper modules under `genome_handlers`. + - Added missing + `src/ariel/body_phenotypes/drone/phenotype_assembly/parts/` + package with API-compatible factories: + `create_core_plate`, `create_arm_mount`, `create_motor_arm`, + `create_motor_mount`. + + **Validation:** reran smoke tests in fresh temporary uv envs. + `rl-sb3 + torch` now imports `DroneGateEnv` successfully; and + `fabrication` now imports + `ariel.body_phenotypes.drone.phenotype_assembly.generator` + successfully. `viz` and `experimental` extra smoke checks also + passed. + ## 7. Asks for the meeting 1. Confirm Isaac Lab as the simulator target the consortium will converge diff --git a/README.md b/README.md index 2bc3e875f..4ecaeeeb4 100644 --- a/README.md +++ b/README.md @@ -37,7 +37,26 @@ cd ariel ```bash uv sync ``` -4. Run an example, in this case, brain evolution (aka learning) using: +4. Install optional extras for your workflow (examples) +```bash +# sb3 gate-training path +uv sync --extra rl-sb3 --extra torch + +# dashboard and rendering tools +uv sync --extra viz + +# CAD / STL assembly tools +uv sync --extra fabrication + +# additional experimental stacks used by selected examples +uv sync --extra experimental +``` +For Isaac Lab workflows, use the Isaac Lab-owned environment and install +ariel without replacing simulator-owned binary packages: +```bash +pip install -e . --no-deps +``` +5. Run an example, in this case, brain evolution (aka learning) using: ```bash uv run examples/re_book/1_brain_evolution.py ``` diff --git a/pyproject.toml b/pyproject.toml index dff402192..fb642fbf5 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -9,39 +9,18 @@ authors = [{ name = "jmdm", email = "jmdm.880@gmail.com" }] classifiers = ["Development Status :: 2 - Pre-Alpha"] dependencies = [ - "attrs>=25.4.0", - "deap>=1.4.3", - "dm-control>=1.0.38", "evotorch>=0.6.1", - "gymnasium>=1.2.3", - "ipykernel>=6.30.1", - "jupyter>=1.1.1", - "kaleido>=1.2.0", - "keyboard>=0.13.5", - "manifold3d>=3.4.0", "matplotlib>=3.9.4", "mujoco>=3.3.6", "mujoco-mjx[warp]>=3.6.0", "networkx>=3.2.1", - "nevergrad>=1.0.12", - "nicegui>=2.24.1", - "numpy>=2.0.2", + "numpy>=1.26,<2", "numpy-quaternion>=2023.0.3", - "omegaconf>=2.3.0", - "opencv-python>=4.11.0.86", - "panel>=1.8.9", - "pillow>=11.3.0", - "plotly>=6.6.0", - "polars>=1.35.2", "pydantic>=2.11.9", "pydantic-settings>=2.10.1", - "pyserial>=3.5", - "pyvista>=0.47.1", "rich>=14.1.0", "sqlalchemy>=2.0.43", "sqlmodel>=0.0.25", - "torch>=2.8.0", - "torchvision>=0.23.0", ] @@ -52,7 +31,37 @@ Documentation = "https://ariel.readthedocs.io" Changelog = "https://github.com/ci-group/ariel/releases" [project.optional-dependencies] +rl-sb3 = [ + "gymnasium==1.2.1", + "stable-baselines3>=2.7.0", +] +torch = [ + "torch>=2.8.0", + "torchvision>=0.23.0", +] +viz = [ + "opencv-python>=4.11.0.86", + "pillow>=11.3.0", + "panel>=1.8.9", + "plotly>=6.6.0", + "kaleido>=1.2.0", +] fabrication = ["cadquery>=2.4.0"] +experimental = [ + "attrs>=25.4.0", + "deap>=1.4.3", + "dm-control>=1.0.38", + "ipykernel>=6.30.1", + "jupyter>=1.1.1", + "keyboard>=0.13.5", + "manifold3d>=3.4.0", + "nevergrad>=1.0.12", + "nicegui>=2.24.1", + "omegaconf>=2.3.0", + "polars>=1.35.2", + "pyserial>=3.5", + "pyvista>=0.47.1", +] [dependency-groups] dev = ["mypy>=1.18.2", "pytest>=8.4.2", "pytest-modern>=0.7.4", "ruff>=0.13.3"] diff --git a/src/ariel/body_phenotypes/drone/phenotype_assembly/parts/__init__.py b/src/ariel/body_phenotypes/drone/phenotype_assembly/parts/__init__.py new file mode 100644 index 000000000..1008844fa --- /dev/null +++ b/src/ariel/body_phenotypes/drone/phenotype_assembly/parts/__init__.py @@ -0,0 +1,13 @@ +"""CAD part factories for drone phenotype assembly.""" + +from .arm_mount import create_arm_mount +from .core_plate import create_core_plate +from .motor_arm import create_motor_arm +from .motor_mount import create_motor_mount + +__all__ = [ + "create_core_plate", + "create_arm_mount", + "create_motor_arm", + "create_motor_mount", +] diff --git a/src/ariel/body_phenotypes/drone/phenotype_assembly/parts/arm_mount.py b/src/ariel/body_phenotypes/drone/phenotype_assembly/parts/arm_mount.py new file mode 100644 index 000000000..fd505b9b9 --- /dev/null +++ b/src/ariel/body_phenotypes/drone/phenotype_assembly/parts/arm_mount.py @@ -0,0 +1,44 @@ +"""Arm mount CAD primitive.""" + +from __future__ import annotations + +import cadquery as cq + + +def create_arm_mount( + *, + sphere_radius: float, + clamp_inset: float, + arm_plate_diameter: float, + arm_plate_thickness: float, + arm_screw_hole_inset: float, + include_arm_socket: bool = False, + arm_elevation: float = 0.0, + arm_azimuth: float = 0.0, +) -> dict[str, cq.Workplane]: + """Create a simple spherical arm mount with a rim clamp notch. + + Extra parameters are accepted for API compatibility with existing callers. + """ + del arm_elevation, arm_azimuth, arm_screw_hole_inset + + sphere = cq.Workplane("XY").sphere(sphere_radius) + + notch_depth = max(0.1, min(sphere_radius * 1.5, clamp_inset + arm_plate_thickness)) + notch = ( + cq.Workplane("XY") + .box(sphere_radius * 2.2, arm_plate_diameter, arm_plate_thickness + 1.0) + .translate((sphere_radius - notch_depth, 0, 0)) + ) + sphere = sphere.cut(notch) + + if include_arm_socket: + socket = ( + cq.Workplane("YZ") + .circle(max(0.6, sphere_radius * 0.35)) + .extrude(sphere_radius * 2.5) + .translate((0.0, 0.0, 0.0)) + ) + sphere = sphere.cut(socket) + + return {"sphere": sphere} diff --git a/src/ariel/body_phenotypes/drone/phenotype_assembly/parts/core_plate.py b/src/ariel/body_phenotypes/drone/phenotype_assembly/parts/core_plate.py new file mode 100644 index 000000000..9033a4667 --- /dev/null +++ b/src/ariel/body_phenotypes/drone/phenotype_assembly/parts/core_plate.py @@ -0,0 +1,36 @@ +"""Core plate CAD primitive.""" + +from __future__ import annotations + +import cadquery as cq + + +def create_core_plate( + *, + plate_diameter: float, + plate_thickness: float, + outer_ring_width: float, + include_hollow_square: bool = True, + hollow_square_outer_size: float = 33.0, + hollow_square_wall_thickness: float = 2.0, +) -> cq.Workplane: + """Create a printable core plate as a ring-like disc. + + The geometry is intentionally simple and robust for export. + """ + plate_radius = plate_diameter / 2.0 + inner_radius = max(0.1, plate_radius - outer_ring_width) + + ring = ( + cq.Workplane("XY") + .circle(plate_radius) + .circle(inner_radius) + .extrude(plate_thickness) + ) + + if include_hollow_square: + inner_square = max(0.1, hollow_square_outer_size - 2.0 * hollow_square_wall_thickness) + if inner_square > 0.0: + ring = ring.faces(">Z").workplane().rect(inner_square, inner_square).cutBlind(-plate_thickness) + + return ring diff --git a/src/ariel/body_phenotypes/drone/phenotype_assembly/parts/motor_arm.py b/src/ariel/body_phenotypes/drone/phenotype_assembly/parts/motor_arm.py new file mode 100644 index 000000000..1008080f4 --- /dev/null +++ b/src/ariel/body_phenotypes/drone/phenotype_assembly/parts/motor_arm.py @@ -0,0 +1,63 @@ +"""Motor arm CAD primitive.""" + +from __future__ import annotations + +import cadquery as cq +import math + + +def create_motor_arm( + *, + arm_length: float, + motor_tilt: float, + motor_azimuth: float, + cylinder_inner_radius: float, + wall_thickness: float, + cylinder_extension: float, + sphere_offset: float, + disc_diameter: float, + disc_thickness: float, + motor_screw_count: int, + motor_screw_start_angle: float, + motor_screw_depth: float, + center_hole_diameter: float, +) -> cq.Workplane: + """Create a hollow arm tube with a motor disc at its tip.""" + del motor_tilt, motor_azimuth, motor_screw_depth + + outer_radius = max(cylinder_inner_radius + wall_thickness, cylinder_inner_radius + 0.2) + tube_height = max(1.0, arm_length + sphere_offset + cylinder_extension) + + tube = ( + cq.Workplane("XY") + .circle(outer_radius) + .circle(max(0.1, cylinder_inner_radius)) + .extrude(tube_height) + ) + + disc = ( + cq.Workplane("XY") + .workplane(offset=tube_height) + .circle(max(1.0, disc_diameter / 2.0)) + .extrude(max(0.5, disc_thickness)) + ) + arm = tube.union(disc) + + if center_hole_diameter > 0: + arm = arm.faces(">Z").workplane().hole(center_hole_diameter) + + if motor_screw_count > 0: + screw_r = max(0.1, disc_diameter * 0.35) + screw_d = max(0.6, wall_thickness) + wp = arm.faces(">Z").workplane() + for i in range(motor_screw_count): + angle_deg = motor_screw_start_angle + i * (360.0 / motor_screw_count) + wp = wp.pushPoints([ + ( + screw_r * math.cos(math.radians(angle_deg)), + screw_r * math.sin(math.radians(angle_deg)), + ) + ]) + arm = wp.hole(screw_d) + + return arm diff --git a/src/ariel/body_phenotypes/drone/phenotype_assembly/parts/motor_mount.py b/src/ariel/body_phenotypes/drone/phenotype_assembly/parts/motor_mount.py new file mode 100644 index 000000000..8936a6b9e --- /dev/null +++ b/src/ariel/body_phenotypes/drone/phenotype_assembly/parts/motor_mount.py @@ -0,0 +1,51 @@ +"""Motor mount CAD primitive for modular assembly exports.""" + +from __future__ import annotations + +import cadquery as cq + + +def create_motor_mount( + *, + motor_tilt: float, + motor_azimuth: float, + cylinder_inner_radius: float, + pocket_thickness: float, + sphere_offset: float, + cylinder_extension: float, + disc_diameter: float, + disc_thickness: float, + motor_screw_count: int, + motor_screw_start_angle: float, + motor_screw_depth: float, + center_hole_diameter: float, +) -> cq.Workplane: + """Create a compact motor-mount socket and disc. + + Angles are accepted for API compatibility; this helper keeps geometry + axis-aligned for robust export and simple smoke testing. + """ + del motor_tilt, motor_azimuth, motor_screw_count, motor_screw_start_angle, motor_screw_depth + + outer_radius = max(1.0, cylinder_inner_radius + pocket_thickness) + body_height = max(1.0, sphere_offset + cylinder_extension) + + body = ( + cq.Workplane("XY") + .circle(outer_radius) + .extrude(body_height) + ) + body = body.faces(">Z").workplane().circle(max(0.1, cylinder_inner_radius)).cutBlind(-body_height) + + disc = ( + cq.Workplane("XY") + .workplane(offset=body_height) + .circle(max(1.0, disc_diameter / 2.0)) + .extrude(max(0.5, disc_thickness)) + ) + mount = body.union(disc) + + if center_hole_diameter > 0: + mount = mount.faces(">Z").workplane().hole(center_hole_diameter) + + return mount diff --git a/src/ariel/ec/drone/genome_handlers/__init__.py b/src/ariel/ec/drone/genome_handlers/__init__.py index f05a51ff1..617bb52fc 100644 --- a/src/ariel/ec/drone/genome_handlers/__init__.py +++ b/src/ariel/ec/drone/genome_handlers/__init__.py @@ -1,26 +1,48 @@ -# Genome handlers for different coordinate representations +"""Genome handlers for different coordinate representations. + +This package intentionally avoids eager imports of every handler module. +Some handlers pull in optional heavy dependencies (for example collision +libraries), and importing them unconditionally breaks light-weight use +cases that only need helper modules under this package. +""" + +from __future__ import annotations + +from typing import TYPE_CHECKING, Any from .base import GenomeHandler -from .cartesian_euler_genome_handler import CartesianEulerDroneGenomeHandler -from .spherical_angular_genome_handler import SphericalAngularDroneGenomeHandler -from .cppn_neat_genome_handler import CPPNNeatDroneGenomeHandler -from .hybrid_cppn_genome_handler import HybridCPPNDroneGenomeHandler -# Optional MLP handler (requires PyTorch) -try: +if TYPE_CHECKING: + from .cartesian_euler_genome_handler import CartesianEulerDroneGenomeHandler + from .cppn_neat_genome_handler import CPPNNeatDroneGenomeHandler + from .hybrid_cppn_genome_handler import HybridCPPNDroneGenomeHandler from .mlp_genome_handler import MLPDroneGenomeHandler - MLP_AVAILABLE = True -except ImportError: - MLP_AVAILABLE = False - MLPDroneGenomeHandler = None + from .spherical_angular_genome_handler import SphericalAngularDroneGenomeHandler __all__ = [ - 'GenomeHandler', - 'CartesianEulerDroneGenomeHandler', - 'SphericalAngularDroneGenomeHandler', - 'CPPNNeatDroneGenomeHandler', - 'HybridCPPNDroneGenomeHandler', + "GenomeHandler", + "CartesianEulerDroneGenomeHandler", + "SphericalAngularDroneGenomeHandler", + "CPPNNeatDroneGenomeHandler", + "HybridCPPNDroneGenomeHandler", + "MLPDroneGenomeHandler", ] -if MLP_AVAILABLE: - __all__.append('MLPDroneGenomeHandler') \ No newline at end of file + +def __getattr__(name: str) -> Any: + if name == "CartesianEulerDroneGenomeHandler": + from .cartesian_euler_genome_handler import CartesianEulerDroneGenomeHandler + return CartesianEulerDroneGenomeHandler + if name == "SphericalAngularDroneGenomeHandler": + from .spherical_angular_genome_handler import SphericalAngularDroneGenomeHandler + return SphericalAngularDroneGenomeHandler + if name == "CPPNNeatDroneGenomeHandler": + from .cppn_neat_genome_handler import CPPNNeatDroneGenomeHandler + return CPPNNeatDroneGenomeHandler + if name == "HybridCPPNDroneGenomeHandler": + from .hybrid_cppn_genome_handler import HybridCPPNDroneGenomeHandler + return HybridCPPNDroneGenomeHandler + if name == "MLPDroneGenomeHandler": + from .mlp_genome_handler import MLPDroneGenomeHandler + return MLPDroneGenomeHandler + raise AttributeError(f"module {__name__!r} has no attribute {name!r}") \ No newline at end of file diff --git a/uv.lock b/uv.lock index a7d8dcf7a..b7a090d88 100644 --- a/uv.lock +++ b/uv.lock @@ -1,16 +1,19 @@ version = 1 revision = 3 -requires-python = ">=3.12" +requires-python = ">=3.11" resolution-markers = [ "python_full_version >= '3.14' and sys_platform == 'darwin'", "python_full_version == '3.13.*' and sys_platform == 'darwin'", - "python_full_version < '3.13' and sys_platform == 'darwin'", + "python_full_version == '3.12.*' and sys_platform == 'darwin'", "python_full_version >= '3.14' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.13.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", - "python_full_version < '3.13' and platform_machine == 'aarch64' and sys_platform == 'linux'", + "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux')", "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux')", - "(python_full_version < '3.13' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.13' and sys_platform != 'darwin' and sys_platform != 'linux')", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux')", + "python_full_version < '3.12' and sys_platform == 'darwin'", + "python_full_version < '3.12' and platform_machine == 'aarch64' and sys_platform == 'linux'", + "(python_full_version < '3.12' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.12' and sys_platform != 'darwin' and sys_platform != 'linux')", ] [[package]] @@ -67,6 +70,23 @@ dependencies = [ ] sdist = { url = "https://files.pythonhosted.org/packages/62/f1/8515650ac3121a9e55c7b217c60e7fae3e0134b5acfe65691781b5356929/aiohttp-3.13.0.tar.gz", hash = "sha256:378dbc57dd8cf341ce243f13fa1fa5394d68e2e02c15cd5f28eae35a70ec7f67", size = 7832348, upload-time = "2025-10-06T19:58:48.089Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/b1/db/df80cacac46cd548a736c5535b13cc18925cf6f9f83cd128cf3839842219/aiohttp-3.13.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:99eb94e97a42367fef5fc11e28cb2362809d3e70837f6e60557816c7106e2e20", size = 741374, upload-time = "2025-10-06T19:55:13.095Z" }, + { url = "https://files.pythonhosted.org/packages/ae/f9/2d6d93fd57ab4726e18a7cdab083772eda8302d682620fbf2aef48322351/aiohttp-3.13.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:4696665b2713021c6eba3e2b882a86013763b442577fe5d2056a42111e732eca", size = 494956, upload-time = "2025-10-06T19:55:14.687Z" }, + { url = "https://files.pythonhosted.org/packages/89/a6/e1c061b079fed04ffd6777950c82f2e8246fd08b7b3c4f56fdd47f697e5a/aiohttp-3.13.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:3e6a38366f7f0d0f6ed7a1198055150c52fda552b107dad4785c0852ad7685d1", size = 491154, upload-time = "2025-10-06T19:55:16.661Z" }, + { url = "https://files.pythonhosted.org/packages/fe/4d/ee8913c0d2c7da37fdc98673a342b51611eaa0871682b37b8430084e35b5/aiohttp-3.13.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:aab715b1a0c37f7f11f9f1f579c6fbaa51ef569e47e3c0a4644fba46077a9409", size = 1745707, upload-time = "2025-10-06T19:55:18.376Z" }, + { url = "https://files.pythonhosted.org/packages/f9/70/26b2c97e8fa68644aec43d788940984c5f3b53a8d1468d5baaa328f809c9/aiohttp-3.13.0-cp311-cp311-manylinux2014_armv7l.manylinux_2_17_armv7l.manylinux_2_31_armv7l.whl", hash = "sha256:7972c82bed87d7bd8e374b60a6b6e816d75ba4f7c2627c2d14eed216e62738e1", size = 1702404, upload-time = "2025-10-06T19:55:20.098Z" }, + { url = "https://files.pythonhosted.org/packages/65/1e/c8aa3c293a0e8b18968b1b88e9bd8fb269eb67eb7449f504a4c3e175b159/aiohttp-3.13.0-cp311-cp311-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:ca8313cb852af788c78d5afdea24c40172cbfff8b35e58b407467732fde20390", size = 1805519, upload-time = "2025-10-06T19:55:21.811Z" }, + { url = "https://files.pythonhosted.org/packages/51/b6/a3753fe86249eb441768658cfc00f8c4e0913b255c13be00ddb8192775e1/aiohttp-3.13.0-cp311-cp311-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:6c333a2385d2a6298265f4b3e960590f787311b87f6b5e6e21bb8375914ef504", size = 1893904, upload-time = "2025-10-06T19:55:23.462Z" }, + { url = "https://files.pythonhosted.org/packages/51/6d/7b1e020fe1d2a2be7cf0ce5e35922f345e3507cf337faa1a6563c42065c1/aiohttp-3.13.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:cc6d5fc5edbfb8041d9607f6a417997fa4d02de78284d386bea7ab767b5ea4f3", size = 1745043, upload-time = "2025-10-06T19:55:25.208Z" }, + { url = "https://files.pythonhosted.org/packages/e6/df/aad5dce268f9d4f29759c3eeb5fb5995c569d76abb267468dc1075218d5b/aiohttp-3.13.0-cp311-cp311-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:7ddedba3d0043349edc79df3dc2da49c72b06d59a45a42c1c8d987e6b8d175b8", size = 1604765, upload-time = "2025-10-06T19:55:27.157Z" }, + { url = "https://files.pythonhosted.org/packages/1c/19/a84a0e97b2da2224c8b85e1aef5cac834d07b2903c17bff1a6bdbc7041d2/aiohttp-3.13.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:23ca762140159417a6bbc959ca1927f6949711851e56f2181ddfe8d63512b5ad", size = 1721737, upload-time = "2025-10-06T19:55:28.854Z" }, + { url = "https://files.pythonhosted.org/packages/6c/61/ca6ad390128d964a08554fd63d6df5810fb5fbc7e599cb9e617f1729ae19/aiohttp-3.13.0-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:bfe824d6707a5dc3c5676685f624bc0c63c40d79dc0239a7fd6c034b98c25ebe", size = 1716052, upload-time = "2025-10-06T19:55:30.563Z" }, + { url = "https://files.pythonhosted.org/packages/2a/71/769e249e6625372c7d14be79b8b8c3b0592963a09793fb3d36758e60952c/aiohttp-3.13.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:3c11fa5dd2ef773a8a5a6daa40243d83b450915992eab021789498dc87acc114", size = 1783532, upload-time = "2025-10-06T19:55:32.798Z" }, + { url = "https://files.pythonhosted.org/packages/66/64/b9cd03cdbb629bc492e4a744fbe96550a8340b0cd7a0cc4a9c90cfecd8d3/aiohttp-3.13.0-cp311-cp311-musllinux_1_2_riscv64.whl", hash = "sha256:00fdfe370cffede3163ba9d3f190b32c0cfc8c774f6f67395683d7b0e48cdb8a", size = 1593072, upload-time = "2025-10-06T19:55:34.686Z" }, + { url = "https://files.pythonhosted.org/packages/24/0e/87922c8cfdbd09f5e2197e9d87714a98c99c423560d44739e3af55400fe3/aiohttp-3.13.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:6475e42ef92717a678bfbf50885a682bb360a6f9c8819fb1a388d98198fdcb80", size = 1798613, upload-time = "2025-10-06T19:55:36.393Z" }, + { url = "https://files.pythonhosted.org/packages/c5/bb/a3adfe2af76e1ee9e3b5464522004b148b266bc99d7ec424ca7843d64a3c/aiohttp-3.13.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:77da5305a410910218b99f2a963092f4277d8a9c1f429c1ff1b026d1826bd0b6", size = 1737480, upload-time = "2025-10-06T19:55:38.043Z" }, + { url = "https://files.pythonhosted.org/packages/ad/53/e124dcbd64e6365602f3493fe37a11ca5b7ac0a40822a6e2bc8260cd08e0/aiohttp-3.13.0-cp311-cp311-win32.whl", hash = "sha256:2f9d9ea547618d907f2ee6670c9a951f059c5994e4b6de8dcf7d9747b420c820", size = 429824, upload-time = "2025-10-06T19:55:39.595Z" }, + { url = "https://files.pythonhosted.org/packages/3e/bd/485d98b372a2cd6998484a93ddd401ec6b6031657661c36846a10e2a1f6e/aiohttp-3.13.0-cp311-cp311-win_amd64.whl", hash = "sha256:0f19f7798996d4458c669bd770504f710014926e9970f4729cf55853ae200469", size = 454137, upload-time = "2025-10-06T19:55:41.617Z" }, { url = "https://files.pythonhosted.org/packages/3a/95/7e8bdfa6e79099a086d59d42589492f1fe9d29aae3cefb58b676015ce278/aiohttp-3.13.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:1c272a9a18a5ecc48a7101882230046b83023bb2a662050ecb9bfcb28d9ab53a", size = 735585, upload-time = "2025-10-06T19:55:43.401Z" }, { url = "https://files.pythonhosted.org/packages/9f/20/2f1d3ee06ee94eafe516810705219bff234d09f135d6951661661d5595ae/aiohttp-3.13.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:97891a23d7fd4e1afe9c2f4473e04595e4acb18e4733b910b6577b74e7e21985", size = 490613, upload-time = "2025-10-06T19:55:45.237Z" }, { url = "https://files.pythonhosted.org/packages/74/15/ab8600ef6dc1dcd599009a81acfed2ea407037e654d32e47e344e0b08c34/aiohttp-3.13.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:475bd56492ce5f4cffe32b5533c6533ee0c406d1d0e6924879f83adcf51da0ae", size = 489750, upload-time = "2025-10-06T19:55:46.937Z" }, @@ -254,45 +274,54 @@ name = "ariel" version = "0.0.0" source = { editable = "." } dependencies = [ - { name = "attrs" }, - { name = "deap" }, - { name = "dm-control" }, { name = "evotorch" }, - { name = "gymnasium" }, - { name = "ipykernel" }, - { name = "jupyter" }, - { name = "kaleido" }, - { name = "keyboard" }, - { name = "manifold3d" }, { name = "matplotlib" }, { name = "mujoco" }, { name = "mujoco-mjx", extra = ["warp"] }, { name = "networkx" }, - { name = "nevergrad" }, - { name = "nicegui" }, { name = "numpy" }, { name = "numpy-quaternion" }, - { name = "omegaconf" }, - { name = "opencv-python" }, - { name = "panel" }, - { name = "pillow" }, - { name = "plotly" }, - { name = "polars" }, { name = "pydantic" }, { name = "pydantic-settings" }, - { name = "pyserial" }, - { name = "pyvista" }, { name = "rich" }, { name = "sqlalchemy" }, { name = "sqlmodel" }, - { name = "torch" }, - { name = "torchvision" }, ] [package.optional-dependencies] +experimental = [ + { name = "attrs" }, + { name = "deap" }, + { name = "dm-control" }, + { name = "ipykernel" }, + { name = "jupyter" }, + { name = "keyboard" }, + { name = "manifold3d" }, + { name = "nevergrad" }, + { name = "nicegui" }, + { name = "omegaconf" }, + { name = "polars" }, + { name = "pyserial" }, + { name = "pyvista" }, +] fabrication = [ { name = "cadquery" }, ] +rl-sb3 = [ + { name = "gymnasium" }, + { name = "stable-baselines3" }, +] +torch = [ + { name = "torch" }, + { name = "torchvision" }, +] +viz = [ + { name = "kaleido" }, + { name = "opencv-python" }, + { name = "panel" }, + { name = "pillow" }, + { name = "plotly" }, +] [package.dev-dependencies] dev = [ @@ -348,42 +377,43 @@ stubs = [ [package.metadata] requires-dist = [ - { name = "attrs", specifier = ">=25.4.0" }, + { name = "attrs", marker = "extra == 'experimental'", specifier = ">=25.4.0" }, { name = "cadquery", marker = "extra == 'fabrication'", specifier = ">=2.4.0" }, - { name = "deap", specifier = ">=1.4.3" }, - { name = "dm-control", specifier = ">=1.0.38" }, + { name = "deap", marker = "extra == 'experimental'", specifier = ">=1.4.3" }, + { name = "dm-control", marker = "extra == 'experimental'", specifier = ">=1.0.38" }, { name = "evotorch", specifier = ">=0.6.1" }, - { name = "gymnasium", specifier = ">=1.2.3" }, - { name = "ipykernel", specifier = ">=6.30.1" }, - { name = "jupyter", specifier = ">=1.1.1" }, - { name = "kaleido", specifier = ">=1.2.0" }, - { name = "keyboard", specifier = ">=0.13.5" }, - { name = "manifold3d", specifier = ">=3.4.0" }, + { name = "gymnasium", marker = "extra == 'rl-sb3'", specifier = "==1.2.1" }, + { name = "ipykernel", marker = "extra == 'experimental'", specifier = ">=6.30.1" }, + { name = "jupyter", marker = "extra == 'experimental'", specifier = ">=1.1.1" }, + { name = "kaleido", marker = "extra == 'viz'", specifier = ">=1.2.0" }, + { name = "keyboard", marker = "extra == 'experimental'", specifier = ">=0.13.5" }, + { name = "manifold3d", marker = "extra == 'experimental'", specifier = ">=3.4.0" }, { name = "matplotlib", specifier = ">=3.9.4" }, { name = "mujoco", specifier = ">=3.3.6" }, { name = "mujoco-mjx", extras = ["warp"], specifier = ">=3.6.0" }, { name = "networkx", specifier = ">=3.2.1" }, - { name = "nevergrad", specifier = ">=1.0.12" }, - { name = "nicegui", specifier = ">=2.24.1" }, - { name = "numpy", specifier = ">=2.0.2" }, + { name = "nevergrad", marker = "extra == 'experimental'", specifier = ">=1.0.12" }, + { name = "nicegui", marker = "extra == 'experimental'", specifier = ">=2.24.1" }, + { name = "numpy", specifier = ">=1.26,<2" }, { name = "numpy-quaternion", specifier = ">=2023.0.3" }, - { name = "omegaconf", specifier = ">=2.3.0" }, - { name = "opencv-python", specifier = ">=4.11.0.86" }, - { name = "panel", specifier = ">=1.8.9" }, - { name = "pillow", specifier = ">=11.3.0" }, - { name = "plotly", specifier = ">=6.6.0" }, - { name = "polars", specifier = ">=1.35.2" }, + { name = "omegaconf", marker = "extra == 'experimental'", specifier = ">=2.3.0" }, + { name = "opencv-python", marker = "extra == 'viz'", specifier = ">=4.11.0.86" }, + { name = "panel", marker = "extra == 'viz'", specifier = ">=1.8.9" }, + { name = "pillow", marker = "extra == 'viz'", specifier = ">=11.3.0" }, + { name = "plotly", marker = "extra == 'viz'", specifier = ">=6.6.0" }, + { name = "polars", marker = "extra == 'experimental'", specifier = ">=1.35.2" }, { name = "pydantic", specifier = ">=2.11.9" }, { name = "pydantic-settings", specifier = ">=2.10.1" }, - { name = "pyserial", specifier = ">=3.5" }, - { name = "pyvista", specifier = ">=0.47.1" }, + { name = "pyserial", marker = "extra == 'experimental'", specifier = ">=3.5" }, + { name = "pyvista", marker = "extra == 'experimental'", specifier = ">=0.47.1" }, { name = "rich", specifier = ">=14.1.0" }, { name = "sqlalchemy", specifier = ">=2.0.43" }, { name = "sqlmodel", specifier = ">=0.0.25" }, - { name = "torch", specifier = ">=2.8.0" }, - { name = "torchvision", specifier = ">=0.23.0" }, + { name = "stable-baselines3", marker = "extra == 'rl-sb3'", specifier = ">=2.7.0" }, + { name = "torch", marker = "extra == 'torch'", specifier = ">=2.8.0" }, + { name = "torchvision", marker = "extra == 'torch'", specifier = ">=0.23.0" }, ] -provides-extras = ["fabrication"] +provides-extras = ["rl-sb3", "torch", "viz", "fabrication", "experimental"] [package.metadata.requires-dev] dev = [ @@ -571,7 +601,7 @@ wheels = [ [[package]] name = "cadquery" -version = "2.7.0" +version = "2.4.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "cadquery-ocp" }, @@ -579,35 +609,28 @@ dependencies = [ { name = "ezdxf" }, { name = "multimethod" }, { name = "nlopt" }, + { name = "nptyping" }, { name = "path" }, - { name = "pyparsing" }, - { name = "runtype" }, - { name = "trame" }, - { name = "trame-components" }, - { name = "trame-vtk" }, - { name = "trame-vuetify" }, + { name = "typish" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/03/c7/23e200821c307b7765661f19494edea93aa3ae9d28fee0db72ab20448855/cadquery-2.7.0.tar.gz", hash = "sha256:224e7d861c018bedd9e77b9727bc2a86b086f630596124d13ccc8a92b2151ee6", size = 270261, upload-time = "2026-02-13T16:50:47.701Z" } +sdist = { url = "https://files.pythonhosted.org/packages/e1/42/38e7e28bafc37206536a6bf119a87b0d325f10c710620004f71dc41a0dcd/cadquery-2.4.0.tar.gz", hash = "sha256:38e8e302060f2e50943ab0f8acab985c37a73009e972c7b02767c90bef7fb3e7", size = 218150, upload-time = "2024-01-15T14:03:13.91Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/85/46/2544f1d16a912770ecfed25602a273ab0ad4648838decf974781a8f83b78/cadquery-2.7.0-py3-none-any.whl", hash = "sha256:13bdffe3a1c9a7b29d86d43313021173b1620f45223929d2631cf8d4c5dbe2c0", size = 182553, upload-time = "2026-02-13T16:50:46.085Z" }, + { url = "https://files.pythonhosted.org/packages/af/19/3c2286e1bedc8ba2e9f916db1100e0275f2c202a279a6c7de8f11abe3156/cadquery-2.4.0-py3-none-any.whl", hash = "sha256:66c865b1e5db205b81a5ddc8533d4741577291292cf2dc80b104ae9e3085b195", size = 150995, upload-time = "2024-01-15T14:03:12.246Z" }, ] [[package]] name = "cadquery-ocp" -version = "7.8.1.1.post1" +version = "7.7.2" source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "vtk" }, -] wheels = [ - { url = "https://files.pythonhosted.org/packages/3a/98/7b81196dd990bfbbdeff7858db7d319dede6fef2fb6c153ede9eb409a9e9/cadquery_ocp-7.8.1.1.post1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:0022e854a3840efd5c7fc14fe933772613794777d5eb056a4754d44a86baf02a", size = 68590290, upload-time = "2025-01-29T14:34:16.804Z" }, - { url = "https://files.pythonhosted.org/packages/b4/b3/aea4e4d84916b6a26bc3635a0aeaa3737b24671ac90c117e5779554eebbb/cadquery_ocp-7.8.1.1.post1-cp312-cp312-macosx_11_0_x86_64.whl", hash = "sha256:53dc24aed402b2ae52634a29b3b17e9c01e857b8ac34bb101d4e8fa76d3cd7f7", size = 69523485, upload-time = "2025-01-29T14:34:27.338Z" }, - { url = "https://files.pythonhosted.org/packages/fa/3f/4b28aedbbb7c6cd5f1aa4e1d6e9a0f88d138941096a3d70f1878a406075f/cadquery_ocp-7.8.1.1.post1-cp312-cp312-manylinux_2_31_x86_64.whl", hash = "sha256:4882074e86722208153579baaee246be4fb10bda22dc20d101c4151f364207b9", size = 70313551, upload-time = "2025-01-29T14:34:36.484Z" }, - { url = "https://files.pythonhosted.org/packages/b9/2f/d8473c8db5f0820449819bf5ce606292ead9e2072712cbdcc5657995f6cb/cadquery_ocp-7.8.1.1.post1-cp312-cp312-win_amd64.whl", hash = "sha256:06982855db94fa0056b922276f0ca94154e5d1eb16f6cba854d704885844924a", size = 51755169, upload-time = "2025-01-29T14:34:45.096Z" }, - { url = "https://files.pythonhosted.org/packages/23/1d/f2ef5da38774f3f1d2a55f01567e81190b15f765bbfc8e97d3bfbeff3fd9/cadquery_ocp-7.8.1.1.post1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:08fdc32b79e6f974cf692584be865985161e4fd8cbf854ed64c8c1530458fce3", size = 68589505, upload-time = "2025-01-29T14:34:53.501Z" }, - { url = "https://files.pythonhosted.org/packages/54/e0/d2b4a5499af452400a49c85d98e83789acdb2b64826a95b634e9069feff6/cadquery_ocp-7.8.1.1.post1-cp313-cp313-macosx_11_0_x86_64.whl", hash = "sha256:fd5ffec5e27846fe4796db9cdc0748324e4d7c59da7c6c7d86a6eb38e823b3f5", size = 69525070, upload-time = "2025-01-29T14:35:02.585Z" }, - { url = "https://files.pythonhosted.org/packages/65/7d/873c560967fc79e4c7c850bdca6418801610acd7f7041a40b71812827588/cadquery_ocp-7.8.1.1.post1-cp313-cp313-manylinux_2_31_x86_64.whl", hash = "sha256:081017e5387debe4bf31a9dc222c2513e26d1860ca990119bfe90a6970a77104", size = 70305329, upload-time = "2025-01-29T14:35:11.799Z" }, - { url = "https://files.pythonhosted.org/packages/fe/08/edb59c820f339f7fb35b20a4580839ed91488bffcd3c7ba341f8b971d91c/cadquery_ocp-7.8.1.1.post1-cp313-cp313-win_amd64.whl", hash = "sha256:22877143d06cb52bd7d48a591510f8e72c2fc5768bafebb99e5cf077798ee939", size = 51752390, upload-time = "2025-01-29T14:35:42.303Z" }, + { url = "https://files.pythonhosted.org/packages/36/c2/8ba0015b2e34f206f28a62f9d53658a7ae4ab74e1005b88b6606192b9313/cadquery_ocp-7.7.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:488401fa4d070e3eb17729fb8b6494bd3577f0913c4e901e674c4d8fcd9ac1fe", size = 185073573, upload-time = "2024-01-02T13:45:36.659Z" }, + { url = "https://files.pythonhosted.org/packages/7a/01/fbb595b765e3a5da35e0b50ccb5a99b1bbfb40d2cdbdf3d819898cfcf72e/cadquery_ocp-7.7.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:6a4d2bd759cc2800ac91664357e55aba889c996c7492bd595ed63b0c517869d3", size = 165369427, upload-time = "2024-11-22T21:00:39.38Z" }, + { url = "https://files.pythonhosted.org/packages/ee/ce/e38d7fb8ee5f3d5c57b2fe8914bea8e8307b693bb07b8c8d87786824d54e/cadquery_ocp-7.7.2-cp311-cp311-manylinux_2_35_x86_64.whl", hash = "sha256:2be9408551c03e1c715e3b158b41ce458178ecf530ba644e3e884a5989feb611", size = 142960738, upload-time = "2024-01-02T13:45:45.325Z" }, + { url = "https://files.pythonhosted.org/packages/fc/50/b28f6b56479c8bd72cfdc0706ce2cef8645a36a47ea0ee1f53552a17ab08/cadquery_ocp-7.7.2-cp311-cp311-win_amd64.whl", hash = "sha256:8e1f90250924ac50344bf0867e3d9a927f077583351b270b4e0e171033dd2046", size = 90967269, upload-time = "2024-01-02T13:45:52.315Z" }, + { url = "https://files.pythonhosted.org/packages/4d/da/52d0d0b148a015ded47b4f51cd0d5dba43f71bdc94f2050e9b8209d30786/cadquery_ocp-7.7.2-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:78a7903267cd9986181b634a315ca66fac1bb9e6dbfaf60724d812b3a2cc77bf", size = 186017529, upload-time = "2024-01-02T13:46:01.745Z" }, + { url = "https://files.pythonhosted.org/packages/9b/15/f738b679609071932395138925eb97358c36eebf6433ac2596e9b7f7a2cf/cadquery_ocp-7.7.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:51ffbcd6d356d4f0c2e5f9e1581226121cd730fe4521eabac05e9d71e6a43f6f", size = 166437260, upload-time = "2024-11-22T21:00:59.664Z" }, + { url = "https://files.pythonhosted.org/packages/c7/78/f81639f0cd4e899ed2cee705a255ef1abe8d97b06f6f3f4b6aaf8d4b2a5d/cadquery_ocp-7.7.2-cp312-cp312-manylinux_2_35_x86_64.whl", hash = "sha256:7ac2d83b4f4b3d7c35421a1d9f8fec2adc73b6ed6cac50c1ffcede5552e38e9b", size = 143036527, upload-time = "2024-01-02T13:46:10.993Z" }, + { url = "https://files.pythonhosted.org/packages/5f/20/0525739dbeb8bac7738efcff2a700ac55256b52bc331fb2cd8d9f1201635/cadquery_ocp-7.7.2-cp312-cp312-win_amd64.whl", hash = "sha256:d9e5c8ef5aeb1d3fb8f0b207ed1a2b781d22dc3e9b9c0551f52342f5a6ee7fc5", size = 91287161, upload-time = "2024-01-02T13:46:17.408Z" }, ] [[package]] @@ -619,6 +642,12 @@ dependencies = [ ] sdist = { url = "https://files.pythonhosted.org/packages/92/62/1e98662024915ecb09c6894c26a3f497f4afa66570af3f53db4651fc45f1/casadi-3.7.2.tar.gz", hash = "sha256:b4d7bd8acdc4180306903ae1c9eddaf41be2a3ae2fa7154c57174ae64acdc60d", size = 6053600, upload-time = "2025-09-10T10:05:49.521Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/29/01/d5e3058775ec8e24a01eb74d36099493b872536ef9e39f1e49624b977778/casadi-3.7.2-cp311-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:f43b0562d05a5e6e81f1885fc4ae426c382e36eebfd8d27f1baff6052178a9b0", size = 47115880, upload-time = "2025-09-10T07:52:24.399Z" }, + { url = "https://files.pythonhosted.org/packages/0e/cf/4af27e010d599a5419129d34fdde41637029a1cca2a40bef0965d6d52228/casadi-3.7.2-cp311-none-macosx_11_0_arm64.whl", hash = "sha256:70add3334b437b60a9bc0f864d094350f1a4fcbf9e8bafec870b61aed64674df", size = 42293337, upload-time = "2025-09-10T08:03:32.556Z" }, + { url = "https://files.pythonhosted.org/packages/ac/4c/d1a50cc840103e00effcbaf8e911b6b3fb6ba2c8f4025466f524854968ed/casadi-3.7.2-cp311-none-manylinux2014_aarch64.whl", hash = "sha256:392d3367a4b33cf223013dad8122a0e549da40b1702a5375f82f85b563e5c0cf", size = 47277175, upload-time = "2025-09-10T08:04:08.811Z" }, + { url = "https://files.pythonhosted.org/packages/be/29/6e5714d124e6ddafbccc3ed774ca603081caa1175c7f0e1c52484184dfb3/casadi-3.7.2-cp311-none-manylinux2014_i686.whl", hash = "sha256:2ce09e0ced6df33048dccd582b5cfa2c9ff5193b12858b2584078afc17761905", size = 72438460, upload-time = "2025-09-10T08:05:02.769Z" }, + { url = "https://files.pythonhosted.org/packages/23/32/ac1f3999273aa4aae48516f6f4b7b267e0cc70d8527866989798cb81312f/casadi-3.7.2-cp311-none-manylinux2014_x86_64.whl", hash = "sha256:5086799a46d10ba884b72fd02c21be09dae52cbc189272354a5d424791b55f37", size = 75574474, upload-time = "2025-09-10T08:06:00.709Z" }, + { url = "https://files.pythonhosted.org/packages/68/78/7fd10709504c1757f70db3893870a891fcb9f1ec9f05e8ef2e3f3b9d7e2f/casadi-3.7.2-cp311-none-win_amd64.whl", hash = "sha256:72aa5727417d781ed216f16b5e93c6ddca5db27d83b0015a729e8ad570cdc465", size = 50994144, upload-time = "2025-09-10T08:06:42.384Z" }, { url = "https://files.pythonhosted.org/packages/65/c8/689d085447b1966f42bdb8aa4fbebef49a09697dbee32ab02a865c17ac1b/casadi-3.7.2-cp312-none-macosx_10_13_x86_64.macosx_10_13_intel.whl", hash = "sha256:309ea41a69c9230390d349b0dd899c6a19504d1904c0756bef463e47fb5c8f9a", size = 47116756, upload-time = "2025-09-10T07:53:00.931Z" }, { url = "https://files.pythonhosted.org/packages/1e/c0/3c4704394a6fd4dfb2123a4fd71ba64a001f340670a3eba45be7a19ac736/casadi-3.7.2-cp312-none-macosx_11_0_arm64.whl", hash = "sha256:6033381234db810b2247d16c6352e679a009ec4365d04008fc768866e011ed58", size = 42293718, upload-time = "2025-09-10T08:07:16.415Z" }, { url = "https://files.pythonhosted.org/packages/f3/24/4cf05469ddf8544da5e92f359f96d716a97e7482999f085a632bc4ef344a/casadi-3.7.2-cp312-none-manylinux2014_aarch64.whl", hash = "sha256:732f2804d0766454bb75596339e4f2da6662ffb669621da0f630ed4af9e83d6a", size = 47276175, upload-time = "2025-09-10T08:08:09.29Z" }, @@ -656,6 +685,19 @@ dependencies = [ ] sdist = { url = "https://files.pythonhosted.org/packages/eb/56/b1ba7935a17738ae8453301356628e8147c79dbb825bcbc73dc7401f9846/cffi-2.0.0.tar.gz", hash = "sha256:44d1b5909021139fe36001ae048dbdde8214afa20200eda0f64c068cac5d5529", size = 523588, upload-time = "2025-09-08T23:24:04.541Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/12/4a/3dfd5f7850cbf0d06dc84ba9aa00db766b52ca38d8b86e3a38314d52498c/cffi-2.0.0-cp311-cp311-macosx_10_13_x86_64.whl", hash = "sha256:b4c854ef3adc177950a8dfc81a86f5115d2abd545751a304c5bcf2c2c7283cfe", size = 184344, upload-time = "2025-09-08T23:22:26.456Z" }, + { url = "https://files.pythonhosted.org/packages/4f/8b/f0e4c441227ba756aafbe78f117485b25bb26b1c059d01f137fa6d14896b/cffi-2.0.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:2de9a304e27f7596cd03d16f1b7c72219bd944e99cc52b84d0145aefb07cbd3c", size = 180560, upload-time = "2025-09-08T23:22:28.197Z" }, + { url = "https://files.pythonhosted.org/packages/b1/b7/1200d354378ef52ec227395d95c2576330fd22a869f7a70e88e1447eb234/cffi-2.0.0-cp311-cp311-manylinux1_i686.manylinux2014_i686.manylinux_2_17_i686.manylinux_2_5_i686.whl", hash = "sha256:baf5215e0ab74c16e2dd324e8ec067ef59e41125d3eade2b863d294fd5035c92", size = 209613, upload-time = "2025-09-08T23:22:29.475Z" }, + { url = "https://files.pythonhosted.org/packages/b8/56/6033f5e86e8cc9bb629f0077ba71679508bdf54a9a5e112a3c0b91870332/cffi-2.0.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:730cacb21e1bdff3ce90babf007d0a0917cc3e6492f336c2f0134101e0944f93", size = 216476, upload-time = "2025-09-08T23:22:31.063Z" }, + { url = "https://files.pythonhosted.org/packages/dc/7f/55fecd70f7ece178db2f26128ec41430d8720f2d12ca97bf8f0a628207d5/cffi-2.0.0-cp311-cp311-manylinux2014_ppc64le.manylinux_2_17_ppc64le.whl", hash = "sha256:6824f87845e3396029f3820c206e459ccc91760e8fa24422f8b0c3d1731cbec5", size = 203374, upload-time = "2025-09-08T23:22:32.507Z" }, + { url = "https://files.pythonhosted.org/packages/84/ef/a7b77c8bdc0f77adc3b46888f1ad54be8f3b7821697a7b89126e829e676a/cffi-2.0.0-cp311-cp311-manylinux2014_s390x.manylinux_2_17_s390x.whl", hash = "sha256:9de40a7b0323d889cf8d23d1ef214f565ab154443c42737dfe52ff82cf857664", size = 202597, upload-time = "2025-09-08T23:22:34.132Z" }, + { url = "https://files.pythonhosted.org/packages/d7/91/500d892b2bf36529a75b77958edfcd5ad8e2ce4064ce2ecfeab2125d72d1/cffi-2.0.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:8941aaadaf67246224cee8c3803777eed332a19d909b47e29c9842ef1e79ac26", size = 215574, upload-time = "2025-09-08T23:22:35.443Z" }, + { url = "https://files.pythonhosted.org/packages/44/64/58f6255b62b101093d5df22dcb752596066c7e89dd725e0afaed242a61be/cffi-2.0.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:a05d0c237b3349096d3981b727493e22147f934b20f6f125a3eba8f994bec4a9", size = 218971, upload-time = "2025-09-08T23:22:36.805Z" }, + { url = "https://files.pythonhosted.org/packages/ab/49/fa72cebe2fd8a55fbe14956f9970fe8eb1ac59e5df042f603ef7c8ba0adc/cffi-2.0.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:94698a9c5f91f9d138526b48fe26a199609544591f859c870d477351dc7b2414", size = 211972, upload-time = "2025-09-08T23:22:38.436Z" }, + { url = "https://files.pythonhosted.org/packages/0b/28/dd0967a76aab36731b6ebfe64dec4e981aff7e0608f60c2d46b46982607d/cffi-2.0.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:5fed36fccc0612a53f1d4d9a816b50a36702c28a2aa880cb8a122b3466638743", size = 217078, upload-time = "2025-09-08T23:22:39.776Z" }, + { url = "https://files.pythonhosted.org/packages/2b/c0/015b25184413d7ab0a410775fdb4a50fca20f5589b5dab1dbbfa3baad8ce/cffi-2.0.0-cp311-cp311-win32.whl", hash = "sha256:c649e3a33450ec82378822b3dad03cc228b8f5963c0c12fc3b1e0ab940f768a5", size = 172076, upload-time = "2025-09-08T23:22:40.95Z" }, + { url = "https://files.pythonhosted.org/packages/ae/8f/dc5531155e7070361eb1b7e4c1a9d896d0cb21c49f807a6c03fd63fc877e/cffi-2.0.0-cp311-cp311-win_amd64.whl", hash = "sha256:66f011380d0e49ed280c789fbd08ff0d40968ee7b665575489afa95c98196ab5", size = 182820, upload-time = "2025-09-08T23:22:42.463Z" }, + { url = "https://files.pythonhosted.org/packages/95/5c/1b493356429f9aecfd56bc171285a4c4ac8697f76e9bbbbb105e537853a1/cffi-2.0.0-cp311-cp311-win_arm64.whl", hash = "sha256:c6638687455baf640e37344fe26d37c404db8b80d037c3d29f58fe8d1c3b194d", size = 177635, upload-time = "2025-09-08T23:22:43.623Z" }, { url = "https://files.pythonhosted.org/packages/ea/47/4f61023ea636104d4f16ab488e268b93008c3d0bb76893b1b31db1f96802/cffi-2.0.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:6d02d6655b0e54f54c4ef0b94eb6be0607b70853c45ce98bd278dc7de718be5d", size = 185271, upload-time = "2025-09-08T23:22:44.795Z" }, { url = "https://files.pythonhosted.org/packages/df/a2/781b623f57358e360d62cdd7a8c681f074a71d445418a776eef0aadb4ab4/cffi-2.0.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:8eca2a813c1cb7ad4fb74d368c2ffbbb4789d377ee5bb8df98373c2cc0dee76c", size = 181048, upload-time = "2025-09-08T23:22:45.938Z" }, { url = "https://files.pythonhosted.org/packages/ff/df/a4f0fbd47331ceeba3d37c2e51e9dfc9722498becbeec2bd8bc856c9538a/cffi-2.0.0-cp312-cp312-manylinux1_i686.manylinux2014_i686.manylinux_2_17_i686.manylinux_2_5_i686.whl", hash = "sha256:21d1152871b019407d8ac3985f6775c079416c282e431a4da6afe7aefd2bccbe", size = 212529, upload-time = "2025-09-08T23:22:47.349Z" }, @@ -710,6 +752,17 @@ version = "3.4.3" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/83/2d/5fd176ceb9b2fc619e63405525573493ca23441330fcdaee6bef9460e924/charset_normalizer-3.4.3.tar.gz", hash = "sha256:6fce4b8500244f6fcb71465d4a4930d132ba9ab8e71a7859e6a5d59851068d14", size = 122371, upload-time = "2025-08-09T07:57:28.46Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/7f/b5/991245018615474a60965a7c9cd2b4efbaabd16d582a5547c47ee1c7730b/charset_normalizer-3.4.3-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:b256ee2e749283ef3ddcff51a675ff43798d92d746d1a6e4631bf8c707d22d0b", size = 204483, upload-time = "2025-08-09T07:55:53.12Z" }, + { url = "https://files.pythonhosted.org/packages/c7/2a/ae245c41c06299ec18262825c1569c5d3298fc920e4ddf56ab011b417efd/charset_normalizer-3.4.3-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:13faeacfe61784e2559e690fc53fa4c5ae97c6fcedb8eb6fb8d0a15b475d2c64", size = 145520, upload-time = "2025-08-09T07:55:54.712Z" }, + { url = "https://files.pythonhosted.org/packages/3a/a4/b3b6c76e7a635748c4421d2b92c7b8f90a432f98bda5082049af37ffc8e3/charset_normalizer-3.4.3-cp311-cp311-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:00237675befef519d9af72169d8604a067d92755e84fe76492fef5441db05b91", size = 158876, upload-time = "2025-08-09T07:55:56.024Z" }, + { url = "https://files.pythonhosted.org/packages/e2/e6/63bb0e10f90a8243c5def74b5b105b3bbbfb3e7bb753915fe333fb0c11ea/charset_normalizer-3.4.3-cp311-cp311-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:585f3b2a80fbd26b048a0be90c5aae8f06605d3c92615911c3a2b03a8a3b796f", size = 156083, upload-time = "2025-08-09T07:55:57.582Z" }, + { url = "https://files.pythonhosted.org/packages/87/df/b7737ff046c974b183ea9aa111b74185ac8c3a326c6262d413bd5a1b8c69/charset_normalizer-3.4.3-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:0e78314bdc32fa80696f72fa16dc61168fda4d6a0c014e0380f9d02f0e5d8a07", size = 150295, upload-time = "2025-08-09T07:55:59.147Z" }, + { url = "https://files.pythonhosted.org/packages/61/f1/190d9977e0084d3f1dc169acd060d479bbbc71b90bf3e7bf7b9927dec3eb/charset_normalizer-3.4.3-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:96b2b3d1a83ad55310de8c7b4a2d04d9277d5591f40761274856635acc5fcb30", size = 148379, upload-time = "2025-08-09T07:56:00.364Z" }, + { url = "https://files.pythonhosted.org/packages/4c/92/27dbe365d34c68cfe0ca76f1edd70e8705d82b378cb54ebbaeabc2e3029d/charset_normalizer-3.4.3-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:939578d9d8fd4299220161fdd76e86c6a251987476f5243e8864a7844476ba14", size = 160018, upload-time = "2025-08-09T07:56:01.678Z" }, + { url = "https://files.pythonhosted.org/packages/99/04/baae2a1ea1893a01635d475b9261c889a18fd48393634b6270827869fa34/charset_normalizer-3.4.3-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:fd10de089bcdcd1be95a2f73dbe6254798ec1bda9f450d5828c96f93e2536b9c", size = 157430, upload-time = "2025-08-09T07:56:02.87Z" }, + { url = "https://files.pythonhosted.org/packages/2f/36/77da9c6a328c54d17b960c89eccacfab8271fdaaa228305330915b88afa9/charset_normalizer-3.4.3-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:1e8ac75d72fa3775e0b7cb7e4629cec13b7514d928d15ef8ea06bca03ef01cae", size = 151600, upload-time = "2025-08-09T07:56:04.089Z" }, + { url = "https://files.pythonhosted.org/packages/64/d4/9eb4ff2c167edbbf08cdd28e19078bf195762e9bd63371689cab5ecd3d0d/charset_normalizer-3.4.3-cp311-cp311-win32.whl", hash = "sha256:6cf8fd4c04756b6b60146d98cd8a77d0cdae0e1ca20329da2ac85eed779b6849", size = 99616, upload-time = "2025-08-09T07:56:05.658Z" }, + { url = "https://files.pythonhosted.org/packages/f4/9c/996a4a028222e7761a96634d1820de8a744ff4327a00ada9c8942033089b/charset_normalizer-3.4.3-cp311-cp311-win_amd64.whl", hash = "sha256:31a9a6f775f9bcd865d88ee350f0ffb0e25936a7f930ca98995c05abf1faf21c", size = 107108, upload-time = "2025-08-09T07:56:07.176Z" }, { url = "https://files.pythonhosted.org/packages/e9/5e/14c94999e418d9b87682734589404a25854d5f5d0408df68bc15b6ff54bb/charset_normalizer-3.4.3-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:e28e334d3ff134e88989d90ba04b47d84382a828c061d0d1027b1b12a62b39b1", size = 205655, upload-time = "2025-08-09T07:56:08.475Z" }, { url = "https://files.pythonhosted.org/packages/7d/a8/c6ec5d389672521f644505a257f50544c074cf5fc292d5390331cd6fc9c3/charset_normalizer-3.4.3-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:0cacf8f7297b0c4fcb74227692ca46b4a5852f8f4f24b3c766dd94a1075c4884", size = 146223, upload-time = "2025-08-09T07:56:09.708Z" }, { url = "https://files.pythonhosted.org/packages/fc/eb/a2ffb08547f4e1e5415fb69eb7db25932c52a52bed371429648db4d84fb1/charset_normalizer-3.4.3-cp312-cp312-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:c6fd51128a41297f5409deab284fecbe5305ebd7e5a1f959bee1c054622b7018", size = 159366, upload-time = "2025-08-09T07:56:11.326Z" }, @@ -831,6 +884,17 @@ dependencies = [ ] sdist = { url = "https://files.pythonhosted.org/packages/58/01/1253e6698a07380cd31a736d248a3f2a50a7c88779a1813da27503cadc2a/contourpy-1.3.3.tar.gz", hash = "sha256:083e12155b210502d0bca491432bb04d56dc3432f95a979b429f2848c3dbe880", size = 13466174, upload-time = "2025-07-26T12:03:12.549Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/91/2e/c4390a31919d8a78b90e8ecf87cd4b4c4f05a5b48d05ec17db8e5404c6f4/contourpy-1.3.3-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:709a48ef9a690e1343202916450bc48b9e51c049b089c7f79a267b46cffcdaa1", size = 288773, upload-time = "2025-07-26T12:01:02.277Z" }, + { url = "https://files.pythonhosted.org/packages/0d/44/c4b0b6095fef4dc9c420e041799591e3b63e9619e3044f7f4f6c21c0ab24/contourpy-1.3.3-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:23416f38bfd74d5d28ab8429cc4d63fa67d5068bd711a85edb1c3fb0c3e2f381", size = 270149, upload-time = "2025-07-26T12:01:04.072Z" }, + { url = "https://files.pythonhosted.org/packages/30/2e/dd4ced42fefac8470661d7cb7e264808425e6c5d56d175291e93890cce09/contourpy-1.3.3-cp311-cp311-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:929ddf8c4c7f348e4c0a5a3a714b5c8542ffaa8c22954862a46ca1813b667ee7", size = 329222, upload-time = "2025-07-26T12:01:05.688Z" }, + { url = "https://files.pythonhosted.org/packages/f2/74/cc6ec2548e3d276c71389ea4802a774b7aa3558223b7bade3f25787fafc2/contourpy-1.3.3-cp311-cp311-manylinux_2_26_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:9e999574eddae35f1312c2b4b717b7885d4edd6cb46700e04f7f02db454e67c1", size = 377234, upload-time = "2025-07-26T12:01:07.054Z" }, + { url = "https://files.pythonhosted.org/packages/03/b3/64ef723029f917410f75c09da54254c5f9ea90ef89b143ccadb09df14c15/contourpy-1.3.3-cp311-cp311-manylinux_2_26_s390x.manylinux_2_28_s390x.whl", hash = "sha256:0bf67e0e3f482cb69779dd3061b534eb35ac9b17f163d851e2a547d56dba0a3a", size = 380555, upload-time = "2025-07-26T12:01:08.801Z" }, + { url = "https://files.pythonhosted.org/packages/5f/4b/6157f24ca425b89fe2eb7e7be642375711ab671135be21e6faa100f7448c/contourpy-1.3.3-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:51e79c1f7470158e838808d4a996fa9bac72c498e93d8ebe5119bc1e6becb0db", size = 355238, upload-time = "2025-07-26T12:01:10.319Z" }, + { url = "https://files.pythonhosted.org/packages/98/56/f914f0dd678480708a04cfd2206e7c382533249bc5001eb9f58aa693e200/contourpy-1.3.3-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:598c3aaece21c503615fd59c92a3598b428b2f01bfb4b8ca9c4edeecc2438620", size = 1326218, upload-time = "2025-07-26T12:01:12.659Z" }, + { url = "https://files.pythonhosted.org/packages/fb/d7/4a972334a0c971acd5172389671113ae82aa7527073980c38d5868ff1161/contourpy-1.3.3-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:322ab1c99b008dad206d406bb61d014cf0174df491ae9d9d0fac6a6fda4f977f", size = 1392867, upload-time = "2025-07-26T12:01:15.533Z" }, + { url = "https://files.pythonhosted.org/packages/75/3e/f2cc6cd56dc8cff46b1a56232eabc6feea52720083ea71ab15523daab796/contourpy-1.3.3-cp311-cp311-win32.whl", hash = "sha256:fd907ae12cd483cd83e414b12941c632a969171bf90fc937d0c9f268a31cafff", size = 183677, upload-time = "2025-07-26T12:01:17.088Z" }, + { url = "https://files.pythonhosted.org/packages/98/4b/9bd370b004b5c9d8045c6c33cf65bae018b27aca550a3f657cdc99acdbd8/contourpy-1.3.3-cp311-cp311-win_amd64.whl", hash = "sha256:3519428f6be58431c56581f1694ba8e50626f2dd550af225f82fb5f5814d2a42", size = 225234, upload-time = "2025-07-26T12:01:18.256Z" }, + { url = "https://files.pythonhosted.org/packages/d9/b6/71771e02c2e004450c12b1120a5f488cad2e4d5b590b1af8bad060360fe4/contourpy-1.3.3-cp311-cp311-win_arm64.whl", hash = "sha256:15ff10bfada4bf92ec8b31c62bf7c1834c244019b4a33095a68000d7075df470", size = 193123, upload-time = "2025-07-26T12:01:19.848Z" }, { url = "https://files.pythonhosted.org/packages/be/45/adfee365d9ea3d853550b2e735f9d66366701c65db7855cd07621732ccfc/contourpy-1.3.3-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:b08a32ea2f8e42cf1d4be3169a98dd4be32bafe4f22b6c4cb4ba810fa9e5d2cb", size = 293419, upload-time = "2025-07-26T12:01:21.16Z" }, { url = "https://files.pythonhosted.org/packages/53/3e/405b59cfa13021a56bba395a6b3aca8cec012b45bf177b0eaf7a202cde2c/contourpy-1.3.3-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:556dba8fb6f5d8742f2923fe9457dbdd51e1049c4a43fd3986a0b14a1d815fc6", size = 273979, upload-time = "2025-07-26T12:01:22.448Z" }, { url = "https://files.pythonhosted.org/packages/d4/1c/a12359b9b2ca3a845e8f7f9ac08bdf776114eb931392fcad91743e2ea17b/contourpy-1.3.3-cp312-cp312-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:92d9abc807cf7d0e047b95ca5d957cf4792fcd04e920ca70d48add15c1a90ea7", size = 332653, upload-time = "2025-07-26T12:01:24.155Z" }, @@ -886,6 +950,11 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/93/8a/68a4ec5c55a2971213d29a9374913f7e9f18581945a7a31d1a39b5d2dfe5/contourpy-1.3.3-cp314-cp314t-win32.whl", hash = "sha256:e74a9a0f5e3fff48fb5a7f2fd2b9b70a3fe014a67522f79b7cca4c0c7e43c9ae", size = 202428, upload-time = "2025-07-26T12:02:48.691Z" }, { url = "https://files.pythonhosted.org/packages/fa/96/fd9f641ffedc4fa3ace923af73b9d07e869496c9cc7a459103e6e978992f/contourpy-1.3.3-cp314-cp314t-win_amd64.whl", hash = "sha256:13b68d6a62db8eafaebb8039218921399baf6e47bf85006fd8529f2a08ef33fc", size = 250331, upload-time = "2025-07-26T12:02:50.137Z" }, { url = "https://files.pythonhosted.org/packages/ae/8c/469afb6465b853afff216f9528ffda78a915ff880ed58813ba4faf4ba0b6/contourpy-1.3.3-cp314-cp314t-win_arm64.whl", hash = "sha256:b7448cb5a725bb1e35ce88771b86fba35ef418952474492cf7c764059933ff8b", size = 203831, upload-time = "2025-07-26T12:02:51.449Z" }, + { url = "https://files.pythonhosted.org/packages/a5/29/8dcfe16f0107943fa92388c23f6e05cff0ba58058c4c95b00280d4c75a14/contourpy-1.3.3-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:cd5dfcaeb10f7b7f9dc8941717c6c2ade08f587be2226222c12b25f0483ed497", size = 278809, upload-time = "2025-07-26T12:02:52.74Z" }, + { url = "https://files.pythonhosted.org/packages/85/a9/8b37ef4f7dafeb335daee3c8254645ef5725be4d9c6aa70b50ec46ef2f7e/contourpy-1.3.3-pp311-pypy311_pp73-macosx_11_0_arm64.whl", hash = "sha256:0c1fc238306b35f246d61a1d416a627348b5cf0648648a031e14bb8705fcdfe8", size = 261593, upload-time = "2025-07-26T12:02:54.037Z" }, + { url = "https://files.pythonhosted.org/packages/0a/59/ebfb8c677c75605cc27f7122c90313fd2f375ff3c8d19a1694bda74aaa63/contourpy-1.3.3-pp311-pypy311_pp73-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:70f9aad7de812d6541d29d2bbf8feb22ff7e1c299523db288004e3157ff4674e", size = 302202, upload-time = "2025-07-26T12:02:55.947Z" }, + { url = "https://files.pythonhosted.org/packages/3c/37/21972a15834d90bfbfb009b9d004779bd5a07a0ec0234e5ba8f64d5736f4/contourpy-1.3.3-pp311-pypy311_pp73-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:5ed3657edf08512fc3fe81b510e35c2012fbd3081d2e26160f27ca28affec989", size = 329207, upload-time = "2025-07-26T12:02:57.468Z" }, + { url = "https://files.pythonhosted.org/packages/0c/58/bd257695f39d05594ca4ad60df5bcb7e32247f9951fd09a9b8edb82d1daa/contourpy-1.3.3-pp311-pypy311_pp73-win_amd64.whl", hash = "sha256:3d1a3799d62d45c18bafd41c5fa05120b96a28079f2393af559b843d1a966a77", size = 225315, upload-time = "2025-07-26T12:02:58.801Z" }, ] [[package]] @@ -921,6 +990,10 @@ dependencies = [ ] sdist = { url = "https://files.pythonhosted.org/packages/c9/37/3a3d82ca07e9eb2d8cdc1979ff82add35f1b41988c984db53ae582959c13/deap-1.4.3.tar.gz", hash = "sha256:7c97088fb05835bdc255bec475cb0e778de2b43e44cbefbf2bcd655aeec865fd", size = 1072325, upload-time = "2025-05-04T12:26:15.237Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/6d/89/48a1f7b94a754d91634183c5a88b76a461620dc9c3fceb0abb3b6badbc3b/deap-1.4.3-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:4a9a940104b5b153e6bf010664882ba6994baf2c9c3f14f4ff515383e1fb16ad", size = 111429, upload-time = "2025-05-04T12:26:18.21Z" }, + { url = "https://files.pythonhosted.org/packages/10/f0/f3e51e16effc8518340288add53ed81659257fd48ad10838241577646c16/deap-1.4.3-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3ecfd57c96736c15edf2999b2fc357a4834fcefbfa59eba86646a48712cd6818", size = 135407, upload-time = "2025-05-04T12:30:04.427Z" }, + { url = "https://files.pythonhosted.org/packages/e6/7c/f7fb20f2fbbae6bd247b4621341cd0aaafb55e379115d57b4e88b21aec08/deap-1.4.3-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:624562222365d8546c65878a028573151916e606f419bd45e0bd653c79435cb9", size = 135605, upload-time = "2025-05-04T12:30:53.437Z" }, + { url = "https://files.pythonhosted.org/packages/b2/98/537dadfab160eb7c39da979f52018b6d416e1d8fc86895cf5638e4538a12/deap-1.4.3-cp311-cp311-win_amd64.whl", hash = "sha256:1b00a3cbd61da09560abccf86a513f33ade55b22b708f14cb54f3a36a4b343a4", size = 109716, upload-time = "2025-05-04T12:28:47.615Z" }, { url = "https://files.pythonhosted.org/packages/cd/11/04eb0940138f07a4241bb548e10671adc5ab5f27439fd505464f603c093d/deap-1.4.3-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:42dc370be0bf315c85da16afcea49eae4d1065a23c2ebee07831e5c635a6af0b", size = 111608, upload-time = "2025-05-04T12:26:26.337Z" }, { url = "https://files.pythonhosted.org/packages/d8/e1/f55c181ae31595715b550e7b80d7b52ff81ac3aa4769d26625aaa1f10c30/deap-1.4.3-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3128ef0b394c9026be7bf532f1e4e2527581af7bba19dabc30e91a42bc480114", size = 135782, upload-time = "2025-05-04T12:29:51.143Z" }, { url = "https://files.pythonhosted.org/packages/b0/34/cba79381bccf50a24294c6a74e397b1c0163f347cf0d402bce7e83484358/deap-1.4.3-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c34f5d132ac23f7554c3a71b6e9c0c402505c0e0b3bcacabd211ddc6283043b8", size = 135963, upload-time = "2025-05-04T12:31:08.026Z" }, @@ -937,6 +1010,10 @@ version = "1.8.17" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/15/ad/71e708ff4ca377c4230530d6a7aa7992592648c122a2cd2b321cf8b35a76/debugpy-1.8.17.tar.gz", hash = "sha256:fd723b47a8c08892b1a16b2c6239a8b96637c62a59b94bb5dab4bac592a58a8e", size = 1644129, upload-time = "2025-09-17T16:33:20.633Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/d8/53/3af72b5c159278c4a0cf4cffa518675a0e73bdb7d1cac0239b815502d2ce/debugpy-1.8.17-cp311-cp311-macosx_15_0_universal2.whl", hash = "sha256:d3fce3f0e3de262a3b67e69916d001f3e767661c6e1ee42553009d445d1cd840", size = 2207154, upload-time = "2025-09-17T16:33:29.457Z" }, + { url = "https://files.pythonhosted.org/packages/8f/6d/204f407df45600e2245b4a39860ed4ba32552330a0b3f5f160ae4cc30072/debugpy-1.8.17-cp311-cp311-manylinux_2_34_x86_64.whl", hash = "sha256:c6bdf134457ae0cac6fb68205776be635d31174eeac9541e1d0c062165c6461f", size = 3170322, upload-time = "2025-09-17T16:33:30.837Z" }, + { url = "https://files.pythonhosted.org/packages/f2/13/1b8f87d39cf83c6b713de2620c31205299e6065622e7dd37aff4808dd410/debugpy-1.8.17-cp311-cp311-win32.whl", hash = "sha256:e79a195f9e059edfe5d8bf6f3749b2599452d3e9380484cd261f6b7cd2c7c4da", size = 5155078, upload-time = "2025-09-17T16:33:33.331Z" }, + { url = "https://files.pythonhosted.org/packages/c2/c5/c012c60a2922cc91caa9675d0ddfbb14ba59e1e36228355f41cab6483469/debugpy-1.8.17-cp311-cp311-win_amd64.whl", hash = "sha256:b532282ad4eca958b1b2d7dbcb2b7218e02cb934165859b918e3b6ba7772d3f4", size = 5179011, upload-time = "2025-09-17T16:33:35.711Z" }, { url = "https://files.pythonhosted.org/packages/08/2b/9d8e65beb2751876c82e1aceb32f328c43ec872711fa80257c7674f45650/debugpy-1.8.17-cp312-cp312-macosx_15_0_universal2.whl", hash = "sha256:f14467edef672195c6f6b8e27ce5005313cb5d03c9239059bc7182b60c176e2d", size = 2549522, upload-time = "2025-09-17T16:33:38.466Z" }, { url = "https://files.pythonhosted.org/packages/b4/78/eb0d77f02971c05fca0eb7465b18058ba84bd957062f5eec82f941ac792a/debugpy-1.8.17-cp312-cp312-manylinux_2_34_x86_64.whl", hash = "sha256:24693179ef9dfa20dca8605905a42b392be56d410c333af82f1c5dff807a64cc", size = 4309417, upload-time = "2025-09-17T16:33:41.299Z" }, { url = "https://files.pythonhosted.org/packages/37/42/c40f1d8cc1fed1e75ea54298a382395b8b937d923fcf41ab0797a554f555/debugpy-1.8.17-cp312-cp312-win32.whl", hash = "sha256:6a4e9dacf2cbb60d2514ff7b04b4534b0139facbf2abdffe0639ddb6088e59cf", size = 5277130, upload-time = "2025-09-17T16:33:43.554Z" }, @@ -1008,7 +1085,8 @@ source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "absl-py" }, { name = "dm-env" }, - { name = "dm-tree" }, + { name = "dm-tree", version = "0.1.8", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.13'" }, + { name = "dm-tree", version = "0.1.10", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.13'" }, { name = "glfw" }, { name = "labmaze" }, { name = "lxml" }, @@ -1033,7 +1111,8 @@ version = "1.6" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "absl-py" }, - { name = "dm-tree" }, + { name = "dm-tree", version = "0.1.8", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.13'" }, + { name = "dm-tree", version = "0.1.10", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.13'" }, { name = "numpy" }, ] sdist = { url = "https://files.pythonhosted.org/packages/62/c9/93e8d6239d5806508a2ee4b370e67c6069943ca149f59f533923737a99b7/dm-env-1.6.tar.gz", hash = "sha256:a436eb1c654c39e0c986a516cee218bea7140b510fceff63f97eb4fcff3d93de", size = 20187, upload-time = "2022-12-21T00:25:29.306Z" } @@ -1041,18 +1120,61 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/08/7e/36d548040e61337bf9182637a589c44da407a47a923ee88aec7f0e89867c/dm_env-1.6-py3-none-any.whl", hash = "sha256:0eabb6759dd453b625e041032f7ae0c1e87d4eb61b6a96b9ca586483837abf29", size = 26339, upload-time = "2022-12-21T00:25:37.128Z" }, ] +[[package]] +name = "dm-tree" +version = "0.1.8" +source = { registry = "https://pypi.org/simple" } +resolution-markers = [ + "python_full_version >= '3.14' and sys_platform == 'darwin'", + "python_full_version == '3.13.*' and sys_platform == 'darwin'", + "python_full_version >= '3.14' and platform_machine == 'aarch64' and sys_platform == 'linux'", + "python_full_version == '3.13.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux')", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux')", +] +sdist = { url = "https://files.pythonhosted.org/packages/f8/6d/f1997aac42e0f550c1e952a0b920eaa0bfc4d27d0421499881b934b969fc/dm-tree-0.1.8.tar.gz", hash = "sha256:0fcaabbb14e7980377439e7140bd05552739ca5e515ecb3119f234acee4b9430", size = 35384, upload-time = "2022-12-18T09:46:55.953Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/e2/64/901b324804793743f0fdc9e47db893bf0ded9e074850fab2440af330fe83/dm_tree-0.1.8-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:ad16ceba90a56ec47cf45b21856d14962ac314787975ef786efb5e6e9ca75ec7", size = 167628, upload-time = "2022-12-18T09:46:14.195Z" }, + { url = "https://files.pythonhosted.org/packages/b1/65/4f10a68dde5fa0c91043c9c899e9bc79b1657ba932d39a5f8525c0058e68/dm_tree-0.1.8-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:803bfc53b4659f447ac694dbd04235f94a73ef7c1fd1e0df7c84ac41e0bc963b", size = 115351, upload-time = "2022-12-18T09:46:16.467Z" }, + { url = "https://files.pythonhosted.org/packages/08/e2/4c29cb9876456517f21979ddcbb6048f28a3b52c61aa9d14d42adafcdca4/dm_tree-0.1.8-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:378cc8ad93c5fe3590f405a309980721f021c790ca1bdf9b15bb1d59daec57f5", size = 110661, upload-time = "2022-12-18T09:46:18.821Z" }, + { url = "https://files.pythonhosted.org/packages/fe/89/386332bbd7567c4ccc13aa2e58f733237503fc75fb389955d3b06b9fb967/dm_tree-0.1.8-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1607ce49aa42f010d1e5e616d92ce899d66835d4d8bea49679582435285515de", size = 146727, upload-time = "2023-01-21T08:49:52.992Z" }, + { url = "https://files.pythonhosted.org/packages/a3/e7/b0c04ea5af82c19fd5984bfe980f4012601c4708634c7c51a952b17c93b2/dm_tree-0.1.8-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:343a4a4ebaa127451ff971254a4be4084eb4bdc0b2513c32b46f6f728fd03f9e", size = 174689, upload-time = "2023-01-21T08:49:56.279Z" }, + { url = "https://files.pythonhosted.org/packages/13/0d/09a4ecb54c03db53d9eb5bbc81609d89de26e3762743f003282c1b48debb/dm_tree-0.1.8-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:fa42a605d099ee7d41ba2b5fb75e21423951fd26e5d50583a00471238fb3021d", size = 150338, upload-time = "2023-01-21T08:49:59.049Z" }, + { url = "https://files.pythonhosted.org/packages/4a/27/c5e3580a952a07e5a1428ae952874796870dc8db789f3d774e886160a9f4/dm_tree-0.1.8-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:83b7764de0d855338abefc6e3ee9fe40d301668310aa3baea3f778ff051f4393", size = 152800, upload-time = "2022-12-18T09:46:21.065Z" }, + { url = "https://files.pythonhosted.org/packages/e4/c1/522041457444b67125ac9527208bb3148f63d7dce0a86ffa589ec763a10e/dm_tree-0.1.8-cp311-cp311-win_amd64.whl", hash = "sha256:a5d819c38c03f0bb5b3b3703c60e4b170355a0fc6b5819325bf3d4ceb3ae7e80", size = 101336, upload-time = "2022-12-18T09:46:23.449Z" }, + { url = "https://files.pythonhosted.org/packages/72/2c/e33dfc96f974ae3cba82c9836371c93fcb4d59d5a82ebb853861618a0b0b/dm_tree-0.1.8-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:ea9e59e0451e7d29aece402d9f908f2e2a80922bcde2ebfd5dcb07750fcbfee8", size = 169495, upload-time = "2024-02-06T09:09:13.276Z" }, + { url = "https://files.pythonhosted.org/packages/17/af/4030827253a5d50eb8da6f7189bc33d3c850c4109cf3414910e9af677cb7/dm_tree-0.1.8-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:94d3f0826311f45ee19b75f5b48c99466e4218a0489e81c0f0167bda50cacf22", size = 116525, upload-time = "2024-02-06T09:09:15.529Z" }, + { url = "https://files.pythonhosted.org/packages/10/10/5f9eed00b1186921e447960443f03cda6374cba8cd5cf7aff2b42ecb8a0e/dm_tree-0.1.8-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:435227cf3c5dc63f4de054cf3d00183790bd9ead4c3623138c74dde7f67f521b", size = 111436, upload-time = "2024-02-06T09:09:16.781Z" }, + { url = "https://files.pythonhosted.org/packages/4a/da/3d3d04f7a572f7649f48edc9402ff5836e2f90e18445ffde110fd6142889/dm_tree-0.1.8-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:09964470f76a5201aff2e8f9b26842976de7889300676f927930f6285e256760", size = 146828, upload-time = "2024-02-13T21:25:21.639Z" }, + { url = "https://files.pythonhosted.org/packages/c4/12/0a8c2152655ca39c1059c762ea1dc12784166c735126eb0ab929c518ef4e/dm_tree-0.1.8-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:75c5d528bb992981c20793b6b453e91560784215dffb8a5440ba999753c14ceb", size = 175054, upload-time = "2024-02-13T21:25:23.532Z" }, + { url = "https://files.pythonhosted.org/packages/c9/d4/8cbb857612ca69763ee4f4f97c7b91659df1d373d62237cb9c772e55ae97/dm_tree-0.1.8-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c0a94aba18a35457a1b5cd716fd7b46c5dafdc4cf7869b4bae665b91c4682a8e", size = 152834, upload-time = "2024-02-06T09:09:18.536Z" }, + { url = "https://files.pythonhosted.org/packages/ad/e3/96f5267fe5a47c882dce7f3d06b26ddd756681fc4fbedd55d51b78b08bca/dm_tree-0.1.8-cp312-cp312-win_amd64.whl", hash = "sha256:96a548a406a6fb15fe58f6a30a57ff2f2aafbf25f05afab00c8f5e5977b6c715", size = 101754, upload-time = "2024-02-06T09:09:20.962Z" }, +] + [[package]] name = "dm-tree" version = "0.1.10" source = { registry = "https://pypi.org/simple" } +resolution-markers = [ + "python_full_version == '3.12.*' and sys_platform == 'darwin'", + "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux')", + "python_full_version < '3.12' and sys_platform == 'darwin'", + "python_full_version < '3.12' and platform_machine == 'aarch64' and sys_platform == 'linux'", + "(python_full_version < '3.12' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.12' and sys_platform != 'darwin' and sys_platform != 'linux')", +] dependencies = [ - { name = "absl-py" }, - { name = "attrs" }, - { name = "numpy" }, - { name = "wrapt" }, + { name = "absl-py", marker = "python_full_version < '3.13'" }, + { name = "attrs", marker = "python_full_version < '3.13'" }, + { name = "numpy", marker = "python_full_version < '3.13'" }, + { name = "wrapt", marker = "python_full_version < '3.13'" }, ] sdist = { url = "https://files.pythonhosted.org/packages/5a/66/a3ec619d22b6baffa5ab853e8dc6ec9d0c837127948af59bb15b988d7312/dm_tree-0.1.10.tar.gz", hash = "sha256:22f37b599e01cc3402a17f79c257a802aebd8d326de05b54657650845956208a", size = 35748, upload-time = "2026-03-31T17:35:39.03Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/87/dc/b01d0f70cde99b306731216a98287ba5926a50f27222f2ada0b99ad0911f/dm_tree-0.1.10-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:8218af7b99701bb8b03001c82961dc2cf81d7a734958206d2ea1ede8fbbe2b5f", size = 314603, upload-time = "2026-03-31T17:35:10.052Z" }, + { url = "https://files.pythonhosted.org/packages/40/72/3bafa58492862360113c1cccb26747c7863d417271e1572bacb3c281162f/dm_tree-0.1.10-cp311-cp311-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:cacef6180fcfef30bab2cac5164e753e2f7a2e60e5da0feb81f2d318416f8d98", size = 182657, upload-time = "2026-03-31T17:35:11.462Z" }, + { url = "https://files.pythonhosted.org/packages/78/10/587a2cdc05995069aa63b659d884eb3e58a3c86a5b4a00acdb7a316bddf3/dm_tree-0.1.10-cp311-cp311-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:f0e8907bb6809dc195be3af077e382126eaebe06c00f835d09ae26e36d2165ff", size = 185008, upload-time = "2026-03-31T17:35:12.838Z" }, + { url = "https://files.pythonhosted.org/packages/60/0e/08d938d84cbf791dde009b3d3a6637f27a0004235e700641a0ac038daac5/dm_tree-0.1.10-cp311-cp311-win_amd64.whl", hash = "sha256:a1c82dd4726a16ac6b6f7a77a5fb097ee396fd349ae301407eb5736f15b8fa16", size = 111472, upload-time = "2026-03-31T17:35:14.035Z" }, { url = "https://files.pythonhosted.org/packages/34/a1/17e0d68eec978c483db4712b14d083ee01484381b29ea85edb2b20210bd0/dm_tree-0.1.10-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:94af18e4fd22ce69eccae89eeed8ed498b6b4cc4957f4ed10b4160e59f620e1d", size = 315976, upload-time = "2026-03-31T17:35:15.21Z" }, { url = "https://files.pythonhosted.org/packages/cc/6f/ed603715fbc29c887a8985252e2cfe0d449497aea96bac51010159771617/dm_tree-0.1.10-cp312-cp312-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:b442a0c1e9d0960e0314a2e4af81fd328a87921b6d6db6dc41bfa420536884d6", size = 184053, upload-time = "2026-03-31T17:35:16.512Z" }, { url = "https://files.pythonhosted.org/packages/83/eb/1d55c679cee9a54e552480d308535753c72e2250cf720d7aa777bff2a4fe/dm_tree-0.1.10-cp312-cp312-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:012c2b376e88d3685c73a4b5c23be41fe933e14e380dcd90172971690b0e02d2", size = 186506, upload-time = "2026-03-31T17:35:17.593Z" }, @@ -1148,6 +1270,14 @@ dependencies = [ ] sdist = { url = "https://files.pythonhosted.org/packages/5e/d7/1b7be8db364f1c4838dfc1a40ca96577aba405deabf896a4eb3aaeb15a62/ezdxf-1.4.4.tar.gz", hash = "sha256:da5a5e0e6bdbb6656f9c017b47edc7eafceb419d61a2b5de64ffb344c168e593", size = 1866886, upload-time = "2026-05-14T09:19:19.511Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/8f/d0/bc515b7f5596bc3d55b93fc9f2c2b4926e2587af6bfae0486ef7cc7ddf43/ezdxf-1.4.4-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:39aadab5bc7a05deddbd0db9b984c8a4bd28bd4c1ac2c5ee03f0d1b096272a88", size = 3553590, upload-time = "2026-05-14T09:25:28.042Z" }, + { url = "https://files.pythonhosted.org/packages/a7/73/207132f13a5280d186f2441d9125639fdc7ddeabf56c2d5da4d691e81ce6/ezdxf-1.4.4-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:2ed65b191113a82133ba47daa6ebdd540b487b17394b1e327e9511dde87ad924", size = 3008276, upload-time = "2026-05-14T09:25:29.424Z" }, + { url = "https://files.pythonhosted.org/packages/82/73/b01af87269726e3719abc5ff694b843b710ef8fc345d21013e90d70e44d8/ezdxf-1.4.4-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:7c3c8f2c2b62fe5b6c9b62ab8257b697535d62b0c79acf3a5040bd95edfab451", size = 3001750, upload-time = "2026-05-14T09:25:31.146Z" }, + { url = "https://files.pythonhosted.org/packages/dd/92/284d7ca6a9da107966c7bd9d81c92245985235bc432fe0837982ef80630a/ezdxf-1.4.4-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d68d5ab9e1071319030da3af27590f34c38c8544a5ea638d9a4a800a96abb3c2", size = 5802382, upload-time = "2026-05-14T09:27:28.462Z" }, + { url = "https://files.pythonhosted.org/packages/7d/fe/e4f37730ca5b5bf7de3a968a26126b404f60324d0b8ae9d59d11d6e55740/ezdxf-1.4.4-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7f75a4f2924ebdda0f5b2779ff2135ba92de2596c95a8fa9b1d9ebcabea1be41", size = 5794671, upload-time = "2026-05-14T09:27:09.867Z" }, + { url = "https://files.pythonhosted.org/packages/fe/3f/c3e7ab74f58cb69ef985fb71eda859b5c287cc506c65cbffe7e55c7cf2d4/ezdxf-1.4.4-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:0eec8a2095b645420a67560e99041c0d25afefd39eab5bff8c736fdb32211a75", size = 5767366, upload-time = "2026-05-14T09:27:30.108Z" }, + { url = "https://files.pythonhosted.org/packages/66/7a/b7070bf05e75b3e709a6fe5ae5bcd3bd899e987ef84ff25cf28327519c03/ezdxf-1.4.4-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:d87a85052e92b9c28e54605dbad65f779a3b61e6288e992d6ef00df7bde4bed3", size = 5830221, upload-time = "2026-05-14T09:27:12.074Z" }, + { url = "https://files.pythonhosted.org/packages/78/cf/a990289808c261c52f5b219484d136a8748773c99a6d25c84f55a0353fea/ezdxf-1.4.4-cp311-cp311-win_amd64.whl", hash = "sha256:473d68c8f2b04ace513efa290a1cd0d3a4a589cdff48124f015f0e51034668b2", size = 2957599, upload-time = "2026-05-14T09:23:46.571Z" }, { url = "https://files.pythonhosted.org/packages/18/3d/98648d221ffa047b5ba898c8e152010861dc71a66b531dcf15053075010e/ezdxf-1.4.4-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:d723d35d08223318c17080a32a05192a1449e544dee867c9d9c6f25998fac303", size = 3563916, upload-time = "2026-05-14T09:25:32.879Z" }, { url = "https://files.pythonhosted.org/packages/2c/f1/84bbaa571412f840c22deeae185e54d4a67aa52f03e1728fd8425748c548/ezdxf-1.4.4-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:6b0c73b46085521bdbd4a3e7d88998da7bec5713ba89bbb502fdeffe6b42fc7e", size = 3016857, upload-time = "2026-05-14T09:25:34.607Z" }, { url = "https://files.pythonhosted.org/packages/b0/ff/f2eb77d22d26aa98abbe0961470871d8b85ef4e73e5527f544d25f958d6e/ezdxf-1.4.4-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:ac3e83a70c1f866dd5114192a6fab6e75cc83b75e907bc08c5d94b98cce14cc0", size = 3003336, upload-time = "2026-05-14T09:25:35.947Z" }, @@ -1214,6 +1344,14 @@ version = "4.60.1" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/4b/42/97a13e47a1e51a5a7142475bbcf5107fe3a68fc34aef331c897d5fb98ad0/fonttools-4.60.1.tar.gz", hash = "sha256:ef00af0439ebfee806b25f24c8f92109157ff3fac5731dc7867957812e87b8d9", size = 3559823, upload-time = "2025-09-29T21:13:27.129Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/ea/85/639aa9bface1537e0fb0f643690672dde0695a5bbbc90736bc571b0b1941/fonttools-4.60.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:7b4c32e232a71f63a5d00259ca3d88345ce2a43295bb049d21061f338124246f", size = 2831872, upload-time = "2025-09-29T21:11:20.329Z" }, + { url = "https://files.pythonhosted.org/packages/6b/47/3c63158459c95093be9618794acb1067b3f4d30dcc5c3e8114b70e67a092/fonttools-4.60.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:3630e86c484263eaac71d117085d509cbcf7b18f677906824e4bace598fb70d2", size = 2356990, upload-time = "2025-09-29T21:11:22.754Z" }, + { url = "https://files.pythonhosted.org/packages/94/dd/1934b537c86fcf99f9761823f1fc37a98fbd54568e8e613f29a90fed95a9/fonttools-4.60.1-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:5c1015318e4fec75dd4943ad5f6a206d9727adf97410d58b7e32ab644a807914", size = 5042189, upload-time = "2025-09-29T21:11:25.061Z" }, + { url = "https://files.pythonhosted.org/packages/d2/d2/9f4e4c4374dd1daa8367784e1bd910f18ba886db1d6b825b12edf6db3edc/fonttools-4.60.1-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:e6c58beb17380f7c2ea181ea11e7db8c0ceb474c9dd45f48e71e2cb577d146a1", size = 4978683, upload-time = "2025-09-29T21:11:27.693Z" }, + { url = "https://files.pythonhosted.org/packages/cc/c4/0fb2dfd1ecbe9a07954cc13414713ed1eab17b1c0214ef07fc93df234a47/fonttools-4.60.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:ec3681a0cb34c255d76dd9d865a55f260164adb9fa02628415cdc2d43ee2c05d", size = 5021372, upload-time = "2025-09-29T21:11:30.257Z" }, + { url = "https://files.pythonhosted.org/packages/0c/d5/495fc7ae2fab20223cc87179a8f50f40f9a6f821f271ba8301ae12bb580f/fonttools-4.60.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:f4b5c37a5f40e4d733d3bbaaef082149bee5a5ea3156a785ff64d949bd1353fa", size = 5132562, upload-time = "2025-09-29T21:11:32.737Z" }, + { url = "https://files.pythonhosted.org/packages/bc/fa/021dab618526323c744e0206b3f5c8596a2e7ae9aa38db5948a131123e83/fonttools-4.60.1-cp311-cp311-win32.whl", hash = "sha256:398447f3d8c0c786cbf1209711e79080a40761eb44b27cdafffb48f52bcec258", size = 2230288, upload-time = "2025-09-29T21:11:35.015Z" }, + { url = "https://files.pythonhosted.org/packages/bb/78/0e1a6d22b427579ea5c8273e1c07def2f325b977faaf60bb7ddc01456cb1/fonttools-4.60.1-cp311-cp311-win_amd64.whl", hash = "sha256:d066ea419f719ed87bc2c99a4a4bfd77c2e5949cb724588b9dd58f3fd90b92bf", size = 2278184, upload-time = "2025-09-29T21:11:37.434Z" }, { url = "https://files.pythonhosted.org/packages/e3/f7/a10b101b7a6f8836a5adb47f2791f2075d044a6ca123f35985c42edc82d8/fonttools-4.60.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:7b0c6d57ab00dae9529f3faf187f2254ea0aa1e04215cf2f1a8ec277c96661bc", size = 2832953, upload-time = "2025-09-29T21:11:39.616Z" }, { url = "https://files.pythonhosted.org/packages/ed/fe/7bd094b59c926acf2304d2151354ddbeb74b94812f3dc943c231db09cb41/fonttools-4.60.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:839565cbf14645952d933853e8ade66a463684ed6ed6c9345d0faf1f0e868877", size = 2352706, upload-time = "2025-09-29T21:11:41.826Z" }, { url = "https://files.pythonhosted.org/packages/c0/ca/4bb48a26ed95a1e7eba175535fe5805887682140ee0a0d10a88e1de84208/fonttools-4.60.1-cp312-cp312-manylinux1_x86_64.manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:8177ec9676ea6e1793c8a084a90b65a9f778771998eb919d05db6d4b1c0b114c", size = 4923716, upload-time = "2025-09-29T21:11:43.893Z" }, @@ -1264,6 +1402,22 @@ version = "1.8.0" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/2d/f5/c831fac6cc817d26fd54c7eaccd04ef7e0288806943f7cc5bbf69f3ac1f0/frozenlist-1.8.0.tar.gz", hash = "sha256:3ede829ed8d842f6cd48fc7081d7a41001a56f1f38603f9d49bf3020d59a31ad", size = 45875, upload-time = "2025-10-06T05:38:17.865Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/bc/03/077f869d540370db12165c0aa51640a873fb661d8b315d1d4d67b284d7ac/frozenlist-1.8.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:09474e9831bc2b2199fad6da3c14c7b0fbdd377cce9d3d77131be28906cb7d84", size = 86912, upload-time = "2025-10-06T05:35:45.98Z" }, + { url = "https://files.pythonhosted.org/packages/df/b5/7610b6bd13e4ae77b96ba85abea1c8cb249683217ef09ac9e0ae93f25a91/frozenlist-1.8.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:17c883ab0ab67200b5f964d2b9ed6b00971917d5d8a92df149dc2c9779208ee9", size = 50046, upload-time = "2025-10-06T05:35:47.009Z" }, + { url = "https://files.pythonhosted.org/packages/6e/ef/0e8f1fe32f8a53dd26bdd1f9347efe0778b0fddf62789ea683f4cc7d787d/frozenlist-1.8.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:fa47e444b8ba08fffd1c18e8cdb9a75db1b6a27f17507522834ad13ed5922b93", size = 50119, upload-time = "2025-10-06T05:35:48.38Z" }, + { url = "https://files.pythonhosted.org/packages/11/b1/71a477adc7c36e5fb628245dfbdea2166feae310757dea848d02bd0689fd/frozenlist-1.8.0-cp311-cp311-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:2552f44204b744fba866e573be4c1f9048d6a324dfe14475103fd51613eb1d1f", size = 231067, upload-time = "2025-10-06T05:35:49.97Z" }, + { url = "https://files.pythonhosted.org/packages/45/7e/afe40eca3a2dc19b9904c0f5d7edfe82b5304cb831391edec0ac04af94c2/frozenlist-1.8.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:957e7c38f250991e48a9a73e6423db1bb9dd14e722a10f6b8bb8e16a0f55f695", size = 233160, upload-time = "2025-10-06T05:35:51.729Z" }, + { url = "https://files.pythonhosted.org/packages/a6/aa/7416eac95603ce428679d273255ffc7c998d4132cfae200103f164b108aa/frozenlist-1.8.0-cp311-cp311-manylinux2014_armv7l.manylinux_2_17_armv7l.manylinux_2_31_armv7l.whl", hash = "sha256:8585e3bb2cdea02fc88ffa245069c36555557ad3609e83be0ec71f54fd4abb52", size = 228544, upload-time = "2025-10-06T05:35:53.246Z" }, + { url = "https://files.pythonhosted.org/packages/8b/3d/2a2d1f683d55ac7e3875e4263d28410063e738384d3adc294f5ff3d7105e/frozenlist-1.8.0-cp311-cp311-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:edee74874ce20a373d62dc28b0b18b93f645633c2943fd90ee9d898550770581", size = 243797, upload-time = "2025-10-06T05:35:54.497Z" }, + { url = "https://files.pythonhosted.org/packages/78/1e/2d5565b589e580c296d3bb54da08d206e797d941a83a6fdea42af23be79c/frozenlist-1.8.0-cp311-cp311-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:c9a63152fe95756b85f31186bddf42e4c02c6321207fd6601a1c89ebac4fe567", size = 247923, upload-time = "2025-10-06T05:35:55.861Z" }, + { url = "https://files.pythonhosted.org/packages/aa/c3/65872fcf1d326a7f101ad4d86285c403c87be7d832b7470b77f6d2ed5ddc/frozenlist-1.8.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:b6db2185db9be0a04fecf2f241c70b63b1a242e2805be291855078f2b404dd6b", size = 230886, upload-time = "2025-10-06T05:35:57.399Z" }, + { url = "https://files.pythonhosted.org/packages/a0/76/ac9ced601d62f6956f03cc794f9e04c81719509f85255abf96e2510f4265/frozenlist-1.8.0-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:f4be2e3d8bc8aabd566f8d5b8ba7ecc09249d74ba3c9ed52e54dc23a293f0b92", size = 245731, upload-time = "2025-10-06T05:35:58.563Z" }, + { url = "https://files.pythonhosted.org/packages/b9/49/ecccb5f2598daf0b4a1415497eba4c33c1e8ce07495eb07d2860c731b8d5/frozenlist-1.8.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:c8d1634419f39ea6f5c427ea2f90ca85126b54b50837f31497f3bf38266e853d", size = 241544, upload-time = "2025-10-06T05:35:59.719Z" }, + { url = "https://files.pythonhosted.org/packages/53/4b/ddf24113323c0bbcc54cb38c8b8916f1da7165e07b8e24a717b4a12cbf10/frozenlist-1.8.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:1a7fa382a4a223773ed64242dbe1c9c326ec09457e6b8428efb4118c685c3dfd", size = 241806, upload-time = "2025-10-06T05:36:00.959Z" }, + { url = "https://files.pythonhosted.org/packages/a7/fb/9b9a084d73c67175484ba2789a59f8eebebd0827d186a8102005ce41e1ba/frozenlist-1.8.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:11847b53d722050808926e785df837353bd4d75f1d494377e59b23594d834967", size = 229382, upload-time = "2025-10-06T05:36:02.22Z" }, + { url = "https://files.pythonhosted.org/packages/95/a3/c8fb25aac55bf5e12dae5c5aa6a98f85d436c1dc658f21c3ac73f9fa95e5/frozenlist-1.8.0-cp311-cp311-win32.whl", hash = "sha256:27c6e8077956cf73eadd514be8fb04d77fc946a7fe9f7fe167648b0b9085cc25", size = 39647, upload-time = "2025-10-06T05:36:03.409Z" }, + { url = "https://files.pythonhosted.org/packages/0a/f5/603d0d6a02cfd4c8f2a095a54672b3cf967ad688a60fb9faf04fc4887f65/frozenlist-1.8.0-cp311-cp311-win_amd64.whl", hash = "sha256:ac913f8403b36a2c8610bbfd25b8013488533e71e62b4b4adce9c86c8cea905b", size = 44064, upload-time = "2025-10-06T05:36:04.368Z" }, + { url = "https://files.pythonhosted.org/packages/5d/16/c2c9ab44e181f043a86f9a8f84d5124b62dbcb3a02c0977ec72b9ac1d3e0/frozenlist-1.8.0-cp311-cp311-win_arm64.whl", hash = "sha256:d4d3214a0f8394edfa3e303136d0575eece0745ff2b47bd2cb2e66dd92d4351a", size = 39937, upload-time = "2025-10-06T05:36:05.669Z" }, { url = "https://files.pythonhosted.org/packages/69/29/948b9aa87e75820a38650af445d2ef2b6b8a6fab1a23b6bb9e4ef0be2d59/frozenlist-1.8.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:78f7b9e5d6f2fdb88cdde9440dc147259b62b9d3b019924def9f6478be254ac1", size = 87782, upload-time = "2025-10-06T05:36:06.649Z" }, { url = "https://files.pythonhosted.org/packages/64/80/4f6e318ee2a7c0750ed724fa33a4bdf1eacdc5a39a7a24e818a773cd91af/frozenlist-1.8.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:229bf37d2e4acdaf808fd3f06e854a4a7a3661e871b10dc1f8f1896a3b05f18b", size = 50594, upload-time = "2025-10-06T05:36:07.69Z" }, { url = "https://files.pythonhosted.org/packages/2b/94/5c8a2b50a496b11dd519f4a24cb5496cf125681dd99e94c604ccdea9419a/frozenlist-1.8.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:f833670942247a14eafbb675458b4e61c82e002a148f49e68257b79296e865c4", size = 50448, upload-time = "2025-10-06T05:36:08.78Z" }, @@ -1410,9 +1564,21 @@ version = "3.2.4" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/03/b8/704d753a5a45507a7aab61f18db9509302ed3d0a27ac7e0359ec2905b1a6/greenlet-3.2.4.tar.gz", hash = "sha256:0dca0d95ff849f9a364385f36ab49f50065d76964944638be9691e1832e9f86d", size = 188260, upload-time = "2025-08-07T13:24:33.51Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/a4/de/f28ced0a67749cac23fecb02b694f6473f47686dff6afaa211d186e2ef9c/greenlet-3.2.4-cp311-cp311-macosx_11_0_universal2.whl", hash = "sha256:96378df1de302bc38e99c3a9aa311967b7dc80ced1dcc6f171e99842987882a2", size = 272305, upload-time = "2025-08-07T13:15:41.288Z" }, + { url = "https://files.pythonhosted.org/packages/09/16/2c3792cba130000bf2a31c5272999113f4764fd9d874fb257ff588ac779a/greenlet-3.2.4-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:1ee8fae0519a337f2329cb78bd7a8e128ec0f881073d43f023c7b8d4831d5246", size = 632472, upload-time = "2025-08-07T13:42:55.044Z" }, + { url = "https://files.pythonhosted.org/packages/ae/8f/95d48d7e3d433e6dae5b1682e4292242a53f22df82e6d3dda81b1701a960/greenlet-3.2.4-cp311-cp311-manylinux2014_ppc64le.manylinux_2_17_ppc64le.whl", hash = "sha256:94abf90142c2a18151632371140b3dba4dee031633fe614cb592dbb6c9e17bc3", size = 644646, upload-time = "2025-08-07T13:45:26.523Z" }, + { url = "https://files.pythonhosted.org/packages/d5/5e/405965351aef8c76b8ef7ad370e5da58d57ef6068df197548b015464001a/greenlet-3.2.4-cp311-cp311-manylinux2014_s390x.manylinux_2_17_s390x.whl", hash = "sha256:4d1378601b85e2e5171b99be8d2dc85f594c79967599328f95c1dc1a40f1c633", size = 640519, upload-time = "2025-08-07T13:53:13.928Z" }, + { url = "https://files.pythonhosted.org/packages/25/5d/382753b52006ce0218297ec1b628e048c4e64b155379331f25a7316eb749/greenlet-3.2.4-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:0db5594dce18db94f7d1650d7489909b57afde4c580806b8d9203b6e79cdc079", size = 639707, upload-time = "2025-08-07T13:18:27.146Z" }, + { url = "https://files.pythonhosted.org/packages/1f/8e/abdd3f14d735b2929290a018ecf133c901be4874b858dd1c604b9319f064/greenlet-3.2.4-cp311-cp311-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:2523e5246274f54fdadbce8494458a2ebdcdbc7b802318466ac5606d3cded1f8", size = 587684, upload-time = "2025-08-07T13:18:25.164Z" }, + { url = "https://files.pythonhosted.org/packages/5d/65/deb2a69c3e5996439b0176f6651e0052542bb6c8f8ec2e3fba97c9768805/greenlet-3.2.4-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:1987de92fec508535687fb807a5cea1560f6196285a4cde35c100b8cd632cc52", size = 1116647, upload-time = "2025-08-07T13:42:38.655Z" }, + { url = "https://files.pythonhosted.org/packages/3f/cc/b07000438a29ac5cfb2194bfc128151d52f333cee74dd7dfe3fb733fc16c/greenlet-3.2.4-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:55e9c5affaa6775e2c6b67659f3a71684de4c549b3dd9afca3bc773533d284fa", size = 1142073, upload-time = "2025-08-07T13:18:21.737Z" }, + { url = "https://files.pythonhosted.org/packages/67/24/28a5b2fa42d12b3d7e5614145f0bd89714c34c08be6aabe39c14dd52db34/greenlet-3.2.4-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:c9c6de1940a7d828635fbd254d69db79e54619f165ee7ce32fda763a9cb6a58c", size = 1548385, upload-time = "2025-11-04T12:42:11.067Z" }, + { url = "https://files.pythonhosted.org/packages/6a/05/03f2f0bdd0b0ff9a4f7b99333d57b53a7709c27723ec8123056b084e69cd/greenlet-3.2.4-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:03c5136e7be905045160b1b9fdca93dd6727b180feeafda6818e6496434ed8c5", size = 1613329, upload-time = "2025-11-04T12:42:12.928Z" }, + { url = "https://files.pythonhosted.org/packages/d8/0f/30aef242fcab550b0b3520b8e3561156857c94288f0332a79928c31a52cf/greenlet-3.2.4-cp311-cp311-win_amd64.whl", hash = "sha256:9c40adce87eaa9ddb593ccb0fa6a07caf34015a29bf8d344811665b573138db9", size = 299100, upload-time = "2025-08-07T13:44:12.287Z" }, { url = "https://files.pythonhosted.org/packages/44/69/9b804adb5fd0671f367781560eb5eb586c4d495277c93bde4307b9e28068/greenlet-3.2.4-cp312-cp312-macosx_11_0_universal2.whl", hash = "sha256:3b67ca49f54cede0186854a008109d6ee71f66bd57bb36abd6d0a0267b540cdd", size = 274079, upload-time = "2025-08-07T13:15:45.033Z" }, { url = "https://files.pythonhosted.org/packages/46/e9/d2a80c99f19a153eff70bc451ab78615583b8dac0754cfb942223d2c1a0d/greenlet-3.2.4-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:ddf9164e7a5b08e9d22511526865780a576f19ddd00d62f8a665949327fde8bb", size = 640997, upload-time = "2025-08-07T13:42:56.234Z" }, { url = "https://files.pythonhosted.org/packages/3b/16/035dcfcc48715ccd345f3a93183267167cdd162ad123cd93067d86f27ce4/greenlet-3.2.4-cp312-cp312-manylinux2014_ppc64le.manylinux_2_17_ppc64le.whl", hash = "sha256:f28588772bb5fb869a8eb331374ec06f24a83a9c25bfa1f38b6993afe9c1e968", size = 655185, upload-time = "2025-08-07T13:45:27.624Z" }, + { url = "https://files.pythonhosted.org/packages/31/da/0386695eef69ffae1ad726881571dfe28b41970173947e7c558d9998de0f/greenlet-3.2.4-cp312-cp312-manylinux2014_s390x.manylinux_2_17_s390x.whl", hash = "sha256:5c9320971821a7cb77cfab8d956fa8e39cd07ca44b6070db358ceb7f8797c8c9", size = 649926, upload-time = "2025-08-07T13:53:15.251Z" }, { url = "https://files.pythonhosted.org/packages/68/88/69bf19fd4dc19981928ceacbc5fd4bb6bc2215d53199e367832e98d1d8fe/greenlet-3.2.4-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:c60a6d84229b271d44b70fb6e5fa23781abb5d742af7b808ae3f6efd7c9c60f6", size = 651839, upload-time = "2025-08-07T13:18:30.281Z" }, { url = "https://files.pythonhosted.org/packages/19/0d/6660d55f7373b2ff8152401a83e02084956da23ae58cddbfb0b330978fe9/greenlet-3.2.4-cp312-cp312-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:3b3812d8d0c9579967815af437d96623f45c0f2ae5f04e366de62a12d83a8fb0", size = 607586, upload-time = "2025-08-07T13:18:28.544Z" }, { url = "https://files.pythonhosted.org/packages/8e/1a/c953fdedd22d81ee4629afbb38d2f9d71e37d23caace44775a3a969147d4/greenlet-3.2.4-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:abbf57b5a870d30c4675928c37278493044d7c14378350b3aa5d484fa65575f0", size = 1123281, upload-time = "2025-08-07T13:42:39.858Z" }, @@ -1423,6 +1589,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/49/e8/58c7f85958bda41dafea50497cbd59738c5c43dbbea5ee83d651234398f4/greenlet-3.2.4-cp313-cp313-macosx_11_0_universal2.whl", hash = "sha256:1a921e542453fe531144e91e1feedf12e07351b1cf6c9e8a3325ea600a715a31", size = 272814, upload-time = "2025-08-07T13:15:50.011Z" }, { url = "https://files.pythonhosted.org/packages/62/dd/b9f59862e9e257a16e4e610480cfffd29e3fae018a68c2332090b53aac3d/greenlet-3.2.4-cp313-cp313-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:cd3c8e693bff0fff6ba55f140bf390fa92c994083f838fece0f63be121334945", size = 641073, upload-time = "2025-08-07T13:42:57.23Z" }, { url = "https://files.pythonhosted.org/packages/f7/0b/bc13f787394920b23073ca3b6c4a7a21396301ed75a655bcb47196b50e6e/greenlet-3.2.4-cp313-cp313-manylinux2014_ppc64le.manylinux_2_17_ppc64le.whl", hash = "sha256:710638eb93b1fa52823aa91bf75326f9ecdfd5e0466f00789246a5280f4ba0fc", size = 655191, upload-time = "2025-08-07T13:45:29.752Z" }, + { url = "https://files.pythonhosted.org/packages/f2/d6/6adde57d1345a8d0f14d31e4ab9c23cfe8e2cd39c3baf7674b4b0338d266/greenlet-3.2.4-cp313-cp313-manylinux2014_s390x.manylinux_2_17_s390x.whl", hash = "sha256:c5111ccdc9c88f423426df3fd1811bfc40ed66264d35aa373420a34377efc98a", size = 649516, upload-time = "2025-08-07T13:53:16.314Z" }, { url = "https://files.pythonhosted.org/packages/7f/3b/3a3328a788d4a473889a2d403199932be55b1b0060f4ddd96ee7cdfcad10/greenlet-3.2.4-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:d76383238584e9711e20ebe14db6c88ddcedc1829a9ad31a584389463b5aa504", size = 652169, upload-time = "2025-08-07T13:18:32.861Z" }, { url = "https://files.pythonhosted.org/packages/ee/43/3cecdc0349359e1a527cbf2e3e28e5f8f06d3343aaf82ca13437a9aa290f/greenlet-3.2.4-cp313-cp313-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:23768528f2911bcd7e475210822ffb5254ed10d71f4028387e5a99b4c6699671", size = 610497, upload-time = "2025-08-07T13:18:31.636Z" }, { url = "https://files.pythonhosted.org/packages/b8/19/06b6cf5d604e2c382a6f31cafafd6f33d5dea706f4db7bdab184bad2b21d/greenlet-3.2.4-cp313-cp313-musllinux_1_1_aarch64.whl", hash = "sha256:00fadb3fedccc447f517ee0d3fd8fe49eae949e1cd0f6a611818f4f6fb7dc83b", size = 1121662, upload-time = "2025-08-07T13:42:41.117Z" }, @@ -1433,6 +1600,7 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/22/5c/85273fd7cc388285632b0498dbbab97596e04b154933dfe0f3e68156c68c/greenlet-3.2.4-cp314-cp314-macosx_11_0_universal2.whl", hash = "sha256:49a30d5fda2507ae77be16479bdb62a660fa51b1eb4928b524975b3bde77b3c0", size = 273586, upload-time = "2025-08-07T13:16:08.004Z" }, { url = "https://files.pythonhosted.org/packages/d1/75/10aeeaa3da9332c2e761e4c50d4c3556c21113ee3f0afa2cf5769946f7a3/greenlet-3.2.4-cp314-cp314-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:299fd615cd8fc86267b47597123e3f43ad79c9d8a22bebdce535e53550763e2f", size = 686346, upload-time = "2025-08-07T13:42:59.944Z" }, { url = "https://files.pythonhosted.org/packages/c0/aa/687d6b12ffb505a4447567d1f3abea23bd20e73a5bed63871178e0831b7a/greenlet-3.2.4-cp314-cp314-manylinux2014_ppc64le.manylinux_2_17_ppc64le.whl", hash = "sha256:c17b6b34111ea72fc5a4e4beec9711d2226285f0386ea83477cbb97c30a3f3a5", size = 699218, upload-time = "2025-08-07T13:45:30.969Z" }, + { url = "https://files.pythonhosted.org/packages/dc/8b/29aae55436521f1d6f8ff4e12fb676f3400de7fcf27fccd1d4d17fd8fecd/greenlet-3.2.4-cp314-cp314-manylinux2014_s390x.manylinux_2_17_s390x.whl", hash = "sha256:b4a1870c51720687af7fa3e7cda6d08d801dae660f75a76f3845b642b4da6ee1", size = 694659, upload-time = "2025-08-07T13:53:17.759Z" }, { url = "https://files.pythonhosted.org/packages/92/2e/ea25914b1ebfde93b6fc4ff46d6864564fba59024e928bdc7de475affc25/greenlet-3.2.4-cp314-cp314-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:061dc4cf2c34852b052a8620d40f36324554bc192be474b9e9770e8c042fd735", size = 695355, upload-time = "2025-08-07T13:18:34.517Z" }, { url = "https://files.pythonhosted.org/packages/72/60/fc56c62046ec17f6b0d3060564562c64c862948c9d4bc8aa807cf5bd74f4/greenlet-3.2.4-cp314-cp314-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:44358b9bf66c8576a9f57a590d5f5d6e72fa4228b763d0e43fee6d3b06d3a337", size = 657512, upload-time = "2025-08-07T13:18:33.969Z" }, { url = "https://files.pythonhosted.org/packages/23/6e/74407aed965a4ab6ddd93a7ded3180b730d281c77b765788419484cdfeef/greenlet-3.2.4-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:2917bdf657f5859fbf3386b12d68ede4cf1f04c90c3a6bc1f013dd68a22e2269", size = 1612508, upload-time = "2025-11-04T12:42:23.427Z" }, @@ -1442,7 +1610,7 @@ wheels = [ [[package]] name = "gymnasium" -version = "1.2.3" +version = "1.2.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "cloudpickle" }, @@ -1450,9 +1618,9 @@ dependencies = [ { name = "numpy" }, { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/76/59/653a9417d98ed3e29ef9734ba52c3495f6c6823b8d5c0c75369f25111708/gymnasium-1.2.3.tar.gz", hash = "sha256:2b2cb5b5fbbbdf3afb9f38ca952cc48aa6aa3e26561400d940747fda3ad42509", size = 829230, upload-time = "2025-12-18T16:51:10.234Z" } +sdist = { url = "https://files.pythonhosted.org/packages/b3/de/b923d09654df8f8ee29a3cc7ec7829ac057efd0d969cc3da0c8a7b219d59/gymnasium-1.2.1.tar.gz", hash = "sha256:4e6480273528523a90b3db99befb6111b13f15fa0866de88c4b675770495b66c", size = 827852, upload-time = "2025-09-23T08:22:39.894Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/56/d3/ea5f088e3638dbab12e5c20d6559d5b3bdaeaa1f2af74e526e6815836285/gymnasium-1.2.3-py3-none-any.whl", hash = "sha256:e6314bba8f549c7fdcc8677f7cd786b64908af6e79b57ddaa5ce1825bffb5373", size = 952113, upload-time = "2025-12-18T16:51:08.445Z" }, + { url = "https://files.pythonhosted.org/packages/ef/73/85bc0412f15388e3068dc93331c858df6c8fc635b1e3cb30c7f7070ca481/gymnasium-1.2.1-py3-none-any.whl", hash = "sha256:85cd1c16351db0b89f73be54e952ddfece97b56d1e5400d2dcd59f58b7707963", size = 951141, upload-time = "2025-09-23T08:22:38.117Z" }, ] [[package]] @@ -1483,6 +1651,13 @@ version = "0.6.4" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/a7/9a/ce5e1f7e131522e6d3426e8e7a490b3a01f39a6696602e1c4f33f9e94277/httptools-0.6.4.tar.gz", hash = "sha256:4e93eee4add6493b59a5c514da98c939b244fce4a0d8879cd3f466562f4b7d5c", size = 240639, upload-time = "2024-10-16T19:45:08.902Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/7b/26/bb526d4d14c2774fe07113ca1db7255737ffbb119315839af2065abfdac3/httptools-0.6.4-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:f47f8ed67cc0ff862b84a1189831d1d33c963fb3ce1ee0c65d3b0cbe7b711069", size = 199029, upload-time = "2024-10-16T19:44:18.427Z" }, + { url = "https://files.pythonhosted.org/packages/a6/17/3e0d3e9b901c732987a45f4f94d4e2c62b89a041d93db89eafb262afd8d5/httptools-0.6.4-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:0614154d5454c21b6410fdf5262b4a3ddb0f53f1e1721cfd59d55f32138c578a", size = 103492, upload-time = "2024-10-16T19:44:19.515Z" }, + { url = "https://files.pythonhosted.org/packages/b7/24/0fe235d7b69c42423c7698d086d4db96475f9b50b6ad26a718ef27a0bce6/httptools-0.6.4-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f8787367fbdfccae38e35abf7641dafc5310310a5987b689f4c32cc8cc3ee975", size = 462891, upload-time = "2024-10-16T19:44:21.067Z" }, + { url = "https://files.pythonhosted.org/packages/b1/2f/205d1f2a190b72da6ffb5f41a3736c26d6fa7871101212b15e9b5cd8f61d/httptools-0.6.4-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:40b0f7fe4fd38e6a507bdb751db0379df1e99120c65fbdc8ee6c1d044897a636", size = 459788, upload-time = "2024-10-16T19:44:22.958Z" }, + { url = "https://files.pythonhosted.org/packages/6e/4c/d09ce0eff09057a206a74575ae8f1e1e2f0364d20e2442224f9e6612c8b9/httptools-0.6.4-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:40a5ec98d3f49904b9fe36827dcf1aadfef3b89e2bd05b0e35e94f97c2b14721", size = 433214, upload-time = "2024-10-16T19:44:24.513Z" }, + { url = "https://files.pythonhosted.org/packages/3e/d2/84c9e23edbccc4a4c6f96a1b8d99dfd2350289e94f00e9ccc7aadde26fb5/httptools-0.6.4-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:dacdd3d10ea1b4ca9df97a0a303cbacafc04b5cd375fa98732678151643d4988", size = 434120, upload-time = "2024-10-16T19:44:26.295Z" }, + { url = "https://files.pythonhosted.org/packages/d0/46/4d8e7ba9581416de1c425b8264e2cadd201eb709ec1584c381f3e98f51c1/httptools-0.6.4-cp311-cp311-win_amd64.whl", hash = "sha256:288cd628406cc53f9a541cfaf06041b4c71d751856bab45e3702191f931ccd17", size = 88565, upload-time = "2024-10-16T19:44:29.188Z" }, { url = "https://files.pythonhosted.org/packages/bb/0e/d0b71465c66b9185f90a091ab36389a7352985fe857e352801c39d6127c8/httptools-0.6.4-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:df017d6c780287d5c80601dafa31f17bddb170232d85c066604d8558683711a2", size = 200683, upload-time = "2024-10-16T19:44:30.175Z" }, { url = "https://files.pythonhosted.org/packages/e2/b8/412a9bb28d0a8988de3296e01efa0bd62068b33856cdda47fe1b5e890954/httptools-0.6.4-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:85071a1e8c2d051b507161f6c3e26155b5c790e4e28d7f236422dbacc2a9cc44", size = 104337, upload-time = "2024-10-16T19:44:31.786Z" }, { url = "https://files.pythonhosted.org/packages/9b/01/6fb20be3196ffdc8eeec4e653bc2a275eca7f36634c86302242c4fbb2760/httptools-0.6.4-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:69422b7f458c5af875922cdb5bd586cc1f1033295aa9ff63ee196a87519ac8e1", size = 508796, upload-time = "2024-10-16T19:44:32.825Z" }, @@ -1598,6 +1773,7 @@ dependencies = [ { name = "pygments" }, { name = "stack-data" }, { name = "traitlets" }, + { name = "typing-extensions", marker = "python_full_version < '3.12'" }, ] sdist = { url = "https://files.pythonhosted.org/packages/2a/34/29b18c62e39ee2f7a6a3bba7efd952729d8aadd45ca17efc34453b717665/ipython-9.6.0.tar.gz", hash = "sha256:5603d6d5d356378be5043e69441a072b50a5b33b4503428c77b04cb8ce7bc731", size = 4396932, upload-time = "2025-09-29T10:55:53.948Z" } wheels = [ @@ -1655,48 +1831,45 @@ wheels = [ [[package]] name = "jax" -version = "0.9.2" +version = "0.5.3" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "jaxlib" }, - { name = "ml-dtypes" }, + { name = "ml-dtypes", version = "0.4.1", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.13'" }, + { name = "ml-dtypes", version = "0.5.4", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.13'" }, { name = "numpy" }, { name = "opt-einsum" }, { name = "scipy" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/92/4c/5aca25abd45fa38dd136e5ae2010376518c67950e1f9408e0c5c93fcf77d/jax-0.9.2.tar.gz", hash = "sha256:42b28017b3e6b57a44b0274cc15f5153239c4873959030399ac1afc009c22365", size = 2662784, upload-time = "2026-03-18T23:28:10.471Z" } +sdist = { url = "https://files.pythonhosted.org/packages/13/e5/dabb73ab10330e9535aba14fc668b04a46fcd8e78f06567c4f4f1adce340/jax-0.5.3.tar.gz", hash = "sha256:f17fcb0fd61dc289394af6ce4de2dada2312f2689bb0d73642c6f026a95fbb2c", size = 2072748, upload-time = "2025-03-19T18:23:40.901Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/17/9c/e897231c880f69e32251d3b1145894d7a04e4342d9bef8d29644c440d11b/jax-0.9.2-py3-none-any.whl", hash = "sha256:822a8ae155ab42e7bc59f2ae7a28705bcfccb01a7e76abfc8ae996190cdc5598", size = 3099142, upload-time = "2026-03-18T23:25:59.94Z" }, + { url = "https://files.pythonhosted.org/packages/86/bb/fdc6513a9aada13fd21e9860e2adee5f6eea2b4f0a145b219288875acb26/jax-0.5.3-py3-none-any.whl", hash = "sha256:1483dc237b4f47e41755d69429e8c3c138736716147cd43bb2b99b259d4e3c41", size = 2406371, upload-time = "2025-03-19T18:23:38.952Z" }, ] [[package]] name = "jaxlib" -version = "0.9.2" +version = "0.5.3" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "ml-dtypes" }, + { name = "ml-dtypes", version = "0.4.1", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.13'" }, + { name = "ml-dtypes", version = "0.5.4", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.13'" }, { name = "numpy" }, { name = "scipy" }, ] wheels = [ - { url = "https://files.pythonhosted.org/packages/51/15/ff3d9fde15b5146a0164505085312d8c9c0b0bbd7be5a15218ead2593307/jaxlib-0.9.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:97c2fbe58cbee4a27d94ca735d709d231b299ab6ed8b3b1075f52d864dfd32c1", size = 58770928, upload-time = "2026-03-18T23:27:08.94Z" }, - { url = "https://files.pythonhosted.org/packages/88/79/699aa47d2256b2edbb75a68a8f1a1ee4d34dfb84b8842a963caeb9a8cb03/jaxlib-0.9.2-cp312-cp312-manylinux_2_27_aarch64.whl", hash = "sha256:fef02d846863b726e72452993883a8596eac325f22a2ec7ea921da0fbc5509b4", size = 77733913, upload-time = "2026-03-18T23:27:12.927Z" }, - { url = "https://files.pythonhosted.org/packages/33/a0/ddb3a71359c1df61f3edc408936b5bda7ed402e78ae7e9ef6afd438577c6/jaxlib-0.9.2-cp312-cp312-manylinux_2_27_x86_64.whl", hash = "sha256:88b276a71f4f2071b1fd2e922abfd67c87c6977a551a1036febcea78d5ef7e22", size = 83318134, upload-time = "2026-03-18T23:27:16.237Z" }, - { url = "https://files.pythonhosted.org/packages/2d/57/09d6a9e2a8bc8e3ea79eb8e980f8ea2aea2d9dec3793755f5765657f6e11/jaxlib-0.9.2-cp312-cp312-win_amd64.whl", hash = "sha256:c2f0837cc0788746301e68ae9eda468e6a8a7734dc4d529f26a2cb60fb56c657", size = 62846539, upload-time = "2026-03-18T23:27:19.869Z" }, - { url = "https://files.pythonhosted.org/packages/09/d5/e5416c39e77eb1987479ef3b67930af9e78ecf65e7eb8a6cbe40b2aa0b66/jaxlib-0.9.2-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:52a0032508f8cf5791c7a7bee142531ee706c3c05518117fb0b6ee8d5e17fde7", size = 58772433, upload-time = "2026-03-18T23:27:23.188Z" }, - { url = "https://files.pythonhosted.org/packages/56/57/f3d4bda9dcaae11f32fcbb29d7ecda1c36689b289f04b9e6902647876c0c/jaxlib-0.9.2-cp313-cp313-manylinux_2_27_aarch64.whl", hash = "sha256:bef61eef36ed38cec1069ea973f88af9e03335e884f6501ec3fe7f6222a1555b", size = 77736401, upload-time = "2026-03-18T23:27:26.387Z" }, - { url = "https://files.pythonhosted.org/packages/a5/52/203497d40f365a6b4f924ad49d93d226d6853b3ada198623c96c11500027/jaxlib-0.9.2-cp313-cp313-manylinux_2_27_x86_64.whl", hash = "sha256:b6d5003e3add5c346a34ae9edc47058cbc2db60c8ed5c50096522176daf01c9f", size = 83319274, upload-time = "2026-03-18T23:27:30.025Z" }, - { url = "https://files.pythonhosted.org/packages/c7/25/2d585ecf7cb4c982387b4f35ae6da8beb09d05665370bbff56b772e22925/jaxlib-0.9.2-cp313-cp313-win_amd64.whl", hash = "sha256:2d445dab57debd8c26b416c8bc91a4704ba6d7169788a961e4b15419bc3f4254", size = 62847296, upload-time = "2026-03-18T23:27:33.362Z" }, - { url = "https://files.pythonhosted.org/packages/38/a9/a458a576f14c61de7a53105aa292acdb2f510352b44278dfe24b926f6d4a/jaxlib-0.9.2-cp313-cp313t-macosx_11_0_arm64.whl", hash = "sha256:6ffb22eccf07bfc8c9760bfbcdaa268df9b3745739e8397bfce5daee5d79cb51", size = 58880385, upload-time = "2026-03-18T23:27:36.297Z" }, - { url = "https://files.pythonhosted.org/packages/5b/10/7eb27c376691f7864becf27844b3c818f015e86e9f8390614c0048c2e62e/jaxlib-0.9.2-cp313-cp313t-manylinux_2_27_aarch64.whl", hash = "sha256:6949d7ecd869c117e7ea8361866e60cf229c3cd9d6afdc37425a43cf83fc89e9", size = 77849690, upload-time = "2026-03-18T23:27:39.943Z" }, - { url = "https://files.pythonhosted.org/packages/80/e0/0bc84ff53bbc599a9925fa7017a226c646de6569ba1871b36694af8e200a/jaxlib-0.9.2-cp313-cp313t-manylinux_2_27_x86_64.whl", hash = "sha256:e8e8165f0f647933f0ff9e1e4d9937d541841d3672a20db73f5ccb5e842b0edc", size = 83427722, upload-time = "2026-03-18T23:27:43.391Z" }, - { url = "https://files.pythonhosted.org/packages/75/06/aa1e2c36db1ed893ea4a89528a9cc8617a31919ffe7307c4f56aaa87e5cc/jaxlib-0.9.2-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:bab168d25555464461bd077323484f690c471e69ce8b0c39a39fb81b3e3a8bf0", size = 58776023, upload-time = "2026-03-18T23:27:46.907Z" }, - { url = "https://files.pythonhosted.org/packages/e5/ed/7f2cd3c9d91c95457f503311be4bc648b3a4aa79bfe1c874b16fa54c2207/jaxlib-0.9.2-cp314-cp314-manylinux_2_27_aarch64.whl", hash = "sha256:be4627c42d44add7fe17d284ef579ff8d159e3cb6947f6437758f34177e878e6", size = 77748670, upload-time = "2026-03-18T23:27:50.009Z" }, - { url = "https://files.pythonhosted.org/packages/c0/a1/461f25959e9eb0a46722d00c01cfb1dd82e8889dfa1c228f13e0cfbe948d/jaxlib-0.9.2-cp314-cp314-manylinux_2_27_x86_64.whl", hash = "sha256:3d7151140a4936f3218b2d1b1343dd237bd2865cf51442884b6d82fe884a3de7", size = 83330703, upload-time = "2026-03-18T23:27:54.578Z" }, - { url = "https://files.pythonhosted.org/packages/21/98/34a9d156f61777abd9d4e74781fcd99fcf1bb77533e617c2d0ee1c5602fe/jaxlib-0.9.2-cp314-cp314-win_amd64.whl", hash = "sha256:87bd42c9f18c9cc9a45371d02ecdbdb574ea1e2277149601a92e14a24c4bbc86", size = 65247657, upload-time = "2026-03-18T23:27:57.855Z" }, - { url = "https://files.pythonhosted.org/packages/ea/c9/5653eb4be25a3235be2606e1e8fb28fb8c6f0f48b33b947e47f0dc7e7ec0/jaxlib-0.9.2-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:b8998f9fa6e67bf956044c310023f6a7bbfaa0d8955f11d928404c8f6eb02fcf", size = 58882789, upload-time = "2026-03-18T23:28:00.834Z" }, - { url = "https://files.pythonhosted.org/packages/41/8d/ef12f6a2f158d47480cded343c85078a02e9fc7d4952dafcd95dab6f9127/jaxlib-0.9.2-cp314-cp314t-manylinux_2_27_aarch64.whl", hash = "sha256:35b473df72dbc2cfda0cb1b3de7521a2150a0aa5ef57ed7583eeceb012dc17c0", size = 77850880, upload-time = "2026-03-18T23:28:04.063Z" }, - { url = "https://files.pythonhosted.org/packages/c9/6a/6dff1e6e3f9d918bc777e087091bdefbd7d33328c1d1b152429c6cdcf723/jaxlib-0.9.2-cp314-cp314t-manylinux_2_27_x86_64.whl", hash = "sha256:bbe59bdef668ff5fd998c6d88e8df9a32ab95bec0dea3d2b5f7a11b86a9a6788", size = 83425685, upload-time = "2026-03-18T23:28:07.906Z" }, + { url = "https://files.pythonhosted.org/packages/c2/f2/d9397f264141f2289e229b2faf3b3ddb6397b014a09abe234367814f9697/jaxlib-0.5.3-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:b62bd8b29e5a4f9bfaa57c8daf6e04820b2c994f448f3dec602d64255545e9f2", size = 63696815, upload-time = "2025-03-19T18:24:14.662Z" }, + { url = "https://files.pythonhosted.org/packages/e8/91/04bf391a21ccfb299b9952f91d5c082e5f9877221e5d98592875af4a50e4/jaxlib-0.5.3-cp311-cp311-manylinux2014_aarch64.whl", hash = "sha256:a4666f81d72c060ed3e581ded116a9caa9b0a70a148a54cb12a1d3afca3624b5", size = 95770114, upload-time = "2025-03-19T18:24:19.498Z" }, + { url = "https://files.pythonhosted.org/packages/67/de/50debb40944baa5ba459604578f8c721be9f38c78ef9e8902895566e6a66/jaxlib-0.5.3-cp311-cp311-manylinux2014_x86_64.whl", hash = "sha256:29e1530fc81833216f1e28b578d0c59697654f72ee31c7a44ed7753baf5ac466", size = 105119259, upload-time = "2025-03-19T18:24:25.39Z" }, + { url = "https://files.pythonhosted.org/packages/20/91/d73c842d1e5cc6b914bb521006d668fbfda4c53cd4424ce9c3a097f6c071/jaxlib-0.5.3-cp311-cp311-win_amd64.whl", hash = "sha256:8eb54e38d789557579f900ea3d70f104a440f8555a9681ed45f4a122dcbfd92e", size = 65765739, upload-time = "2025-03-19T18:24:30.264Z" }, + { url = "https://files.pythonhosted.org/packages/d5/a5/646af791ccf75641b4df84fb6cb6e3914b0df87ec5fa5f82397fd5dc30ee/jaxlib-0.5.3-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:d394dbde4a1c6bd67501cfb29d3819a10b900cb534cc0fc603319f7092f24cfa", size = 63711839, upload-time = "2025-03-19T18:24:34.555Z" }, + { url = "https://files.pythonhosted.org/packages/53/8c/cbd861e40f0efe7923962ade21919fddcea43fae2794634833e800009b14/jaxlib-0.5.3-cp312-cp312-manylinux2014_aarch64.whl", hash = "sha256:bddf6360377aa1c792e47fd87f307c342e331e5ff3582f940b1bca00f6b4bc73", size = 95764647, upload-time = "2025-03-19T18:24:39.376Z" }, + { url = "https://files.pythonhosted.org/packages/3e/03/bace4acec295febca9329b3d2dd927b8ac74841e620e0d675f76109b805b/jaxlib-0.5.3-cp312-cp312-manylinux2014_x86_64.whl", hash = "sha256:5a5e88ab1cd6fdf78d69abe3544e8f09cce200dd339bb85fbe3c2ea67f2a5e68", size = 105132789, upload-time = "2025-03-19T18:24:45.232Z" }, + { url = "https://files.pythonhosted.org/packages/79/f8/34568ec75f53d55b68649b6e1d6befd976fb9646e607954477264f5379ce/jaxlib-0.5.3-cp312-cp312-win_amd64.whl", hash = "sha256:520665929649f29f7d948d4070dbaf3e032a4c1f7c11f2863eac73320fcee784", size = 65789714, upload-time = "2025-03-19T18:24:51.218Z" }, + { url = "https://files.pythonhosted.org/packages/b4/d0/ed6007cd17dc0f37f950f89e785092d9f0541f3fa6021d029657955206b5/jaxlib-0.5.3-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:31321c25282a06a6dfc940507bc14d0a0ac838d8ced6c07aa00a7fae34ce7b3f", size = 63710483, upload-time = "2025-03-19T18:24:55.41Z" }, + { url = "https://files.pythonhosted.org/packages/36/8f/cafdf24170084de897ffe2a030241c2ba72d12eede85b940a81a94cab156/jaxlib-0.5.3-cp313-cp313-manylinux2014_aarch64.whl", hash = "sha256:e904b92dedfbc7e545725a8d7676987030ae9c069001d94701bc109c6dab4100", size = 95765995, upload-time = "2025-03-19T18:25:00.062Z" }, + { url = "https://files.pythonhosted.org/packages/86/c7/fc0755ebd999c7c66ac4203d99f958d5ffc0a34eb270f57932ca0213bb54/jaxlib-0.5.3-cp313-cp313-manylinux2014_x86_64.whl", hash = "sha256:bb7593cb7fffcb13963f22fa5229ed960b8fb4ae5ec3b0820048cbd67f1e8e31", size = 105130796, upload-time = "2025-03-19T18:25:05.574Z" }, + { url = "https://files.pythonhosted.org/packages/83/98/e32da21a490dc408d172ba246d6c47428482fe50d771c3f813e5fc063781/jaxlib-0.5.3-cp313-cp313-win_amd64.whl", hash = "sha256:8019f73a10b1290f988dd3768c684f3a8a147239091c3b790ce7e47e3bbc00bd", size = 65792205, upload-time = "2025-03-19T18:25:10.684Z" }, + { url = "https://files.pythonhosted.org/packages/88/c6/0d69ed0d408c811959a471563afa99baecacdc56ed1799002e309520b565/jaxlib-0.5.3-cp313-cp313t-manylinux2014_x86_64.whl", hash = "sha256:4c9a9d4cda091a3ef068ace8379fff9e98eea2fc51dbdd7c3386144a1bdf715d", size = 105318736, upload-time = "2025-03-25T15:00:12.514Z" }, ] [[package]] @@ -1901,6 +2074,7 @@ dependencies = [ { name = "jupyter-server-terminals" }, { name = "nbconvert" }, { name = "nbformat" }, + { name = "overrides", marker = "python_full_version < '3.12'" }, { name = "packaging" }, { name = "prometheus-client" }, { name = "pywinpty", marker = "(os_name == 'nt' and platform_machine != 'aarch64' and sys_platform == 'linux') or (os_name == 'nt' and sys_platform != 'darwin' and sys_platform != 'linux')" }, @@ -2040,6 +2214,19 @@ version = "1.4.9" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/5c/3c/85844f1b0feb11ee581ac23fe5fce65cd049a200c1446708cc1b7f922875/kiwisolver-1.4.9.tar.gz", hash = "sha256:c3b22c26c6fd6811b0ae8363b95ca8ce4ea3c202d3d0975b2914310ceb1bcc4d", size = 97564, upload-time = "2025-08-10T21:27:49.279Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/6f/ab/c80b0d5a9d8a1a65f4f815f2afff9798b12c3b9f31f1d304dd233dd920e2/kiwisolver-1.4.9-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:eb14a5da6dc7642b0f3a18f13654847cd8b7a2550e2645a5bda677862b03ba16", size = 124167, upload-time = "2025-08-10T21:25:53.403Z" }, + { url = "https://files.pythonhosted.org/packages/a0/c0/27fe1a68a39cf62472a300e2879ffc13c0538546c359b86f149cc19f6ac3/kiwisolver-1.4.9-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:39a219e1c81ae3b103643d2aedb90f1ef22650deb266ff12a19e7773f3e5f089", size = 66579, upload-time = "2025-08-10T21:25:54.79Z" }, + { url = "https://files.pythonhosted.org/packages/31/a2/a12a503ac1fd4943c50f9822678e8015a790a13b5490354c68afb8489814/kiwisolver-1.4.9-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:2405a7d98604b87f3fc28b1716783534b1b4b8510d8142adca34ee0bc3c87543", size = 65309, upload-time = "2025-08-10T21:25:55.76Z" }, + { url = "https://files.pythonhosted.org/packages/66/e1/e533435c0be77c3f64040d68d7a657771194a63c279f55573188161e81ca/kiwisolver-1.4.9-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:dc1ae486f9abcef254b5618dfb4113dd49f94c68e3e027d03cf0143f3f772b61", size = 1435596, upload-time = "2025-08-10T21:25:56.861Z" }, + { url = "https://files.pythonhosted.org/packages/67/1e/51b73c7347f9aabdc7215aa79e8b15299097dc2f8e67dee2b095faca9cb0/kiwisolver-1.4.9-cp311-cp311-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:8a1f570ce4d62d718dce3f179ee78dac3b545ac16c0c04bb363b7607a949c0d1", size = 1246548, upload-time = "2025-08-10T21:25:58.246Z" }, + { url = "https://files.pythonhosted.org/packages/21/aa/72a1c5d1e430294f2d32adb9542719cfb441b5da368d09d268c7757af46c/kiwisolver-1.4.9-cp311-cp311-manylinux_2_24_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:cb27e7b78d716c591e88e0a09a2139c6577865d7f2e152488c2cc6257f460872", size = 1263618, upload-time = "2025-08-10T21:25:59.857Z" }, + { url = "https://files.pythonhosted.org/packages/a3/af/db1509a9e79dbf4c260ce0cfa3903ea8945f6240e9e59d1e4deb731b1a40/kiwisolver-1.4.9-cp311-cp311-manylinux_2_24_s390x.manylinux_2_28_s390x.whl", hash = "sha256:15163165efc2f627eb9687ea5f3a28137217d217ac4024893d753f46bce9de26", size = 1317437, upload-time = "2025-08-10T21:26:01.105Z" }, + { url = "https://files.pythonhosted.org/packages/e0/f2/3ea5ee5d52abacdd12013a94130436e19969fa183faa1e7c7fbc89e9a42f/kiwisolver-1.4.9-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:bdee92c56a71d2b24c33a7d4c2856bd6419d017e08caa7802d2963870e315028", size = 2195742, upload-time = "2025-08-10T21:26:02.675Z" }, + { url = "https://files.pythonhosted.org/packages/6f/9b/1efdd3013c2d9a2566aa6a337e9923a00590c516add9a1e89a768a3eb2fc/kiwisolver-1.4.9-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:412f287c55a6f54b0650bd9b6dce5aceddb95864a1a90c87af16979d37c89771", size = 2290810, upload-time = "2025-08-10T21:26:04.009Z" }, + { url = "https://files.pythonhosted.org/packages/fb/e5/cfdc36109ae4e67361f9bc5b41323648cb24a01b9ade18784657e022e65f/kiwisolver-1.4.9-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:2c93f00dcba2eea70af2be5f11a830a742fe6b579a1d4e00f47760ef13be247a", size = 2461579, upload-time = "2025-08-10T21:26:05.317Z" }, + { url = "https://files.pythonhosted.org/packages/62/86/b589e5e86c7610842213994cdea5add00960076bef4ae290c5fa68589cac/kiwisolver-1.4.9-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:f117e1a089d9411663a3207ba874f31be9ac8eaa5b533787024dc07aeb74f464", size = 2268071, upload-time = "2025-08-10T21:26:06.686Z" }, + { url = "https://files.pythonhosted.org/packages/3b/c6/f8df8509fd1eee6c622febe54384a96cfaf4d43bf2ccec7a0cc17e4715c9/kiwisolver-1.4.9-cp311-cp311-win_amd64.whl", hash = "sha256:be6a04e6c79819c9a8c2373317d19a96048e5a3f90bec587787e86a1153883c2", size = 73840, upload-time = "2025-08-10T21:26:07.94Z" }, + { url = "https://files.pythonhosted.org/packages/e2/2d/16e0581daafd147bc11ac53f032a2b45eabac897f42a338d0a13c1e5c436/kiwisolver-1.4.9-cp311-cp311-win_arm64.whl", hash = "sha256:0ae37737256ba2de764ddc12aed4956460277f00c4996d51a197e72f62f5eec7", size = 65159, upload-time = "2025-08-10T21:26:09.048Z" }, { url = "https://files.pythonhosted.org/packages/86/c9/13573a747838aeb1c76e3267620daa054f4152444d1f3d1a2324b78255b5/kiwisolver-1.4.9-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:ac5a486ac389dddcc5bef4f365b6ae3ffff2c433324fb38dd35e3fab7c957999", size = 123686, upload-time = "2025-08-10T21:26:10.034Z" }, { url = "https://files.pythonhosted.org/packages/51/ea/2ecf727927f103ffd1739271ca19c424d0e65ea473fbaeea1c014aea93f6/kiwisolver-1.4.9-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:f2ba92255faa7309d06fe44c3a4a97efe1c8d640c2a79a5ef728b685762a6fd2", size = 66460, upload-time = "2025-08-10T21:26:11.083Z" }, { url = "https://files.pythonhosted.org/packages/5b/5a/51f5464373ce2aeb5194508298a508b6f21d3867f499556263c64c621914/kiwisolver-1.4.9-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:4a2899935e724dd1074cb568ce7ac0dce28b2cd6ab539c8e001a8578eb106d14", size = 64952, upload-time = "2025-08-10T21:26:12.058Z" }, @@ -2104,6 +2291,11 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/99/dd/841e9a66c4715477ea0abc78da039832fbb09dac5c35c58dc4c41a407b8a/kiwisolver-1.4.9-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:aedff62918805fb62d43a4aa2ecd4482c380dc76cd31bd7c8878588a61bd0369", size = 2391835, upload-time = "2025-08-10T21:27:34.23Z" }, { url = "https://files.pythonhosted.org/packages/0c/28/4b2e5c47a0da96896fdfdb006340ade064afa1e63675d01ea5ac222b6d52/kiwisolver-1.4.9-cp314-cp314t-win_amd64.whl", hash = "sha256:1fa333e8b2ce4d9660f2cda9c0e1b6bafcfb2457a9d259faa82289e73ec24891", size = 79988, upload-time = "2025-08-10T21:27:35.587Z" }, { url = "https://files.pythonhosted.org/packages/80/be/3578e8afd18c88cdf9cb4cffde75a96d2be38c5a903f1ed0ceec061bd09e/kiwisolver-1.4.9-cp314-cp314t-win_arm64.whl", hash = "sha256:4a48a2ce79d65d363597ef7b567ce3d14d68783d2b2263d98db3d9477805ba32", size = 70260, upload-time = "2025-08-10T21:27:36.606Z" }, + { url = "https://files.pythonhosted.org/packages/a3/0f/36d89194b5a32c054ce93e586d4049b6c2c22887b0eb229c61c68afd3078/kiwisolver-1.4.9-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:720e05574713db64c356e86732c0f3c5252818d05f9df320f0ad8380641acea5", size = 60104, upload-time = "2025-08-10T21:27:43.287Z" }, + { url = "https://files.pythonhosted.org/packages/52/ba/4ed75f59e4658fd21fe7dde1fee0ac397c678ec3befba3fe6482d987af87/kiwisolver-1.4.9-pp311-pypy311_pp73-macosx_11_0_arm64.whl", hash = "sha256:17680d737d5335b552994a2008fab4c851bcd7de33094a82067ef3a576ff02fa", size = 58592, upload-time = "2025-08-10T21:27:44.314Z" }, + { url = "https://files.pythonhosted.org/packages/33/01/a8ea7c5ea32a9b45ceeaee051a04c8ed4320f5add3c51bfa20879b765b70/kiwisolver-1.4.9-pp311-pypy311_pp73-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:85b5352f94e490c028926ea567fc569c52ec79ce131dadb968d3853e809518c2", size = 80281, upload-time = "2025-08-10T21:27:45.369Z" }, + { url = "https://files.pythonhosted.org/packages/da/e3/dbd2ecdce306f1d07a1aaf324817ee993aab7aee9db47ceac757deabafbe/kiwisolver-1.4.9-pp311-pypy311_pp73-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:464415881e4801295659462c49461a24fb107c140de781d55518c4b80cb6790f", size = 78009, upload-time = "2025-08-10T21:27:46.376Z" }, + { url = "https://files.pythonhosted.org/packages/da/e9/0d4add7873a73e462aeb45c036a2dead2562b825aa46ba326727b3f31016/kiwisolver-1.4.9-pp311-pypy311_pp73-win_amd64.whl", hash = "sha256:fb940820c63a9590d31d88b815e7a3aa5915cad3ce735ab45f0c730b39547de1", size = 73929, upload-time = "2025-08-10T21:27:48.236Z" }, ] [[package]] @@ -2117,6 +2309,11 @@ dependencies = [ ] sdist = { url = "https://files.pythonhosted.org/packages/93/0a/139c4ae896b9413bd4ca69c62b08ee98dcfc78a9cbfdb7cadd0dce2ad31d/labmaze-1.0.6.tar.gz", hash = "sha256:2e8de7094042a77d6972f1965cf5c9e8f971f1b34d225752f343190a825ebe73", size = 4670455, upload-time = "2022-12-05T18:42:43.566Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/6d/3c/cdc95db2aa8cd80c193b7b30b9a9be071897c4f0b558d5fc007b1adf74c3/labmaze-1.0.6-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:a0c2cb9dec971814ea9c5d7150af15fa3964482131fa969e0afb94bd224348af", size = 4815406, upload-time = "2022-12-05T18:42:00.412Z" }, + { url = "https://files.pythonhosted.org/packages/75/46/eb96e23ccddd40f403cea3f9f5d15eae7759317a1762b761692541edd6d9/labmaze-1.0.6-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:2c6ba9538d819543f4be448d36b4926a3881e53646a2b331ebb5a1f353047d05", size = 4806777, upload-time = "2022-12-05T18:42:02.345Z" }, + { url = "https://files.pythonhosted.org/packages/0d/7e/787e0d3c17e29a46484158460e21fcf5cd7a076c81b2ec31807f2753ea43/labmaze-1.0.6-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:70635d1cdb0147a02efb6b3f607a52cdc51723bc3dcc42717a0d4ef55fa0a987", size = 4871563, upload-time = "2022-12-05T18:42:04.538Z" }, + { url = "https://files.pythonhosted.org/packages/a7/ce/be3952d7036b009f6dd004b6f5dfe97bbff79572ef0cf56a734aaead030f/labmaze-1.0.6-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ff472793238bd9b6dabea8094594d6074ad3c111455de3afcae72f6c40c6817e", size = 4875913, upload-time = "2022-12-05T18:42:06.969Z" }, + { url = "https://files.pythonhosted.org/packages/50/a5/8c9f9be038401a31f9f87bd44f28c8edff63c0c3f1168ca882e351215761/labmaze-1.0.6-cp311-cp311-win_amd64.whl", hash = "sha256:2317e65e12fa3d1abecda7e0488dab15456cee8a2e717a586bfc8f02a91579e7", size = 4813089, upload-time = "2022-12-05T18:42:09.481Z" }, { url = "https://files.pythonhosted.org/packages/cf/12/670a6e6beeeb166aa911fe861c1a16f62a9f3cfc7b54ea4b114cc23d0380/labmaze-1.0.6-cp312-cp312-macosx_10_12_x86_64.whl", hash = "sha256:e36b6fadcd78f22057b597c1c77823e806a0987b3bdfbf850e14b6b5b502075e", size = 4814941, upload-time = "2023-10-04T16:54:25.613Z" }, { url = "https://files.pythonhosted.org/packages/e5/3a/47a3f83736e0b70f78b22d53e0a3230160a61e8ba6267003f25d2b24b832/labmaze-1.0.6-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:d1a4f8de29c2c3d7f14163759b69cd3f237093b85334c983619c1db5403a223b", size = 4807545, upload-time = "2023-10-04T16:56:00.113Z" }, { url = "https://files.pythonhosted.org/packages/ad/95/2ca4dd1efff4456f44baf4c4a980cfea6f6fb8729912a760ec9bf912876b/labmaze-1.0.6-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a394f8bb857fcaa2884b809d63e750841c2662a106cfe8c045f2112d201ac7d5", size = 4873133, upload-time = "2023-10-04T17:32:24.246Z" }, @@ -2160,6 +2357,22 @@ version = "6.1.0" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/28/30/9abc9e34c657c33834eaf6cd02124c61bdf5944d802aa48e69be8da3585d/lxml-6.1.0.tar.gz", hash = "sha256:bfd57d8008c4965709a919c3e9a98f76c2c7cb319086b3d26858250620023b13", size = 4197006, upload-time = "2026-04-18T04:32:51.613Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/5e/5d/3bccad330292946f97962df9d5f2d3ae129cce6e212732a781e856b91e07/lxml-6.1.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:cec05be8c876f92a5aa07b01d60bbb4d11cfbdd654cad0561c0d7b5c043a61b9", size = 8526232, upload-time = "2026-04-18T04:27:40.389Z" }, + { url = "https://files.pythonhosted.org/packages/a7/51/adc8826570a112f83bb4ddb3a2ab510bbc2ccd62c1b9fe1f34fae2d90b57/lxml-6.1.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:9c03e048b6ce8e77b09c734e931584894ecd58d08296804ca2d0b184c933ce50", size = 4595448, upload-time = "2026-04-18T04:27:44.208Z" }, + { url = "https://files.pythonhosted.org/packages/54/84/5a9ec07cbe1d2334a6465f863b949a520d2699a755738986dcd3b6b89e3f/lxml-6.1.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:942454ff253da14218f972b23dc72fa4edf6c943f37edd19cd697618b626fac5", size = 4923771, upload-time = "2026-04-18T04:32:17.402Z" }, + { url = "https://files.pythonhosted.org/packages/a7/23/851cfa33b6b38adb628e45ad51fb27105fa34b2b3ba9d1d4aa7a9428dfe0/lxml-6.1.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:d036ee7b99d5148072ac7c9b847193decdfeac633db350363f7bce4fff108f0e", size = 5068101, upload-time = "2026-04-18T04:32:21.437Z" }, + { url = "https://files.pythonhosted.org/packages/b0/38/41bf99c2023c6b79916ba057d83e9db21d642f473cac210201222882d38b/lxml-6.1.0-cp311-cp311-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:3ae5d8d5427f3cc317e7950f2da7ad276df0cfa37b8de2f5658959e618ea8512", size = 5002573, upload-time = "2026-04-18T04:32:25.373Z" }, + { url = "https://files.pythonhosted.org/packages/c2/20/053aa10bdc39747e1e923ce2d45413075e84f70a136045bb09e5eaca41d3/lxml-6.1.0-cp311-cp311-manylinux_2_26_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:363e47283bde87051b821826e71dde47f107e08614e1aa312ba0c5711e77738c", size = 5202816, upload-time = "2026-04-18T04:32:29.393Z" }, + { url = "https://files.pythonhosted.org/packages/9a/da/bc710fad8bf04b93baee752c192eaa2210cd3a84f969d0be7830fea55802/lxml-6.1.0-cp311-cp311-manylinux_2_28_i686.whl", hash = "sha256:f504d861d9f2a8f94020130adac88d66de93841707a23a86244263d1e54682f5", size = 5329999, upload-time = "2026-04-18T04:32:34.019Z" }, + { url = "https://files.pythonhosted.org/packages/b3/cb/bf035dedbdf7fab49411aa52e4236f3445e98d38647d85419e6c0d2806b9/lxml-6.1.0-cp311-cp311-manylinux_2_31_armv7l.whl", hash = "sha256:23a5dc68e08ed13331d61815c08f260f46b4a60fdd1640bbeb82cf89a9d90289", size = 4659643, upload-time = "2026-04-18T04:32:37.932Z" }, + { url = "https://files.pythonhosted.org/packages/5c/4f/22be31f33727a5e4c7b01b0a874503026e50329b259d3587e0b923cf964b/lxml-6.1.0-cp311-cp311-manylinux_2_38_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:f15401d8d3dbf239e23c818afc10c7207f7b95f9a307e092122b6f86dd43209a", size = 5265963, upload-time = "2026-04-18T04:32:41.881Z" }, + { url = "https://files.pythonhosted.org/packages/c8/2b/d44d0e5c79226017f4ab8c87a802ebe4f89f97e6585a8e4166dffcdd7b6e/lxml-6.1.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:fcf3da95e93349e0647d48d4b36a12783105bcc74cb0c416952f9988410846a3", size = 5045444, upload-time = "2026-04-18T04:32:44.512Z" }, + { url = "https://files.pythonhosted.org/packages/d3/c3/3f034fec1594c331a6dbf9491238fdcc9d66f68cc529e109ec75b97197e1/lxml-6.1.0-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:0d082495c5fcf426e425a6e28daaba1fcb6d8f854a4ff01effb1f1f381203eb9", size = 4712703, upload-time = "2026-04-18T04:32:47.16Z" }, + { url = "https://files.pythonhosted.org/packages/12/16/0b83fccc158218aca75a7aa33e97441df737950734246b9fffa39301603d/lxml-6.1.0-cp311-cp311-musllinux_1_2_riscv64.whl", hash = "sha256:e3c4f84b24a1fcba435157d111c4b755099c6ff00a3daee1ad281817de75ed11", size = 5252745, upload-time = "2026-04-18T04:32:50.427Z" }, + { url = "https://files.pythonhosted.org/packages/dd/ee/12e6c1b39a77666c02eaa77f94a870aaf63c4ac3a497b2d52319448b01c6/lxml-6.1.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:976a6b39b1b13e8c354ad8d3f261f3a4ac6609518af91bdb5094760a08f132c4", size = 5226822, upload-time = "2026-04-18T04:32:53.437Z" }, + { url = "https://files.pythonhosted.org/packages/34/20/c7852904858b4723af01d2fc14b5d38ff57cb92f01934a127ebd9a9e51aa/lxml-6.1.0-cp311-cp311-win32.whl", hash = "sha256:857efde87d365706590847b916baff69c0bc9252dc5af030e378c9800c0b10e3", size = 3594026, upload-time = "2026-04-18T04:27:31.903Z" }, + { url = "https://files.pythonhosted.org/packages/02/05/d60c732b56da5085175c07c74b2df4e6d181b0c9a61e1691474f06ef4b39/lxml-6.1.0-cp311-cp311-win_amd64.whl", hash = "sha256:183bfb45a493081943be7ea2b5adfc2b611e1cf377cefa8b8a8be404f45ef9a7", size = 4025114, upload-time = "2026-04-18T04:27:34.077Z" }, + { url = "https://files.pythonhosted.org/packages/c2/df/c84dcc175fd690823436d15b41cb920cd5ba5e14cd8bfb00949d5903b320/lxml-6.1.0-cp311-cp311-win_arm64.whl", hash = "sha256:19f4164243fc206d12ed3d866e80e74f5bc3627966520da1a5f97e42c32a3f39", size = 3667742, upload-time = "2026-04-18T04:27:38.45Z" }, { url = "https://files.pythonhosted.org/packages/d2/d4/9326838b59dc36dfae42eec9656b97520f9997eee1de47b8316aaeed169c/lxml-6.1.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:d2f17a16cd8751e8eb233a7e41aecdf8e511712e00088bf9be455f604cd0d28d", size = 8570663, upload-time = "2026-04-18T04:27:48.253Z" }, { url = "https://files.pythonhosted.org/packages/d8/a4/053745ce1f8303ccbb788b86c0db3a91b973675cefc42566a188637b7c40/lxml-6.1.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:f0cea5b1d3e6e77d71bd2b9972eb2446221a69dc52bb0b9c3c6f6e5700592d93", size = 4624024, upload-time = "2026-04-18T04:27:52.594Z" }, { url = "https://files.pythonhosted.org/packages/90/97/a517944b20f8fd0932ad2109482bee4e29fe721416387a363306667941f6/lxml-6.1.0-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:fc46da94826188ed45cb53bd8e3fc076ae22675aea2087843d4735627f867c6d", size = 4930895, upload-time = "2026-04-18T04:32:56.29Z" }, @@ -2232,6 +2445,12 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/c2/ca/77123e4d77df3cb1e968ade7b1f808f5d3a5c1c96b18a33895397de292c1/lxml-6.1.0-cp314-cp314t-win32.whl", hash = "sha256:00750d63ef0031a05331b9223463b1c7c02b9004cef2346a5b2877f0f9494dd2", size = 3897377, upload-time = "2026-04-18T04:32:07.656Z" }, { url = "https://files.pythonhosted.org/packages/64/ce/3554833989d074267c063209bae8b09815e5656456a2d332b947806b05ff/lxml-6.1.0-cp314-cp314t-win_amd64.whl", hash = "sha256:80410c3a7e3c617af04de17caa9f9f20adaa817093293d69eae7d7d0522836f5", size = 4392701, upload-time = "2026-04-18T04:32:12.113Z" }, { url = "https://files.pythonhosted.org/packages/2b/a0/9b916c68c0e57752c07f8f64b30138d9d4059dbeb27b90274dedbea128ff/lxml-6.1.0-cp314-cp314t-win_arm64.whl", hash = "sha256:26dd9f57ee3bd41e7d35b4c98a2ffd89ed11591649f421f0ec19f67d50ec67ac", size = 3817120, upload-time = "2026-04-18T04:32:15.803Z" }, + { url = "https://files.pythonhosted.org/packages/f2/88/55143966481409b1740a3ac669e611055f49efd68087a5ce41582325db3e/lxml-6.1.0-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:546b66c0dd1bb8d9fa89d7123e5fa19a8aff3a1f2141eb22df96112afb17b842", size = 3930134, upload-time = "2026-04-18T04:32:35.008Z" }, + { url = "https://files.pythonhosted.org/packages/b5/97/28b985c2983938d3cb696dd5501423afb90a8c3e869ef5d3c62569282c0f/lxml-6.1.0-pp311-pypy311_pp73-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:5cfa1a34df366d9dc0d5eaf420f4cf2bb1e1bebe1066d1c2fc28c179f8a4004c", size = 4210749, upload-time = "2026-04-18T04:36:03.626Z" }, + { url = "https://files.pythonhosted.org/packages/29/67/dfab2b7d58214921935ccea7ce9b3df9b7d46f305d12f0f532ac7cf6b804/lxml-6.1.0-pp311-pypy311_pp73-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:db88156fcf544cdbf0d95588051515cfdfd4c876fc66444eb98bceb5d6db76de", size = 4318463, upload-time = "2026-04-18T04:36:06.309Z" }, + { url = "https://files.pythonhosted.org/packages/32/a2/4ac7eb32a4d997dd352c32c32399aae27b3f268d440e6f9cfa405b575d2f/lxml-6.1.0-pp311-pypy311_pp73-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:07f98f5496f96bf724b1e3c933c107f0cbf2745db18c03d2e13a291c3afd2635", size = 4251124, upload-time = "2026-04-18T04:36:09.056Z" }, + { url = "https://files.pythonhosted.org/packages/33/ef/d6abd850bb4822f9b720cfe36b547a558e694881010ff7d012191e8769c6/lxml-6.1.0-pp311-pypy311_pp73-manylinux_2_26_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:4642e04449a1e164b5ff71ffd901ddb772dfabf5c9adf1b7be5dffe1212bc037", size = 4401758, upload-time = "2026-04-18T04:36:11.803Z" }, + { url = "https://files.pythonhosted.org/packages/40/44/3ee09a5b60cb44c4f2fbc1c9015cfd6ff5afc08f991cab295d3024dcbf2d/lxml-6.1.0-pp311-pypy311_pp73-win_amd64.whl", hash = "sha256:7da13bb6fbadfafb474e0226a30570a3445cfd47c86296f2446dafbd77079ace", size = 3508860, upload-time = "2026-04-18T04:32:48.619Z" }, ] [[package]] @@ -2252,6 +2471,12 @@ dependencies = [ ] sdist = { url = "https://files.pythonhosted.org/packages/b0/fd/4dfc246e076e3912c45a821764f4de8b6c8117fa36fc67f8e44bf9dfe59b/manifold3d-3.4.1.tar.gz", hash = "sha256:b517927e2c15dc52169fff0cd12e1949eceb4ca49f3a5b8c0568b1116a561ab1", size = 269275, upload-time = "2026-03-24T06:22:40.062Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/af/14/42f1d0fbe0dbbaf7abd9ffb83596a84cea7b3d84c40f0c20a3474a23e397/manifold3d-3.4.1-cp311-cp311-macosx_10_14_universal2.whl", hash = "sha256:5b4ba7b71ffd6bf16682acff89cb72ade3eba54ea05d58d956c3a95d982ed8e4", size = 1753383, upload-time = "2026-03-24T06:21:45.602Z" }, + { url = "https://files.pythonhosted.org/packages/35/47/3d5369c2485c48c2510eab4e803b29296edecbce78c9069995731bff9635/manifold3d-3.4.1-cp311-cp311-macosx_10_14_x86_64.whl", hash = "sha256:095b072e89485f00af8aeed0a88e72c19f9740467824d6653b329851c3928c14", size = 956296, upload-time = "2026-03-24T06:21:47.257Z" }, + { url = "https://files.pythonhosted.org/packages/75/d4/d01a5579b636e49a106071365f82d0c7a695226cbc6dc077304e51bfc86f/manifold3d-3.4.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:539c2467abc58754b74dc9bb3422ddd4e73a5b11b006f27c0ba6302bab6ecfe9", size = 841995, upload-time = "2026-03-24T06:21:48.529Z" }, + { url = "https://files.pythonhosted.org/packages/d8/63/32c64efc0a34f23776dc339f8b1cdbcc61b12a80ade261f2e7a358af52d9/manifold3d-3.4.1-cp311-cp311-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:42c0c8ab2495acd514e8f46e5acd9465937c46c8c06e45e2f02da983b849bcea", size = 1252454, upload-time = "2026-03-24T06:21:50.317Z" }, + { url = "https://files.pythonhosted.org/packages/d7/f2/6c7ec5986bc3cfc9251878ade6e65354538a8bc569c5e51c483aa4310063/manifold3d-3.4.1-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:aa75de877ccda5482493f65659de240d4bb7c96e3cc4ce96509ecd6ef9f91fbc", size = 1353505, upload-time = "2026-03-24T06:21:52.428Z" }, + { url = "https://files.pythonhosted.org/packages/94/61/9e8ab3a9ce6e7e6099794afd25abe1e4e7934f31529c55331bf8019bc736/manifold3d-3.4.1-cp311-cp311-win_amd64.whl", hash = "sha256:2aff8707558e2fa5ff241185fe71da18ac8bd4156fb2811401df3366e461c562", size = 983641, upload-time = "2026-03-24T06:21:53.876Z" }, { url = "https://files.pythonhosted.org/packages/d9/59/def4c589dd55aa32026a720f8a31d71aa2162fef8e3963b6241a7945ef4e/manifold3d-3.4.1-cp312-cp312-macosx_10_14_universal2.whl", hash = "sha256:967c89daf24ec9ff863323d593cce98e4c130abbaaa9504df6789f9d8c780d0d", size = 1752517, upload-time = "2026-03-24T06:21:55.203Z" }, { url = "https://files.pythonhosted.org/packages/b1/a9/377800999cc8421ce8bfa40787d09570bb635e0099f44959170fee751dd7/manifold3d-3.4.1-cp312-cp312-macosx_10_14_x86_64.whl", hash = "sha256:c29db9a1bda414ecaa56dd2cd274f06bbbe740e463133c5b69943d82c3dcfb96", size = 956343, upload-time = "2026-03-24T06:21:57.134Z" }, { url = "https://files.pythonhosted.org/packages/6a/72/7f988a0deae9b3fbed3a6b2e9285e96fd9105e95f6755f5457e3a80e103e/manifold3d-3.4.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:2ae6855a6f652acd89e228f1981e5b710d4b10e06d7c06e5bada3b3fb31904a3", size = 840924, upload-time = "2026-03-24T06:21:58.462Z" }, @@ -2314,6 +2539,17 @@ version = "3.0.3" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/7e/99/7690b6d4034fffd95959cbe0c02de8deb3098cc577c67bb6a24fe5d7caa7/markupsafe-3.0.3.tar.gz", hash = "sha256:722695808f4b6457b320fdc131280796bdceb04ab50fe1795cd540799ebe1698", size = 80313, upload-time = "2025-09-27T18:37:40.426Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/08/db/fefacb2136439fc8dd20e797950e749aa1f4997ed584c62cfb8ef7c2be0e/markupsafe-3.0.3-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:1cc7ea17a6824959616c525620e387f6dd30fec8cb44f649e31712db02123dad", size = 11631, upload-time = "2025-09-27T18:36:18.185Z" }, + { url = "https://files.pythonhosted.org/packages/e1/2e/5898933336b61975ce9dc04decbc0a7f2fee78c30353c5efba7f2d6ff27a/markupsafe-3.0.3-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:4bd4cd07944443f5a265608cc6aab442e4f74dff8088b0dfc8238647b8f6ae9a", size = 12058, upload-time = "2025-09-27T18:36:19.444Z" }, + { url = "https://files.pythonhosted.org/packages/1d/09/adf2df3699d87d1d8184038df46a9c80d78c0148492323f4693df54e17bb/markupsafe-3.0.3-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:6b5420a1d9450023228968e7e6a9ce57f65d148ab56d2313fcd589eee96a7a50", size = 24287, upload-time = "2025-09-27T18:36:20.768Z" }, + { url = "https://files.pythonhosted.org/packages/30/ac/0273f6fcb5f42e314c6d8cd99effae6a5354604d461b8d392b5ec9530a54/markupsafe-3.0.3-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:0bf2a864d67e76e5c9a34dc26ec616a66b9888e25e7b9460e1c76d3293bd9dbf", size = 22940, upload-time = "2025-09-27T18:36:22.249Z" }, + { url = "https://files.pythonhosted.org/packages/19/ae/31c1be199ef767124c042c6c3e904da327a2f7f0cd63a0337e1eca2967a8/markupsafe-3.0.3-cp311-cp311-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:bc51efed119bc9cfdf792cdeaa4d67e8f6fcccab66ed4bfdd6bde3e59bfcbb2f", size = 21887, upload-time = "2025-09-27T18:36:23.535Z" }, + { url = "https://files.pythonhosted.org/packages/b2/76/7edcab99d5349a4532a459e1fe64f0b0467a3365056ae550d3bcf3f79e1e/markupsafe-3.0.3-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:068f375c472b3e7acbe2d5318dea141359e6900156b5b2ba06a30b169086b91a", size = 23692, upload-time = "2025-09-27T18:36:24.823Z" }, + { url = "https://files.pythonhosted.org/packages/a4/28/6e74cdd26d7514849143d69f0bf2399f929c37dc2b31e6829fd2045b2765/markupsafe-3.0.3-cp311-cp311-musllinux_1_2_riscv64.whl", hash = "sha256:7be7b61bb172e1ed687f1754f8e7484f1c8019780f6f6b0786e76bb01c2ae115", size = 21471, upload-time = "2025-09-27T18:36:25.95Z" }, + { url = "https://files.pythonhosted.org/packages/62/7e/a145f36a5c2945673e590850a6f8014318d5577ed7e5920a4b3448e0865d/markupsafe-3.0.3-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:f9e130248f4462aaa8e2552d547f36ddadbeaa573879158d721bbd33dfe4743a", size = 22923, upload-time = "2025-09-27T18:36:27.109Z" }, + { url = "https://files.pythonhosted.org/packages/0f/62/d9c46a7f5c9adbeeeda52f5b8d802e1094e9717705a645efc71b0913a0a8/markupsafe-3.0.3-cp311-cp311-win32.whl", hash = "sha256:0db14f5dafddbb6d9208827849fad01f1a2609380add406671a26386cdf15a19", size = 14572, upload-time = "2025-09-27T18:36:28.045Z" }, + { url = "https://files.pythonhosted.org/packages/83/8a/4414c03d3f891739326e1783338e48fb49781cc915b2e0ee052aa490d586/markupsafe-3.0.3-cp311-cp311-win_amd64.whl", hash = "sha256:de8a88e63464af587c950061a5e6a67d3632e36df62b986892331d4620a35c01", size = 15077, upload-time = "2025-09-27T18:36:29.025Z" }, + { url = "https://files.pythonhosted.org/packages/35/73/893072b42e6862f319b5207adc9ae06070f095b358655f077f69a35601f0/markupsafe-3.0.3-cp311-cp311-win_arm64.whl", hash = "sha256:3b562dd9e9ea93f13d53989d23a7e775fdfd1066c33494ff43f5418bc8c58a5c", size = 13876, upload-time = "2025-09-27T18:36:29.954Z" }, { url = "https://files.pythonhosted.org/packages/5a/72/147da192e38635ada20e0a2e1a51cf8823d2119ce8883f7053879c2199b5/markupsafe-3.0.3-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:d53197da72cc091b024dd97249dfc7794d6a56530370992a5e1a08983ad9230e", size = 11615, upload-time = "2025-09-27T18:36:30.854Z" }, { url = "https://files.pythonhosted.org/packages/9a/81/7e4e08678a1f98521201c3079f77db69fb552acd56067661f8c2f534a718/markupsafe-3.0.3-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:1872df69a4de6aead3491198eaf13810b565bdbeec3ae2dc8780f14458ec73ce", size = 12020, upload-time = "2025-09-27T18:36:31.971Z" }, { url = "https://files.pythonhosted.org/packages/1e/2c/799f4742efc39633a1b54a92eec4082e4f815314869865d876824c257c1e/markupsafe-3.0.3-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:3a7e8ae81ae39e62a41ec302f972ba6ae23a5c5396c8e60113e9066ef893da0d", size = 24332, upload-time = "2025-09-27T18:36:32.813Z" }, @@ -2388,6 +2624,13 @@ dependencies = [ ] sdist = { url = "https://files.pythonhosted.org/packages/63/1b/4be5be87d43d327a0cf4de1a56e86f7f84c89312452406cf122efe2839e6/matplotlib-3.10.9.tar.gz", hash = "sha256:fd66508e8c6877d98e586654b608a0456db8d7e8a546eb1e2600efd957302358", size = 34811233, upload-time = "2026-04-24T00:14:13.539Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/4c/8c/290f021104741fea63769c31494f5324c0cd249bf536a65a4350767b1f22/matplotlib-3.10.9-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:68cfdcede415f7c8f5577b03303dd94526cdb6d11036cecdc205e08733b2d2bb", size = 8306860, upload-time = "2026-04-24T00:12:01.207Z" }, + { url = "https://files.pythonhosted.org/packages/51/18/325cd32ece1120d1da51cc4e4294c6580190699490183fc2fe8cb6d61ec5/matplotlib-3.10.9-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:dfca0129678bd56379db26c52b5d77ed7de314c047492fbdc763aa7501710cfb", size = 8199254, upload-time = "2026-04-24T00:12:04.239Z" }, + { url = "https://files.pythonhosted.org/packages/79/db/e28c1b83e3680740aa78925f5fb2ae4d16207207419ad75ea9fe604f8676/matplotlib-3.10.9-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:8e436d155fa8a3399dc62683f8f5d0e2e50d25d0144a73edd73f82eec8f4abfb", size = 8777092, upload-time = "2026-04-24T00:12:06.793Z" }, + { url = "https://files.pythonhosted.org/packages/55/fa/3ce7adfe9ba101748f465211660d9c6374c876b671bdb8c2bb6d347e8b94/matplotlib-3.10.9-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:56fc0bd271b00025c6edfdc7c2dcd247372c8e1544971d62e1dc7c17367e8bf9", size = 9595691, upload-time = "2026-04-24T00:12:09.706Z" }, + { url = "https://files.pythonhosted.org/packages/36/c4/6960a76686ed668f2c60f84e9799ba4c0d56abdb36b1577b60c1d061d1ec/matplotlib-3.10.9-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:a5a6104ed666402ba5106d7f36e0e0cdca4e8d7fa4d39708ca88019e2835a2eb", size = 9659771, upload-time = "2026-04-24T00:12:12.766Z" }, + { url = "https://files.pythonhosted.org/packages/7e/0d/271aace3342157c64700c9ff4c59c7b392f3dbab393692e8db6fbe7ab96c/matplotlib-3.10.9-cp311-cp311-win_amd64.whl", hash = "sha256:d730e984eddf56974c3e72b6129c7ca462ac38dc624338f4b0b23eb23ecba00f", size = 8205112, upload-time = "2026-04-24T00:12:15.773Z" }, + { url = "https://files.pythonhosted.org/packages/e2/ee/cb57ad4754f3e7b9174ce6ce66d9205fb827067e48a9f58ac09d7e7d6b77/matplotlib-3.10.9-cp311-cp311-win_arm64.whl", hash = "sha256:51bf0ddbdc598e060d46c16b5590708f81a1624cefbaaf62f6a81bf9285b8c80", size = 8132310, upload-time = "2026-04-24T00:12:18.645Z" }, { url = "https://files.pythonhosted.org/packages/35/c6/5581e26c72233ebb2a2a6fed2d24fb7c66b4700120b813f51b0555acf0b6/matplotlib-3.10.9-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:f0c3c28d9fbcc1fe7a03be236d73430cf6409c41fb2383a7ac52fe932b072cb1", size = 8319908, upload-time = "2026-04-24T00:12:21.323Z" }, { url = "https://files.pythonhosted.org/packages/b7/18/4880dd762e40cd360c1bf06e890c5a97b997e91cb324602b1a19950ad5ce/matplotlib-3.10.9-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:41cb28c2bd769aa3e98322c6ab09854cbcc52ab69d2759d681bba3e327b2b320", size = 8216016, upload-time = "2026-04-24T00:12:23.4Z" }, { url = "https://files.pythonhosted.org/packages/32/91/d024616abdba99e83120e07a20658976f6a343646710760c4a51df126029/matplotlib-3.10.9-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:ae20801130378b82d647ff5047c07316295b68dc054ca6b3c13519d0ea624285", size = 8789336, upload-time = "2026-04-24T00:12:26.096Z" }, @@ -2423,6 +2666,9 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/67/b2/ef8d6bb59b0edb6c16c968b70f548aa13b54348972def5aa6ac85df67145/matplotlib-3.10.9-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:4e42042d54db34fda4e95a7bd3e5789c2a995d2dad3eb8850232ee534092fbbf", size = 9680884, upload-time = "2026-04-24T00:13:48.066Z" }, { url = "https://files.pythonhosted.org/packages/61/1c/d21bfeb9931881ebe96bcfcff27c7ae4b160ae0ec291a714c42641a56d75/matplotlib-3.10.9-cp314-cp314t-win_amd64.whl", hash = "sha256:c27df8b3848f32a83d1767566595e43cfaa4460380974da06f4279a7ec143c39", size = 8432333, upload-time = "2026-04-24T00:13:51.008Z" }, { url = "https://files.pythonhosted.org/packages/78/23/92493c3e6e1b635ccfff146f7b99e674808787915420373ac399283764c2/matplotlib-3.10.9-cp314-cp314t-win_arm64.whl", hash = "sha256:a49f1eadc84ca85fd72fa4e89e70e61bf86452df6f971af04b12c60761a0772c", size = 8324785, upload-time = "2026-04-24T00:13:53.633Z" }, + { url = "https://files.pythonhosted.org/packages/63/e2/9f66ca6a651a52abfe0d4964ce01439ed34f3f1e119de10ff3a07f403043/matplotlib-3.10.9-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:42fb814efabe95c06c1994d8ab5a8385f43a249e23badd3ba931d4308e5bca20", size = 8304420, upload-time = "2026-04-24T00:14:04.57Z" }, + { url = "https://files.pythonhosted.org/packages/e8/e8/467c03568218792906aa87b5e7bb379b605e056ed0c74fe00c051786d925/matplotlib-3.10.9-pp311-pypy311_pp73-macosx_11_0_arm64.whl", hash = "sha256:f76e640a5268850bfda54b5131b1b1941cc685e42c5fa98ed9f2d64038308cba", size = 8197981, upload-time = "2026-04-24T00:14:07.233Z" }, + { url = "https://files.pythonhosted.org/packages/6f/87/afead29192170917537934c6aff4b008c805fff7b1ccea0c79120d96beda/matplotlib-3.10.9-pp311-pypy311_pp73-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:3fc0364dfbe1d07f6d15c5ebd0c5bf89e126916e5a8667dd4a7a6e84c36653d4", size = 8774002, upload-time = "2026-04-24T00:14:09.816Z" }, ] [[package]] @@ -2467,15 +2713,55 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/7a/f0/8282d9641415e9e33df173516226b404d367a0fc55e1a60424a152913abc/mistune-3.1.4-py3-none-any.whl", hash = "sha256:93691da911e5d9d2e23bc54472892aff676df27a75274962ff9edc210364266d", size = 53481, upload-time = "2025-08-29T07:20:42.218Z" }, ] +[[package]] +name = "ml-dtypes" +version = "0.4.1" +source = { registry = "https://pypi.org/simple" } +resolution-markers = [ + "python_full_version >= '3.14' and sys_platform == 'darwin'", + "python_full_version == '3.13.*' and sys_platform == 'darwin'", + "python_full_version >= '3.14' and platform_machine == 'aarch64' and sys_platform == 'linux'", + "python_full_version == '3.13.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux')", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux')", +] +dependencies = [ + { name = "numpy", marker = "python_full_version >= '3.13'" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/fd/15/76f86faa0902836cc133939732f7611ace68cf54148487a99c539c272dc8/ml_dtypes-0.4.1.tar.gz", hash = "sha256:fad5f2de464fd09127e49b7fd1252b9006fb43d2edc1ff112d390c324af5ca7a", size = 692594, upload-time = "2024-09-13T19:07:11.624Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/d1/76/9835c8609c29f2214359e88f29255fc4aad4ea0f613fb48aa8815ceda1b6/ml_dtypes-0.4.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:2d55b588116a7085d6e074cf0cdb1d6fa3875c059dddc4d2c94a4cc81c23e975", size = 397973, upload-time = "2024-09-13T19:06:51.748Z" }, + { url = "https://files.pythonhosted.org/packages/7e/99/e68c56fac5de973007a10254b6e17a0362393724f40f66d5e4033f4962c2/ml_dtypes-0.4.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e138a9b7a48079c900ea969341a5754019a1ad17ae27ee330f7ebf43f23877f9", size = 2185134, upload-time = "2024-09-13T19:06:53.197Z" }, + { url = "https://files.pythonhosted.org/packages/28/bc/6a2344338ea7b61cd7b46fb24ec459360a5a0903b57c55b156c1e46c644a/ml_dtypes-0.4.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:74c6cfb5cf78535b103fde9ea3ded8e9f16f75bc07789054edc7776abfb3d752", size = 2163661, upload-time = "2024-09-13T19:06:54.519Z" }, + { url = "https://files.pythonhosted.org/packages/e8/d3/ddfd9878b223b3aa9a930c6100a99afca5cfab7ea703662e00323acb7568/ml_dtypes-0.4.1-cp311-cp311-win_amd64.whl", hash = "sha256:274cc7193dd73b35fb26bef6c5d40ae3eb258359ee71cd82f6e96a8c948bdaa6", size = 126727, upload-time = "2024-09-13T19:06:55.897Z" }, + { url = "https://files.pythonhosted.org/packages/ba/1a/99e924f12e4b62139fbac87419698c65f956d58de0dbfa7c028fa5b096aa/ml_dtypes-0.4.1-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:827d3ca2097085cf0355f8fdf092b888890bb1b1455f52801a2d7756f056f54b", size = 405077, upload-time = "2024-09-13T19:06:57.538Z" }, + { url = "https://files.pythonhosted.org/packages/8f/8c/7b610bd500617854c8cc6ed7c8cfb9d48d6a5c21a1437a36a4b9bc8a3598/ml_dtypes-0.4.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:772426b08a6172a891274d581ce58ea2789cc8abc1c002a27223f314aaf894e7", size = 2181554, upload-time = "2024-09-13T19:06:59.196Z" }, + { url = "https://files.pythonhosted.org/packages/c7/c6/f89620cecc0581dc1839e218c4315171312e46c62a62da6ace204bda91c0/ml_dtypes-0.4.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:126e7d679b8676d1a958f2651949fbfa182832c3cd08020d8facd94e4114f3e9", size = 2160488, upload-time = "2024-09-13T19:07:03.131Z" }, + { url = "https://files.pythonhosted.org/packages/ae/11/a742d3c31b2cc8557a48efdde53427fd5f9caa2fa3c9c27d826e78a66f51/ml_dtypes-0.4.1-cp312-cp312-win_amd64.whl", hash = "sha256:df0fb650d5c582a9e72bb5bd96cfebb2cdb889d89daff621c8fbc60295eba66c", size = 127462, upload-time = "2024-09-13T19:07:04.916Z" }, +] + [[package]] name = "ml-dtypes" version = "0.5.4" source = { registry = "https://pypi.org/simple" } +resolution-markers = [ + "python_full_version == '3.12.*' and sys_platform == 'darwin'", + "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux')", + "python_full_version < '3.12' and sys_platform == 'darwin'", + "python_full_version < '3.12' and platform_machine == 'aarch64' and sys_platform == 'linux'", + "(python_full_version < '3.12' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.12' and sys_platform != 'darwin' and sys_platform != 'linux')", +] dependencies = [ - { name = "numpy" }, + { name = "numpy", marker = "python_full_version < '3.13'" }, ] sdist = { url = "https://files.pythonhosted.org/packages/0e/4a/c27b42ed9b1c7d13d9ba8b6905dece787d6259152f2309338aed29b2447b/ml_dtypes-0.5.4.tar.gz", hash = "sha256:8ab06a50fb9bf9666dd0fe5dfb4676fa2b0ac0f31ecff72a6c3af8e22c063453", size = 692314, upload-time = "2025-11-17T22:32:31.031Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/c6/5e/712092cfe7e5eb667b8ad9ca7c54442f21ed7ca8979745f1000e24cf8737/ml_dtypes-0.5.4-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:6c7ecb74c4bd71db68a6bea1edf8da8c34f3d9fe218f038814fd1d310ac76c90", size = 679734, upload-time = "2025-11-17T22:31:39.223Z" }, + { url = "https://files.pythonhosted.org/packages/4f/cf/912146dfd4b5c0eea956836c01dcd2fce6c9c844b2691f5152aca196ce4f/ml_dtypes-0.5.4-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:bc11d7e8c44a65115d05e2ab9989d1e045125d7be8e05a071a48bc76eb6d6040", size = 5056165, upload-time = "2025-11-17T22:31:41.071Z" }, + { url = "https://files.pythonhosted.org/packages/a9/80/19189ea605017473660e43762dc853d2797984b3c7bf30ce656099add30c/ml_dtypes-0.5.4-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:19b9a53598f21e453ea2fbda8aa783c20faff8e1eeb0d7ab899309a0053f1483", size = 5034975, upload-time = "2025-11-17T22:31:42.758Z" }, + { url = "https://files.pythonhosted.org/packages/b4/24/70bd59276883fdd91600ca20040b41efd4902a923283c4d6edcb1de128d2/ml_dtypes-0.5.4-cp311-cp311-win_amd64.whl", hash = "sha256:7c23c54a00ae43edf48d44066a7ec31e05fdc2eee0be2b8b50dd1903a1db94bb", size = 210742, upload-time = "2025-11-17T22:31:44.068Z" }, + { url = "https://files.pythonhosted.org/packages/a0/c9/64230ef14e40aa3f1cb254ef623bf812735e6bec7772848d19131111ac0d/ml_dtypes-0.5.4-cp311-cp311-win_arm64.whl", hash = "sha256:557a31a390b7e9439056644cb80ed0735a6e3e3bb09d67fd5687e4b04238d1de", size = 160709, upload-time = "2025-11-17T22:31:46.557Z" }, { url = "https://files.pythonhosted.org/packages/a8/b8/3c70881695e056f8a32f8b941126cf78775d9a4d7feba8abcb52cb7b04f2/ml_dtypes-0.5.4-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:a174837a64f5b16cab6f368171a1a03a27936b31699d167684073ff1c4237dac", size = 676927, upload-time = "2025-11-17T22:31:48.182Z" }, { url = "https://files.pythonhosted.org/packages/54/0f/428ef6881782e5ebb7eca459689448c0394fa0a80bea3aa9262cba5445ea/ml_dtypes-0.5.4-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:a7f7c643e8b1320fd958bf098aa7ecf70623a42ec5154e3be3be673f4c34d900", size = 5028464, upload-time = "2025-11-17T22:31:50.135Z" }, { url = "https://files.pythonhosted.org/packages/3a/cb/28ce52eb94390dda42599c98ea0204d74799e4d8047a0eb559b6fd648056/ml_dtypes-0.5.4-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:9ad459e99793fa6e13bd5b7e6792c8f9190b4e5a1b45c63aba14a4d0a7f1d5ff", size = 5009002, upload-time = "2025-11-17T22:31:52.001Z" }, @@ -2503,15 +2789,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/ad/3f/3d42e9a78fe5edf792a83c074b13b9b770092a4fbf3462872f4303135f09/ml_dtypes-0.5.4-cp314-cp314t-win_arm64.whl", hash = "sha256:11942cbf2cf92157db91e5022633c0d9474d4dfd813a909383bd23ce828a4b7d", size = 168825, upload-time = "2025-11-17T22:32:23.766Z" }, ] -[[package]] -name = "more-itertools" -version = "11.0.2" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/a2/f7/139d22fef48ac78127d18e01d80cf1be40236ae489769d17f35c3d425293/more_itertools-11.0.2.tar.gz", hash = "sha256:392a9e1e362cbc106a2457d37cabf9b36e5e12efd4ebff1654630e76597df804", size = 144659, upload-time = "2026-04-09T15:01:33.297Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/cb/98/6af411189d9413534c3eb691182bff1f5c6d44ed2f93f2edfe52a1bbceb8/more_itertools-11.0.2-py3-none-any.whl", hash = "sha256:6e35b35f818b01f691643c6c611bc0902f2e92b46c18fffa77ae1e7c46e912e4", size = 71939, upload-time = "2026-04-09T15:01:32.21Z" }, -] - [[package]] name = "mpmath" version = "1.3.0" @@ -2527,6 +2804,15 @@ version = "1.1.2" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/4d/f2/bfb55a6236ed8725a96b0aa3acbd0ec17588e6a2c3b62a93eb513ed8783f/msgpack-1.1.2.tar.gz", hash = "sha256:3b60763c1373dd60f398488069bcdc703cd08a711477b5d480eecc9f9626f47e", size = 173581, upload-time = "2025-10-08T09:15:56.596Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/2c/97/560d11202bcd537abca693fd85d81cebe2107ba17301de42b01ac1677b69/msgpack-1.1.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:2e86a607e558d22985d856948c12a3fa7b42efad264dca8a3ebbcfa2735d786c", size = 82271, upload-time = "2025-10-08T09:14:49.967Z" }, + { url = "https://files.pythonhosted.org/packages/83/04/28a41024ccbd67467380b6fb440ae916c1e4f25e2cd4c63abe6835ac566e/msgpack-1.1.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:283ae72fc89da59aa004ba147e8fc2f766647b1251500182fac0350d8af299c0", size = 84914, upload-time = "2025-10-08T09:14:50.958Z" }, + { url = "https://files.pythonhosted.org/packages/71/46/b817349db6886d79e57a966346cf0902a426375aadc1e8e7a86a75e22f19/msgpack-1.1.2-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:61c8aa3bd513d87c72ed0b37b53dd5c5a0f58f2ff9f26e1555d3bd7948fb7296", size = 416962, upload-time = "2025-10-08T09:14:51.997Z" }, + { url = "https://files.pythonhosted.org/packages/da/e0/6cc2e852837cd6086fe7d8406af4294e66827a60a4cf60b86575a4a65ca8/msgpack-1.1.2-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:454e29e186285d2ebe65be34629fa0e8605202c60fbc7c4c650ccd41870896ef", size = 426183, upload-time = "2025-10-08T09:14:53.477Z" }, + { url = "https://files.pythonhosted.org/packages/25/98/6a19f030b3d2ea906696cedd1eb251708e50a5891d0978b012cb6107234c/msgpack-1.1.2-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:7bc8813f88417599564fafa59fd6f95be417179f76b40325b500b3c98409757c", size = 411454, upload-time = "2025-10-08T09:14:54.648Z" }, + { url = "https://files.pythonhosted.org/packages/b7/cd/9098fcb6adb32187a70b7ecaabf6339da50553351558f37600e53a4a2a23/msgpack-1.1.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:bafca952dc13907bdfdedfc6a5f579bf4f292bdd506fadb38389afa3ac5b208e", size = 422341, upload-time = "2025-10-08T09:14:56.328Z" }, + { url = "https://files.pythonhosted.org/packages/e6/ae/270cecbcf36c1dc85ec086b33a51a4d7d08fc4f404bdbc15b582255d05ff/msgpack-1.1.2-cp311-cp311-win32.whl", hash = "sha256:602b6740e95ffc55bfb078172d279de3773d7b7db1f703b2f1323566b878b90e", size = 64747, upload-time = "2025-10-08T09:14:57.882Z" }, + { url = "https://files.pythonhosted.org/packages/2a/79/309d0e637f6f37e83c711f547308b91af02b72d2326ddd860b966080ef29/msgpack-1.1.2-cp311-cp311-win_amd64.whl", hash = "sha256:d198d275222dc54244bf3327eb8cbe00307d220241d9cec4d306d49a44e85f68", size = 71633, upload-time = "2025-10-08T09:14:59.177Z" }, + { url = "https://files.pythonhosted.org/packages/73/4d/7c4e2b3d9b1106cd0aa6cb56cc57c6267f59fa8bfab7d91df5adc802c847/msgpack-1.1.2-cp311-cp311-win_arm64.whl", hash = "sha256:86f8136dfa5c116365a8a651a7d7484b65b13339731dd6faebb9a0242151c406", size = 64755, upload-time = "2025-10-08T09:15:00.48Z" }, { url = "https://files.pythonhosted.org/packages/ad/bd/8b0d01c756203fbab65d265859749860682ccd2a59594609aeec3a144efa/msgpack-1.1.2-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:70a0dff9d1f8da25179ffcf880e10cf1aad55fdb63cd59c9a49a1b82290062aa", size = 81939, upload-time = "2025-10-08T09:15:01.472Z" }, { url = "https://files.pythonhosted.org/packages/34/68/ba4f155f793a74c1483d4bdef136e1023f7bcba557f0db4ef3db3c665cf1/msgpack-1.1.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:446abdd8b94b55c800ac34b102dffd2f6aa0ce643c55dfc017ad89347db3dbdb", size = 85064, upload-time = "2025-10-08T09:15:03.764Z" }, { url = "https://files.pythonhosted.org/packages/f2/60/a064b0345fc36c4c3d2c743c82d9100c40388d77f0b48b2f04d6041dbec1/msgpack-1.1.2-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:c63eea553c69ab05b6747901b97d620bb2a690633c77f23feb0c6a947a8a7b8f", size = 417131, upload-time = "2025-10-08T09:15:05.136Z" }, @@ -2578,6 +2864,11 @@ dependencies = [ ] sdist = { url = "https://files.pythonhosted.org/packages/e2/d8/9aae1a021b6e15ee69d805d893e01dda71cbaae1c75d5f8ec8e12916cb7c/mujoco-3.8.0.tar.gz", hash = "sha256:250afe57458d6881b2d7659fa0029a128cb57cbbb620268d95647fb9ad742183", size = 918250, upload-time = "2026-04-24T22:59:07.531Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/83/46/e68d7a05c0c8367e38f5925fc85553df735c379dfbfe0c8adee4833e610b/mujoco-3.8.0-cp311-cp311-macosx_10_16_x86_64.whl", hash = "sha256:c3579cdbeb2bd157be43e13272953e941acdc59f4a74495a567fa4bc2b4f0166", size = 7235564, upload-time = "2026-04-24T22:58:24.097Z" }, + { url = "https://files.pythonhosted.org/packages/7a/ae/aeda34f9e07b295be5757ffa006218be341f193138db1e6ee0e7f88a245e/mujoco-3.8.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:d400c0489d8b958eaba361af84d0315a642215e5236485a23460b9636d665730", size = 7255745, upload-time = "2026-04-24T22:58:26.066Z" }, + { url = "https://files.pythonhosted.org/packages/1a/ae/89c113e77e25e4a5e76c9856c51229ea75d790ffc65f10f0aec794b2e4fe/mujoco-3.8.0-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:0d4297fbd8bce087b52c47c4a4ef4a8e49e9e27db8e419f048c25ebe8d4ba0cb", size = 6705135, upload-time = "2026-04-24T22:58:27.735Z" }, + { url = "https://files.pythonhosted.org/packages/b1/1f/046931077b28e62a5540f8a942c77fec323b7d5e713d3831d0d55edbe08f/mujoco-3.8.0-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:4c764f37204219506ff0ed7acf7cc3848c65dcf39438cefbe26056b3fd649cd8", size = 7145390, upload-time = "2026-04-24T22:58:29.756Z" }, + { url = "https://files.pythonhosted.org/packages/26/b4/fbe055a11cc98542a3f0c78051247ae2b34d0ed468cf85feb2c21b7ecde2/mujoco-3.8.0-cp311-cp311-win_amd64.whl", hash = "sha256:0d4521c322a1d1b4925610246548af42031c04ba0ca73956be0fb9fd0465aaa4", size = 5739709, upload-time = "2026-04-24T22:58:31.805Z" }, { url = "https://files.pythonhosted.org/packages/b4/0d/35aad24bef1f36e9ebf63367938b16abec82407338d612c37624ff20b0e3/mujoco-3.8.0-cp312-cp312-macosx_10_16_x86_64.whl", hash = "sha256:a495da0cd01aff6ac94ec97f0a1d913e1afe071daf107e220f81814435227982", size = 7265096, upload-time = "2026-04-24T22:58:33.475Z" }, { url = "https://files.pythonhosted.org/packages/60/d7/2ee5a123431eb50f234de2759e46f3d0c02876e0b1ffce1b26102ed388e7/mujoco-3.8.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:cc1d25b0cd47248fd39681310950b2bea0f6098f57358c0c02730d365bb80ba1", size = 7204862, upload-time = "2026-04-24T22:58:35.978Z" }, { url = "https://files.pythonhosted.org/packages/aa/62/a488e6e0963e0210b8262650d25e51c4c597ff7beed4fe01a7e88e3abfc5/mujoco-3.8.0-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:980ab5a2210777cf766e53eb574726f9360e2a87e47d83a6c8d801fb71f2fe52", size = 6743542, upload-time = "2026-04-24T22:58:38.137Z" }, @@ -2624,6 +2915,24 @@ version = "6.7.0" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/80/1e/5492c365f222f907de1039b91f922b93fa4f764c713ee858d235495d8f50/multidict-6.7.0.tar.gz", hash = "sha256:c6e99d9a65ca282e578dfea819cfa9c0a62b2499d8677392e09feaf305e9e6f5", size = 101834, upload-time = "2025-10-06T14:52:30.657Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/34/9e/5c727587644d67b2ed479041e4b1c58e30afc011e3d45d25bbe35781217c/multidict-6.7.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:4d409aa42a94c0b3fa617708ef5276dfe81012ba6753a0370fcc9d0195d0a1fc", size = 76604, upload-time = "2025-10-06T14:48:54.277Z" }, + { url = "https://files.pythonhosted.org/packages/17/e4/67b5c27bd17c085a5ea8f1ec05b8a3e5cba0ca734bfcad5560fb129e70ca/multidict-6.7.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:14c9e076eede3b54c636f8ce1c9c252b5f057c62131211f0ceeec273810c9721", size = 44715, upload-time = "2025-10-06T14:48:55.445Z" }, + { url = "https://files.pythonhosted.org/packages/4d/e1/866a5d77be6ea435711bef2a4291eed11032679b6b28b56b4776ab06ba3e/multidict-6.7.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:4c09703000a9d0fa3c3404b27041e574cc7f4df4c6563873246d0e11812a94b6", size = 44332, upload-time = "2025-10-06T14:48:56.706Z" }, + { url = "https://files.pythonhosted.org/packages/31/61/0c2d50241ada71ff61a79518db85ada85fdabfcf395d5968dae1cbda04e5/multidict-6.7.0-cp311-cp311-manylinux1_i686.manylinux_2_28_i686.manylinux_2_5_i686.whl", hash = "sha256:a265acbb7bb33a3a2d626afbe756371dce0279e7b17f4f4eda406459c2b5ff1c", size = 245212, upload-time = "2025-10-06T14:48:58.042Z" }, + { url = "https://files.pythonhosted.org/packages/ac/e0/919666a4e4b57fff1b57f279be1c9316e6cdc5de8a8b525d76f6598fefc7/multidict-6.7.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:51cb455de290ae462593e5b1cb1118c5c22ea7f0d3620d9940bf695cea5a4bd7", size = 246671, upload-time = "2025-10-06T14:49:00.004Z" }, + { url = "https://files.pythonhosted.org/packages/a1/cc/d027d9c5a520f3321b65adea289b965e7bcbd2c34402663f482648c716ce/multidict-6.7.0-cp311-cp311-manylinux2014_armv7l.manylinux_2_17_armv7l.manylinux_2_31_armv7l.whl", hash = "sha256:db99677b4457c7a5c5a949353e125ba72d62b35f74e26da141530fbb012218a7", size = 225491, upload-time = "2025-10-06T14:49:01.393Z" }, + { url = "https://files.pythonhosted.org/packages/75/c4/bbd633980ce6155a28ff04e6a6492dd3335858394d7bb752d8b108708558/multidict-6.7.0-cp311-cp311-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:f470f68adc395e0183b92a2f4689264d1ea4b40504a24d9882c27375e6662bb9", size = 257322, upload-time = "2025-10-06T14:49:02.745Z" }, + { url = "https://files.pythonhosted.org/packages/4c/6d/d622322d344f1f053eae47e033b0b3f965af01212de21b10bcf91be991fb/multidict-6.7.0-cp311-cp311-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:0db4956f82723cc1c270de9c6e799b4c341d327762ec78ef82bb962f79cc07d8", size = 254694, upload-time = "2025-10-06T14:49:04.15Z" }, + { url = "https://files.pythonhosted.org/packages/a8/9f/78f8761c2705d4c6d7516faed63c0ebdac569f6db1bef95e0d5218fdc146/multidict-6.7.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:3e56d780c238f9e1ae66a22d2adf8d16f485381878250db8d496623cd38b22bd", size = 246715, upload-time = "2025-10-06T14:49:05.967Z" }, + { url = "https://files.pythonhosted.org/packages/78/59/950818e04f91b9c2b95aab3d923d9eabd01689d0dcd889563988e9ea0fd8/multidict-6.7.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:9d14baca2ee12c1a64740d4531356ba50b82543017f3ad6de0deb943c5979abb", size = 243189, upload-time = "2025-10-06T14:49:07.37Z" }, + { url = "https://files.pythonhosted.org/packages/7a/3d/77c79e1934cad2ee74991840f8a0110966d9599b3af95964c0cd79bb905b/multidict-6.7.0-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:295a92a76188917c7f99cda95858c822f9e4aae5824246bba9b6b44004ddd0a6", size = 237845, upload-time = "2025-10-06T14:49:08.759Z" }, + { url = "https://files.pythonhosted.org/packages/63/1b/834ce32a0a97a3b70f86437f685f880136677ac00d8bce0027e9fd9c2db7/multidict-6.7.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:39f1719f57adbb767ef592a50ae5ebb794220d1188f9ca93de471336401c34d2", size = 246374, upload-time = "2025-10-06T14:49:10.574Z" }, + { url = "https://files.pythonhosted.org/packages/23/ef/43d1c3ba205b5dec93dc97f3fba179dfa47910fc73aaaea4f7ceb41cec2a/multidict-6.7.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:0a13fb8e748dfc94749f622de065dd5c1def7e0d2216dba72b1d8069a389c6ff", size = 253345, upload-time = "2025-10-06T14:49:12.331Z" }, + { url = "https://files.pythonhosted.org/packages/6b/03/eaf95bcc2d19ead522001f6a650ef32811aa9e3624ff0ad37c445c7a588c/multidict-6.7.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:e3aa16de190d29a0ea1b48253c57d99a68492c8dd8948638073ab9e74dc9410b", size = 246940, upload-time = "2025-10-06T14:49:13.821Z" }, + { url = "https://files.pythonhosted.org/packages/e8/df/ec8a5fd66ea6cd6f525b1fcbb23511b033c3e9bc42b81384834ffa484a62/multidict-6.7.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:a048ce45dcdaaf1defb76b2e684f997fb5abf74437b6cb7b22ddad934a964e34", size = 242229, upload-time = "2025-10-06T14:49:15.603Z" }, + { url = "https://files.pythonhosted.org/packages/8a/a2/59b405d59fd39ec86d1142630e9049243015a5f5291ba49cadf3c090c541/multidict-6.7.0-cp311-cp311-win32.whl", hash = "sha256:a90af66facec4cebe4181b9e62a68be65e45ac9b52b67de9eec118701856e7ff", size = 41308, upload-time = "2025-10-06T14:49:16.871Z" }, + { url = "https://files.pythonhosted.org/packages/32/0f/13228f26f8b882c34da36efa776c3b7348455ec383bab4a66390e42963ae/multidict-6.7.0-cp311-cp311-win_amd64.whl", hash = "sha256:95b5ffa4349df2887518bb839409bcf22caa72d82beec453216802f475b23c81", size = 46037, upload-time = "2025-10-06T14:49:18.457Z" }, + { url = "https://files.pythonhosted.org/packages/84/1f/68588e31b000535a3207fd3c909ebeec4fb36b52c442107499c18a896a2a/multidict-6.7.0-cp311-cp311-win_arm64.whl", hash = "sha256:329aa225b085b6f004a4955271a7ba9f1087e39dcb7e65f6284a988264a63912", size = 43023, upload-time = "2025-10-06T14:49:19.648Z" }, { url = "https://files.pythonhosted.org/packages/c2/9e/9f61ac18d9c8b475889f32ccfa91c9f59363480613fc807b6e3023d6f60b/multidict-6.7.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:8a3862568a36d26e650a19bb5cbbba14b71789032aebc0423f8cc5f150730184", size = 76877, upload-time = "2025-10-06T14:49:20.884Z" }, { url = "https://files.pythonhosted.org/packages/38/6f/614f09a04e6184f8824268fce4bc925e9849edfa654ddd59f0b64508c595/multidict-6.7.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:960c60b5849b9b4f9dcc9bea6e3626143c252c74113df2c1540aebce70209b45", size = 45467, upload-time = "2025-10-06T14:49:22.054Z" }, { url = "https://files.pythonhosted.org/packages/b3/93/c4f67a436dd026f2e780c433277fff72be79152894d9fc36f44569cab1a6/multidict-6.7.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:2049be98fb57a31b4ccf870bf377af2504d4ae35646a19037ec271e4c07998aa", size = 43834, upload-time = "2025-10-06T14:49:23.566Z" }, @@ -2719,11 +3028,11 @@ wheels = [ [[package]] name = "multimethod" -version = "1.12" +version = "1.9.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/ed/f3/930a6dc1d35b2ab65faffa2a75bbcc67f12d8227857188273783df4e5134/multimethod-1.12.tar.gz", hash = "sha256:8db8ef2a8d2a247e3570cc23317680892fdf903d84c8c1053667c8e8f7671a67", size = 17423, upload-time = "2024-07-04T16:10:08.179Z" } +sdist = { url = "https://files.pythonhosted.org/packages/50/17/4f169e5f0176d35d622737a76128e07c46590b1a0a73b1584222744f96d8/multimethod-1.9.1.tar.gz", hash = "sha256:1589bf52ca294667fd15527ea830127c763f5bfc38562e3642591ffd0fd9d56f", size = 12565, upload-time = "2022-12-22T02:30:29.014Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/af/98/cff14d53a2f2f67d7fe8a4e235a383ee71aba6a1da12aeea24b325d0c72a/multimethod-1.12-py3-none-any.whl", hash = "sha256:fd0c473c43558908d97cc06e4d68e8f69202f167db46f7b4e4058893e7dbdf60", size = 10646, upload-time = "2024-07-04T16:10:06.482Z" }, + { url = "https://files.pythonhosted.org/packages/21/91/01ec16d3d0cadb499b83e6f6435c63e43f3c122c146d82a4eb9575169817/multimethod-1.9.1-py3-none-any.whl", hash = "sha256:52f8f1f2b9d5a4c7adfdcc114dbeeebe3245a4420801e8807e26522a79fb6bc2", size = 10213, upload-time = "2022-12-22T02:30:27.745Z" }, ] [[package]] @@ -2737,6 +3046,12 @@ dependencies = [ ] sdist = { url = "https://files.pythonhosted.org/packages/c0/77/8f0d0001ffad290cef2f7f216f96c814866248a0b92a722365ed54648e7e/mypy-1.18.2.tar.gz", hash = "sha256:06a398102a5f203d7477b2923dda3634c36727fa5c237d8f859ef90c42a9924b", size = 3448846, upload-time = "2025-09-19T00:11:10.519Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/88/87/cafd3ae563f88f94eec33f35ff722d043e09832ea8530ef149ec1efbaf08/mypy-1.18.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:807d9315ab9d464125aa9fcf6d84fde6e1dc67da0b6f80e7405506b8ac72bc7f", size = 12731198, upload-time = "2025-09-19T00:09:44.857Z" }, + { url = "https://files.pythonhosted.org/packages/0f/e0/1e96c3d4266a06d4b0197ace5356d67d937d8358e2ee3ffac71faa843724/mypy-1.18.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:776bb00de1778caf4db739c6e83919c1d85a448f71979b6a0edd774ea8399341", size = 11817879, upload-time = "2025-09-19T00:09:47.131Z" }, + { url = "https://files.pythonhosted.org/packages/72/ef/0c9ba89eb03453e76bdac5a78b08260a848c7bfc5d6603634774d9cd9525/mypy-1.18.2-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:1379451880512ffce14505493bd9fe469e0697543717298242574882cf8cdb8d", size = 12427292, upload-time = "2025-09-19T00:10:22.472Z" }, + { url = "https://files.pythonhosted.org/packages/1a/52/ec4a061dd599eb8179d5411d99775bec2a20542505988f40fc2fee781068/mypy-1.18.2-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:1331eb7fd110d60c24999893320967594ff84c38ac6d19e0a76c5fd809a84c86", size = 13163750, upload-time = "2025-09-19T00:09:51.472Z" }, + { url = "https://files.pythonhosted.org/packages/c4/5f/2cf2ceb3b36372d51568f2208c021870fe7834cf3186b653ac6446511839/mypy-1.18.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:3ca30b50a51e7ba93b00422e486cbb124f1c56a535e20eff7b2d6ab72b3b2e37", size = 13351827, upload-time = "2025-09-19T00:09:58.311Z" }, + { url = "https://files.pythonhosted.org/packages/c8/7d/2697b930179e7277529eaaec1513f8de622818696857f689e4a5432e5e27/mypy-1.18.2-cp311-cp311-win_amd64.whl", hash = "sha256:664dc726e67fa54e14536f6e1224bcfce1d9e5ac02426d2326e2bb4e081d1ce8", size = 9757983, upload-time = "2025-09-19T00:10:09.071Z" }, { url = "https://files.pythonhosted.org/packages/07/06/dfdd2bc60c66611dd8335f463818514733bc763e4760dee289dcc33df709/mypy-1.18.2-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:33eca32dd124b29400c31d7cf784e795b050ace0e1f91b8dc035672725617e34", size = 12908273, upload-time = "2025-09-19T00:10:58.321Z" }, { url = "https://files.pythonhosted.org/packages/81/14/6a9de6d13a122d5608e1a04130724caf9170333ac5a924e10f670687d3eb/mypy-1.18.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:a3c47adf30d65e89b2dcd2fa32f3aeb5e94ca970d2c15fcb25e297871c8e4764", size = 11920910, upload-time = "2025-09-19T00:10:20.043Z" }, { url = "https://files.pythonhosted.org/packages/5f/a9/b29de53e42f18e8cc547e38daa9dfa132ffdc64f7250e353f5c8cdd44bee/mypy-1.18.2-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:5d6c838e831a062f5f29d11c9057c6009f60cb294fea33a98422688181fe2893", size = 12465585, upload-time = "2025-09-19T00:10:33.005Z" }, @@ -2934,21 +3249,18 @@ wheels = [ [[package]] name = "nlopt" -version = "2.10.0" +version = "2.7.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "numpy" }, ] wheels = [ - { url = "https://files.pythonhosted.org/packages/a4/39/76558756c758962fcf2c6f8450384e43a8e65cb8dfbb8a93d40014b09b3a/nlopt-2.10.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:19e7a5dd823eab1d167a4fb2f3da13978b997029c9b5e6164d33c747fc7ec542", size = 637168, upload-time = "2025-12-23T15:23:59.667Z" }, - { url = "https://files.pythonhosted.org/packages/2e/57/87a00a49664ae90f312cf9fd12262a3803d4f81709e01653bc2be6299b63/nlopt-2.10.0-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:939a0f3ed1710a6b9493a029744e07e8703f56aea4cfd3010d8619c4fba0df8e", size = 440214, upload-time = "2025-12-23T15:24:00.774Z" }, - { url = "https://files.pythonhosted.org/packages/a5/03/3140b6417a4cb113cd0f5d53b27ada263f81f158355ad991aaeee770e10e/nlopt-2.10.0-cp312-cp312-win_amd64.whl", hash = "sha256:8364bdd98c8265eb87779155f4ab144dd67c7990620244b629f2ebc024d727d1", size = 641684, upload-time = "2025-12-23T15:24:02.094Z" }, - { url = "https://files.pythonhosted.org/packages/99/85/9f4d06c156d6007da8594f04343c360978595b0de6c1fa41c2fa1295cb11/nlopt-2.10.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:4ff0577b4e866f5696f44d546368f5ee752a249ac73f9c45d8a29513c5f2430f", size = 636965, upload-time = "2025-12-23T15:24:03.226Z" }, - { url = "https://files.pythonhosted.org/packages/c0/eb/1dbdb4fa2ac8550870eef7f74dcd5c35f4c4df58d223e068daeac20f7c98/nlopt-2.10.0-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:c3a9697d24f3cb92b53c37cad7dc8900c7cc125dbe95da73bc92a4fed133eaf0", size = 439869, upload-time = "2025-12-23T15:24:04.598Z" }, - { url = "https://files.pythonhosted.org/packages/b6/44/20f39446c3edb9bd80e37fa0f996118170f8509eea0e118595a6c5aa3b18/nlopt-2.10.0-cp313-cp313-win_amd64.whl", hash = "sha256:98cbe9012ae641970366c9935ffcbb9cdcd6deef8521881a3e2ad7d35ed33506", size = 641822, upload-time = "2025-12-23T15:24:05.708Z" }, - { url = "https://files.pythonhosted.org/packages/60/87/6e2b468190f8a4467efb9165c94e3ab6c13e03a579fe821fae10479a5003/nlopt-2.10.0-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:404ddd3f77958d54edf8b1dbed187730fe2ab13cd6e6fb2e7b80cfac2958460f", size = 636962, upload-time = "2025-12-23T15:24:06.823Z" }, - { url = "https://files.pythonhosted.org/packages/10/92/87b81b0d149ef4439c1edd475ac62127904e63efe7aacc89f6279aba957c/nlopt-2.10.0-cp314-cp314-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:6a49ba09083bdb10c2fde31e2190a16e0e57050a2e98e37ece9b606ad2cb2a31", size = 439883, upload-time = "2025-12-23T15:24:08.233Z" }, - { url = "https://files.pythonhosted.org/packages/e8/1d/be16a2bd80f28f7cc838448950c1468ab6fced9939806b6a88396cc4028c/nlopt-2.10.0-cp314-cp314-win_amd64.whl", hash = "sha256:0b0cb9de4270b7ed2d9a299ba379ae6b24d5095b0365a2af9702ff0ccdff5235", size = 660414, upload-time = "2025-12-23T15:24:09.296Z" }, + { url = "https://files.pythonhosted.org/packages/6e/89/493a6310da558412d9aba161510625f03ac7618ed4382480d3e8aa86c3d9/nlopt-2.7.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:7a12fe3cbfb36a6a18f84a1ac23ed3dda323860235381b3d2d182d8b771783ef", size = 341110, upload-time = "2023-07-06T03:59:06.904Z" }, + { url = "https://files.pythonhosted.org/packages/54/4e/a7123adf391ed71175c5c8e8217be2ac3c335cb67c3601d183e94337393d/nlopt-2.7.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3e1653de0060a42d6709423e6160888893bb688f4ff79aa0f1def4701ea25dd8", size = 426449, upload-time = "2023-07-06T03:59:08.235Z" }, + { url = "https://files.pythonhosted.org/packages/32/d0/8e025d067e22f60907c84a6a4d253f3ea3b48b2ffd193033b6aa8c79c856/nlopt-2.7.1-cp311-cp311-win_amd64.whl", hash = "sha256:88ec7cf491da150d497ecc61889bc7adb0af0ad05a67e925a4f5ac88e20f1b9c", size = 347597, upload-time = "2023-07-06T03:59:09.989Z" }, + { url = "https://files.pythonhosted.org/packages/e9/55/690349cdf57e2c94136ece9b172b877405e58bae7c6d6d22e95daaff724f/nlopt-2.7.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:da0ac81b10f838afe7c1b99a2f895c31e05ca68328571fe430f382ce08cbfb07", size = 341686, upload-time = "2024-04-03T02:29:57.837Z" }, + { url = "https://files.pythonhosted.org/packages/7d/5c/f2f676df69694b774df64ec6725cff1f43b5b4d43a421339cac865731906/nlopt-2.7.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:592ded3b34bb888cd99c5da3fb1c3c9269ddd996dade578a8ec325cd8b6be752", size = 427217, upload-time = "2024-04-03T02:29:59.667Z" }, + { url = "https://files.pythonhosted.org/packages/d5/2e/6e78c39b1ab918520711d7eb9d9ad0761a80e59f2b1ca4f73cd7889a3717/nlopt-2.7.1-cp312-cp312-win_amd64.whl", hash = "sha256:1647131d53302e72f5c4851ab04a92401a342c3e0fcfaac0eda316f5e8f3b283", size = 346174, upload-time = "2024-04-03T02:30:00.962Z" }, ] [[package]] @@ -2996,67 +3308,39 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/a6/be/7b423b02b09eb856beffe76fe8c4121c99852db74dd12a422dcb72d1134e/nox-2025.5.1-py3-none-any.whl", hash = "sha256:56abd55cf37ff523c254fcec4d152ed51e5fe80e2ab8317221d8b828ac970a31", size = 71753, upload-time = "2025-05-01T16:35:46.037Z" }, ] +[[package]] +name = "nptyping" +version = "2.0.1" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "numpy" }, +] +wheels = [ + { url = "https://files.pythonhosted.org/packages/48/03/3f5af42a8858c223f1a4b1d5a773f3a4f7cb9ae9dcbd1ad61bdb8539e633/nptyping-2.0.1-py3-none-any.whl", hash = "sha256:0fc5c4d76c65e12a77e750b9e2701dab6468d00926c8c4f383867bd70598a532", size = 19435, upload-time = "2022-04-28T21:02:07.815Z" }, +] + [[package]] name = "numpy" -version = "2.3.3" +version = "1.26.4" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/d0/19/95b3d357407220ed24c139018d2518fab0a61a948e68286a25f1a4d049ff/numpy-2.3.3.tar.gz", hash = "sha256:ddc7c39727ba62b80dfdbedf400d1c10ddfa8eefbd7ec8dcb118be8b56d31029", size = 20576648, upload-time = "2025-09-09T16:54:12.543Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/51/5d/bb7fc075b762c96329147799e1bcc9176ab07ca6375ea976c475482ad5b3/numpy-2.3.3-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:cfdd09f9c84a1a934cde1eec2267f0a43a7cd44b2cca4ff95b7c0d14d144b0bf", size = 20957014, upload-time = "2025-09-09T15:56:29.966Z" }, - { url = "https://files.pythonhosted.org/packages/6b/0e/c6211bb92af26517acd52125a237a92afe9c3124c6a68d3b9f81b62a0568/numpy-2.3.3-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:cb32e3cf0f762aee47ad1ddc6672988f7f27045b0783c887190545baba73aa25", size = 14185220, upload-time = "2025-09-09T15:56:32.175Z" }, - { url = "https://files.pythonhosted.org/packages/22/f2/07bb754eb2ede9073f4054f7c0286b0d9d2e23982e090a80d478b26d35ca/numpy-2.3.3-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:396b254daeb0a57b1fe0ecb5e3cff6fa79a380fa97c8f7781a6d08cd429418fe", size = 5113918, upload-time = "2025-09-09T15:56:34.175Z" }, - { url = "https://files.pythonhosted.org/packages/81/0a/afa51697e9fb74642f231ea36aca80fa17c8fb89f7a82abd5174023c3960/numpy-2.3.3-cp312-cp312-macosx_14_0_x86_64.whl", hash = "sha256:067e3d7159a5d8f8a0b46ee11148fc35ca9b21f61e3c49fbd0a027450e65a33b", size = 6647922, upload-time = "2025-09-09T15:56:36.149Z" }, - { url = "https://files.pythonhosted.org/packages/5d/f5/122d9cdb3f51c520d150fef6e87df9279e33d19a9611a87c0d2cf78a89f4/numpy-2.3.3-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:1c02d0629d25d426585fb2e45a66154081b9fa677bc92a881ff1d216bc9919a8", size = 14281991, upload-time = "2025-09-09T15:56:40.548Z" }, - { url = "https://files.pythonhosted.org/packages/51/64/7de3c91e821a2debf77c92962ea3fe6ac2bc45d0778c1cbe15d4fce2fd94/numpy-2.3.3-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:d9192da52b9745f7f0766531dcfa978b7763916f158bb63bdb8a1eca0068ab20", size = 16641643, upload-time = "2025-09-09T15:56:43.343Z" }, - { url = "https://files.pythonhosted.org/packages/30/e4/961a5fa681502cd0d68907818b69f67542695b74e3ceaa513918103b7e80/numpy-2.3.3-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:cd7de500a5b66319db419dc3c345244404a164beae0d0937283b907d8152e6ea", size = 16056787, upload-time = "2025-09-09T15:56:46.141Z" }, - { url = "https://files.pythonhosted.org/packages/99/26/92c912b966e47fbbdf2ad556cb17e3a3088e2e1292b9833be1dfa5361a1a/numpy-2.3.3-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:93d4962d8f82af58f0b2eb85daaf1b3ca23fe0a85d0be8f1f2b7bb46034e56d7", size = 18579598, upload-time = "2025-09-09T15:56:49.844Z" }, - { url = "https://files.pythonhosted.org/packages/17/b6/fc8f82cb3520768718834f310c37d96380d9dc61bfdaf05fe5c0b7653e01/numpy-2.3.3-cp312-cp312-win32.whl", hash = "sha256:5534ed6b92f9b7dca6c0a19d6df12d41c68b991cef051d108f6dbff3babc4ebf", size = 6320800, upload-time = "2025-09-09T15:56:52.499Z" }, - { url = "https://files.pythonhosted.org/packages/32/ee/de999f2625b80d043d6d2d628c07d0d5555a677a3cf78fdf868d409b8766/numpy-2.3.3-cp312-cp312-win_amd64.whl", hash = "sha256:497d7cad08e7092dba36e3d296fe4c97708c93daf26643a1ae4b03f6294d30eb", size = 12786615, upload-time = "2025-09-09T15:56:54.422Z" }, - { url = "https://files.pythonhosted.org/packages/49/6e/b479032f8a43559c383acb20816644f5f91c88f633d9271ee84f3b3a996c/numpy-2.3.3-cp312-cp312-win_arm64.whl", hash = "sha256:ca0309a18d4dfea6fc6262a66d06c26cfe4640c3926ceec90e57791a82b6eee5", size = 10195936, upload-time = "2025-09-09T15:56:56.541Z" }, - { url = "https://files.pythonhosted.org/packages/7d/b9/984c2b1ee61a8b803bf63582b4ac4242cf76e2dbd663efeafcb620cc0ccb/numpy-2.3.3-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:f5415fb78995644253370985342cd03572ef8620b934da27d77377a2285955bf", size = 20949588, upload-time = "2025-09-09T15:56:59.087Z" }, - { url = "https://files.pythonhosted.org/packages/a6/e4/07970e3bed0b1384d22af1e9912527ecbeb47d3b26e9b6a3bced068b3bea/numpy-2.3.3-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:d00de139a3324e26ed5b95870ce63be7ec7352171bc69a4cf1f157a48e3eb6b7", size = 14177802, upload-time = "2025-09-09T15:57:01.73Z" }, - { url = "https://files.pythonhosted.org/packages/35/c7/477a83887f9de61f1203bad89cf208b7c19cc9fef0cebef65d5a1a0619f2/numpy-2.3.3-cp313-cp313-macosx_14_0_arm64.whl", hash = "sha256:9dc13c6a5829610cc07422bc74d3ac083bd8323f14e2827d992f9e52e22cd6a6", size = 5106537, upload-time = "2025-09-09T15:57:03.765Z" }, - { url = "https://files.pythonhosted.org/packages/52/47/93b953bd5866a6f6986344d045a207d3f1cfbad99db29f534ea9cee5108c/numpy-2.3.3-cp313-cp313-macosx_14_0_x86_64.whl", hash = "sha256:d79715d95f1894771eb4e60fb23f065663b2298f7d22945d66877aadf33d00c7", size = 6640743, upload-time = "2025-09-09T15:57:07.921Z" }, - { url = "https://files.pythonhosted.org/packages/23/83/377f84aaeb800b64c0ef4de58b08769e782edcefa4fea712910b6f0afd3c/numpy-2.3.3-cp313-cp313-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:952cfd0748514ea7c3afc729a0fc639e61655ce4c55ab9acfab14bda4f402b4c", size = 14278881, upload-time = "2025-09-09T15:57:11.349Z" }, - { url = "https://files.pythonhosted.org/packages/9a/a5/bf3db6e66c4b160d6ea10b534c381a1955dfab34cb1017ea93aa33c70ed3/numpy-2.3.3-cp313-cp313-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:5b83648633d46f77039c29078751f80da65aa64d5622a3cd62aaef9d835b6c93", size = 16636301, upload-time = "2025-09-09T15:57:14.245Z" }, - { url = "https://files.pythonhosted.org/packages/a2/59/1287924242eb4fa3f9b3a2c30400f2e17eb2707020d1c5e3086fe7330717/numpy-2.3.3-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:b001bae8cea1c7dfdb2ae2b017ed0a6f2102d7a70059df1e338e307a4c78a8ae", size = 16053645, upload-time = "2025-09-09T15:57:16.534Z" }, - { url = "https://files.pythonhosted.org/packages/e6/93/b3d47ed882027c35e94ac2320c37e452a549f582a5e801f2d34b56973c97/numpy-2.3.3-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:8e9aced64054739037d42fb84c54dd38b81ee238816c948c8f3ed134665dcd86", size = 18578179, upload-time = "2025-09-09T15:57:18.883Z" }, - { url = "https://files.pythonhosted.org/packages/20/d9/487a2bccbf7cc9d4bfc5f0f197761a5ef27ba870f1e3bbb9afc4bbe3fcc2/numpy-2.3.3-cp313-cp313-win32.whl", hash = "sha256:9591e1221db3f37751e6442850429b3aabf7026d3b05542d102944ca7f00c8a8", size = 6312250, upload-time = "2025-09-09T15:57:21.296Z" }, - { url = "https://files.pythonhosted.org/packages/1b/b5/263ebbbbcede85028f30047eab3d58028d7ebe389d6493fc95ae66c636ab/numpy-2.3.3-cp313-cp313-win_amd64.whl", hash = "sha256:f0dadeb302887f07431910f67a14d57209ed91130be0adea2f9793f1a4f817cf", size = 12783269, upload-time = "2025-09-09T15:57:23.034Z" }, - { url = "https://files.pythonhosted.org/packages/fa/75/67b8ca554bbeaaeb3fac2e8bce46967a5a06544c9108ec0cf5cece559b6c/numpy-2.3.3-cp313-cp313-win_arm64.whl", hash = "sha256:3c7cf302ac6e0b76a64c4aecf1a09e51abd9b01fc7feee80f6c43e3ab1b1dbc5", size = 10195314, upload-time = "2025-09-09T15:57:25.045Z" }, - { url = "https://files.pythonhosted.org/packages/11/d0/0d1ddec56b162042ddfafeeb293bac672de9b0cfd688383590090963720a/numpy-2.3.3-cp313-cp313t-macosx_10_13_x86_64.whl", hash = "sha256:eda59e44957d272846bb407aad19f89dc6f58fecf3504bd144f4c5cf81a7eacc", size = 21048025, upload-time = "2025-09-09T15:57:27.257Z" }, - { url = "https://files.pythonhosted.org/packages/36/9e/1996ca6b6d00415b6acbdd3c42f7f03ea256e2c3f158f80bd7436a8a19f3/numpy-2.3.3-cp313-cp313t-macosx_11_0_arm64.whl", hash = "sha256:823d04112bc85ef5c4fda73ba24e6096c8f869931405a80aa8b0e604510a26bc", size = 14301053, upload-time = "2025-09-09T15:57:30.077Z" }, - { url = "https://files.pythonhosted.org/packages/05/24/43da09aa764c68694b76e84b3d3f0c44cb7c18cdc1ba80e48b0ac1d2cd39/numpy-2.3.3-cp313-cp313t-macosx_14_0_arm64.whl", hash = "sha256:40051003e03db4041aa325da2a0971ba41cf65714e65d296397cc0e32de6018b", size = 5229444, upload-time = "2025-09-09T15:57:32.733Z" }, - { url = "https://files.pythonhosted.org/packages/bc/14/50ffb0f22f7218ef8af28dd089f79f68289a7a05a208db9a2c5dcbe123c1/numpy-2.3.3-cp313-cp313t-macosx_14_0_x86_64.whl", hash = "sha256:6ee9086235dd6ab7ae75aba5662f582a81ced49f0f1c6de4260a78d8f2d91a19", size = 6738039, upload-time = "2025-09-09T15:57:34.328Z" }, - { url = "https://files.pythonhosted.org/packages/55/52/af46ac0795e09657d45a7f4db961917314377edecf66db0e39fa7ab5c3d3/numpy-2.3.3-cp313-cp313t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:94fcaa68757c3e2e668ddadeaa86ab05499a70725811e582b6a9858dd472fb30", size = 14352314, upload-time = "2025-09-09T15:57:36.255Z" }, - { url = "https://files.pythonhosted.org/packages/a7/b1/dc226b4c90eb9f07a3fff95c2f0db3268e2e54e5cce97c4ac91518aee71b/numpy-2.3.3-cp313-cp313t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:da1a74b90e7483d6ce5244053399a614b1d6b7bc30a60d2f570e5071f8959d3e", size = 16701722, upload-time = "2025-09-09T15:57:38.622Z" }, - { url = "https://files.pythonhosted.org/packages/9d/9d/9d8d358f2eb5eced14dba99f110d83b5cd9a4460895230f3b396ad19a323/numpy-2.3.3-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:2990adf06d1ecee3b3dcbb4977dfab6e9f09807598d647f04d385d29e7a3c3d3", size = 16132755, upload-time = "2025-09-09T15:57:41.16Z" }, - { url = "https://files.pythonhosted.org/packages/b6/27/b3922660c45513f9377b3fb42240bec63f203c71416093476ec9aa0719dc/numpy-2.3.3-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:ed635ff692483b8e3f0fcaa8e7eb8a75ee71aa6d975388224f70821421800cea", size = 18651560, upload-time = "2025-09-09T15:57:43.459Z" }, - { url = "https://files.pythonhosted.org/packages/5b/8e/3ab61a730bdbbc201bb245a71102aa609f0008b9ed15255500a99cd7f780/numpy-2.3.3-cp313-cp313t-win32.whl", hash = "sha256:a333b4ed33d8dc2b373cc955ca57babc00cd6f9009991d9edc5ddbc1bac36bcd", size = 6442776, upload-time = "2025-09-09T15:57:45.793Z" }, - { url = "https://files.pythonhosted.org/packages/1c/3a/e22b766b11f6030dc2decdeff5c2fb1610768055603f9f3be88b6d192fb2/numpy-2.3.3-cp313-cp313t-win_amd64.whl", hash = "sha256:4384a169c4d8f97195980815d6fcad04933a7e1ab3b530921c3fef7a1c63426d", size = 12927281, upload-time = "2025-09-09T15:57:47.492Z" }, - { url = "https://files.pythonhosted.org/packages/7b/42/c2e2bc48c5e9b2a83423f99733950fbefd86f165b468a3d85d52b30bf782/numpy-2.3.3-cp313-cp313t-win_arm64.whl", hash = "sha256:75370986cc0bc66f4ce5110ad35aae6d182cc4ce6433c40ad151f53690130bf1", size = 10265275, upload-time = "2025-09-09T15:57:49.647Z" }, - { url = "https://files.pythonhosted.org/packages/6b/01/342ad585ad82419b99bcf7cebe99e61da6bedb89e213c5fd71acc467faee/numpy-2.3.3-cp314-cp314-macosx_10_13_x86_64.whl", hash = "sha256:cd052f1fa6a78dee696b58a914b7229ecfa41f0a6d96dc663c1220a55e137593", size = 20951527, upload-time = "2025-09-09T15:57:52.006Z" }, - { url = "https://files.pythonhosted.org/packages/ef/d8/204e0d73fc1b7a9ee80ab1fe1983dd33a4d64a4e30a05364b0208e9a241a/numpy-2.3.3-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:414a97499480067d305fcac9716c29cf4d0d76db6ebf0bf3cbce666677f12652", size = 14186159, upload-time = "2025-09-09T15:57:54.407Z" }, - { url = "https://files.pythonhosted.org/packages/22/af/f11c916d08f3a18fb8ba81ab72b5b74a6e42ead4c2846d270eb19845bf74/numpy-2.3.3-cp314-cp314-macosx_14_0_arm64.whl", hash = "sha256:50a5fe69f135f88a2be9b6ca0481a68a136f6febe1916e4920e12f1a34e708a7", size = 5114624, upload-time = "2025-09-09T15:57:56.5Z" }, - { url = "https://files.pythonhosted.org/packages/fb/11/0ed919c8381ac9d2ffacd63fd1f0c34d27e99cab650f0eb6f110e6ae4858/numpy-2.3.3-cp314-cp314-macosx_14_0_x86_64.whl", hash = "sha256:b912f2ed2b67a129e6a601e9d93d4fa37bef67e54cac442a2f588a54afe5c67a", size = 6642627, upload-time = "2025-09-09T15:57:58.206Z" }, - { url = "https://files.pythonhosted.org/packages/ee/83/deb5f77cb0f7ba6cb52b91ed388b47f8f3c2e9930d4665c600408d9b90b9/numpy-2.3.3-cp314-cp314-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:9e318ee0596d76d4cb3d78535dc005fa60e5ea348cd131a51e99d0bdbe0b54fe", size = 14296926, upload-time = "2025-09-09T15:58:00.035Z" }, - { url = "https://files.pythonhosted.org/packages/77/cc/70e59dcb84f2b005d4f306310ff0a892518cc0c8000a33d0e6faf7ca8d80/numpy-2.3.3-cp314-cp314-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:ce020080e4a52426202bdb6f7691c65bb55e49f261f31a8f506c9f6bc7450421", size = 16638958, upload-time = "2025-09-09T15:58:02.738Z" }, - { url = "https://files.pythonhosted.org/packages/b6/5a/b2ab6c18b4257e099587d5b7f903317bd7115333ad8d4ec4874278eafa61/numpy-2.3.3-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:e6687dc183aa55dae4a705b35f9c0f8cb178bcaa2f029b241ac5356221d5c021", size = 16071920, upload-time = "2025-09-09T15:58:05.029Z" }, - { url = "https://files.pythonhosted.org/packages/b8/f1/8b3fdc44324a259298520dd82147ff648979bed085feeacc1250ef1656c0/numpy-2.3.3-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:d8f3b1080782469fdc1718c4ed1d22549b5fb12af0d57d35e992158a772a37cf", size = 18577076, upload-time = "2025-09-09T15:58:07.745Z" }, - { url = "https://files.pythonhosted.org/packages/f0/a1/b87a284fb15a42e9274e7fcea0dad259d12ddbf07c1595b26883151ca3b4/numpy-2.3.3-cp314-cp314-win32.whl", hash = "sha256:cb248499b0bc3be66ebd6578b83e5acacf1d6cb2a77f2248ce0e40fbec5a76d0", size = 6366952, upload-time = "2025-09-09T15:58:10.096Z" }, - { url = "https://files.pythonhosted.org/packages/70/5f/1816f4d08f3b8f66576d8433a66f8fa35a5acfb3bbd0bf6c31183b003f3d/numpy-2.3.3-cp314-cp314-win_amd64.whl", hash = "sha256:691808c2b26b0f002a032c73255d0bd89751425f379f7bcd22d140db593a96e8", size = 12919322, upload-time = "2025-09-09T15:58:12.138Z" }, - { url = "https://files.pythonhosted.org/packages/8c/de/072420342e46a8ea41c324a555fa90fcc11637583fb8df722936aed1736d/numpy-2.3.3-cp314-cp314-win_arm64.whl", hash = "sha256:9ad12e976ca7b10f1774b03615a2a4bab8addce37ecc77394d8e986927dc0dfe", size = 10478630, upload-time = "2025-09-09T15:58:14.64Z" }, - { url = "https://files.pythonhosted.org/packages/d5/df/ee2f1c0a9de7347f14da5dd3cd3c3b034d1b8607ccb6883d7dd5c035d631/numpy-2.3.3-cp314-cp314t-macosx_10_13_x86_64.whl", hash = "sha256:9cc48e09feb11e1db00b320e9d30a4151f7369afb96bd0e48d942d09da3a0d00", size = 21047987, upload-time = "2025-09-09T15:58:16.889Z" }, - { url = "https://files.pythonhosted.org/packages/d6/92/9453bdc5a4e9e69cf4358463f25e8260e2ffc126d52e10038b9077815989/numpy-2.3.3-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:901bf6123879b7f251d3631967fd574690734236075082078e0571977c6a8e6a", size = 14301076, upload-time = "2025-09-09T15:58:20.343Z" }, - { url = "https://files.pythonhosted.org/packages/13/77/1447b9eb500f028bb44253105bd67534af60499588a5149a94f18f2ca917/numpy-2.3.3-cp314-cp314t-macosx_14_0_arm64.whl", hash = "sha256:7f025652034199c301049296b59fa7d52c7e625017cae4c75d8662e377bf487d", size = 5229491, upload-time = "2025-09-09T15:58:22.481Z" }, - { url = "https://files.pythonhosted.org/packages/3d/f9/d72221b6ca205f9736cb4b2ce3b002f6e45cd67cd6a6d1c8af11a2f0b649/numpy-2.3.3-cp314-cp314t-macosx_14_0_x86_64.whl", hash = "sha256:533ca5f6d325c80b6007d4d7fb1984c303553534191024ec6a524a4c92a5935a", size = 6737913, upload-time = "2025-09-09T15:58:24.569Z" }, - { url = "https://files.pythonhosted.org/packages/3c/5f/d12834711962ad9c46af72f79bb31e73e416ee49d17f4c797f72c96b6ca5/numpy-2.3.3-cp314-cp314t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:0edd58682a399824633b66885d699d7de982800053acf20be1eaa46d92009c54", size = 14352811, upload-time = "2025-09-09T15:58:26.416Z" }, - { url = "https://files.pythonhosted.org/packages/a1/0d/fdbec6629d97fd1bebed56cd742884e4eead593611bbe1abc3eb40d304b2/numpy-2.3.3-cp314-cp314t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:367ad5d8fbec5d9296d18478804a530f1191e24ab4d75ab408346ae88045d25e", size = 16702689, upload-time = "2025-09-09T15:58:28.831Z" }, - { url = "https://files.pythonhosted.org/packages/9b/09/0a35196dc5575adde1eb97ddfbc3e1687a814f905377621d18ca9bc2b7dd/numpy-2.3.3-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:8f6ac61a217437946a1fa48d24c47c91a0c4f725237871117dea264982128097", size = 16133855, upload-time = "2025-09-09T15:58:31.349Z" }, - { url = "https://files.pythonhosted.org/packages/7a/ca/c9de3ea397d576f1b6753eaa906d4cdef1bf97589a6d9825a349b4729cc2/numpy-2.3.3-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:179a42101b845a816d464b6fe9a845dfaf308fdfc7925387195570789bb2c970", size = 18652520, upload-time = "2025-09-09T15:58:33.762Z" }, - { url = "https://files.pythonhosted.org/packages/fd/c2/e5ed830e08cd0196351db55db82f65bc0ab05da6ef2b72a836dcf1936d2f/numpy-2.3.3-cp314-cp314t-win32.whl", hash = "sha256:1250c5d3d2562ec4174bce2e3a1523041595f9b651065e4a4473f5f48a6bc8a5", size = 6515371, upload-time = "2025-09-09T15:58:36.04Z" }, - { url = "https://files.pythonhosted.org/packages/47/c7/b0f6b5b67f6788a0725f744496badbb604d226bf233ba716683ebb47b570/numpy-2.3.3-cp314-cp314t-win_amd64.whl", hash = "sha256:b37a0b2e5935409daebe82c1e42274d30d9dd355852529eab91dab8dcca7419f", size = 13112576, upload-time = "2025-09-09T15:58:37.927Z" }, - { url = "https://files.pythonhosted.org/packages/06/b9/33bba5ff6fb679aa0b1f8a07e853f002a6b04b9394db3069a1270a7784ca/numpy-2.3.3-cp314-cp314t-win_arm64.whl", hash = "sha256:78c9f6560dc7e6b3990e32df7ea1a50bbd0e2a111e05209963f5ddcab7073b0b", size = 10545953, upload-time = "2025-09-09T15:58:40.576Z" }, +sdist = { url = "https://files.pythonhosted.org/packages/65/6e/09db70a523a96d25e115e71cc56a6f9031e7b8cd166c1ac8438307c14058/numpy-1.26.4.tar.gz", hash = "sha256:2a02aba9ed12e4ac4eb3ea9421c420301a0c6460d9830d74a9df87efa4912010", size = 15786129, upload-time = "2024-02-06T00:26:44.495Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/11/57/baae43d14fe163fa0e4c47f307b6b2511ab8d7d30177c491960504252053/numpy-1.26.4-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:4c66707fabe114439db9068ee468c26bbdf909cac0fb58686a42a24de1760c71", size = 20630554, upload-time = "2024-02-05T23:51:50.149Z" }, + { url = "https://files.pythonhosted.org/packages/1a/2e/151484f49fd03944c4a3ad9c418ed193cfd02724e138ac8a9505d056c582/numpy-1.26.4-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:edd8b5fe47dab091176d21bb6de568acdd906d1887a4584a15a9a96a1dca06ef", size = 13997127, upload-time = "2024-02-05T23:52:15.314Z" }, + { url = "https://files.pythonhosted.org/packages/79/ae/7e5b85136806f9dadf4878bf73cf223fe5c2636818ba3ab1c585d0403164/numpy-1.26.4-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7ab55401287bfec946ced39700c053796e7cc0e3acbef09993a9ad2adba6ca6e", size = 14222994, upload-time = "2024-02-05T23:52:47.569Z" }, + { url = "https://files.pythonhosted.org/packages/3a/d0/edc009c27b406c4f9cbc79274d6e46d634d139075492ad055e3d68445925/numpy-1.26.4-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:666dbfb6ec68962c033a450943ded891bed2d54e6755e35e5835d63f4f6931d5", size = 18252005, upload-time = "2024-02-05T23:53:15.637Z" }, + { url = "https://files.pythonhosted.org/packages/09/bf/2b1aaf8f525f2923ff6cfcf134ae5e750e279ac65ebf386c75a0cf6da06a/numpy-1.26.4-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:96ff0b2ad353d8f990b63294c8986f1ec3cb19d749234014f4e7eb0112ceba5a", size = 13885297, upload-time = "2024-02-05T23:53:42.16Z" }, + { url = "https://files.pythonhosted.org/packages/df/a0/4e0f14d847cfc2a633a1c8621d00724f3206cfeddeb66d35698c4e2cf3d2/numpy-1.26.4-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:60dedbb91afcbfdc9bc0b1f3f402804070deed7392c23eb7a7f07fa857868e8a", size = 18093567, upload-time = "2024-02-05T23:54:11.696Z" }, + { url = "https://files.pythonhosted.org/packages/d2/b7/a734c733286e10a7f1a8ad1ae8c90f2d33bf604a96548e0a4a3a6739b468/numpy-1.26.4-cp311-cp311-win32.whl", hash = "sha256:1af303d6b2210eb850fcf03064d364652b7120803a0b872f5211f5234b399f20", size = 5968812, upload-time = "2024-02-05T23:54:26.453Z" }, + { url = "https://files.pythonhosted.org/packages/3f/6b/5610004206cf7f8e7ad91c5a85a8c71b2f2f8051a0c0c4d5916b76d6cbb2/numpy-1.26.4-cp311-cp311-win_amd64.whl", hash = "sha256:cd25bcecc4974d09257ffcd1f098ee778f7834c3ad767fe5db785be9a4aa9cb2", size = 15811913, upload-time = "2024-02-05T23:54:53.933Z" }, + { url = "https://files.pythonhosted.org/packages/95/12/8f2020a8e8b8383ac0177dc9570aad031a3beb12e38847f7129bacd96228/numpy-1.26.4-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:b3ce300f3644fb06443ee2222c2201dd3a89ea6040541412b8fa189341847218", size = 20335901, upload-time = "2024-02-05T23:55:32.801Z" }, + { url = "https://files.pythonhosted.org/packages/75/5b/ca6c8bd14007e5ca171c7c03102d17b4f4e0ceb53957e8c44343a9546dcc/numpy-1.26.4-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:03a8c78d01d9781b28a6989f6fa1bb2c4f2d51201cf99d3dd875df6fbd96b23b", size = 13685868, upload-time = "2024-02-05T23:55:56.28Z" }, + { url = "https://files.pythonhosted.org/packages/79/f8/97f10e6755e2a7d027ca783f63044d5b1bc1ae7acb12afe6a9b4286eac17/numpy-1.26.4-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9fad7dcb1aac3c7f0584a5a8133e3a43eeb2fe127f47e3632d43d677c66c102b", size = 13925109, upload-time = "2024-02-05T23:56:20.368Z" }, + { url = "https://files.pythonhosted.org/packages/0f/50/de23fde84e45f5c4fda2488c759b69990fd4512387a8632860f3ac9cd225/numpy-1.26.4-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:675d61ffbfa78604709862923189bad94014bef562cc35cf61d3a07bba02a7ed", size = 17950613, upload-time = "2024-02-05T23:56:56.054Z" }, + { url = "https://files.pythonhosted.org/packages/4c/0c/9c603826b6465e82591e05ca230dfc13376da512b25ccd0894709b054ed0/numpy-1.26.4-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:ab47dbe5cc8210f55aa58e4805fe224dac469cde56b9f731a4c098b91917159a", size = 13572172, upload-time = "2024-02-05T23:57:21.56Z" }, + { url = "https://files.pythonhosted.org/packages/76/8c/2ba3902e1a0fc1c74962ea9bb33a534bb05984ad7ff9515bf8d07527cadd/numpy-1.26.4-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:1dda2e7b4ec9dd512f84935c5f126c8bd8b9f2fc001e9f54af255e8c5f16b0e0", size = 17786643, upload-time = "2024-02-05T23:57:56.585Z" }, + { url = "https://files.pythonhosted.org/packages/28/4a/46d9e65106879492374999e76eb85f87b15328e06bd1550668f79f7b18c6/numpy-1.26.4-cp312-cp312-win32.whl", hash = "sha256:50193e430acfc1346175fcbdaa28ffec49947a06918b7b92130744e81e640110", size = 5677803, upload-time = "2024-02-05T23:58:08.963Z" }, + { url = "https://files.pythonhosted.org/packages/16/2e/86f24451c2d530c88daf997cb8d6ac622c1d40d19f5a031ed68a4b73a374/numpy-1.26.4-cp312-cp312-win_amd64.whl", hash = "sha256:08beddf13648eb95f8d867350f6a018a4be2e5ad54c8d8caed89ebca558b2818", size = 15517754, upload-time = "2024-02-05T23:58:36.364Z" }, ] [[package]] @@ -3069,6 +3353,12 @@ dependencies = [ ] sdist = { url = "https://files.pythonhosted.org/packages/c5/eb/7af61dd6c1063b56f452c0de867955ad4d733aca517e38658829cf4d6b83/numpy_quaternion-2024.0.12.tar.gz", hash = "sha256:5ecb4e310e732bc21687474c1bc6cd6187d5c22da78d342379fe81f12f46037f", size = 67291, upload-time = "2025-09-09T04:49:33.215Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/81/05/5a57db959ee902d2e938ea88c4a09a6ad3cca65a73c80528b412bf48aabb/numpy_quaternion-2024.0.12-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:19e6ba157bc15d48f8d6f8be25f200d3a0858ae655e54a30bd423ca0d3aa5659", size = 86238, upload-time = "2025-09-09T04:49:40.469Z" }, + { url = "https://files.pythonhosted.org/packages/bc/18/94d6f6ff1069bd46bd4ef9644c44f777346ddf0183e315d69f719fce06be/numpy_quaternion-2024.0.12-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:fb8087c737422ff893163782dd99188e159aac5dcddec83538ad53a172755d3d", size = 61198, upload-time = "2025-09-09T04:49:35.363Z" }, + { url = "https://files.pythonhosted.org/packages/a0/24/608f9212b81eca06f1df916a4d3077cfc3fe3f97201740e2fbae229f41ce/numpy_quaternion-2024.0.12-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:fa37c4102f47dc5e675dd6714f390edcc6a9c3151a427d34bd5778e71f26d489", size = 55310, upload-time = "2025-09-09T04:49:19.142Z" }, + { url = "https://files.pythonhosted.org/packages/db/75/01f319414f031b75703dfd72243adfa0a1b90d372e218dbb040e4ce8c2c1/numpy_quaternion-2024.0.12-cp311-cp311-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:16f797e1733d04b48f3ad86b4e38398d49415f28a9d7d55b5e541533c3badddf", size = 187988, upload-time = "2025-09-09T04:49:10.787Z" }, + { url = "https://files.pythonhosted.org/packages/7a/e9/ebb4ee9603ae1ea2495cb1ecab5a8f07b28bcc0892f03ba62d81de7cbcba/numpy_quaternion-2024.0.12-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:989e6edf66b8b083354b24e7303d405ed9cd76d29b37852474794c8b2cab5b38", size = 183338, upload-time = "2025-09-09T04:49:36.777Z" }, + { url = "https://files.pythonhosted.org/packages/62/fe/3f7aec5a1a68b0ea2d34f511bf12b8b444bd28a6e663ecd604406ac9ffb9/numpy_quaternion-2024.0.12-cp311-cp311-win_amd64.whl", hash = "sha256:63b959ed309dbd0e8da2e41f2574b4b8f3d8f972bf3c49fdc54de56cdf28687f", size = 70005, upload-time = "2025-09-09T04:49:16.768Z" }, { url = "https://files.pythonhosted.org/packages/bd/4f/fa07dd8b41aba82bbc0dd91e3a6e051bab59e6095205c932e2180eb923f7/numpy_quaternion-2024.0.12-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:f7c96c1faac4d6c6ab2505beb26a82f2e8b3d3470d72c92af1837bc8f883378e", size = 86467, upload-time = "2025-09-09T04:49:18.194Z" }, { url = "https://files.pythonhosted.org/packages/06/28/6a72b54d92fc5ef3fb5f4f654b1d0d652b76040bfc07cfe6783655f5c4c6/numpy_quaternion-2024.0.12-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:947a5afbf1f42f6a86c5ea288165631bde3eb243fcb50e50af611149863bb541", size = 61267, upload-time = "2025-09-09T04:49:30.534Z" }, { url = "https://files.pythonhosted.org/packages/87/f2/ade6fde482f92adb0521c86678591416025623dcab9b7f73c1fe21846f5b/numpy_quaternion-2024.0.12-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:28cbece557ab04b393b1864f8790d1b4482e49cbc98566549ec3490e5af4d8db", size = 55503, upload-time = "2025-09-09T04:49:31.517Z" }, @@ -3085,14 +3375,14 @@ wheels = [ [[package]] name = "numpy-typing-compat" -version = "20250818.2.3" +version = "20250818.1.25" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "numpy" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/c9/e3/1a29f174c1e09a2bf111d37a41afceea1b501371abb39e73170ca31a7599/numpy_typing_compat-20250818.2.3.tar.gz", hash = "sha256:72e83d535b635d668ba7315e43ae80be1469a6faea6fc96d312516f39b3d8fa5", size = 4974, upload-time = "2025-08-18T23:46:42.968Z" } +sdist = { url = "https://files.pythonhosted.org/packages/ff/a7/780dc00f4fed2f2b653f76a196b3a6807c7c667f30ae95a7fd082c1081d8/numpy_typing_compat-20250818.1.25.tar.gz", hash = "sha256:8ff461725af0b436e9b0445d07712f1e6e3a97540a3542810f65f936dcc587a5", size = 5027, upload-time = "2025-08-18T23:46:39.062Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/c9/4a/fa4c90a03d6a8ee1a7f0e0fb101887d9a8cdb9b07a5901af9ae831e9feea/numpy_typing_compat-20250818.2.3-py3-none-any.whl", hash = "sha256:930413d34dd9083c0bf418815576222f1c66ea2d68950f447fd27ea1a78b26b0", size = 6286, upload-time = "2025-08-18T23:46:35.681Z" }, + { url = "https://files.pythonhosted.org/packages/1e/71/30e8d317b6896acbc347d3089764b6209ba299095550773e14d27dcf035f/numpy_typing_compat-20250818.1.25-py3-none-any.whl", hash = "sha256:4f91427369583074b236c804dd27559134f08ec4243485034c8e7d258cbd9cd3", size = 6355, upload-time = "2025-08-18T23:46:30.927Z" }, ] [[package]] @@ -3144,7 +3434,7 @@ name = "nvidia-cudnn-cu12" version = "9.10.2.21" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "nvidia-cublas-cu12", marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux')" }, + { name = "nvidia-cublas-cu12" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/ba/51/e123d997aa098c61d029f76663dedbfb9bc8dcf8c60cbd6adbe42f76d049/nvidia_cudnn_cu12-9.10.2.21-py3-none-manylinux_2_27_x86_64.whl", hash = "sha256:949452be657fa16687d0930933f032835951ef0892b37d2d53824d1a84dc97a8", size = 706758467, upload-time = "2025-06-06T21:54:08.597Z" }, @@ -3155,7 +3445,7 @@ name = "nvidia-cufft-cu12" version = "11.3.3.83" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "nvidia-nvjitlink-cu12", marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux')" }, + { name = "nvidia-nvjitlink-cu12" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/1f/13/ee4e00f30e676b66ae65b4f08cb5bcbb8392c03f54f2d5413ea99a5d1c80/nvidia_cufft_cu12-11.3.3.83-py3-none-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:4d2dd21ec0b88cf61b62e6b43564355e5222e4a3fb394cac0db101f2dd0d4f74", size = 193118695, upload-time = "2025-03-07T01:45:27.821Z" }, @@ -3182,9 +3472,9 @@ name = "nvidia-cusolver-cu12" version = "11.7.3.90" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "nvidia-cublas-cu12", marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux')" }, - { name = "nvidia-cusparse-cu12", marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux')" }, - { name = "nvidia-nvjitlink-cu12", marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux')" }, + { name = "nvidia-cublas-cu12" }, + { name = "nvidia-cusparse-cu12" }, + { name = "nvidia-nvjitlink-cu12" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/85/48/9a13d2975803e8cf2777d5ed57b87a0b6ca2cc795f9a4f59796a910bfb80/nvidia_cusolver_cu12-11.7.3.90-py3-none-manylinux_2_27_x86_64.whl", hash = "sha256:4376c11ad263152bd50ea295c05370360776f8c3427b30991df774f9fb26c450", size = 267506905, upload-time = "2025-03-07T01:47:16.273Z" }, @@ -3195,7 +3485,7 @@ name = "nvidia-cusparse-cu12" version = "12.5.8.93" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "nvidia-nvjitlink-cu12", marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux')" }, + { name = "nvidia-nvjitlink-cu12" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/c2/f5/e1854cb2f2bcd4280c44736c93550cc300ff4b8c95ebe370d0aa7d2b473d/nvidia_cusparse_cu12-12.5.8.93-py3-none-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:1ec05d76bbbd8b61b06a80e1eaf8cf4959c3d4ce8e711b65ebd0443bb0ebb13b", size = 288216466, upload-time = "2025-03-07T01:48:13.779Z" }, @@ -3305,6 +3595,21 @@ version = "3.11.3" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/be/4d/8df5f83256a809c22c4d6792ce8d43bb503be0fb7a8e4da9025754b09658/orjson-3.11.3.tar.gz", hash = "sha256:1c0603b1d2ffcd43a411d64797a19556ef76958aef1c182f22dc30860152a98a", size = 5482394, upload-time = "2025-08-26T17:46:43.171Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/cd/8b/360674cd817faef32e49276187922a946468579fcaf37afdfb6c07046e92/orjson-3.11.3-cp311-cp311-macosx_10_15_x86_64.macosx_11_0_arm64.macosx_10_15_universal2.whl", hash = "sha256:9d2ae0cc6aeb669633e0124531f342a17d8e97ea999e42f12a5ad4adaa304c5f", size = 238238, upload-time = "2025-08-26T17:44:54.214Z" }, + { url = "https://files.pythonhosted.org/packages/05/3d/5fa9ea4b34c1a13be7d9046ba98d06e6feb1d8853718992954ab59d16625/orjson-3.11.3-cp311-cp311-macosx_15_0_arm64.whl", hash = "sha256:ba21dbb2493e9c653eaffdc38819b004b7b1b246fb77bfc93dc016fe664eac91", size = 127713, upload-time = "2025-08-26T17:44:55.596Z" }, + { url = "https://files.pythonhosted.org/packages/e5/5f/e18367823925e00b1feec867ff5f040055892fc474bf5f7875649ecfa586/orjson-3.11.3-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:00f1a271e56d511d1569937c0447d7dce5a99a33ea0dec76673706360a051904", size = 123241, upload-time = "2025-08-26T17:44:57.185Z" }, + { url = "https://files.pythonhosted.org/packages/0f/bd/3c66b91c4564759cf9f473251ac1650e446c7ba92a7c0f9f56ed54f9f0e6/orjson-3.11.3-cp311-cp311-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:b67e71e47caa6680d1b6f075a396d04fa6ca8ca09aafb428731da9b3ea32a5a6", size = 127895, upload-time = "2025-08-26T17:44:58.349Z" }, + { url = "https://files.pythonhosted.org/packages/82/b5/dc8dcd609db4766e2967a85f63296c59d4722b39503e5b0bf7fd340d387f/orjson-3.11.3-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d7d012ebddffcce8c85734a6d9e5f08180cd3857c5f5a3ac70185b43775d043d", size = 130303, upload-time = "2025-08-26T17:44:59.491Z" }, + { url = "https://files.pythonhosted.org/packages/48/c2/d58ec5fd1270b2aa44c862171891adc2e1241bd7dab26c8f46eb97c6c6f1/orjson-3.11.3-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:dd759f75d6b8d1b62012b7f5ef9461d03c804f94d539a5515b454ba3a6588038", size = 132366, upload-time = "2025-08-26T17:45:00.654Z" }, + { url = "https://files.pythonhosted.org/packages/73/87/0ef7e22eb8dd1ef940bfe3b9e441db519e692d62ed1aae365406a16d23d0/orjson-3.11.3-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:6890ace0809627b0dff19cfad92d69d0fa3f089d3e359a2a532507bb6ba34efb", size = 135180, upload-time = "2025-08-26T17:45:02.424Z" }, + { url = "https://files.pythonhosted.org/packages/bb/6a/e5bf7b70883f374710ad74faf99bacfc4b5b5a7797c1d5e130350e0e28a3/orjson-3.11.3-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f9d4a5e041ae435b815e568537755773d05dac031fee6a57b4ba70897a44d9d2", size = 132741, upload-time = "2025-08-26T17:45:03.663Z" }, + { url = "https://files.pythonhosted.org/packages/bd/0c/4577fd860b6386ffaa56440e792af01c7882b56d2766f55384b5b0e9d39b/orjson-3.11.3-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:2d68bf97a771836687107abfca089743885fb664b90138d8761cce61d5625d55", size = 131104, upload-time = "2025-08-26T17:45:04.939Z" }, + { url = "https://files.pythonhosted.org/packages/66/4b/83e92b2d67e86d1c33f2ea9411742a714a26de63641b082bdbf3d8e481af/orjson-3.11.3-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:bfc27516ec46f4520b18ef645864cee168d2a027dbf32c5537cb1f3e3c22dac1", size = 403887, upload-time = "2025-08-26T17:45:06.228Z" }, + { url = "https://files.pythonhosted.org/packages/6d/e5/9eea6a14e9b5ceb4a271a1fd2e1dec5f2f686755c0fab6673dc6ff3433f4/orjson-3.11.3-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:f66b001332a017d7945e177e282a40b6997056394e3ed7ddb41fb1813b83e824", size = 145855, upload-time = "2025-08-26T17:45:08.338Z" }, + { url = "https://files.pythonhosted.org/packages/45/78/8d4f5ad0c80ba9bf8ac4d0fc71f93a7d0dc0844989e645e2074af376c307/orjson-3.11.3-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:212e67806525d2561efbfe9e799633b17eb668b8964abed6b5319b2f1cfbae1f", size = 135361, upload-time = "2025-08-26T17:45:09.625Z" }, + { url = "https://files.pythonhosted.org/packages/0b/5f/16386970370178d7a9b438517ea3d704efcf163d286422bae3b37b88dbb5/orjson-3.11.3-cp311-cp311-win32.whl", hash = "sha256:6e8e0c3b85575a32f2ffa59de455f85ce002b8bdc0662d6b9c2ed6d80ab5d204", size = 136190, upload-time = "2025-08-26T17:45:10.962Z" }, + { url = "https://files.pythonhosted.org/packages/09/60/db16c6f7a41dd8ac9fb651f66701ff2aeb499ad9ebc15853a26c7c152448/orjson-3.11.3-cp311-cp311-win_amd64.whl", hash = "sha256:6be2f1b5d3dc99a5ce5ce162fc741c22ba9f3443d3dd586e6a1211b7bc87bc7b", size = 131389, upload-time = "2025-08-26T17:45:12.285Z" }, + { url = "https://files.pythonhosted.org/packages/3e/2a/bb811ad336667041dea9b8565c7c9faf2f59b47eb5ab680315eea612ef2e/orjson-3.11.3-cp311-cp311-win_arm64.whl", hash = "sha256:fafb1a99d740523d964b15c8db4eabbfc86ff29f84898262bf6e3e4c9e97e43e", size = 126120, upload-time = "2025-08-26T17:45:13.515Z" }, { url = "https://files.pythonhosted.org/packages/3d/b0/a7edab2a00cdcb2688e1c943401cb3236323e7bfd2839815c6131a3742f4/orjson-3.11.3-cp312-cp312-macosx_10_15_x86_64.macosx_11_0_arm64.macosx_10_15_universal2.whl", hash = "sha256:8c752089db84333e36d754c4baf19c0e1437012242048439c7e80eb0e6426e3b", size = 238259, upload-time = "2025-08-26T17:45:15.093Z" }, { url = "https://files.pythonhosted.org/packages/e1/c6/ff4865a9cc398a07a83342713b5932e4dc3cb4bf4bc04e8f83dedfc0d736/orjson-3.11.3-cp312-cp312-macosx_15_0_arm64.whl", hash = "sha256:9b8761b6cf04a856eb544acdd82fc594b978f12ac3602d6374a7edb9d86fd2c2", size = 127633, upload-time = "2025-08-26T17:45:16.417Z" }, { url = "https://files.pythonhosted.org/packages/6e/e6/e00bea2d9472f44fe8794f523e548ce0ad51eb9693cf538a753a27b8bda4/orjson-3.11.3-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8b13974dc8ac6ba22feaa867fc19135a3e01a134b4f7c9c28162fed4d615008a", size = 123061, upload-time = "2025-08-26T17:45:17.673Z" }, @@ -3348,6 +3653,15 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/28/01/d6b274a0635be0468d4dbd9cafe80c47105937a0d42434e805e67cd2ed8b/orjson-3.11.3-cp314-cp314-win_arm64.whl", hash = "sha256:e8f6a7a27d7b7bec81bd5924163e9af03d49bbb63013f107b48eb5d16db711bc", size = 125985, upload-time = "2025-08-26T17:46:16.67Z" }, ] +[[package]] +name = "overrides" +version = "7.7.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/36/86/b585f53236dec60aba864e050778b25045f857e17f6e5ea0ae95fe80edd2/overrides-7.7.0.tar.gz", hash = "sha256:55158fa3d93b98cc75299b1e67078ad9003ca27945c76162c1c0766d6f91820a", size = 22812, upload-time = "2024-01-27T21:01:33.423Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/2c/ab/fc8290c6a4c722e5514d80f62b2dc4c4df1a68a41d1364e625c35990fcf3/overrides-7.7.0-py3-none-any.whl", hash = "sha256:c7ed9d062f78b8e4c1a7b70bd8796b35ead4d9f510227ef9c5dc7626c60d7e49", size = 17832, upload-time = "2024-01-27T21:01:31.393Z" }, +] + [[package]] name = "packaging" version = "25.0" @@ -3369,6 +3683,13 @@ dependencies = [ ] sdist = { url = "https://files.pythonhosted.org/packages/33/01/d40b85317f86cf08d853a4f495195c73815fdf205eef3993821720274518/pandas-2.3.3.tar.gz", hash = "sha256:e05e1af93b977f7eafa636d043f9f94c7ee3ac81af99c13508215942e64c993b", size = 4495223, upload-time = "2025-09-29T23:34:51.853Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/c1/fa/7ac648108144a095b4fb6aa3de1954689f7af60a14cf25583f4960ecb878/pandas-2.3.3-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:602b8615ebcc4a0c1751e71840428ddebeb142ec02c786e8ad6b1ce3c8dec523", size = 11578790, upload-time = "2025-09-29T23:18:30.065Z" }, + { url = "https://files.pythonhosted.org/packages/9b/35/74442388c6cf008882d4d4bdfc4109be87e9b8b7ccd097ad1e7f006e2e95/pandas-2.3.3-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:8fe25fc7b623b0ef6b5009149627e34d2a4657e880948ec3c840e9402e5c1b45", size = 10833831, upload-time = "2025-09-29T23:38:56.071Z" }, + { url = "https://files.pythonhosted.org/packages/fe/e4/de154cbfeee13383ad58d23017da99390b91d73f8c11856f2095e813201b/pandas-2.3.3-cp311-cp311-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:b468d3dad6ff947df92dcb32ede5b7bd41a9b3cceef0a30ed925f6d01fb8fa66", size = 12199267, upload-time = "2025-09-29T23:18:41.627Z" }, + { url = "https://files.pythonhosted.org/packages/bf/c9/63f8d545568d9ab91476b1818b4741f521646cbdd151c6efebf40d6de6f7/pandas-2.3.3-cp311-cp311-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:b98560e98cb334799c0b07ca7967ac361a47326e9b4e5a7dfb5ab2b1c9d35a1b", size = 12789281, upload-time = "2025-09-29T23:18:56.834Z" }, + { url = "https://files.pythonhosted.org/packages/f2/00/a5ac8c7a0e67fd1a6059e40aa08fa1c52cc00709077d2300e210c3ce0322/pandas-2.3.3-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:1d37b5848ba49824e5c30bedb9c830ab9b7751fd049bc7914533e01c65f79791", size = 13240453, upload-time = "2025-09-29T23:19:09.247Z" }, + { url = "https://files.pythonhosted.org/packages/27/4d/5c23a5bc7bd209231618dd9e606ce076272c9bc4f12023a70e03a86b4067/pandas-2.3.3-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:db4301b2d1f926ae677a751eb2bd0e8c5f5319c9cb3f88b0becbbb0b07b34151", size = 13890361, upload-time = "2025-09-29T23:19:25.342Z" }, + { url = "https://files.pythonhosted.org/packages/8e/59/712db1d7040520de7a4965df15b774348980e6df45c129b8c64d0dbe74ef/pandas-2.3.3-cp311-cp311-win_amd64.whl", hash = "sha256:f086f6fe114e19d92014a1966f43a3e62285109afe874f067f5abbdcbb10e59c", size = 11348702, upload-time = "2025-09-29T23:19:38.296Z" }, { url = "https://files.pythonhosted.org/packages/9c/fb/231d89e8637c808b997d172b18e9d4a4bc7bf31296196c260526055d1ea0/pandas-2.3.3-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:6d21f6d74eb1725c2efaa71a2bfc661a0689579b58e9c0ca58a739ff0b002b53", size = 11597846, upload-time = "2025-09-29T23:19:48.856Z" }, { url = "https://files.pythonhosted.org/packages/5c/bd/bf8064d9cfa214294356c2d6702b716d3cf3bb24be59287a6a21e24cae6b/pandas-2.3.3-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:3fd2f887589c7aa868e02632612ba39acb0b8948faf5cc58f0850e165bd46f35", size = 10729618, upload-time = "2025-09-29T23:39:08.659Z" }, { url = "https://files.pythonhosted.org/packages/57/56/cf2dbe1a3f5271370669475ead12ce77c61726ffd19a35546e31aa8edf4e/pandas-2.3.3-cp312-cp312-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:ecaf1e12bdc03c86ad4a7ea848d66c685cb6851d807a26aa245ca3d2017a1908", size = 11737212, upload-time = "2025-09-29T23:19:59.765Z" }, @@ -3515,6 +3836,17 @@ version = "11.3.0" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/f3/0d/d0d6dea55cd152ce3d6767bb38a8fc10e33796ba4ba210cbab9354b6d238/pillow-11.3.0.tar.gz", hash = "sha256:3828ee7586cd0b2091b6209e5ad53e20d0649bbe87164a459d0676e035e8f523", size = 47113069, upload-time = "2025-07-01T09:16:30.666Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/db/26/77f8ed17ca4ffd60e1dcd220a6ec6d71210ba398cfa33a13a1cd614c5613/pillow-11.3.0-cp311-cp311-macosx_10_10_x86_64.whl", hash = "sha256:1cd110edf822773368b396281a2293aeb91c90a2db00d78ea43e7e861631b722", size = 5316531, upload-time = "2025-07-01T09:13:59.203Z" }, + { url = "https://files.pythonhosted.org/packages/cb/39/ee475903197ce709322a17a866892efb560f57900d9af2e55f86db51b0a5/pillow-11.3.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:9c412fddd1b77a75aa904615ebaa6001f169b26fd467b4be93aded278266b288", size = 4686560, upload-time = "2025-07-01T09:14:01.101Z" }, + { url = "https://files.pythonhosted.org/packages/d5/90/442068a160fd179938ba55ec8c97050a612426fae5ec0a764e345839f76d/pillow-11.3.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:7d1aa4de119a0ecac0a34a9c8bde33f34022e2e8f99104e47a3ca392fd60e37d", size = 5870978, upload-time = "2025-07-03T13:09:55.638Z" }, + { url = "https://files.pythonhosted.org/packages/13/92/dcdd147ab02daf405387f0218dcf792dc6dd5b14d2573d40b4caeef01059/pillow-11.3.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:91da1d88226663594e3f6b4b8c3c8d85bd504117d043740a8e0ec449087cc494", size = 7641168, upload-time = "2025-07-03T13:10:00.37Z" }, + { url = "https://files.pythonhosted.org/packages/6e/db/839d6ba7fd38b51af641aa904e2960e7a5644d60ec754c046b7d2aee00e5/pillow-11.3.0-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:643f189248837533073c405ec2f0bb250ba54598cf80e8c1e043381a60632f58", size = 5973053, upload-time = "2025-07-01T09:14:04.491Z" }, + { url = "https://files.pythonhosted.org/packages/f2/2f/d7675ecae6c43e9f12aa8d58b6012683b20b6edfbdac7abcb4e6af7a3784/pillow-11.3.0-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:106064daa23a745510dabce1d84f29137a37224831d88eb4ce94bb187b1d7e5f", size = 6640273, upload-time = "2025-07-01T09:14:06.235Z" }, + { url = "https://files.pythonhosted.org/packages/45/ad/931694675ede172e15b2ff03c8144a0ddaea1d87adb72bb07655eaffb654/pillow-11.3.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:cd8ff254faf15591e724dc7c4ddb6bf4793efcbe13802a4ae3e863cd300b493e", size = 6082043, upload-time = "2025-07-01T09:14:07.978Z" }, + { url = "https://files.pythonhosted.org/packages/3a/04/ba8f2b11fc80d2dd462d7abec16351b45ec99cbbaea4387648a44190351a/pillow-11.3.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:932c754c2d51ad2b2271fd01c3d121daaa35e27efae2a616f77bf164bc0b3e94", size = 6715516, upload-time = "2025-07-01T09:14:10.233Z" }, + { url = "https://files.pythonhosted.org/packages/48/59/8cd06d7f3944cc7d892e8533c56b0acb68399f640786313275faec1e3b6f/pillow-11.3.0-cp311-cp311-win32.whl", hash = "sha256:b4b8f3efc8d530a1544e5962bd6b403d5f7fe8b9e08227c6b255f98ad82b4ba0", size = 6274768, upload-time = "2025-07-01T09:14:11.921Z" }, + { url = "https://files.pythonhosted.org/packages/f1/cc/29c0f5d64ab8eae20f3232da8f8571660aa0ab4b8f1331da5c2f5f9a938e/pillow-11.3.0-cp311-cp311-win_amd64.whl", hash = "sha256:1a992e86b0dd7aeb1f053cd506508c0999d710a8f07b4c791c63843fc6a807ac", size = 6986055, upload-time = "2025-07-01T09:14:13.623Z" }, + { url = "https://files.pythonhosted.org/packages/c6/df/90bd886fabd544c25addd63e5ca6932c86f2b701d5da6c7839387a076b4a/pillow-11.3.0-cp311-cp311-win_arm64.whl", hash = "sha256:30807c931ff7c095620fe04448e2c2fc673fcbb1ffe2a7da3fb39613489b1ddd", size = 2423079, upload-time = "2025-07-01T09:14:15.268Z" }, { url = "https://files.pythonhosted.org/packages/40/fe/1bc9b3ee13f68487a99ac9529968035cca2f0a51ec36892060edcc51d06a/pillow-11.3.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:fdae223722da47b024b867c1ea0be64e0df702c5e0a60e27daad39bf960dd1e4", size = 5278800, upload-time = "2025-07-01T09:14:17.648Z" }, { url = "https://files.pythonhosted.org/packages/2c/32/7e2ac19b5713657384cec55f89065fb306b06af008cfd87e572035b27119/pillow-11.3.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:921bd305b10e82b4d1f5e802b6850677f965d8394203d182f078873851dada69", size = 4686296, upload-time = "2025-07-01T09:14:19.828Z" }, { url = "https://files.pythonhosted.org/packages/8e/1e/b9e12bbe6e4c2220effebc09ea0923a07a6da1e1f1bfbc8d7d29a01ce32b/pillow-11.3.0-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:eb76541cba2f958032d79d143b98a3a6b3ea87f0959bbe256c0b5e416599fd5d", size = 5871726, upload-time = "2025-07-03T13:10:04.448Z" }, @@ -3573,6 +3905,13 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/f0/77/bc6f92a3e8e6e46c0ca78abfffec0037845800ea38c73483760362804c41/pillow-11.3.0-cp314-cp314t-win32.whl", hash = "sha256:118ca10c0d60b06d006be10a501fd6bbdfef559251ed31b794668ed569c87e12", size = 6377370, upload-time = "2025-07-01T09:15:46.673Z" }, { url = "https://files.pythonhosted.org/packages/4a/82/3a721f7d69dca802befb8af08b7c79ebcab461007ce1c18bd91a5d5896f9/pillow-11.3.0-cp314-cp314t-win_amd64.whl", hash = "sha256:8924748b688aa210d79883357d102cd64690e56b923a186f35a82cbc10f997db", size = 7121500, upload-time = "2025-07-01T09:15:48.512Z" }, { url = "https://files.pythonhosted.org/packages/89/c7/5572fa4a3f45740eaab6ae86fcdf7195b55beac1371ac8c619d880cfe948/pillow-11.3.0-cp314-cp314t-win_arm64.whl", hash = "sha256:79ea0d14d3ebad43ec77ad5272e6ff9bba5b679ef73375ea760261207fa8e0aa", size = 2512835, upload-time = "2025-07-01T09:15:50.399Z" }, + { url = "https://files.pythonhosted.org/packages/9e/e3/6fa84033758276fb31da12e5fb66ad747ae83b93c67af17f8c6ff4cc8f34/pillow-11.3.0-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:7c8ec7a017ad1bd562f93dbd8505763e688d388cde6e4a010ae1486916e713e6", size = 5270566, upload-time = "2025-07-01T09:16:19.801Z" }, + { url = "https://files.pythonhosted.org/packages/5b/ee/e8d2e1ab4892970b561e1ba96cbd59c0d28cf66737fc44abb2aec3795a4e/pillow-11.3.0-pp311-pypy311_pp73-macosx_11_0_arm64.whl", hash = "sha256:9ab6ae226de48019caa8074894544af5b53a117ccb9d3b3dcb2871464c829438", size = 4654618, upload-time = "2025-07-01T09:16:21.818Z" }, + { url = "https://files.pythonhosted.org/packages/f2/6d/17f80f4e1f0761f02160fc433abd4109fa1548dcfdca46cfdadaf9efa565/pillow-11.3.0-pp311-pypy311_pp73-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:fe27fb049cdcca11f11a7bfda64043c37b30e6b91f10cb5bab275806c32f6ab3", size = 4874248, upload-time = "2025-07-03T13:11:20.738Z" }, + { url = "https://files.pythonhosted.org/packages/de/5f/c22340acd61cef960130585bbe2120e2fd8434c214802f07e8c03596b17e/pillow-11.3.0-pp311-pypy311_pp73-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:465b9e8844e3c3519a983d58b80be3f668e2a7a5db97f2784e7079fbc9f9822c", size = 6583963, upload-time = "2025-07-03T13:11:26.283Z" }, + { url = "https://files.pythonhosted.org/packages/31/5e/03966aedfbfcbb4d5f8aa042452d3361f325b963ebbadddac05b122e47dd/pillow-11.3.0-pp311-pypy311_pp73-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:5418b53c0d59b3824d05e029669efa023bbef0f3e92e75ec8428f3799487f361", size = 4957170, upload-time = "2025-07-01T09:16:23.762Z" }, + { url = "https://files.pythonhosted.org/packages/cc/2d/e082982aacc927fc2cab48e1e731bdb1643a1406acace8bed0900a61464e/pillow-11.3.0-pp311-pypy311_pp73-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:504b6f59505f08ae014f724b6207ff6222662aab5cc9542577fb084ed0676ac7", size = 5581505, upload-time = "2025-07-01T09:16:25.593Z" }, + { url = "https://files.pythonhosted.org/packages/34/e7/ae39f538fd6844e982063c3a5e4598b8ced43b9633baa3a85ef33af8c05c/pillow-11.3.0-pp311-pypy311_pp73-win_amd64.whl", hash = "sha256:c84d689db21a1c397d001aa08241044aa2069e7587b398c8cc63020390b1c1b8", size = 6984598, upload-time = "2025-07-01T09:16:27.732Z" }, ] [[package]] @@ -3694,6 +4033,21 @@ version = "0.4.1" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/9e/da/e9fc233cf63743258bff22b3dfa7ea5baef7b5bc324af47a0ad89b8ffc6f/propcache-0.4.1.tar.gz", hash = "sha256:f48107a8c637e80362555f37ecf49abe20370e557cc4ab374f04ec4423c97c3d", size = 46442, upload-time = "2025-10-08T19:49:02.291Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/8c/d4/4e2c9aaf7ac2242b9358f98dccd8f90f2605402f5afeff6c578682c2c491/propcache-0.4.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:60a8fda9644b7dfd5dece8c61d8a85e271cb958075bfc4e01083c148b61a7caf", size = 80208, upload-time = "2025-10-08T19:46:24.597Z" }, + { url = "https://files.pythonhosted.org/packages/c2/21/d7b68e911f9c8e18e4ae43bdbc1e1e9bbd971f8866eb81608947b6f585ff/propcache-0.4.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:c30b53e7e6bda1d547cabb47c825f3843a0a1a42b0496087bb58d8fedf9f41b5", size = 45777, upload-time = "2025-10-08T19:46:25.733Z" }, + { url = "https://files.pythonhosted.org/packages/d3/1d/11605e99ac8ea9435651ee71ab4cb4bf03f0949586246476a25aadfec54a/propcache-0.4.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:6918ecbd897443087a3b7cd978d56546a812517dcaaca51b49526720571fa93e", size = 47647, upload-time = "2025-10-08T19:46:27.304Z" }, + { url = "https://files.pythonhosted.org/packages/58/1a/3c62c127a8466c9c843bccb503d40a273e5cc69838805f322e2826509e0d/propcache-0.4.1-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:3d902a36df4e5989763425a8ab9e98cd8ad5c52c823b34ee7ef307fd50582566", size = 214929, upload-time = "2025-10-08T19:46:28.62Z" }, + { url = "https://files.pythonhosted.org/packages/56/b9/8fa98f850960b367c4b8fe0592e7fc341daa7a9462e925228f10a60cf74f/propcache-0.4.1-cp311-cp311-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:a9695397f85973bb40427dedddf70d8dc4a44b22f1650dd4af9eedf443d45165", size = 221778, upload-time = "2025-10-08T19:46:30.358Z" }, + { url = "https://files.pythonhosted.org/packages/46/a6/0ab4f660eb59649d14b3d3d65c439421cf2f87fe5dd68591cbe3c1e78a89/propcache-0.4.1-cp311-cp311-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:2bb07ffd7eaad486576430c89f9b215f9e4be68c4866a96e97db9e97fead85dc", size = 228144, upload-time = "2025-10-08T19:46:32.607Z" }, + { url = "https://files.pythonhosted.org/packages/52/6a/57f43e054fb3d3a56ac9fc532bc684fc6169a26c75c353e65425b3e56eef/propcache-0.4.1-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:fd6f30fdcf9ae2a70abd34da54f18da086160e4d7d9251f81f3da0ff84fc5a48", size = 210030, upload-time = "2025-10-08T19:46:33.969Z" }, + { url = "https://files.pythonhosted.org/packages/40/e2/27e6feebb5f6b8408fa29f5efbb765cd54c153ac77314d27e457a3e993b7/propcache-0.4.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:fc38cba02d1acba4e2869eef1a57a43dfbd3d49a59bf90dda7444ec2be6a5570", size = 208252, upload-time = "2025-10-08T19:46:35.309Z" }, + { url = "https://files.pythonhosted.org/packages/9e/f8/91c27b22ccda1dbc7967f921c42825564fa5336a01ecd72eb78a9f4f53c2/propcache-0.4.1-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:67fad6162281e80e882fb3ec355398cf72864a54069d060321f6cd0ade95fe85", size = 202064, upload-time = "2025-10-08T19:46:36.993Z" }, + { url = "https://files.pythonhosted.org/packages/f2/26/7f00bd6bd1adba5aafe5f4a66390f243acab58eab24ff1a08bebb2ef9d40/propcache-0.4.1-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:f10207adf04d08bec185bae14d9606a1444715bc99180f9331c9c02093e1959e", size = 212429, upload-time = "2025-10-08T19:46:38.398Z" }, + { url = "https://files.pythonhosted.org/packages/84/89/fd108ba7815c1117ddca79c228f3f8a15fc82a73bca8b142eb5de13b2785/propcache-0.4.1-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:e9b0d8d0845bbc4cfcdcbcdbf5086886bc8157aa963c31c777ceff7846c77757", size = 216727, upload-time = "2025-10-08T19:46:39.732Z" }, + { url = "https://files.pythonhosted.org/packages/79/37/3ec3f7e3173e73f1d600495d8b545b53802cbf35506e5732dd8578db3724/propcache-0.4.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:981333cb2f4c1896a12f4ab92a9cc8f09ea664e9b7dbdc4eff74627af3a11c0f", size = 205097, upload-time = "2025-10-08T19:46:41.025Z" }, + { url = "https://files.pythonhosted.org/packages/61/b0/b2631c19793f869d35f47d5a3a56fb19e9160d3c119f15ac7344fc3ccae7/propcache-0.4.1-cp311-cp311-win32.whl", hash = "sha256:f1d2f90aeec838a52f1c1a32fe9a619fefd5e411721a9117fbf82aea638fe8a1", size = 38084, upload-time = "2025-10-08T19:46:42.693Z" }, + { url = "https://files.pythonhosted.org/packages/f4/78/6cce448e2098e9f3bfc91bb877f06aa24b6ccace872e39c53b2f707c4648/propcache-0.4.1-cp311-cp311-win_amd64.whl", hash = "sha256:364426a62660f3f699949ac8c621aad6977be7126c5807ce48c0aeb8e7333ea6", size = 41637, upload-time = "2025-10-08T19:46:43.778Z" }, + { url = "https://files.pythonhosted.org/packages/9c/e9/754f180cccd7f51a39913782c74717c581b9cc8177ad0e949f4d51812383/propcache-0.4.1-cp311-cp311-win_arm64.whl", hash = "sha256:e53f3a38d3510c11953f3e6a33f205c6d1b001129f972805ca9b42fc308bc239", size = 38064, upload-time = "2025-10-08T19:46:44.872Z" }, { url = "https://files.pythonhosted.org/packages/a2/0f/f17b1b2b221d5ca28b4b876e8bb046ac40466513960646bda8e1853cdfa2/propcache-0.4.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:e153e9cd40cc8945138822807139367f256f89c6810c2634a4f6902b52d3b4e2", size = 80061, upload-time = "2025-10-08T19:46:46.075Z" }, { url = "https://files.pythonhosted.org/packages/76/47/8ccf75935f51448ba9a16a71b783eb7ef6b9ee60f5d14c7f8a8a79fbeed7/propcache-0.4.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:cd547953428f7abb73c5ad82cbb32109566204260d98e41e5dfdc682eb7f8403", size = 46037, upload-time = "2025-10-08T19:46:47.23Z" }, { url = "https://files.pythonhosted.org/packages/0a/b6/5c9a0e42df4d00bfb4a3cbbe5cf9f54260300c88a0e9af1f47ca5ce17ac0/propcache-0.4.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:f048da1b4f243fc44f205dfd320933a951b8d89e0afd4c7cacc762a8b9165207", size = 47324, upload-time = "2025-10-08T19:46:48.384Z" }, @@ -3863,6 +4217,20 @@ dependencies = [ ] sdist = { url = "https://files.pythonhosted.org/packages/7d/14/12b4a0d2b0b10d8e1d9a24ad94e7bbb43335eaf29c0c4e57860e8a30734a/pydantic_core-2.41.1.tar.gz", hash = "sha256:1ad375859a6d8c356b7704ec0f547a58e82ee80bb41baa811ad710e124bc8f2f", size = 454870, upload-time = "2025-10-07T10:50:45.974Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/f6/a9/ec440f02e57beabdfd804725ef1e38ac1ba00c49854d298447562e119513/pydantic_core-2.41.1-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:4f276a6134fe1fc1daa692642a3eaa2b7b858599c49a7610816388f5e37566a1", size = 2111456, upload-time = "2025-10-06T21:10:09.824Z" }, + { url = "https://files.pythonhosted.org/packages/f0/f9/6bc15bacfd8dcfc073a1820a564516d9c12a435a9a332d4cbbfd48828ddd/pydantic_core-2.41.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:07588570a805296ece009c59d9a679dc08fab72fb337365afb4f3a14cfbfc176", size = 1915012, upload-time = "2025-10-06T21:10:11.599Z" }, + { url = "https://files.pythonhosted.org/packages/38/8a/d9edcdcdfe80bade17bed424284427c08bea892aaec11438fa52eaeaf79c/pydantic_core-2.41.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:28527e4b53400cd60ffbd9812ccb2b5135d042129716d71afd7e45bf42b855c0", size = 1973762, upload-time = "2025-10-06T21:10:13.154Z" }, + { url = "https://files.pythonhosted.org/packages/d5/b3/ff225c6d49fba4279de04677c1c876fc3dc6562fd0c53e9bfd66f58c51a8/pydantic_core-2.41.1-cp311-cp311-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:46a1c935c9228bad738c8a41de06478770927baedf581d172494ab36a6b96575", size = 2065386, upload-time = "2025-10-06T21:10:14.436Z" }, + { url = "https://files.pythonhosted.org/packages/47/ba/183e8c0be4321314af3fd1ae6bfc7eafdd7a49bdea5da81c56044a207316/pydantic_core-2.41.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:447ddf56e2b7d28d200d3e9eafa936fe40485744b5a824b67039937580b3cb20", size = 2252317, upload-time = "2025-10-06T21:10:15.719Z" }, + { url = "https://files.pythonhosted.org/packages/57/c5/aab61e94fd02f45c65f1f8c9ec38bb3b33fbf001a1837c74870e97462572/pydantic_core-2.41.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:63892ead40c1160ac860b5debcc95c95c5a0035e543a8b5a4eac70dd22e995f4", size = 2373405, upload-time = "2025-10-06T21:10:17.017Z" }, + { url = "https://files.pythonhosted.org/packages/e5/4f/3aaa3bd1ea420a15acc42d7d3ccb3b0bbc5444ae2f9dbc1959f8173e16b8/pydantic_core-2.41.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f4a9543ca355e6df8fbe9c83e9faab707701e9103ae857ecb40f1c0cf8b0e94d", size = 2073794, upload-time = "2025-10-06T21:10:18.383Z" }, + { url = "https://files.pythonhosted.org/packages/58/bd/e3975cdebe03ec080ef881648de316c73f2a6be95c14fc4efb2f7bdd0d41/pydantic_core-2.41.1-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:f2611bdb694116c31e551ed82e20e39a90bea9b7ad9e54aaf2d045ad621aa7a1", size = 2194430, upload-time = "2025-10-06T21:10:19.638Z" }, + { url = "https://files.pythonhosted.org/packages/2b/b8/6b7e7217f147d3b3105b57fb1caec3c4f667581affdfaab6d1d277e1f749/pydantic_core-2.41.1-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:fecc130893a9b5f7bfe230be1bb8c61fe66a19db8ab704f808cb25a82aad0bc9", size = 2154611, upload-time = "2025-10-06T21:10:21.28Z" }, + { url = "https://files.pythonhosted.org/packages/fe/7b/239c2fe76bd8b7eef9ae2140d737368a3c6fea4fd27f8f6b4cde6baa3ce9/pydantic_core-2.41.1-cp311-cp311-musllinux_1_1_armv7l.whl", hash = "sha256:1e2df5f8344c99b6ea5219f00fdc8950b8e6f2c422fbc1cc122ec8641fac85a1", size = 2329809, upload-time = "2025-10-06T21:10:22.678Z" }, + { url = "https://files.pythonhosted.org/packages/bd/2e/77a821a67ff0786f2f14856d6bd1348992f695ee90136a145d7a445c1ff6/pydantic_core-2.41.1-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:35291331e9d8ed94c257bab6be1cb3a380b5eee570a2784bffc055e18040a2ea", size = 2327907, upload-time = "2025-10-06T21:10:24.447Z" }, + { url = "https://files.pythonhosted.org/packages/fd/9a/b54512bb9df7f64c586b369328c30481229b70ca6a5fcbb90b715e15facf/pydantic_core-2.41.1-cp311-cp311-win32.whl", hash = "sha256:2876a095292668d753f1a868c4a57c4ac9f6acbd8edda8debe4218d5848cf42f", size = 1989964, upload-time = "2025-10-06T21:10:25.676Z" }, + { url = "https://files.pythonhosted.org/packages/9d/72/63c9a4f1a5c950e65dd522d7dd67f167681f9d4f6ece3b80085a0329f08f/pydantic_core-2.41.1-cp311-cp311-win_amd64.whl", hash = "sha256:b92d6c628e9a338846a28dfe3fcdc1a3279388624597898b105e078cdfc59298", size = 2025158, upload-time = "2025-10-06T21:10:27.522Z" }, + { url = "https://files.pythonhosted.org/packages/d8/16/4e2706184209f61b50c231529257c12eb6bd9eb36e99ea1272e4815d2200/pydantic_core-2.41.1-cp311-cp311-win_arm64.whl", hash = "sha256:7d82ae99409eb69d507a89835488fb657faa03ff9968a9379567b0d2e2e56bc5", size = 1972297, upload-time = "2025-10-06T21:10:28.814Z" }, { url = "https://files.pythonhosted.org/packages/ee/bc/5f520319ee1c9e25010412fac4154a72e0a40d0a19eb00281b1f200c0947/pydantic_core-2.41.1-cp312-cp312-macosx_10_12_x86_64.whl", hash = "sha256:db2f82c0ccbce8f021ad304ce35cbe02aa2f95f215cac388eed542b03b4d5eb4", size = 2099300, upload-time = "2025-10-06T21:10:30.463Z" }, { url = "https://files.pythonhosted.org/packages/31/14/010cd64c5c3814fb6064786837ec12604be0dd46df3327cf8474e38abbbd/pydantic_core-2.41.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:47694a31c710ced9205d5f1e7e8af3ca57cbb8a503d98cb9e33e27c97a501601", size = 1910179, upload-time = "2025-10-06T21:10:31.782Z" }, { url = "https://files.pythonhosted.org/packages/8e/2e/23fc2a8a93efad52df302fdade0a60f471ecc0c7aac889801ac24b4c07d6/pydantic_core-2.41.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:93e9decce94daf47baf9e9d392f5f2557e783085f7c5e522011545d9d6858e00", size = 1957225, upload-time = "2025-10-06T21:10:33.11Z" }, @@ -3911,10 +4279,22 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/e7/7e/8ac10ccb047dc0221aa2530ec3c7c05ab4656d4d4bd984ee85da7f3d5525/pydantic_core-2.41.1-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:f9b9c968cfe5cd576fdd7361f47f27adeb120517e637d1b189eea1c3ece573f4", size = 1875124, upload-time = "2025-10-06T21:11:47.591Z" }, { url = "https://files.pythonhosted.org/packages/c3/e4/7d9791efeb9c7d97e7268f8d20e0da24d03438a7fa7163ab58f1073ba968/pydantic_core-2.41.1-cp314-cp314t-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f1ebc7ab67b856384aba09ed74e3e977dded40e693de18a4f197c67d0d4e6d8e", size = 2043075, upload-time = "2025-10-06T21:11:49.542Z" }, { url = "https://files.pythonhosted.org/packages/2d/c3/3f6e6b2342ac11ac8cd5cb56e24c7b14afa27c010e82a765ffa5f771884a/pydantic_core-2.41.1-cp314-cp314t-win_amd64.whl", hash = "sha256:8ae0dc57b62a762985bc7fbf636be3412394acc0ddb4ade07fe104230f1b9762", size = 1995341, upload-time = "2025-10-06T21:11:51.497Z" }, + { url = "https://files.pythonhosted.org/packages/16/89/d0afad37ba25f5801735af1472e650b86baad9fe807a42076508e4824a2a/pydantic_core-2.41.1-graalpy311-graalpy242_311_native-macosx_10_12_x86_64.whl", hash = "sha256:68f2251559b8efa99041bb63571ec7cdd2d715ba74cc82b3bc9eff824ebc8bf0", size = 2124001, upload-time = "2025-10-07T10:49:54.369Z" }, + { url = "https://files.pythonhosted.org/packages/8e/c4/08609134b34520568ddebb084d9ed0a2a3f5f52b45739e6e22cb3a7112eb/pydantic_core-2.41.1-graalpy311-graalpy242_311_native-macosx_11_0_arm64.whl", hash = "sha256:c7bc140c596097cb53b30546ca257dbe3f19282283190b1b5142928e5d5d3a20", size = 1941841, upload-time = "2025-10-07T10:49:56.248Z" }, + { url = "https://files.pythonhosted.org/packages/2a/43/94a4877094e5fe19a3f37e7e817772263e2c573c94f1e3fa2b1eee56ef3b/pydantic_core-2.41.1-graalpy311-graalpy242_311_native-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2896510fce8f4725ec518f8b9d7f015a00db249d2fd40788f442af303480063d", size = 1961129, upload-time = "2025-10-07T10:49:58.298Z" }, + { url = "https://files.pythonhosted.org/packages/a2/30/23a224d7e25260eb5f69783a63667453037e07eb91ff0e62dabaadd47128/pydantic_core-2.41.1-graalpy311-graalpy242_311_native-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ced20e62cfa0f496ba68fa5d6c7ee71114ea67e2a5da3114d6450d7f4683572a", size = 2148770, upload-time = "2025-10-07T10:49:59.959Z" }, { url = "https://files.pythonhosted.org/packages/2b/3e/a51c5f5d37b9288ba30683d6e96f10fa8f1defad1623ff09f1020973b577/pydantic_core-2.41.1-graalpy312-graalpy250_312_native-macosx_10_12_x86_64.whl", hash = "sha256:b04fa9ed049461a7398138c604b00550bc89e3e1151d84b81ad6dc93e39c4c06", size = 2115344, upload-time = "2025-10-07T10:50:02.466Z" }, { url = "https://files.pythonhosted.org/packages/5a/bd/389504c9e0600ef4502cd5238396b527afe6ef8981a6a15cd1814fc7b434/pydantic_core-2.41.1-graalpy312-graalpy250_312_native-macosx_11_0_arm64.whl", hash = "sha256:b3b7d9cfbfdc43c80a16638c6dc2768e3956e73031fca64e8e1a3ae744d1faeb", size = 1927994, upload-time = "2025-10-07T10:50:04.379Z" }, { url = "https://files.pythonhosted.org/packages/ff/9c/5111c6b128861cb792a4c082677e90dac4f2e090bb2e2fe06aa5b2d39027/pydantic_core-2.41.1-graalpy312-graalpy250_312_native-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:eec83fc6abef04c7f9bec616e2d76ee9a6a4ae2a359b10c21d0f680e24a247ca", size = 1959394, upload-time = "2025-10-07T10:50:06.335Z" }, { url = "https://files.pythonhosted.org/packages/14/3f/cfec8b9a0c48ce5d64409ec5e1903cb0b7363da38f14b41de2fcb3712700/pydantic_core-2.41.1-graalpy312-graalpy250_312_native-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6771a2d9f83c4038dfad5970a3eef215940682b2175e32bcc817bdc639019b28", size = 2147365, upload-time = "2025-10-07T10:50:07.978Z" }, + { url = "https://files.pythonhosted.org/packages/e6/6c/fa3e45c2b054a1e627a89a364917f12cbe3abc3e91b9004edaae16e7b3c5/pydantic_core-2.41.1-pp311-pypy311_pp73-macosx_10_12_x86_64.whl", hash = "sha256:af2385d3f98243fb733862f806c5bb9122e5fba05b373e3af40e3c82d711cef1", size = 2112094, upload-time = "2025-10-07T10:50:25.513Z" }, + { url = "https://files.pythonhosted.org/packages/e5/17/7eebc38b4658cc8e6902d0befc26388e4c2a5f2e179c561eeb43e1922c7b/pydantic_core-2.41.1-pp311-pypy311_pp73-macosx_11_0_arm64.whl", hash = "sha256:6550617a0c2115be56f90c31a5370261d8ce9dbf051c3ed53b51172dd34da696", size = 1935300, upload-time = "2025-10-07T10:50:27.715Z" }, + { url = "https://files.pythonhosted.org/packages/2b/00/9fe640194a1717a464ab861d43595c268830f98cb1e2705aa134b3544b70/pydantic_core-2.41.1-pp311-pypy311_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:dc17b6ecf4983d298686014c92ebc955a9f9baf9f57dad4065e7906e7bee6222", size = 1970417, upload-time = "2025-10-07T10:50:29.573Z" }, + { url = "https://files.pythonhosted.org/packages/b2/ad/f4cdfaf483b78ee65362363e73b6b40c48e067078d7b146e8816d5945ad6/pydantic_core-2.41.1-pp311-pypy311_pp73-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:42ae9352cf211f08b04ea110563d6b1e415878eea5b4c70f6bdb17dca3b932d2", size = 2190745, upload-time = "2025-10-07T10:50:31.48Z" }, + { url = "https://files.pythonhosted.org/packages/cb/c1/18f416d40a10f44e9387497ba449f40fdb1478c61ba05c4b6bdb82300362/pydantic_core-2.41.1-pp311-pypy311_pp73-musllinux_1_1_aarch64.whl", hash = "sha256:e82947de92068b0a21681a13dd2102387197092fbe7defcfb8453e0913866506", size = 2150888, upload-time = "2025-10-07T10:50:33.477Z" }, + { url = "https://files.pythonhosted.org/packages/42/30/134c8a921630d8a88d6f905a562495a6421e959a23c19b0f49b660801d67/pydantic_core-2.41.1-pp311-pypy311_pp73-musllinux_1_1_armv7l.whl", hash = "sha256:e244c37d5471c9acdcd282890c6c4c83747b77238bfa19429b8473586c907656", size = 2324489, upload-time = "2025-10-07T10:50:36.48Z" }, + { url = "https://files.pythonhosted.org/packages/9c/48/a9263aeaebdec81e941198525b43edb3b44f27cfa4cb8005b8d3eb8dec72/pydantic_core-2.41.1-pp311-pypy311_pp73-musllinux_1_1_x86_64.whl", hash = "sha256:1e798b4b304a995110d41ec93653e57975620ccb2842ba9420037985e7d7284e", size = 2322763, upload-time = "2025-10-07T10:50:38.751Z" }, + { url = "https://files.pythonhosted.org/packages/1d/62/755d2bd2593f701c5839fc084e9c2c5e2418f460383ad04e3b5d0befc3ca/pydantic_core-2.41.1-pp311-pypy311_pp73-win_amd64.whl", hash = "sha256:f1fc716c0eb1663c59699b024428ad5ec2bcc6b928527b8fe28de6cb89f47efb", size = 2144046, upload-time = "2025-10-07T10:50:40.686Z" }, ] [[package]] @@ -3957,164 +4337,164 @@ name = "pyobjc" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-accessibility", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-accounts", marker = "platform_release >= '12.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-addressbook", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-adservices", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-adsupport", marker = "platform_release >= '18.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-applescriptkit", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-applescriptobjc", marker = "platform_release >= '10.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-applicationservices", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-apptrackingtransparency", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-audiovideobridging", marker = "platform_release >= '12.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-authenticationservices", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-automaticassessmentconfiguration", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-automator", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-avfoundation", marker = "platform_release >= '11.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-avkit", marker = "platform_release >= '13.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-avrouting", marker = "platform_release >= '22.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-backgroundassets", marker = "platform_release >= '22.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-browserenginekit", marker = "platform_release >= '23.4' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-businesschat", marker = "platform_release >= '18.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-calendarstore", marker = "platform_release >= '9.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-callkit", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-carbon", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cfnetwork", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cinematic", marker = "platform_release >= '23.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-classkit", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cloudkit", marker = "platform_release >= '14.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-collaboration", marker = "platform_release >= '9.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-colorsync", marker = "platform_release >= '17.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-contacts", marker = "platform_release >= '15.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-contactsui", marker = "platform_release >= '15.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreaudio", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreaudiokit", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-corebluetooth", marker = "platform_release >= '14.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coredata", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-corehaptics", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-corelocation", marker = "platform_release >= '10.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremedia", marker = "platform_release >= '11.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremediaio", marker = "platform_release >= '11.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremidi", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreml", marker = "platform_release >= '17.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremotion", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreservices", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-corespotlight", marker = "platform_release >= '17.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coretext", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-corewlan", marker = "platform_release >= '10.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cryptotokenkit", marker = "platform_release >= '14.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-datadetection", marker = "platform_release >= '21.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-devicecheck", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-devicediscoveryextension", marker = "platform_release >= '24.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-dictionaryservices", marker = "platform_release >= '9.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-discrecording", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-discrecordingui", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-diskarbitration", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-dvdplayback", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-eventkit", marker = "platform_release >= '12.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-exceptionhandling", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-executionpolicy", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-extensionkit", marker = "platform_release >= '22.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-externalaccessory", marker = "platform_release >= '17.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-fileprovider", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-fileproviderui", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-findersync", marker = "platform_release >= '14.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-fsevents", marker = "platform_release >= '9.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-fskit", marker = "platform_release >= '24.4' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-gamecenter", marker = "platform_release >= '12.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-gamecontroller", marker = "platform_release >= '13.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-gamekit", marker = "platform_release >= '12.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-gameplaykit", marker = "platform_release >= '15.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-healthkit", marker = "platform_release >= '22.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-imagecapturecore", marker = "platform_release >= '10.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-inputmethodkit", marker = "platform_release >= '9.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-installerplugins", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-instantmessage", marker = "platform_release >= '9.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-intents", marker = "platform_release >= '16.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-intentsui", marker = "platform_release >= '21.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-iobluetooth", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-iobluetoothui", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-iosurface", marker = "platform_release >= '10.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-ituneslibrary", marker = "platform_release >= '10.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-kernelmanagement", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-latentsemanticmapping", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-launchservices", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-libdispatch", marker = "platform_release >= '12.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-libxpc", marker = "platform_release >= '12.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-linkpresentation", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-localauthentication", marker = "platform_release >= '14.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-localauthenticationembeddedui", marker = "platform_release >= '21.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-mailkit", marker = "platform_release >= '21.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-mapkit", marker = "platform_release >= '13.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-mediaaccessibility", marker = "platform_release >= '13.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-mediaextension", marker = "platform_release >= '24.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-medialibrary", marker = "platform_release >= '13.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-mediaplayer", marker = "platform_release >= '16.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-mediatoolbox", marker = "platform_release >= '13.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metal", marker = "platform_release >= '15.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metalfx", marker = "platform_release >= '22.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metalkit", marker = "platform_release >= '15.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metalperformanceshaders", marker = "platform_release >= '17.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metalperformanceshadersgraph", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metrickit", marker = "platform_release >= '21.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-mlcompute", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-modelio", marker = "platform_release >= '15.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-multipeerconnectivity", marker = "platform_release >= '14.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-naturallanguage", marker = "platform_release >= '18.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-netfs", marker = "platform_release >= '10.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-network", marker = "platform_release >= '18.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-networkextension", marker = "platform_release >= '15.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-notificationcenter", marker = "platform_release >= '14.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-opendirectory", marker = "platform_release >= '10.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-osakit", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-oslog", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-passkit", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-pencilkit", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-phase", marker = "platform_release >= '21.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-photos", marker = "platform_release >= '15.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-photosui", marker = "platform_release >= '15.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-preferencepanes", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-pushkit", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quicklookthumbnailing", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-replaykit", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-safariservices", marker = "platform_release >= '16.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-safetykit", marker = "platform_release >= '22.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-scenekit", marker = "platform_release >= '11.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-screencapturekit", marker = "platform_release >= '21.4' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-screensaver", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-screentime", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-scriptingbridge", marker = "platform_release >= '9.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-searchkit", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-security", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-securityfoundation", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-securityinterface", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-securityui", marker = "platform_release >= '24.4' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-sensitivecontentanalysis", marker = "platform_release >= '23.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-servicemanagement", marker = "platform_release >= '10.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-sharedwithyou", marker = "platform_release >= '22.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-sharedwithyoucore", marker = "platform_release >= '22.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-shazamkit", marker = "platform_release >= '21.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-social", marker = "platform_release >= '12.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-soundanalysis", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-speech", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-spritekit", marker = "platform_release >= '13.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-storekit", marker = "platform_release >= '11.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-symbols", marker = "platform_release >= '23.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-syncservices", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-systemconfiguration", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-systemextensions", marker = "platform_release >= '19.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-threadnetwork", marker = "platform_release >= '22.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-uniformtypeidentifiers", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-usernotifications", marker = "platform_release >= '18.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-usernotificationsui", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-videosubscriberaccount", marker = "platform_release >= '18.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-videotoolbox", marker = "platform_release >= '12.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-virtualization", marker = "platform_release >= '20.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-vision", marker = "platform_release >= '17.0' and sys_platform == 'darwin'" }, - { name = "pyobjc-framework-webkit", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-accessibility", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-accounts", marker = "platform_release >= '12.0'" }, + { name = "pyobjc-framework-addressbook" }, + { name = "pyobjc-framework-adservices", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-adsupport", marker = "platform_release >= '18.0'" }, + { name = "pyobjc-framework-applescriptkit" }, + { name = "pyobjc-framework-applescriptobjc", marker = "platform_release >= '10.0'" }, + { name = "pyobjc-framework-applicationservices" }, + { name = "pyobjc-framework-apptrackingtransparency", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-audiovideobridging", marker = "platform_release >= '12.0'" }, + { name = "pyobjc-framework-authenticationservices", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-automaticassessmentconfiguration", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-automator" }, + { name = "pyobjc-framework-avfoundation", marker = "platform_release >= '11.0'" }, + { name = "pyobjc-framework-avkit", marker = "platform_release >= '13.0'" }, + { name = "pyobjc-framework-avrouting", marker = "platform_release >= '22.0'" }, + { name = "pyobjc-framework-backgroundassets", marker = "platform_release >= '22.0'" }, + { name = "pyobjc-framework-browserenginekit", marker = "platform_release >= '23.4'" }, + { name = "pyobjc-framework-businesschat", marker = "platform_release >= '18.0'" }, + { name = "pyobjc-framework-calendarstore", marker = "platform_release >= '9.0'" }, + { name = "pyobjc-framework-callkit", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-carbon" }, + { name = "pyobjc-framework-cfnetwork" }, + { name = "pyobjc-framework-cinematic", marker = "platform_release >= '23.0'" }, + { name = "pyobjc-framework-classkit", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-cloudkit", marker = "platform_release >= '14.0'" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-collaboration", marker = "platform_release >= '9.0'" }, + { name = "pyobjc-framework-colorsync", marker = "platform_release >= '17.0'" }, + { name = "pyobjc-framework-contacts", marker = "platform_release >= '15.0'" }, + { name = "pyobjc-framework-contactsui", marker = "platform_release >= '15.0'" }, + { name = "pyobjc-framework-coreaudio" }, + { name = "pyobjc-framework-coreaudiokit" }, + { name = "pyobjc-framework-corebluetooth", marker = "platform_release >= '14.0'" }, + { name = "pyobjc-framework-coredata" }, + { name = "pyobjc-framework-corehaptics", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-corelocation", marker = "platform_release >= '10.0'" }, + { name = "pyobjc-framework-coremedia", marker = "platform_release >= '11.0'" }, + { name = "pyobjc-framework-coremediaio", marker = "platform_release >= '11.0'" }, + { name = "pyobjc-framework-coremidi" }, + { name = "pyobjc-framework-coreml", marker = "platform_release >= '17.0'" }, + { name = "pyobjc-framework-coremotion", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-coreservices" }, + { name = "pyobjc-framework-corespotlight", marker = "platform_release >= '17.0'" }, + { name = "pyobjc-framework-coretext" }, + { name = "pyobjc-framework-corewlan", marker = "platform_release >= '10.0'" }, + { name = "pyobjc-framework-cryptotokenkit", marker = "platform_release >= '14.0'" }, + { name = "pyobjc-framework-datadetection", marker = "platform_release >= '21.0'" }, + { name = "pyobjc-framework-devicecheck", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-devicediscoveryextension", marker = "platform_release >= '24.0'" }, + { name = "pyobjc-framework-dictionaryservices", marker = "platform_release >= '9.0'" }, + { name = "pyobjc-framework-discrecording" }, + { name = "pyobjc-framework-discrecordingui" }, + { name = "pyobjc-framework-diskarbitration" }, + { name = "pyobjc-framework-dvdplayback" }, + { name = "pyobjc-framework-eventkit", marker = "platform_release >= '12.0'" }, + { name = "pyobjc-framework-exceptionhandling" }, + { name = "pyobjc-framework-executionpolicy", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-extensionkit", marker = "platform_release >= '22.0'" }, + { name = "pyobjc-framework-externalaccessory", marker = "platform_release >= '17.0'" }, + { name = "pyobjc-framework-fileprovider", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-fileproviderui", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-findersync", marker = "platform_release >= '14.0'" }, + { name = "pyobjc-framework-fsevents", marker = "platform_release >= '9.0'" }, + { name = "pyobjc-framework-fskit", marker = "platform_release >= '24.4'" }, + { name = "pyobjc-framework-gamecenter", marker = "platform_release >= '12.0'" }, + { name = "pyobjc-framework-gamecontroller", marker = "platform_release >= '13.0'" }, + { name = "pyobjc-framework-gamekit", marker = "platform_release >= '12.0'" }, + { name = "pyobjc-framework-gameplaykit", marker = "platform_release >= '15.0'" }, + { name = "pyobjc-framework-healthkit", marker = "platform_release >= '22.0'" }, + { name = "pyobjc-framework-imagecapturecore", marker = "platform_release >= '10.0'" }, + { name = "pyobjc-framework-inputmethodkit", marker = "platform_release >= '9.0'" }, + { name = "pyobjc-framework-installerplugins" }, + { name = "pyobjc-framework-instantmessage", marker = "platform_release >= '9.0'" }, + { name = "pyobjc-framework-intents", marker = "platform_release >= '16.0'" }, + { name = "pyobjc-framework-intentsui", marker = "platform_release >= '21.0'" }, + { name = "pyobjc-framework-iobluetooth" }, + { name = "pyobjc-framework-iobluetoothui" }, + { name = "pyobjc-framework-iosurface", marker = "platform_release >= '10.0'" }, + { name = "pyobjc-framework-ituneslibrary", marker = "platform_release >= '10.0'" }, + { name = "pyobjc-framework-kernelmanagement", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-latentsemanticmapping" }, + { name = "pyobjc-framework-launchservices" }, + { name = "pyobjc-framework-libdispatch", marker = "platform_release >= '12.0'" }, + { name = "pyobjc-framework-libxpc", marker = "platform_release >= '12.0'" }, + { name = "pyobjc-framework-linkpresentation", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-localauthentication", marker = "platform_release >= '14.0'" }, + { name = "pyobjc-framework-localauthenticationembeddedui", marker = "platform_release >= '21.0'" }, + { name = "pyobjc-framework-mailkit", marker = "platform_release >= '21.0'" }, + { name = "pyobjc-framework-mapkit", marker = "platform_release >= '13.0'" }, + { name = "pyobjc-framework-mediaaccessibility", marker = "platform_release >= '13.0'" }, + { name = "pyobjc-framework-mediaextension", marker = "platform_release >= '24.0'" }, + { name = "pyobjc-framework-medialibrary", marker = "platform_release >= '13.0'" }, + { name = "pyobjc-framework-mediaplayer", marker = "platform_release >= '16.0'" }, + { name = "pyobjc-framework-mediatoolbox", marker = "platform_release >= '13.0'" }, + { name = "pyobjc-framework-metal", marker = "platform_release >= '15.0'" }, + { name = "pyobjc-framework-metalfx", marker = "platform_release >= '22.0'" }, + { name = "pyobjc-framework-metalkit", marker = "platform_release >= '15.0'" }, + { name = "pyobjc-framework-metalperformanceshaders", marker = "platform_release >= '17.0'" }, + { name = "pyobjc-framework-metalperformanceshadersgraph", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-metrickit", marker = "platform_release >= '21.0'" }, + { name = "pyobjc-framework-mlcompute", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-modelio", marker = "platform_release >= '15.0'" }, + { name = "pyobjc-framework-multipeerconnectivity", marker = "platform_release >= '14.0'" }, + { name = "pyobjc-framework-naturallanguage", marker = "platform_release >= '18.0'" }, + { name = "pyobjc-framework-netfs", marker = "platform_release >= '10.0'" }, + { name = "pyobjc-framework-network", marker = "platform_release >= '18.0'" }, + { name = "pyobjc-framework-networkextension", marker = "platform_release >= '15.0'" }, + { name = "pyobjc-framework-notificationcenter", marker = "platform_release >= '14.0'" }, + { name = "pyobjc-framework-opendirectory", marker = "platform_release >= '10.0'" }, + { name = "pyobjc-framework-osakit" }, + { name = "pyobjc-framework-oslog", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-passkit", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-pencilkit", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-phase", marker = "platform_release >= '21.0'" }, + { name = "pyobjc-framework-photos", marker = "platform_release >= '15.0'" }, + { name = "pyobjc-framework-photosui", marker = "platform_release >= '15.0'" }, + { name = "pyobjc-framework-preferencepanes" }, + { name = "pyobjc-framework-pushkit", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-quartz" }, + { name = "pyobjc-framework-quicklookthumbnailing", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-replaykit", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-safariservices", marker = "platform_release >= '16.0'" }, + { name = "pyobjc-framework-safetykit", marker = "platform_release >= '22.0'" }, + { name = "pyobjc-framework-scenekit", marker = "platform_release >= '11.0'" }, + { name = "pyobjc-framework-screencapturekit", marker = "platform_release >= '21.4'" }, + { name = "pyobjc-framework-screensaver" }, + { name = "pyobjc-framework-screentime", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-scriptingbridge", marker = "platform_release >= '9.0'" }, + { name = "pyobjc-framework-searchkit" }, + { name = "pyobjc-framework-security" }, + { name = "pyobjc-framework-securityfoundation" }, + { name = "pyobjc-framework-securityinterface" }, + { name = "pyobjc-framework-securityui", marker = "platform_release >= '24.4'" }, + { name = "pyobjc-framework-sensitivecontentanalysis", marker = "platform_release >= '23.0'" }, + { name = "pyobjc-framework-servicemanagement", marker = "platform_release >= '10.0'" }, + { name = "pyobjc-framework-sharedwithyou", marker = "platform_release >= '22.0'" }, + { name = "pyobjc-framework-sharedwithyoucore", marker = "platform_release >= '22.0'" }, + { name = "pyobjc-framework-shazamkit", marker = "platform_release >= '21.0'" }, + { name = "pyobjc-framework-social", marker = "platform_release >= '12.0'" }, + { name = "pyobjc-framework-soundanalysis", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-speech", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-spritekit", marker = "platform_release >= '13.0'" }, + { name = "pyobjc-framework-storekit", marker = "platform_release >= '11.0'" }, + { name = "pyobjc-framework-symbols", marker = "platform_release >= '23.0'" }, + { name = "pyobjc-framework-syncservices" }, + { name = "pyobjc-framework-systemconfiguration" }, + { name = "pyobjc-framework-systemextensions", marker = "platform_release >= '19.0'" }, + { name = "pyobjc-framework-threadnetwork", marker = "platform_release >= '22.0'" }, + { name = "pyobjc-framework-uniformtypeidentifiers", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-usernotifications", marker = "platform_release >= '18.0'" }, + { name = "pyobjc-framework-usernotificationsui", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-videosubscriberaccount", marker = "platform_release >= '18.0'" }, + { name = "pyobjc-framework-videotoolbox", marker = "platform_release >= '12.0'" }, + { name = "pyobjc-framework-virtualization", marker = "platform_release >= '20.0'" }, + { name = "pyobjc-framework-vision", marker = "platform_release >= '17.0'" }, + { name = "pyobjc-framework-webkit" }, ] sdist = { url = "https://files.pythonhosted.org/packages/db/5e/16bc372806790d295c76b5c7851767cc9ee3787b3e581f5d7cc44158e4e0/pyobjc-11.1.tar.gz", hash = "sha256:a71b14389657811d658526ba4d5faba4ef7eadbddcf9fe8bf4fb3a6261effba3", size = 11161, upload-time = "2025-06-14T20:56:32.819Z" } wheels = [ @@ -4127,6 +4507,7 @@ version = "11.1" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/e8/e9/0b85c81e2b441267bca707b5d89f56c2f02578ef8f3eafddf0e0c0b8848c/pyobjc_core-11.1.tar.gz", hash = "sha256:b63d4d90c5df7e762f34739b39cc55bc63dbcf9fb2fb3f2671e528488c7a87fe", size = 974602, upload-time = "2025-06-14T20:56:34.189Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/5a/a7/55afc166d89e3fcd87966f48f8bca3305a3a2d7c62100715b9ffa7153a90/pyobjc_core-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:ec36680b5c14e2f73d432b03ba7c1457dc6ca70fa59fd7daea1073f2b4157d33", size = 671075, upload-time = "2025-06-14T20:44:46.594Z" }, { url = "https://files.pythonhosted.org/packages/c0/09/e83228e878e73bf756749939f906a872da54488f18d75658afa7f1abbab1/pyobjc_core-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:765b97dea6b87ec4612b3212258024d8496ea23517c95a1c5f0735f96b7fd529", size = 677985, upload-time = "2025-06-14T20:44:48.375Z" }, { url = "https://files.pythonhosted.org/packages/c5/24/12e4e2dae5f85fd0c0b696404ed3374ea6ca398e7db886d4f1322eb30799/pyobjc_core-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:18986f83998fbd5d3f56d8a8428b2f3e0754fd15cef3ef786ca0d29619024f2c", size = 676431, upload-time = "2025-06-14T20:44:49.908Z" }, { url = "https://files.pythonhosted.org/packages/f7/79/031492497624de4c728f1857181b06ce8c56444db4d49418fa459cba217c/pyobjc_core-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:8849e78cfe6595c4911fbba29683decfb0bf57a350aed8a43316976ba6f659d2", size = 719330, upload-time = "2025-06-14T20:44:51.621Z" }, @@ -4139,12 +4520,13 @@ name = "pyobjc-framework-accessibility" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/78/b4/10c16e9d48568a68da2f61866b19468d4ac7129c377d4b1333ee936ae5d0/pyobjc_framework_accessibility-11.1.tar.gz", hash = "sha256:c0fa5f1e00906ec002f582c7d3d80463a46d19f672bf5ec51144f819eeb40656", size = 45098, upload-time = "2025-06-14T20:56:35.287Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/ff/c5/8803e4f9c3f2d3f5672097438e305be9ccfb87ad092c68cbf02b172bf1d2/pyobjc_framework_accessibility-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:332263153d829b946b311ddc8b9a4402b52d40a572b44c69c3242451ced1b008", size = 11135, upload-time = "2025-06-14T20:44:58.339Z" }, { url = "https://files.pythonhosted.org/packages/5d/bd/087d511e0ea356434399609a38e8819978943cbeaca3ca7cc5f35c93d0b2/pyobjc_framework_accessibility-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:a049b63b32514da68aaaeef0d6c00a125e0618e4042aa6dbe3867b74fb2a8b2b", size = 11158, upload-time = "2025-06-14T20:44:59.032Z" }, { url = "https://files.pythonhosted.org/packages/0e/1e/4095d683954401d5f7926827fd09f4d399a8923e0e66d386a8903c0950e0/pyobjc_framework_accessibility-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:fd5a03b731d1a2bbb2bf706b58889a5e82df82ac69210ec3245c7dc69e42a63a", size = 11177, upload-time = "2025-06-14T20:45:00.111Z" }, { url = "https://files.pythonhosted.org/packages/28/7f/63d88c16e87f07b7bfff2adc7e74dcb2739cc1aed2110d29489514c05afa/pyobjc_framework_accessibility-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:3496c55569a421ef3c98ea66fc0ebaf68c686ede5b26db0fdcb0b0ad4191a20b", size = 11356, upload-time = "2025-06-14T20:45:01.183Z" }, @@ -4157,8 +4539,8 @@ name = "pyobjc-framework-accounts" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/12/45/ca21003f68ad0f13b5a9ac1761862ad2ddd83224b4314a2f7d03ca437c8d/pyobjc_framework_accounts-11.1.tar.gz", hash = "sha256:384fec156e13ff75253bb094339013f4013464f6dfd47e2f7de3e2ae7441c030", size = 17086, upload-time = "2025-06-14T20:56:36.035Z" } wheels = [ @@ -4170,11 +4552,12 @@ name = "pyobjc-framework-addressbook" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/eb/d3/f5bb5c72be5c6e52224f43e23e5a44e86d2c35ee9af36939e5514c6c7a0f/pyobjc_framework_addressbook-11.1.tar.gz", hash = "sha256:ce2db3be4a3128bf79d5c41319a6d16b73754785ce75ac694d0d658c690922fc", size = 97609, upload-time = "2025-06-14T20:56:37.324Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/8f/46/27ade210b0bcf2903540c37e96f5e88ec5303e98dc12b255148f12ef9c04/pyobjc_framework_addressbook-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:d1d69330b5a87a29d26feea95dcf40681fd00ba3b40ac89579072ce536b6b647", size = 13156, upload-time = "2025-06-14T20:45:06.788Z" }, { url = "https://files.pythonhosted.org/packages/c2/de/e1ba5f113c05b543a097040add795fa4b85fdd5ad850b56d83cd6ce8afff/pyobjc_framework_addressbook-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:fb3d0a710f8342a0c63a8e4caf64a044b4d7e42d6d242c8e1b54470238b938cb", size = 13173, upload-time = "2025-06-14T20:45:07.755Z" }, { url = "https://files.pythonhosted.org/packages/59/53/a0487a0fbc9134e69e29f18334d0b610c44578d753e8264ea1ac649f2839/pyobjc_framework_addressbook-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:411adf4874cc4343f2928a26fe4cb3673d2f5f73365b45cd3650aa7304a45e24", size = 13188, upload-time = "2025-06-14T20:45:08.811Z" }, { url = "https://files.pythonhosted.org/packages/81/07/1ca336107358ad526394a720598b8549f613ef1797350c764535f26e47bc/pyobjc_framework_addressbook-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:6735f297f0e5fd109fa77ca90cace57eb2e10eb65e3c15ccd249df2228030d3b", size = 13358, upload-time = "2025-06-14T20:45:09.877Z" }, @@ -4187,8 +4570,8 @@ name = "pyobjc-framework-adservices" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/2a/3f/af76eab6eee0a405a4fdee172e7181773040158476966ecd757b0a98bfc5/pyobjc_framework_adservices-11.1.tar.gz", hash = "sha256:44c72f8163705c9aa41baca938fdb17dde257639e5797e6a5c3a2b2d8afdade9", size = 12473, upload-time = "2025-06-14T20:56:38.147Z" } wheels = [ @@ -4200,8 +4583,8 @@ name = "pyobjc-framework-adsupport" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/7f/03/9c51edd964796a97def4e1433d76a128dd7059b685fb4366081bf4e292ba/pyobjc_framework_adsupport-11.1.tar.gz", hash = "sha256:78b9667c275785df96219d205bd4309731869c3298d0931e32aed83bede29096", size = 12556, upload-time = "2025-06-14T20:56:38.741Z" } wheels = [ @@ -4213,8 +4596,8 @@ name = "pyobjc-framework-applescriptkit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/bc/63/1bcfcdca53bf5bba3a7b4d73d24232ae1721a378a32fd4ebc34a35549df2/pyobjc_framework_applescriptkit-11.1.tar.gz", hash = "sha256:477707352eaa6cc4a5f8c593759dc3227a19d5958481b1482f0d59394a4601c3", size = 12392, upload-time = "2025-06-14T20:56:39.331Z" } wheels = [ @@ -4226,8 +4609,8 @@ name = "pyobjc-framework-applescriptobjc" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/a3/27/687b55b575367df045879b786f358355e40e41f847968e557d0718a6c4a4/pyobjc_framework_applescriptobjc-11.1.tar.gz", hash = "sha256:c8a0ec975b64411a4f16a1280c5ea8dbe949fd361e723edd343102f0f95aba6e", size = 12445, upload-time = "2025-06-14T20:56:39.976Z" } wheels = [ @@ -4239,13 +4622,14 @@ name = "pyobjc-framework-applicationservices" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coretext", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coretext" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/be/3f/b33ce0cecc3a42f6c289dcbf9ff698b0d9e85f5796db2e9cb5dadccffbb9/pyobjc_framework_applicationservices-11.1.tar.gz", hash = "sha256:03fcd8c0c600db98fa8b85eb7b3bc31491701720c795e3f762b54e865138bbaf", size = 224842, upload-time = "2025-06-14T20:56:40.648Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/39/2d/9fde6de0b2a95fbb3d77ba11b3cc4f289dd208f38cb3a28389add87c0f44/pyobjc_framework_applicationservices-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:cf45d15eddae36dec2330a9992fc852476b61c8f529874b9ec2805c768a75482", size = 30991, upload-time = "2025-06-14T20:45:18.169Z" }, { url = "https://files.pythonhosted.org/packages/38/ec/46a5c710e2d7edf55105223c34fed5a7b7cc7aba7d00a3a7b0405d6a2d1a/pyobjc_framework_applicationservices-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:f4a85ccd78bab84f7f05ac65ff9be117839dfc09d48c39edd65c617ed73eb01c", size = 31056, upload-time = "2025-06-14T20:45:18.925Z" }, { url = "https://files.pythonhosted.org/packages/c4/06/c2a309e6f37bfa73a2a581d3301321b2033e25b249e2a01e417a3c34e799/pyobjc_framework_applicationservices-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:385a89f4d0838c97a331e247519d9e9745aa3f7427169d18570e3c664076a63c", size = 31072, upload-time = "2025-06-14T20:45:19.707Z" }, { url = "https://files.pythonhosted.org/packages/b4/5f/357bf498c27f1b4d48385860d8374b2569adc1522aabe32befd77089c070/pyobjc_framework_applicationservices-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:f480fab20f3005e559c9d06c9a3874a1f1c60dde52c6d28a53ab59b45e79d55f", size = 31335, upload-time = "2025-06-14T20:45:20.462Z" }, @@ -4258,8 +4642,8 @@ name = "pyobjc-framework-apptrackingtransparency" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/49/68/7aa3afffd038dd6e5af764336bca734eb910121013ca71030457b61e5b99/pyobjc_framework_apptrackingtransparency-11.1.tar.gz", hash = "sha256:796cc5f83346c10973806cfb535d4200b894a5d2626ff2eeb1972d594d14fed4", size = 13135, upload-time = "2025-06-14T20:56:41.494Z" } wheels = [ @@ -4271,11 +4655,12 @@ name = "pyobjc-framework-audiovideobridging" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/c3/25/6c5a7b1443d30139cc722029880284ea9dfa575f0436471b9364fcd499f5/pyobjc_framework_audiovideobridging-11.1.tar.gz", hash = "sha256:12756b3aa35083b8ad5c9139b6a0e2f4792e217096b5bf6b702d499038203991", size = 72913, upload-time = "2025-06-14T20:56:42.128Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/3f/d0/952ccd59944f98f10f39c061ef7c3dceecbcd2654910e763c0ad2fd1c910/pyobjc_framework_audiovideobridging-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:db570433910d1df49cc45d25f7a966227033c794fb41133d59212689b86b1ac6", size = 11021, upload-time = "2025-06-14T20:45:25.498Z" }, { url = "https://files.pythonhosted.org/packages/1d/69/3e8e3da4db835168d18155a2c90fcca441047fc9c2e021d2ea01b4c6eb8c/pyobjc_framework_audiovideobridging-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:591e80ff6973ea51a12f7c1a2e3fd59496633a51d5a1bf73f4fb989a43e23681", size = 11032, upload-time = "2025-06-14T20:45:26.196Z" }, { url = "https://files.pythonhosted.org/packages/0b/93/cf38f503f378e224a57f99f8ca7f044f2690221dc8deaf49b305a6ee439a/pyobjc_framework_audiovideobridging-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:30a12be3784f41e1c6b5ef532c08e73bae7071d9a036b26b1e36b919ee5b6f57", size = 11043, upload-time = "2025-06-14T20:45:27.214Z" }, { url = "https://files.pythonhosted.org/packages/cf/ed/b2804e0415429292fd2f891f29e57b5008a2ecebb7de83aa9b78281e9284/pyobjc_framework_audiovideobridging-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:3bef4383dc9233dbd9efc3817ce9c8fe8670c61d21a94de3c149e7f460245792", size = 11217, upload-time = "2025-06-14T20:45:27.892Z" }, @@ -4288,11 +4673,12 @@ name = "pyobjc-framework-authenticationservices" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/8f/b7/3e9ad0ed3625dc02e495615ea5dbf55ca95cbd25b3e31f25092f5caad640/pyobjc_framework_authenticationservices-11.1.tar.gz", hash = "sha256:8fd801cdb53d426b4e678b0a8529c005d0c44f5a17ccd7052a7c3a1a87caed6a", size = 115266, upload-time = "2025-06-14T20:56:42.889Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/31/99/0a9d2b9c1aa3b9713d322ddb90a59537013afdae5661af233409e7a24dc9/pyobjc_framework_authenticationservices-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:3987b7fc9493c2ba77b773df99f6631bff1ee9b957d99e34afa6b4e1c9d48bfb", size = 20280, upload-time = "2025-06-14T20:45:32.617Z" }, { url = "https://files.pythonhosted.org/packages/7e/2d/cbb5e88c3713fb68cda7d76d37737076c1653bf1ac95418c30d4b614f4be/pyobjc_framework_authenticationservices-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:6655dd53d9135ef85265a4297da5e7459ed7836973f2796027fdfbfd7f08e433", size = 20385, upload-time = "2025-06-14T20:45:33.359Z" }, { url = "https://files.pythonhosted.org/packages/53/ac/cfd8aed9fba6974f291b3beb198c7270e4a3cae9f1ff9600bd0e4c904ae9/pyobjc_framework_authenticationservices-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:364035d265129192e6906f7a94cbdf714d737b6b9f20e56bfe74d0007c8761b1", size = 20401, upload-time = "2025-06-14T20:45:34.114Z" }, { url = "https://files.pythonhosted.org/packages/58/37/949c2f06ea52d976ff7c2c52a58504456ae4cc4f6c681e65ea9fa448a676/pyobjc_framework_authenticationservices-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:e92bf7e829229fbecba4f7f649d3ae38760cf25aa9e909c0e737b1945f36b62d", size = 20636, upload-time = "2025-06-14T20:45:34.875Z" }, @@ -4305,11 +4691,12 @@ name = "pyobjc-framework-automaticassessmentconfiguration" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/3d/39/d4c94e0245d290b83919854c4f205851cc0b2603f843448fdfb8e74aad71/pyobjc_framework_automaticassessmentconfiguration-11.1.tar.gz", hash = "sha256:70eadbf8600101901a56fcd7014d8941604e14f3b3728bc4fb0178a9a9420032", size = 24933, upload-time = "2025-06-14T20:56:43.984Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/b0/ca/f4ee1c9c274e0a41f8885f842fc78e520a367437edf9ca86eca46709e62d/pyobjc_framework_automaticassessmentconfiguration-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:50cc5466bec1f58f79921d49544b525b56897cb985dfcfabf825ee231c27bcfc", size = 9167, upload-time = "2025-06-14T20:45:39.52Z" }, { url = "https://files.pythonhosted.org/packages/5e/e0/5a67f8ee0393447ca8251cbd06788cb7f3a1f4b9b052afd2e1b2cdfcb504/pyobjc_framework_automaticassessmentconfiguration-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:55d1684dd676730fb1afbc7c67e0669e3a7159f18c126fea7453fe6182c098f9", size = 9193, upload-time = "2025-06-14T20:45:40.52Z" }, { url = "https://files.pythonhosted.org/packages/58/04/e2fb203d36b7ec96b06ef26cb44b833d64195435bc5d879987238111b524/pyobjc_framework_automaticassessmentconfiguration-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:fbcbe406c2a02d632885f6b23285c259b715f019b938d666cc554a66ecf5f9c3", size = 9199, upload-time = "2025-06-14T20:45:41.742Z" }, { url = "https://files.pythonhosted.org/packages/03/d7/bd947463be8b6f1512a99cb605a57a52f960bb70da060e21a23131a55386/pyobjc_framework_automaticassessmentconfiguration-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:e5fa297c7d4db225f75e5d11121fa68e0956c104e14b24250a52157a180e5f6c", size = 9359, upload-time = "2025-06-14T20:45:42.444Z" }, @@ -4322,11 +4709,12 @@ name = "pyobjc-framework-automator" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/63/9f/097ed9f4de9e9491a1b08bb7d85d35a95d726c9e9f5f5bf203b359a436b6/pyobjc_framework_automator-11.1.tar.gz", hash = "sha256:9b46c55a4f9ae2b3c39ff560f42ced66bdd18c093188f0b5fc4060ad911838e4", size = 201439, upload-time = "2025-06-14T20:56:44.767Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/f0/c0/ebcc5a041440625ca984cde4ff96bc3e2cac4e5a37ca5bf4506ef4a98c54/pyobjc_framework_automator-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:bf675a19edd97de9c19dcfd0fea9af9ebbd3409786c162670d1d71cb2738e341", size = 10004, upload-time = "2025-06-14T20:45:46.111Z" }, { url = "https://files.pythonhosted.org/packages/0e/1e/3ed1df2168e596151da2329258951dae334e194d7de3b117c7e29a768ffc/pyobjc_framework_automator-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:af5941f8d90167244209b352512b7779e5590d17dc1e703e087a6cfe79ee3d64", size = 10029, upload-time = "2025-06-14T20:45:46.823Z" }, { url = "https://files.pythonhosted.org/packages/25/ed/a92cea530aac0cf08287321ec8123e8447f93461521f46bb329058b322eb/pyobjc_framework_automator-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:3458f836671ea922ad0771f617c927e9c52841c0a6e71b4a5a9dbb438736c207", size = 10040, upload-time = "2025-06-14T20:45:47.549Z" }, { url = "https://files.pythonhosted.org/packages/e9/30/c284723dd871e59756d24ddb4a9728db87b9e1b1610d22f3f60ad9de8b45/pyobjc_framework_automator-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:203b888152a78b39a8c67be663ff78a749ebff208ce993b4419fc4409faa1fda", size = 10186, upload-time = "2025-06-14T20:45:48.265Z" }, @@ -4339,14 +4727,15 @@ name = "pyobjc-framework-avfoundation" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreaudio", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremedia", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coreaudio" }, + { name = "pyobjc-framework-coremedia" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/3c/1f/90cdbce1d3b4861cbb17c12adf57daeec32477eb1df8d3f9ab8551bdadfb/pyobjc_framework_avfoundation-11.1.tar.gz", hash = "sha256:6663056cc6ca49af8de6d36a7fff498f51e1a9a7f1bde7afba718a8ceaaa7377", size = 832178, upload-time = "2025-06-14T20:56:46.329Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/0f/48/31286b2b09a619d8047256d7180e0d511be71ab598e5f54f034977b59bbf/pyobjc_framework_avfoundation-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:8a0ccbdba46b69dec1d12eea52eef56fcd63c492f73e41011bb72508b2aa2d0e", size = 70711, upload-time = "2025-06-14T20:45:52.461Z" }, { url = "https://files.pythonhosted.org/packages/43/30/d5d03dd4a508bdaa2156ff379e9e109020de23cbb6316c5865d341aa6db1/pyobjc_framework_avfoundation-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:94f065db4e87b1baebb5cf9f464cf9d82c5f903fff192001ebc974d9e3132c7e", size = 70746, upload-time = "2025-06-14T20:45:53.253Z" }, { url = "https://files.pythonhosted.org/packages/3f/8c/b8ced7700b0e931dc37d14b05e2bead28d2598c887832b3d697da55b1845/pyobjc_framework_avfoundation-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:e204d155a09c186601490e4402dcffb2845a5831079e389b47bd6a341fe5ee63", size = 70773, upload-time = "2025-06-14T20:45:54.059Z" }, { url = "https://files.pythonhosted.org/packages/d6/4c/086f4713793aaabdb5134debbf1fdc6c7d4ef5a32a6b35529e2e69580ec8/pyobjc_framework_avfoundation-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:dd3965aad0b236b8ac12f216d688c1a22b963f63e7e4fdb7107dd6790e80ee12", size = 71352, upload-time = "2025-06-14T20:45:54.871Z" }, @@ -4359,12 +4748,13 @@ name = "pyobjc-framework-avkit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/61/ff/9f41f2b8de786871184b48c4e5052cb7c9fcc204e7fee06687fa32b08bed/pyobjc_framework_avkit-11.1.tar.gz", hash = "sha256:d948204a7b94e0e878b19a909f9b33342e19d9ea519571d66a21fce8f72e3263", size = 46825, upload-time = "2025-06-14T20:56:47.494Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/a4/6c/ee7504367f4a9337d3e78cd34beb9fcb58ad30e274c2a9f1d8058b9837f2/pyobjc_framework_avkit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:88f70e2a399e43ce7bc3124b3b35d65537daddb358ea542fbb0146fa6406be8a", size = 11517, upload-time = "2025-06-14T20:45:59.676Z" }, { url = "https://files.pythonhosted.org/packages/b2/2f/6ec6a4ec7eb9ca329f36bbd2a51750fe5064d44dd437d8615abb7121ec93/pyobjc_framework_avkit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:ef9cd9fe37c6199bfde7ee5cd6e76ede23a6797932882785c53ef3070e209afb", size = 11539, upload-time = "2025-06-14T20:46:00.375Z" }, { url = "https://files.pythonhosted.org/packages/16/c8/6f0131f62f70e201a605b762cc05804b01fd493a7f21824d714140b7fd99/pyobjc_framework_avkit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:c5810b349745078ef8b4a562e85afe40de3245127f633d8cabe98aeca765c7fc", size = 11551, upload-time = "2025-06-14T20:46:01.071Z" }, { url = "https://files.pythonhosted.org/packages/a9/e6/a5bfa072393416c940a35b182457fee4779cf2f010c5772a9b690522afef/pyobjc_framework_avkit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:023b1cdb78c3aa5873d8abe69697396872b47278208991ec5e5aea4464309b01", size = 11749, upload-time = "2025-06-14T20:46:01.785Z" }, @@ -4377,11 +4767,12 @@ name = "pyobjc-framework-avrouting" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/cf/42/94bc18b968a4ee8b6427257f907ffbfc97f8ba6a6202953da149b649d638/pyobjc_framework_avrouting-11.1.tar.gz", hash = "sha256:7db1291d9f53cc58d34b2a826feb721a85f50ceb5e71952e8762baacd3db3fc0", size = 21069, upload-time = "2025-06-14T20:56:48.57Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/54/d4/0d17fd5a761d8a3d7dab0e096315de694b47dd48d2bb9655534e44399385/pyobjc_framework_avrouting-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:45cbabbf69764b2467d78adb8f3b7f209d1a8ee690e19f9a32d05c62a9c3a131", size = 8192, upload-time = "2025-06-14T20:46:05.479Z" }, { url = "https://files.pythonhosted.org/packages/01/17/ce199bc7fb3ba1f7b0474554bd71d1bdd3d5a141e1d9722ff9f46c104e1d/pyobjc_framework_avrouting-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:dc309e175abf3961f933f8b341c0504b17f4717931242ebb121a83256b8b5c13", size = 8212, upload-time = "2025-06-14T20:46:06.17Z" }, { url = "https://files.pythonhosted.org/packages/72/39/5c550da37c6d5a18a9b4a7d0fd6f7396ca8fbbee8cfccf82f3298e0f86b3/pyobjc_framework_avrouting-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:f52f9d62a3c8485b5687187ea58d905d7edccac9941c444b4add8129841cd031", size = 8230, upload-time = "2025-06-14T20:46:06.919Z" }, { url = "https://files.pythonhosted.org/packages/6b/ee/fec9662a0f7756a3440cd1c31be8c3a2db98d9b88210e46ca76b36e151ca/pyobjc_framework_avrouting-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:6a7b335161d327792f42054acb3ff415f7778e1492582df8e91b8609b4b02244", size = 8383, upload-time = "2025-06-14T20:46:07.593Z" }, @@ -4394,11 +4785,12 @@ name = "pyobjc-framework-backgroundassets" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/08/76/21e1632a212f997d7a5f26d53eb997951978916858039b79f43ebe3d10b2/pyobjc_framework_backgroundassets-11.1.tar.gz", hash = "sha256:2e14b50539d96d5fca70c49f21b69fdbad81a22549e3630f5e4f20d5c0204fc2", size = 24803, upload-time = "2025-06-14T20:56:49.566Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/74/ac/b1cb5c0ec2691ea225d53c2b9411d5ea1896f8f72eb5ca92978664443bb0/pyobjc_framework_backgroundassets-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:bd371ce08d1b79f540d5994139898097b83b1d4e4471c264892433d448b24de0", size = 9691, upload-time = "2025-06-14T20:46:12.197Z" }, { url = "https://files.pythonhosted.org/packages/ad/77/a6ad2df35fd71b3c26f52698d25174899ba1be134766022f5bf804ebf12d/pyobjc_framework_backgroundassets-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:13bf451c59b409b6ce1ac0e717a970a1b03bca7a944a7f19219da0d46ab7c561", size = 9707, upload-time = "2025-06-14T20:46:12.88Z" }, { url = "https://files.pythonhosted.org/packages/1d/7f/ed035866ab6c0573c445a9ed1ceb0912119866c130df7684a2332642520e/pyobjc_framework_backgroundassets-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:708466d847a479e1798f31c59fbc5307473d03fa1083f40cfcaa18fd31819c40", size = 9722, upload-time = "2025-06-14T20:46:13.574Z" }, { url = "https://files.pythonhosted.org/packages/05/e9/15f540b4bee160fd4b66f294ee4cd326aaa94632bcbee12d4b2448bb74ee/pyobjc_framework_backgroundassets-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:2484a2f9c87e8cae2fc375a39d68ea7ff02e4fb786e4afe88237c51fd5e78ec9", size = 9899, upload-time = "2025-06-14T20:46:14.277Z" }, @@ -4411,14 +4803,15 @@ name = "pyobjc-framework-browserenginekit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreaudio", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremedia", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coreaudio" }, + { name = "pyobjc-framework-coremedia" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/30/75/087270d9f81e913b57c7db58eaff8691fa0574b11faf9302340b3b8320f1/pyobjc_framework_browserenginekit-11.1.tar.gz", hash = "sha256:918440cefb10480024f645169de3733e30ede65e41267fa12c7b90c264a0a479", size = 31944, upload-time = "2025-06-14T20:56:50.195Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/ea/29/ec0a0cc6fb15911769cb8e5ad8ada85e3f5cf4889fafbb90d936c6b7053b/pyobjc_framework_browserenginekit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:29b5f5949170af0235485e79aa465a7af2b2e0913d0c2c9ab1ac033224a90edb", size = 11088, upload-time = "2025-06-14T20:46:18.696Z" }, { url = "https://files.pythonhosted.org/packages/89/90/a50bb66a5e041ace99b6c8b1df43b38d5f2e1bf771f57409e4aebf1dfae5/pyobjc_framework_browserenginekit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:9b815b167533015d62832b956e9cfb962bd2026f5a4ccd66718cf3bb2e15ab27", size = 11115, upload-time = "2025-06-14T20:46:19.401Z" }, { url = "https://files.pythonhosted.org/packages/44/0a/3cbfc8ca58ed9aeef7498f318ad209164903e64eba1ea94a661a59ee67e6/pyobjc_framework_browserenginekit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:dfe469f8eb1313ea0cbe0616cd3bbc56f62bdd8a683c959819ef01d7e9ac0de7", size = 11134, upload-time = "2025-06-14T20:46:20.445Z" }, { url = "https://files.pythonhosted.org/packages/4d/d6/013d10fc2ad2c7095e1b61b1b3db2c38aec403784f81b70237d11ba615a8/pyobjc_framework_browserenginekit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:f3332ffa9ae74cc6633fd17f6d998ac77b8939abbe9ecf95ae56df200ee93853", size = 11322, upload-time = "2025-06-14T20:46:21.476Z" }, @@ -4431,8 +4824,8 @@ name = "pyobjc-framework-businesschat" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/85/be/9d9d9d9383c411a58323ea510d768443287ca21610af652b815b3205ea80/pyobjc_framework_businesschat-11.1.tar.gz", hash = "sha256:69589d2f0cb4e7892e5ecc6aed79b1abd1ec55c099a7faacae6a326bc921259d", size = 12698, upload-time = "2025-06-14T20:56:51.173Z" } wheels = [ @@ -4444,8 +4837,8 @@ name = "pyobjc-framework-calendarstore" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/41/df/7ca8ee65b16d5fc862d7e8664289472eed918cf4d76921de6bdaa1461c65/pyobjc_framework_calendarstore-11.1.tar.gz", hash = "sha256:858ee00e6a380d9c086c2d7db82c116a6c406234038e0ec8fc2ad02e385dc437", size = 68215, upload-time = "2025-06-14T20:56:51.799Z" } wheels = [ @@ -4457,11 +4850,12 @@ name = "pyobjc-framework-callkit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/51/d5/4f0b62ab35be619e8c8d96538a03cf56fde6fd53540e1837e0fa588b3f6c/pyobjc_framework_callkit-11.1.tar.gz", hash = "sha256:b84d5ea38dff0cbe0754f5f9f6f33c742e216f12e7166179a8ec2cf4b0bfca94", size = 46648, upload-time = "2025-06-14T20:56:52.579Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/5a/f8/6e368225634cad9e457c4f8f0580ed318cb2f2c8110f2e56935fc12502f3/pyobjc_framework_callkit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:1db8b74abd6489d73c8619972730bea87a7d1f55d47649150fc1a30fdc6840fb", size = 11211, upload-time = "2025-06-14T20:46:27.146Z" }, { url = "https://files.pythonhosted.org/packages/18/2a/209572a6dba6768a57667e1f87a83ce8cadf18de5d6b1a91b95ce548d0f8/pyobjc_framework_callkit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:554e09ca3dab44d93a89927d9e300f004d2ef0db020b10425a4622b432e7b684", size = 11269, upload-time = "2025-06-14T20:46:28.164Z" }, { url = "https://files.pythonhosted.org/packages/8f/74/b0a22adb7ebcd0b81c24ed6e49d3df3b84f73192b667ebd90cb1b6eba917/pyobjc_framework_callkit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:fc5e638ddbc9dd3e9993205d2b077f5db41b6cd4e97b9c5592b7249575f23f04", size = 11284, upload-time = "2025-06-14T20:46:29.197Z" }, { url = "https://files.pythonhosted.org/packages/a2/98/3f65e4853a4a45b0cf369e5bbb0d9efaad93589461d155119feb88e8ff7b/pyobjc_framework_callkit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:bc1d2349dab93f7a0d298b01893828d7f46aded9122a341469b835d977a0646d", size = 11494, upload-time = "2025-06-14T20:46:30.09Z" }, @@ -4474,8 +4868,8 @@ name = "pyobjc-framework-carbon" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/39/a4/d751851865d9a78405cfec0c8b2931b1e96b9914e9788cd441fa4e8290d0/pyobjc_framework_carbon-11.1.tar.gz", hash = "sha256:047f098535479efa3ab89da1ebdf3cf9ec0b439a33a4f32806193886e9fcea71", size = 37291, upload-time = "2025-06-14T20:56:53.642Z" } wheels = [ @@ -4487,11 +4881,12 @@ name = "pyobjc-framework-cfnetwork" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/6f/49/7b24172e3d6eb0ddffc33a7498a2bea264aa2958c3fecaeb463bef88f0b8/pyobjc_framework_cfnetwork-11.1.tar.gz", hash = "sha256:ad600163eeadb7bf71abc51a9b6f2b5462a018d3f9bb1510c5ce3fdf2f22959d", size = 79069, upload-time = "2025-06-14T20:56:54.615Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/e7/61/74b0d0430807615b7f91a688a871ffd94a61d4764a101e2a53e0c95dd05e/pyobjc_framework_cfnetwork-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:d7a24746d0754b3a0042def2cd64aa205e5614f12ea0de9461c8e26d97633c72", size = 18953, upload-time = "2025-06-14T20:46:35.409Z" }, { url = "https://files.pythonhosted.org/packages/c2/31/05b4fb79e7f738f7f7d7a58734de2fab47d9a1fb219c2180e8c07efe2550/pyobjc_framework_cfnetwork-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:70beb8095df76e0e8eb7ab218be1e69ae180e01a4d77f7cad73c97b4eb7a296a", size = 19141, upload-time = "2025-06-14T20:46:36.134Z" }, { url = "https://files.pythonhosted.org/packages/2d/b1/5ea76ffd6413be8c65ec02e4552e3da3ee2bd37449e0854e3c8c559e7e42/pyobjc_framework_cfnetwork-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:5dd866fcbe6870931373636d19144544344f0f89685f6720e4a45453957702dd", size = 19148, upload-time = "2025-06-14T20:46:36.876Z" }, { url = "https://files.pythonhosted.org/packages/ba/df/b4897033b0368e4b6c4e5f643c593801677b2590d48dcb93d1c5a1d66c0f/pyobjc_framework_cfnetwork-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:62ccc6dcaaa5877534d21f93a15861a3d8af95888123d659f9ff5383d1a2a1f4", size = 19406, upload-time = "2025-06-14T20:46:37.648Z" }, @@ -4504,11 +4899,11 @@ name = "pyobjc-framework-cinematic" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-avfoundation", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremedia", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metal", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-avfoundation" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coremedia" }, + { name = "pyobjc-framework-metal" }, ] sdist = { url = "https://files.pythonhosted.org/packages/57/6f/c2d0b49e01e654496a1781bafb9da72a6fbd00f5abb39dc4a3a0045167c7/pyobjc_framework_cinematic-11.1.tar.gz", hash = "sha256:efde39a6a2379e1738dbc5434b2470cd187cf3114ffb81390b3b1abda470b382", size = 25522, upload-time = "2025-06-14T20:56:55.379Z" } wheels = [ @@ -4520,11 +4915,12 @@ name = "pyobjc-framework-classkit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/7a/8b/5150b4faddd15d5dd795bc62b2256c4f7dafc983cfa694fcf88121ea0016/pyobjc_framework_classkit-11.1.tar.gz", hash = "sha256:ee1e26395eb00b3ed5442e3234cdbfe925d2413185af38eca0477d7166651df4", size = 39831, upload-time = "2025-06-14T20:56:56.036Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/89/86/5b9ef1d5aa3f4835d164c9be46afae634911db56c6ad7795e212ef9bb50b/pyobjc_framework_classkit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:018da363d06f3615c07a8623cbdb024a31b1f8b96a933ff2656c0e903063842c", size = 8895, upload-time = "2025-06-14T20:46:42.689Z" }, { url = "https://files.pythonhosted.org/packages/75/79/2552fd5e1da73dffb35589469b3cd8c0928e3100462761350d19ea922e59/pyobjc_framework_classkit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:161dcb9b718649e6331a5eab5a76c2b43a9b322b15b37b3f8f9c5faad12ee6d1", size = 8911, upload-time = "2025-06-14T20:46:43.714Z" }, { url = "https://files.pythonhosted.org/packages/59/1c/a06623c3d78949c9d5eae7c7e753e6c8c75e2ae7a0b8ccae40a1b6180e0a/pyobjc_framework_classkit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:08000deb43004d16fb39ccd83b3de30e1e3b72639a79d05206d7d5c15f005b3a", size = 8928, upload-time = "2025-06-14T20:46:44.426Z" }, { url = "https://files.pythonhosted.org/packages/b3/c3/e0a966134c8022f1d922b27fea6a50ec1118c12fdfa65b2ce4efaa7c84d6/pyobjc_framework_classkit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:ef28d042964b0f757569e72df737bb049b531c33b7d06a705ce2dcfa4e6e45d8", size = 9082, upload-time = "2025-06-14T20:46:45.309Z" }, @@ -4537,11 +4933,11 @@ name = "pyobjc-framework-cloudkit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-accounts", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coredata", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-corelocation", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-accounts" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coredata" }, + { name = "pyobjc-framework-corelocation" }, ] sdist = { url = "https://files.pythonhosted.org/packages/58/a6/bfe5be55ed95704efca0e86b218155a9c801735107cedba3af8ea4580a05/pyobjc_framework_cloudkit-11.1.tar.gz", hash = "sha256:40d2dc4bf28c5be9b836b01e4d267a15d847d756c2a65530e1fcd79b2825e86d", size = 122778, upload-time = "2025-06-14T20:56:56.73Z" } wheels = [ @@ -4553,10 +4949,11 @@ name = "pyobjc-framework-cocoa" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, ] sdist = { url = "https://files.pythonhosted.org/packages/4b/c5/7a866d24bc026f79239b74d05e2cf3088b03263da66d53d1b4cf5207f5ae/pyobjc_framework_cocoa-11.1.tar.gz", hash = "sha256:87df76b9b73e7ca699a828ff112564b59251bb9bbe72e610e670a4dc9940d038", size = 5565335, upload-time = "2025-06-14T20:56:59.683Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/90/43/6841046aa4e257b6276cd23e53cacedfb842ecaf3386bb360fa9cc319aa1/pyobjc_framework_cocoa-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:7b9a9b8ba07f5bf84866399e3de2aa311ed1c34d5d2788a995bdbe82cc36cfa0", size = 388177, upload-time = "2025-06-14T20:46:51.454Z" }, { url = "https://files.pythonhosted.org/packages/68/da/41c0f7edc92ead461cced7e67813e27fa17da3c5da428afdb4086c69d7ba/pyobjc_framework_cocoa-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:806de56f06dfba8f301a244cce289d54877c36b4b19818e3b53150eb7c2424d0", size = 388983, upload-time = "2025-06-14T20:46:52.591Z" }, { url = "https://files.pythonhosted.org/packages/4e/0b/a01477cde2a040f97e226f3e15e5ffd1268fcb6d1d664885a95ba592eca9/pyobjc_framework_cocoa-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:54e93e1d9b0fc41c032582a6f0834befe1d418d73893968f3f450281b11603da", size = 389049, upload-time = "2025-06-14T20:46:53.757Z" }, { url = "https://files.pythonhosted.org/packages/bc/e6/64cf2661f6ab7c124d0486ec6d1d01a9bb2838a0d2a46006457d8c5e6845/pyobjc_framework_cocoa-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:fd5245ee1997d93e78b72703be1289d75d88ff6490af94462b564892e9266350", size = 393110, upload-time = "2025-06-14T20:46:54.894Z" }, @@ -4569,8 +4966,8 @@ name = "pyobjc-framework-collaboration" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/66/49/9dbe8407d5dd663747267c1234d1b914bab66e1878d22f57926261a3063b/pyobjc_framework_collaboration-11.1.tar.gz", hash = "sha256:4564e3931bfc51773623d4f57f2431b58a39b75cb964ae5c48d27ee4dde2f4ea", size = 16839, upload-time = "2025-06-14T20:57:01.101Z" } wheels = [ @@ -4582,8 +4979,8 @@ name = "pyobjc-framework-colorsync" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/b5/97/7613b6041f62c52f972e42dd5d79476b56b84d017a8b5e4add4d9cfaca36/pyobjc_framework_colorsync-11.1.tar.gz", hash = "sha256:7a346f71f34b2ccd1b020a34c219b85bf8b6f6e05283d503185aeb7767a269dd", size = 38999, upload-time = "2025-06-14T20:57:01.761Z" } wheels = [ @@ -4595,11 +4992,12 @@ name = "pyobjc-framework-contacts" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/a6/85/34868b6447d552adf8674bac226b55c2baacacee0d67ee031e33805d6faa/pyobjc_framework_contacts-11.1.tar.gz", hash = "sha256:752036e7d8952a4122296d7772f274170a5f35a53ee6454a27f3e1d9603222cc", size = 84814, upload-time = "2025-06-14T20:57:02.582Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/68/e1/27715ef476441cb05d4442b93fe6380a57a946cda008f70399cadb4ff1fd/pyobjc_framework_contacts-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:68148653f27c1eaeff2ad4831b5e68393071a382aab773629cd047ce55556726", size = 12067, upload-time = "2025-06-14T20:47:02.178Z" }, { url = "https://files.pythonhosted.org/packages/30/c8/0d47af11112bf382e059cfe2dd03be98914f0621ddff8858bb9af864f8c5/pyobjc_framework_contacts-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:576ee4aec05d755444bff10b45833f73083b5b3d1b2740e133b92111f7765e54", size = 12141, upload-time = "2025-06-14T20:47:02.884Z" }, { url = "https://files.pythonhosted.org/packages/11/af/375aa44e9e00aa66e373c4c3893a0db341d93f90e2d62a277287dc553841/pyobjc_framework_contacts-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:09b873d2bd739fea63d744430defb04ce4b44af064aaf0b6bf558eea23f82bd7", size = 12160, upload-time = "2025-06-14T20:47:03.614Z" }, { url = "https://files.pythonhosted.org/packages/a0/b9/effeda0eefedced16d4a002ab0c0a331be506d5bc7ff290788ac8eb0b2a9/pyobjc_framework_contacts-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:23312bb4bfc5aafecdac84ca402189e312e754e9dc0586d8f282d225c3952c00", size = 12319, upload-time = "2025-06-14T20:47:04.316Z" }, @@ -4612,12 +5010,13 @@ name = "pyobjc-framework-contactsui" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-contacts", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-contacts" }, ] sdist = { url = "https://files.pythonhosted.org/packages/3f/57/8765b54a30edaa2a56df62e11e7c32e41b6ea300513256adffa191689368/pyobjc_framework_contactsui-11.1.tar.gz", hash = "sha256:5bc29ea2b10a342018e1b96be6b140c10ebe3cfb6417278770feef5e88026a1f", size = 20031, upload-time = "2025-06-14T20:57:03.603Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/38/02/f65f2eb6e2ad91c95e5a6b532fe8dd5cd0c190fbaff71e4a85346e16c0f6/pyobjc_framework_contactsui-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:1c0f03c71e63daf5dbf760bf0e45620618a6f1ea62f8c17e288463c1fd4d2685", size = 7858, upload-time = "2025-06-14T20:47:08.346Z" }, { url = "https://files.pythonhosted.org/packages/46/b6/50ec09f1bb18c422b8c079e02328689f32e977b43ab7651c05e8274854dc/pyobjc_framework_contactsui-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:c34a6f27ef5aa4742cc44fd5b4d16fe1e1745ff839578b4c059faf2c58eee3ca", size = 7875, upload-time = "2025-06-14T20:47:09.041Z" }, { url = "https://files.pythonhosted.org/packages/8b/3f/72170303c11945c360b83fa1c0d3f91638dc5de1ef9f9a2b880252378430/pyobjc_framework_contactsui-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:f3b4f0225645a26ed9e6c008c2e8c217035b4a50fa9cd6623c628a11c37924d0", size = 7886, upload-time = "2025-06-14T20:47:09.726Z" }, { url = "https://files.pythonhosted.org/packages/ad/d7/fd11ac75bd6eb5d23225f7d1ac910c2b47481caff6e04b883bec04c28de2/pyobjc_framework_contactsui-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:666586174b306b33b791d2edee021cd979a8c970d444f906ed294e27583a6b54", size = 8044, upload-time = "2025-06-14T20:47:10.427Z" }, @@ -4630,11 +5029,12 @@ name = "pyobjc-framework-coreaudio" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/39/c0/4ab6005cf97e534725b0c14b110d4864b367c282b1c5b0d8f42aad74a83f/pyobjc_framework_coreaudio-11.1.tar.gz", hash = "sha256:b7b89540ae7efc6c1e3208ac838ef2acfc4d2c506dd629d91f6b3b3120e55c1b", size = 141032, upload-time = "2025-06-14T20:57:04.348Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/54/1d/81339c1087519a9f125396c717b85a05b49c2c54137bdf4ca01c1ccb6239/pyobjc_framework_coreaudio-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:73a46f0db2fa8ca2e8c47c3ddcc2751e67a0f8600246a6718553b15ee0dbbdb6", size = 35383, upload-time = "2025-06-14T20:47:14.234Z" }, { url = "https://files.pythonhosted.org/packages/3d/fe/c43521642db98a4ec29fa535781c1316342bb52d5fc709696cbb1e8ca6cd/pyobjc_framework_coreaudio-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:2538d1242dab4e27efb346eafbad50594e7e95597fa7220f0bab2099c825da55", size = 36765, upload-time = "2025-06-14T20:47:15.344Z" }, { url = "https://files.pythonhosted.org/packages/82/9b/24d03ace273585de2d04385f06b895ce92caf8f5af430b060618ebce9dbe/pyobjc_framework_coreaudio-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:f73d996df1e721931d9f78050e1708735a173dbe3a76d9c71fb36e04f7208478", size = 36779, upload-time = "2025-06-14T20:47:16.123Z" }, { url = "https://files.pythonhosted.org/packages/91/23/aa78365e45d0d04fc37e21cf7d69dc0d11e17b564e83cb5bcd98e89cdf45/pyobjc_framework_coreaudio-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:67dae111b78d91c26c753dbfbccc3ea5498cfda3dfe83c6f3778628b435e1e7b", size = 38480, upload-time = "2025-06-14T20:47:16.911Z" }, @@ -4647,12 +5047,13 @@ name = "pyobjc-framework-coreaudiokit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreaudio", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coreaudio" }, ] sdist = { url = "https://files.pythonhosted.org/packages/f1/4e/c49b26c60047c511727efe994b412276c487dfe90f1ee0fced0bddbdf8a3/pyobjc_framework_coreaudiokit-11.1.tar.gz", hash = "sha256:0b461c3d6123fda4da6b6aaa022efc918c1de2e126a5cf07d2189d63fa54ba40", size = 21955, upload-time = "2025-06-14T20:57:05.218Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/07/44/0de5d26e383d0b00f2f44394db74e0953bc1e35b74072a67fde916e8e31e/pyobjc_framework_coreaudiokit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:4743fbd210159cffffb0a7b8e06bf8b8527ba4bf01e76806fae2696fd6990e77", size = 7234, upload-time = "2025-06-14T20:47:21.271Z" }, { url = "https://files.pythonhosted.org/packages/18/27/d8ff6293851a7d9665724fa5c324d28200776ec10a04b850ba21ad1f9be1/pyobjc_framework_coreaudiokit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:20440a2926b1d91da8efc8bc060e77c7a195cb0443dbf3770eaca9e597276748", size = 7266, upload-time = "2025-06-14T20:47:22.136Z" }, { url = "https://files.pythonhosted.org/packages/13/e6/89aa525271d19f0ea11799021f364181dd62dbfe77ecb4fc0a7d4e579cd2/pyobjc_framework_coreaudiokit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:11d42770dfbc6a8af8d5fa39a4f700f0067d7e6c7ba9335e6624d89de3c599a9", size = 7273, upload-time = "2025-06-14T20:47:23.137Z" }, { url = "https://files.pythonhosted.org/packages/a5/70/f9b13b7822a53bed794525214ccca63b018901c113ebfd45e2159447f3cf/pyobjc_framework_coreaudiokit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:6fea7c7ea5305e8cbd75808ec4edcde8e2320137f227b3d771266dd9a71e1fa5", size = 7429, upload-time = "2025-06-14T20:47:24.17Z" }, @@ -4665,11 +5066,12 @@ name = "pyobjc-framework-corebluetooth" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/3d/fe/2081dfd9413b7b4d719935c33762fbed9cce9dc06430f322d1e2c9dbcd91/pyobjc_framework_corebluetooth-11.1.tar.gz", hash = "sha256:1deba46e3fcaf5e1c314f4bbafb77d9fe49ec248c493ad00d8aff2df212d6190", size = 60337, upload-time = "2025-06-14T20:57:05.919Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/8c/75/3318e85b7328c99c752e40592a907fc5c755cddc6d73beacbb432f6aa2d0/pyobjc_framework_corebluetooth-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:433b8593eb1ea8b6262b243ec903e1de4434b768ce103ebe15aac249b890cc2a", size = 13143, upload-time = "2025-06-14T20:47:28.889Z" }, { url = "https://files.pythonhosted.org/packages/8a/bc/083ea1ae57a31645df7fad59921528f6690995f7b7c84a203399ded7e7fe/pyobjc_framework_corebluetooth-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:36bef95a822c68b72f505cf909913affd61a15b56eeaeafea7302d35a82f4f05", size = 13163, upload-time = "2025-06-14T20:47:29.624Z" }, { url = "https://files.pythonhosted.org/packages/3e/b5/d07cfa229e3fa0cd1cdaa385774c41907941d25b693cf55ad92e8584a3b3/pyobjc_framework_corebluetooth-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:992404b03033ecf637e9174caed70cb22fd1be2a98c16faa699217678e62a5c7", size = 13179, upload-time = "2025-06-14T20:47:30.376Z" }, { url = "https://files.pythonhosted.org/packages/7a/10/476bca43002a6d009aed956d5ed3f3867c8d1dcd085dde8989be7020c495/pyobjc_framework_corebluetooth-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:ebb8648f5e33d98446eb1d6c4654ba4fcc15d62bfcb47fa3bbd5596f6ecdb37c", size = 13358, upload-time = "2025-06-14T20:47:31.114Z" }, @@ -4682,11 +5084,12 @@ name = "pyobjc-framework-coredata" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/00/e3/af497da7a7c895b6ff529d709d855a783f34afcc4b87ab57a1a2afb3f876/pyobjc_framework_coredata-11.1.tar.gz", hash = "sha256:fe9fd985f8e06c70c0fb1e6bbea5b731461f9e76f8f8d8e89c7c72667cdc6adf", size = 260628, upload-time = "2025-06-14T20:57:06.729Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/29/d9/7f12bdba0503d0ef7b1ac26e05429aecc33b4aaf190155a6bec8b576850d/pyobjc_framework_coredata-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:c66ae04cc658eafdfb987f9705e21f9782edee6773a8adb6bfa190500e4e7e29", size = 16428, upload-time = "2025-06-14T20:47:34.981Z" }, { url = "https://files.pythonhosted.org/packages/5b/ac/77935aa9891bd6be952b1e6780df2bae748971dd0fe0b5155894004840bd/pyobjc_framework_coredata-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:c9b2374784e67694a18fc8c120a12f11b355a20b643c01f23ae2ce87330a75e0", size = 16443, upload-time = "2025-06-14T20:47:35.711Z" }, { url = "https://files.pythonhosted.org/packages/75/50/17631c3f172d9681faad210b035fa3d2c01f59468b574dbc088512853cc2/pyobjc_framework_coredata-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:007160eb10bb8c789076f231e3d625d8875ca42eb5a806fdab5d0277c48866f8", size = 16457, upload-time = "2025-06-14T20:47:36.439Z" }, { url = "https://files.pythonhosted.org/packages/1f/d7/c736d0a945efe806996335324a241f9e2726ebc8a91c9c3cfaa2d788c63b/pyobjc_framework_coredata-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:699ad568f98f58e88e642159c91ffff0c68ce3d1ec798e4af8333b27431fd058", size = 16608, upload-time = "2025-06-14T20:47:37.526Z" }, @@ -4699,8 +5102,8 @@ name = "pyobjc-framework-corehaptics" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/5f/83/cc997ec4687a68214dd3ad1bdf64353305f5c7e827fad211adac4c28b39f/pyobjc_framework_corehaptics-11.1.tar.gz", hash = "sha256:e5da3a97ed6aca9b7268c8c5196c0a339773a50baa72d1502d3435dc1a2a80f1", size = 42722, upload-time = "2025-06-14T20:57:08.019Z" } wheels = [ @@ -4712,11 +5115,12 @@ name = "pyobjc-framework-corelocation" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/95/ef/fbd2e01ec137208af7bfefe222773748d27f16f845b0efa950d65e2bd719/pyobjc_framework_corelocation-11.1.tar.gz", hash = "sha256:46a67b99925ee3d53914331759c6ee110b31bb790b74b05915acfca41074c206", size = 104508, upload-time = "2025-06-14T20:57:08.731Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/f9/f9/8137e8bf86f8e6350298217dcc635fd6577d64b484f9d250ddb85a84efa0/pyobjc_framework_corelocation-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:ea261e7d87c6f62f1b03c252c273ea7fd6f314e3e73c69c6fb3fe807bf183462", size = 12741, upload-time = "2025-06-14T20:47:42.583Z" }, { url = "https://files.pythonhosted.org/packages/95/cb/282d59421cdb89a5e5fcce72fc37d6eeace98a2a86d71f3be3cd47801298/pyobjc_framework_corelocation-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:562e31124f80207becfd8df01868f73fa5aa70169cc4460e1209fb16916e4fb4", size = 12752, upload-time = "2025-06-14T20:47:43.273Z" }, { url = "https://files.pythonhosted.org/packages/de/cb/c4672fcfa5e998cfd0dd165717ec312f7e6cbac06ecb4a0e227dbc4d7e27/pyobjc_framework_corelocation-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:0f8182835429118a55ed65963c80f5b2892d190747b986e8395b1cd99f41a1d0", size = 12768, upload-time = "2025-06-14T20:47:43.987Z" }, { url = "https://files.pythonhosted.org/packages/47/e7/ef83b4d6fca57bd09a56064fdcb55792b7497279b1dac3de781c86ed40ec/pyobjc_framework_corelocation-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:bc3f27802415aa62330a2d2507adc3a9b98a89d6de7d1033ebe6b8c461610831", size = 12910, upload-time = "2025-06-14T20:47:44.744Z" }, @@ -4729,11 +5133,12 @@ name = "pyobjc-framework-coremedia" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/95/5d/81513acd219df77a89176f1574d936b81ad6f6002225cabb64d55efb7e8d/pyobjc_framework_coremedia-11.1.tar.gz", hash = "sha256:82cdc087f61e21b761e677ea618a575d4c0dbe00e98230bf9cea540cff931db3", size = 216389, upload-time = "2025-06-14T20:57:09.546Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/32/48/811ccea77d2c0d8156a489e2900298502eb6648d9c041c7f0c514c8f8a29/pyobjc_framework_coremedia-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:aacf47006e1c6bf6124fb2b5016a8d5fd5cf504b6b488f9eba4e389ab0f0a051", size = 29118, upload-time = "2025-06-14T20:47:48.895Z" }, { url = "https://files.pythonhosted.org/packages/2c/d1/b3d004d6a2d2188d196779d92fe8cfa2533f5722cd216fbc4f0cffc63b24/pyobjc_framework_coremedia-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:ea5055298af91e463ffa7977d573530f9bada57b8f2968dcc76a75e339b9a598", size = 29015, upload-time = "2025-06-14T20:47:49.655Z" }, { url = "https://files.pythonhosted.org/packages/1c/23/cafd29011d14eac27fc55770157ebb8e02ffed9f75e01f24e97616417c4c/pyobjc_framework_coremedia-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:7ecdb64c743ffe9fd3949c7cc9109891b9f399a0852717fcb969d33c4e7ba527", size = 29031, upload-time = "2025-06-14T20:47:50.395Z" }, { url = "https://files.pythonhosted.org/packages/de/a6/ca85b7d9d000e8e2748bcacde356278cb90f6ca9aed54dce6a42d1716ba8/pyobjc_framework_coremedia-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:969ce357c616f6835f47e27d1e73964374cdb671476571dfd358894a8ced06f2", size = 29094, upload-time = "2025-06-14T20:47:51.318Z" }, @@ -4746,11 +5151,12 @@ name = "pyobjc-framework-coremediaio" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/64/68/9cef2aefba8e69916049ff43120e8794df8051bdf1f690a55994bbe4eb57/pyobjc_framework_coremediaio-11.1.tar.gz", hash = "sha256:bccd69712578b177144ded398f4695d71a765ef61204da51a21f0c90b4ad4c64", size = 108326, upload-time = "2025-06-14T20:57:10.435Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/aa/38/6bcddd7d57fa19173621aa29b46342756ed1a081103d24e4bdac1cf882fe/pyobjc_framework_coremediaio-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:4438713ee4611d5310f4f2e71e557b6138bc79c0363e3d45ecb8c09227dfa58e", size = 17203, upload-time = "2025-06-14T20:47:55.781Z" }, { url = "https://files.pythonhosted.org/packages/4b/b5/5dd941c1d7020a78b563a213fb8be7c6c3c1073c488914e158cd5417f4f7/pyobjc_framework_coremediaio-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:39ad2518de9943c474e5ca0037e78f92423c3352deeee6c513a489016dac1266", size = 17250, upload-time = "2025-06-14T20:47:56.505Z" }, { url = "https://files.pythonhosted.org/packages/08/44/cd98e1dacdd28c4e80fe1b0dde3a5171494735cb4a7b8b5775825b824b96/pyobjc_framework_coremediaio-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:9e0a079fe790ce8a69d11bea46b315c9a0d3f3999a2f09e2ef4fcc4430a47c42", size = 17226, upload-time = "2025-06-14T20:47:57.267Z" }, { url = "https://files.pythonhosted.org/packages/f9/66/89a3c01d1d1a0e7b510ade14a2c604883d6846d8279095ff4849f9989f9c/pyobjc_framework_coremediaio-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:5a94f9e507b470ce7dcb887e79ccf19e98693a606ad34462d711004e3edd88c3", size = 17564, upload-time = "2025-06-14T20:47:58.483Z" }, @@ -4763,11 +5169,12 @@ name = "pyobjc-framework-coremidi" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/06/ca/2ae5149966ccd78290444f88fa62022e2b96ed2fddd47e71d9fd249a9f82/pyobjc_framework_coremidi-11.1.tar.gz", hash = "sha256:095030c59d50c23aa53608777102bc88744ff8b10dfb57afe24b428dcd12e376", size = 107817, upload-time = "2025-06-14T20:57:11.245Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/37/fc/db75c55e492e5e34be637da2eeeaadbb579655b6d17159de419237bc9bdf/pyobjc_framework_coremidi-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:5f8c2fdc9d1b7967e2a5ec0d5281eaddc00477bed9753aa14d5b881dc3a9ad8f", size = 24256, upload-time = "2025-06-14T20:48:02.448Z" }, { url = "https://files.pythonhosted.org/packages/c2/2d/57c279dd74a9073d1416b10b05ebb9598f4868cad010d87f46ef4b517324/pyobjc_framework_coremidi-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:deb9120478a831a898f22f68737fc683bb9b937e77556e78b75986aebd349c55", size = 24277, upload-time = "2025-06-14T20:48:03.184Z" }, { url = "https://files.pythonhosted.org/packages/1e/66/dfdc7a5dc5a44b1660015bb24454ca0cbdf436e631e39917c495475dbb24/pyobjc_framework_coremidi-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:c2e1ab122501206ceae07123fdc433e91a5f1a97224f80ece0717b6f36ad2029", size = 24308, upload-time = "2025-06-14T20:48:04.285Z" }, { url = "https://files.pythonhosted.org/packages/46/fe/200f286d5506efdc6c6d150eda24909a89f5c856a7a5003db0a423f66943/pyobjc_framework_coremidi-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:3462a158214adb7ebc785fb6924e674c58dcd471888dbca5e2e77381f3f1bbdc", size = 24463, upload-time = "2025-06-14T20:48:05.014Z" }, @@ -4780,11 +5187,12 @@ name = "pyobjc-framework-coreml" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/0d/5d/4309f220981d769b1a2f0dcb2c5c104490d31389a8ebea67e5595ce1cb74/pyobjc_framework_coreml-11.1.tar.gz", hash = "sha256:775923eefb9eac2e389c0821b10564372de8057cea89f1ea1cdaf04996c970a7", size = 82005, upload-time = "2025-06-14T20:57:12.004Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/76/9c/2218a8f457f56075a8a3f2490bd9d01c8e69c807139eaa0a6ac570531ca5/pyobjc_framework_coreml-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:b5be7889ad99da1aca040238fd99af9ee87ea8a6628f24d33e2e4890b88dd139", size = 11414, upload-time = "2025-06-14T20:48:09.267Z" }, { url = "https://files.pythonhosted.org/packages/3e/9e/a1b6d30b4f91c7cc4780e745e1e73a322bd3524a773f66f5eac0b1600d85/pyobjc_framework_coreml-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:c768b03d72488b964d753392e9c587684961d8237b69cca848b3a5a00aea79c9", size = 11436, upload-time = "2025-06-14T20:48:10.048Z" }, { url = "https://files.pythonhosted.org/packages/95/95/f8739958ccf7cbaaf172653b3665cfcee406c5503a49828130b618b93d3f/pyobjc_framework_coreml-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:10d51f8a5fe8d30c7ec70304a2324df76b48b9fbef30ee0f0c33b99a49ae8853", size = 11452, upload-time = "2025-06-14T20:48:10.74Z" }, { url = "https://files.pythonhosted.org/packages/57/d1/881cef8f09f022ba6534d98f0bb1c3ad5e68dbdda91173d88fa1524c0526/pyobjc_framework_coreml-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:4df25ee233430f016ffcb4e88506b54c8e7b668c93197e6a1341761530a5922c", size = 11682, upload-time = "2025-06-14T20:48:11.421Z" }, @@ -4797,11 +5205,12 @@ name = "pyobjc-framework-coremotion" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/a5/95/e469dc7100ea6b9c29a074a4f713d78b32a78d7ec5498c25c83a56744fc2/pyobjc_framework_coremotion-11.1.tar.gz", hash = "sha256:5884a568521c0836fac39d46683a4dea3d259a23837920897042ffb922d9ac3e", size = 67050, upload-time = "2025-06-14T20:57:12.705Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/1d/3f/137c983dbccbdbc4a07fb2453e494af938078969bcde9252fbbad0ba939d/pyobjc_framework_coremotion-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:501248a726816e05552d1c1f7e2be2c7305cda792c46905d9aee7079dfad2eea", size = 10353, upload-time = "2025-06-14T20:48:15.365Z" }, { url = "https://files.pythonhosted.org/packages/e9/17/ffa3cf9fde9df31f3d6ecb38507c61c6d8d81276d0a9116979cafd5a0ab7/pyobjc_framework_coremotion-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:8c3b33228a170bf8495508a8923451ec600435c7bff93d7614f19c913baeafd1", size = 10368, upload-time = "2025-06-14T20:48:16.066Z" }, { url = "https://files.pythonhosted.org/packages/7c/2b/ade312f6bda6c368112bc2151834e664c22ae7d6d1f2ce33347b84ece7fb/pyobjc_framework_coremotion-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:ac5302deaab99a7443cad63f125061a90040852d4f8efb58492542a612b2afe3", size = 10393, upload-time = "2025-06-14T20:48:16.784Z" }, { url = "https://files.pythonhosted.org/packages/63/51/380d1b2b072b379a4740b725bdec4119c0c82bc66c55a2a62ca2fa0ec478/pyobjc_framework_coremotion-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:d67413a56989154dab7bf1b69c14b0b2387d87d3a4c8e3c8a9fc0230f061e8ab", size = 10534, upload-time = "2025-06-14T20:48:17.466Z" }, @@ -4814,12 +5223,13 @@ name = "pyobjc-framework-coreservices" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-fsevents", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-fsevents" }, ] sdist = { url = "https://files.pythonhosted.org/packages/a8/a9/141d18019a25776f507992f9e7ffc051ca5a734848d8ea8d848f7c938efc/pyobjc_framework_coreservices-11.1.tar.gz", hash = "sha256:cf8eb5e272c60a96d025313eca26ff2487dcd02c47034cc9db39f6852d077873", size = 1245086, upload-time = "2025-06-14T20:57:13.914Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/fc/35/a984b9aace173e92b3509f82afe5e0f8ecddf5cf43bf0c01c803f60a19ce/pyobjc_framework_coreservices-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:f7260e09a0550d57756ad655f3d3815f21fc3f0386aed014be4b46194c346941", size = 30243, upload-time = "2025-06-14T20:48:21.563Z" }, { url = "https://files.pythonhosted.org/packages/fa/0f/52827197a1fa1dabefd77803920eaf340f25e0c81944844ab329d511cade/pyobjc_framework_coreservices-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:6bd313ec326efd715b4b10c3ebcc9f054e3ee3178be407b97ea225cd871351d2", size = 30252, upload-time = "2025-06-14T20:48:22.657Z" }, { url = "https://files.pythonhosted.org/packages/9d/dc/8a0414dd81054062a56a54db5c1cbb35c715081c9210ed69d5fed8046ebe/pyobjc_framework_coreservices-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:8aee505dca56afc5363d8d0dff0b2d26583a8d0f3ac37674cef86f66c51a2934", size = 30271, upload-time = "2025-06-14T20:48:23.427Z" }, { url = "https://files.pythonhosted.org/packages/44/e3/494bbc589b0a02ad7ab657fdf67359298b007112b65a2f4416d61176a4c4/pyobjc_framework_coreservices-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:4ffa188322ab9d05c6964926959dedba5cc04534232f1eff03aee5f09faa499e", size = 30282, upload-time = "2025-06-14T20:48:24.175Z" }, @@ -4832,11 +5242,12 @@ name = "pyobjc-framework-corespotlight" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/31/c7/b67ebfb63b7ccbfda780d583056d1fd4b610ba3839c8ebe3435b86122c61/pyobjc_framework_corespotlight-11.1.tar.gz", hash = "sha256:4dd363c8d3ff7619659b63dd31400f135b03e32435b5d151459ecdacea14e0f2", size = 87161, upload-time = "2025-06-14T20:57:14.934Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/46/d4/87a87384bbb2e27864d527eb00973a056bae72603e6c581711231f2479fc/pyobjc_framework_corespotlight-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:d3c571289ce9107f1ade92ad036633f81355f22f70e8ba82d7335f1757381b89", size = 9954, upload-time = "2025-06-14T20:48:28.065Z" }, { url = "https://files.pythonhosted.org/packages/b9/f8/06b7edfeabe5b3874485b6e5bbe4a39d9f2e1f44348faa7cb320fbc6f21a/pyobjc_framework_corespotlight-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:7cedd3792fe1fe2a8dc65a8ff1f70baf12415a5dc9dc4d88f987059567d7e694", size = 9977, upload-time = "2025-06-14T20:48:28.757Z" }, { url = "https://files.pythonhosted.org/packages/7d/ce/812ae5a7f97a57abce1b2232280d5838a77d5454e5b05d79c3e654ad7400/pyobjc_framework_corespotlight-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:546d0d9b101de4ca20449f3807d1f88e5c26de0345a8bfefc70f12f87efb8433", size = 9997, upload-time = "2025-06-14T20:48:29.833Z" }, { url = "https://files.pythonhosted.org/packages/5c/ee/9c432c1735f537c5b56dae43f6d2f2dd4922cac45c8e072e5a405b3ab81b/pyobjc_framework_corespotlight-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:f562cc65865066f8e2e5d96c868fd7f463d8280f1ef01df85250fc1150feed0e", size = 10137, upload-time = "2025-06-14T20:48:30.513Z" }, @@ -4849,12 +5260,13 @@ name = "pyobjc-framework-coretext" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/65/e9/d3231c4f87d07b8525401fd6ad3c56607c9e512c5490f0a7a6abb13acab6/pyobjc_framework_coretext-11.1.tar.gz", hash = "sha256:a29bbd5d85c77f46a8ee81d381b847244c88a3a5a96ac22f509027ceceaffaf6", size = 274702, upload-time = "2025-06-14T20:57:16.059Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/4c/59/d6cc5470157cfd328b2d1ee2c1b6f846a5205307fce17291b57236d9f46e/pyobjc_framework_coretext-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:b4f4d2d2a6331fa64465247358d7aafce98e4fb654b99301a490627a073d021e", size = 30072, upload-time = "2025-06-14T20:48:34.248Z" }, { url = "https://files.pythonhosted.org/packages/32/67/9cc5189c366e67dc3e5b5976fac73cc6405841095f795d3fa0d5fc43d76a/pyobjc_framework_coretext-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:1597bf7234270ee1b9963bf112e9061050d5fb8e1384b3f50c11bde2fe2b1570", size = 30175, upload-time = "2025-06-14T20:48:35.023Z" }, { url = "https://files.pythonhosted.org/packages/b0/d1/6ec2ef4f8133177203a742d5db4db90bbb3ae100aec8d17f667208da84c9/pyobjc_framework_coretext-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:37e051e8f12a0f47a81b8efc8c902156eb5bc3d8123c43e5bd4cebd24c222228", size = 30180, upload-time = "2025-06-14T20:48:35.766Z" }, { url = "https://files.pythonhosted.org/packages/0a/84/d4a95e49f6af59503ba257fbed0471b6932f0afe8b3725c018dd3ba40150/pyobjc_framework_coretext-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:56a3a02202e0d50be3c43e781c00f9f1859ab9b73a8342ff56260b908e911e37", size = 30768, upload-time = "2025-06-14T20:48:36.869Z" }, @@ -4867,11 +5279,12 @@ name = "pyobjc-framework-corewlan" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/c6/d8/03aff3c75485fc999e260946ef1e9adf17640a6e08d7bf603d31cfcf73fc/pyobjc_framework_corewlan-11.1.tar.gz", hash = "sha256:4a8afea75393cc0a6fe696e136233aa0ed54266f35a47b55a3583f4cb078e6ce", size = 65792, upload-time = "2025-06-14T20:57:16.931Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/03/ba/e73152fc1beee1bf75489d4a6f89ebd9783340e50ca1948cde029d7b0411/pyobjc_framework_corewlan-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:e12f127b37a7ab8f349167332633392f2d6d29b87c9b98137a289d0fc1e07b5b", size = 9993, upload-time = "2025-06-14T20:48:41.081Z" }, { url = "https://files.pythonhosted.org/packages/09/8a/74feabaad1225eb2c44d043924ed8caea31683e6760cd9b918b8d965efea/pyobjc_framework_corewlan-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:7bd0775d2466ad500aad4747d8a889993db3a14240239f30ef53c087745e9c8e", size = 10016, upload-time = "2025-06-14T20:48:41.792Z" }, { url = "https://files.pythonhosted.org/packages/ef/12/792146e163aa4504bc7870c77c4ec2425f9a05fa615a2b5c9cbec89b0fc6/pyobjc_framework_corewlan-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:3c66643a97fcf3aa797fda997a3afc28d8d9bba9727dd5c0e68a313899d780f7", size = 10026, upload-time = "2025-06-14T20:48:42.626Z" }, { url = "https://files.pythonhosted.org/packages/d8/e8/e0bf4c66192e85fb92a3ae01b50e34f2283568f7a0e5548f52db81b8b146/pyobjc_framework_corewlan-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:6dc28264b56b18096c8869cce3f85e519fd27936f19524bb77458572ccfd7518", size = 10178, upload-time = "2025-06-14T20:48:43.309Z" }, @@ -4884,11 +5297,12 @@ name = "pyobjc-framework-cryptotokenkit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/eb/92/7fab6fcc6bb659d6946cfb2f670058180bcc4ca1626878b0f7c95107abf0/pyobjc_framework_cryptotokenkit-11.1.tar.gz", hash = "sha256:5f82f44d9ab466c715a7c8ad4d5ec47c68aacd78bd67b5466a7b8215a2265328", size = 59223, upload-time = "2025-06-14T20:57:17.658Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/eb/b6/783495dc440277a330930bac7b560cf54d5e1838fc30fdc3162722db8a62/pyobjc_framework_cryptotokenkit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:2b76fb928bc398091141dc52b26e02511065afd0b6de5533fa0e71ab13c51589", size = 12515, upload-time = "2025-06-14T20:48:47.346Z" }, { url = "https://files.pythonhosted.org/packages/76/f1/4cb9c90a55ec13301d60ac1c4d774c37b4ebc6db6331d3853021c933fcc8/pyobjc_framework_cryptotokenkit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:6384cb1d86fc586e2da934a5a37900825bd789e3a5df97517691de9af354af0c", size = 12543, upload-time = "2025-06-14T20:48:48.079Z" }, { url = "https://files.pythonhosted.org/packages/c6/c8/b64a56ed65719b1dfb9c06da0772d4a76eceb830672aab237df745bc31f7/pyobjc_framework_cryptotokenkit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:a55c0e57ab164aa5ce562e4d9e69026339067ecb4888638995690f1c43b79cfa", size = 12559, upload-time = "2025-06-14T20:48:49.115Z" }, { url = "https://files.pythonhosted.org/packages/9a/32/bb53ae388a99927fee626ba2746d3a6ec388cbc14b8f4ce91a35dd6b55e2/pyobjc_framework_cryptotokenkit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:cb3e1bd344e794cb98343171b5501a1a3b75548ef5385bda3d5ec613c0b98045", size = 12742, upload-time = "2025-06-14T20:48:49.837Z" }, @@ -4901,8 +5315,8 @@ name = "pyobjc-framework-datadetection" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/7d/4d/65c61d8878b44689e28d5729be9edbb73e20b1b0500d1095172cfd24aea6/pyobjc_framework_datadetection-11.1.tar.gz", hash = "sha256:cbe0080b51e09b2f91eaf2a9babec3dcf2883d7966bc0abd8393ef7abfcfc5db", size = 13485, upload-time = "2025-06-14T20:57:18.829Z" } wheels = [ @@ -4914,8 +5328,8 @@ name = "pyobjc-framework-devicecheck" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/f3/f2/b1d263f8231f815a9eeff15809f4b7428dacdc0a6aa267db5ed907445066/pyobjc_framework_devicecheck-11.1.tar.gz", hash = "sha256:8b05973eb2673571144d81346336e749a21cec90bd7fcaade76ffd3b147a0741", size = 13954, upload-time = "2025-06-14T20:57:19.782Z" } wheels = [ @@ -4927,8 +5341,8 @@ name = "pyobjc-framework-devicediscoveryextension" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/9a/b8/102863bfa2f1e414c88bb9f51151a9a58b99c268a841b59d46e0dcc5fe6d/pyobjc_framework_devicediscoveryextension-11.1.tar.gz", hash = "sha256:ae160ea40f25d3ee5e7ce80ac9c1b315f94d0a4c7ccb86920396f71c6bf799a0", size = 14298, upload-time = "2025-06-14T20:57:20.738Z" } wheels = [ @@ -4940,8 +5354,8 @@ name = "pyobjc-framework-dictionaryservices" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreservices", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-coreservices" }, ] sdist = { url = "https://files.pythonhosted.org/packages/d6/13/c46f6db61133fee15e3471f33a679da2af10d63fa2b4369e0cd476988721/pyobjc_framework_dictionaryservices-11.1.tar.gz", hash = "sha256:39c24452d0ddd037afeb73a1742614c94535f15b1c024a8a6cc7ff081e1d22e7", size = 10578, upload-time = "2025-06-14T20:57:21.392Z" } wheels = [ @@ -4953,11 +5367,12 @@ name = "pyobjc-framework-discrecording" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/a5/b2/d8d1a28643c2ab681b517647bacb68496c98886336ffbd274f0b2ad28cdc/pyobjc_framework_discrecording-11.1.tar.gz", hash = "sha256:37585458e363b20bb28acdb5cc265dfca934d8a07b7baed2584953c11c927a87", size = 123004, upload-time = "2025-06-14T20:57:22.01Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/a8/8c/0ff85cc34218e54236eb866e71c35e3308a661f50aea090d400e9121d9c4/pyobjc_framework_discrecording-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:dc8a7820fc193c2bfcd843c31de945dc45e77e5413089eabbc72be16a4f52e53", size = 14558, upload-time = "2025-06-14T20:48:58.495Z" }, { url = "https://files.pythonhosted.org/packages/5e/17/032fa44bb66b6a20c432f3311072f88478b42dcf39b21ebb6c3bbdf2954f/pyobjc_framework_discrecording-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:e29bc8c3741ae52fae092f892de856dbab2363e71537a8ae6fd026ecb88e2252", size = 14581, upload-time = "2025-06-14T20:48:59.228Z" }, { url = "https://files.pythonhosted.org/packages/55/d4/a9e2fa7aa38b4ecca9668b3ae9ae4244bf335974c42b46313c3ec631c73a/pyobjc_framework_discrecording-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:2d18158366d124852ad58291954611ebdcc43263a3bb75d7fd273408e67720e2", size = 14592, upload-time = "2025-06-14T20:49:00.002Z" }, { url = "https://files.pythonhosted.org/packages/5e/3c/660d06446b8e67121b755aeb20ba369234845675d25c658127e43fdbc835/pyobjc_framework_discrecording-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:b027eca3a0391196d4335fcbd50c03ef1e8f5ce095411ed51a081328b4945bf5", size = 14763, upload-time = "2025-06-14T20:49:00.742Z" }, @@ -4970,9 +5385,9 @@ name = "pyobjc-framework-discrecordingui" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-discrecording", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-discrecording" }, ] sdist = { url = "https://files.pythonhosted.org/packages/25/53/d71717f00332b8fc3d8a5c7234fdc270adadfeb5ca9318a55986f5c29c44/pyobjc_framework_discrecordingui-11.1.tar.gz", hash = "sha256:a9f10e2e7ee19582c77f0755ae11a64e3d61c652cbd8a5bf52756f599be24797", size = 19370, upload-time = "2025-06-14T20:57:22.791Z" } wheels = [ @@ -4984,8 +5399,8 @@ name = "pyobjc-framework-diskarbitration" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/da/2a/68fa0c99e04ec1ec24b0b7d6f5b7ec735d5e8a73277c5c0671438a69a403/pyobjc_framework_diskarbitration-11.1.tar.gz", hash = "sha256:a933efc6624779a393fafe0313e43378bcae2b85d6d15cff95ac30048c1ef490", size = 19866, upload-time = "2025-06-14T20:57:23.435Z" } wheels = [ @@ -4997,8 +5412,8 @@ name = "pyobjc-framework-dvdplayback" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/b8/76/77046325b1957f0cbcdf4f96667496d042ed4758f3413f1d21df5b085939/pyobjc_framework_dvdplayback-11.1.tar.gz", hash = "sha256:b44c36a62c8479e649133216e22941859407cca5796b5f778815ef9340a838f4", size = 64558, upload-time = "2025-06-14T20:57:24.118Z" } wheels = [ @@ -5010,8 +5425,8 @@ name = "pyobjc-framework-eventkit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/b4/c4/cbba8f2dce13b9be37ecfd423ba2b92aa3f209dbb58ede6c4ce3b242feee/pyobjc_framework_eventkit-11.1.tar.gz", hash = "sha256:5643150f584243681099c5e9435efa833a913e93fe9ca81f62007e287349b561", size = 75177, upload-time = "2025-06-14T20:57:24.81Z" } wheels = [ @@ -5023,8 +5438,8 @@ name = "pyobjc-framework-exceptionhandling" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/19/0d/c72a885b40d28a99b586447f9ea6f400589f13d554fcd6f13a2c841bb6d2/pyobjc_framework_exceptionhandling-11.1.tar.gz", hash = "sha256:e010f56bf60ab4e9e3225954ebb53e9d7135d37097043ac6dd2a3f35770d4efa", size = 17890, upload-time = "2025-06-14T20:57:25.521Z" } wheels = [ @@ -5036,8 +5451,8 @@ name = "pyobjc-framework-executionpolicy" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/0b/cf/54431846508c5d5bb114a415ebb96187da5847105918169e42f4ca3b00e6/pyobjc_framework_executionpolicy-11.1.tar.gz", hash = "sha256:3280ad2f4c5eaf45901f310cee0c52db940c0c63e959ad082efb8df41055d986", size = 13496, upload-time = "2025-06-14T20:57:26.173Z" } wheels = [ @@ -5049,11 +5464,12 @@ name = "pyobjc-framework-extensionkit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/ce/7d/89adf16c7de4246477714dce8fcffae4242778aecd0c5f0ad9904725f42c/pyobjc_framework_extensionkit-11.1.tar.gz", hash = "sha256:c114a96f13f586dbbab8b6219a92fa4829896a645c8cd15652a6215bc8ff5409", size = 19766, upload-time = "2025-06-14T20:57:27.106Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/0f/90/e6607b779756e039c0a4725a37cf70dc5b13c54a8cedbcf01ec1608866b1/pyobjc_framework_extensionkit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:61fd9f9758f95bcff2bf26fe475f679dfff9457d7130f114089e88fd5009675a", size = 7894, upload-time = "2025-06-14T20:49:10.593Z" }, { url = "https://files.pythonhosted.org/packages/90/2a/93105b5452d2ff680a47e38a3ec6f2a37164babd95e0ab976c07984366de/pyobjc_framework_extensionkit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:d505a64617c9db4373eb386664d62a82ba9ffc909bffad42cb4da8ca8e244c66", size = 7914, upload-time = "2025-06-14T20:49:11.842Z" }, { url = "https://files.pythonhosted.org/packages/b8/67/1dbd000d9d0c17d838c471dbb48229fca1ca18fad8453c19ecc01d3312a1/pyobjc_framework_extensionkit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:abbadbea5b18e4a6944c3c428753ee298a133cbf601c70e9586b14e3aebf649b", size = 7927, upload-time = "2025-06-14T20:49:12.542Z" }, { url = "https://files.pythonhosted.org/packages/fb/35/e5d1e633ad5b0c5163afd19ac0b02740e47a45de78d6f2599de3bc6542a5/pyobjc_framework_extensionkit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:5c2e203cb8134be1dd7df73d74c630adbaaf43d78eba04be451ea4f8bf582e22", size = 8069, upload-time = "2025-06-14T20:49:13.228Z" }, @@ -5066,11 +5482,12 @@ name = "pyobjc-framework-externalaccessory" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/d9/a3/519242e6822e1ddc9e64e21f717529079dbc28a353474420da8315d0a8b1/pyobjc_framework_externalaccessory-11.1.tar.gz", hash = "sha256:50887e948b78a1d94646422c243ac2a9e40761675e38b9184487870a31e83371", size = 23123, upload-time = "2025-06-14T20:57:27.845Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/63/54/d532badd43eba2db3fed2501b8e47a57cab233de2090ee97f4cff723e706/pyobjc_framework_externalaccessory-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:a2b22f72b83721d841e5a3128df29fc41d785597357c6bbce84555a2b51a1e9d", size = 8887, upload-time = "2025-06-14T20:49:17.703Z" }, { url = "https://files.pythonhosted.org/packages/7d/1b/e2def12aca9162b0fe0bbf0790d35595d46b2ef12603749c42af9234ffca/pyobjc_framework_externalaccessory-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:00caf75b959db5d14118d78c04085e2148255498839cdee735a0b9f6ef86b6a2", size = 8903, upload-time = "2025-06-14T20:49:18.393Z" }, { url = "https://files.pythonhosted.org/packages/b4/6f/1340c193c30ade7b0394b2c8f29f3e6dd501eb23a416a728cc9a23efaec2/pyobjc_framework_externalaccessory-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:50b796a4721db87863a28cd55668cb1547fcc28834afda2032e500cdab5b3d95", size = 8915, upload-time = "2025-06-14T20:49:19.076Z" }, { url = "https://files.pythonhosted.org/packages/ec/27/1617435d3827a544c2ed2660ecd2e317c82cc8e819a55daa491973349e58/pyobjc_framework_externalaccessory-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:569124b686569c48e3855fff128f438a2b46af06280eac2a516aaa214ad325de", size = 9080, upload-time = "2025-06-14T20:49:19.772Z" }, @@ -5083,11 +5500,12 @@ name = "pyobjc-framework-fileprovider" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/1b/80/3ebba2c1e5e3aeae989fe038c259a93e7e7e18fd56666ece514d000d38ea/pyobjc_framework_fileprovider-11.1.tar.gz", hash = "sha256:748ca1c75f84afdf5419346a24bf8eec44dca071986f31f00071dc191b3e9ca8", size = 91696, upload-time = "2025-06-14T20:57:28.546Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/d1/e4/c7b985d1199e3697ab5c3247027fe488b9d81b1fb597c34350942dc5838c/pyobjc_framework_fileprovider-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:888d6fb3fd625889ce0e409320c3379330473a386095cb4eda2b4caf0198ff66", size = 19546, upload-time = "2025-06-14T20:49:23.436Z" }, { url = "https://files.pythonhosted.org/packages/49/b2/859d733b0110e56511478ba837fd8a7ba43aa8f8c7e5231b9e3f0258bfbf/pyobjc_framework_fileprovider-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:ce6092dfe74c78c0b2abc03bfc18a0f5d8ddc624fc6a1d8dfef26d7796653072", size = 19622, upload-time = "2025-06-14T20:49:24.162Z" }, { url = "https://files.pythonhosted.org/packages/91/ed/ae5ce4a18752ea2da5d7238f7847119af8c7dc69ffd9fb1369414c9745d2/pyobjc_framework_fileprovider-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:9af41255df395a40a6e0b08c4410be5463f3ea91d8c9be61f6bd114252490ab2", size = 19627, upload-time = "2025-06-14T20:49:24.926Z" }, { url = "https://files.pythonhosted.org/packages/84/83/530daae946318689d29457da995577996de5965ff41b4b3b8b604617ff46/pyobjc_framework_fileprovider-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:d2720acdd582756ebda34418981e7646b7b85588b0b8fdafba7016eb657be6b8", size = 19859, upload-time = "2025-06-14T20:49:26.008Z" }, @@ -5100,8 +5518,8 @@ name = "pyobjc-framework-fileproviderui" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-fileprovider", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-fileprovider" }, ] sdist = { url = "https://files.pythonhosted.org/packages/75/ed/0f5af06869661822c4a70aacd674da5d1e6b6661240e2883bbc7142aa525/pyobjc_framework_fileproviderui-11.1.tar.gz", hash = "sha256:162a23e67f59e1bb247e84dda88d513d7944d815144901a46be6fe051b6c7970", size = 13163, upload-time = "2025-06-14T20:57:29.568Z" } wheels = [ @@ -5113,8 +5531,8 @@ name = "pyobjc-framework-findersync" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/2a/82/c6b670494ac0c4cf14cf2db0dfbe0df71925d20595404939383ddbcc56d3/pyobjc_framework_findersync-11.1.tar.gz", hash = "sha256:692364937f418f0e4e4abd395a09a7d4a0cdd55fd4e0184de85ee59642defb6e", size = 15045, upload-time = "2025-06-14T20:57:30.173Z" } wheels = [ @@ -5126,11 +5544,12 @@ name = "pyobjc-framework-fsevents" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/8e/83/ec0b9ba355dbc34f27ed748df9df4eb6dbfdd9bbd614b0f193752f36f419/pyobjc_framework_fsevents-11.1.tar.gz", hash = "sha256:d29157d04124503c4dfa9dcbbdc8c34d3bab134d3db3a48d96d93f26bd94c14d", size = 29587, upload-time = "2025-06-14T20:57:30.796Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/14/6a/25118832a128db99a53be4c45f473192f72923d9b9690785539cee1a9858/pyobjc_framework_fsevents-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:95cc5d839d298b8e95175fb72df8a8e1b08773fd2e0d031efe91eee23e0c8830", size = 13076, upload-time = "2025-06-14T20:49:32.269Z" }, { url = "https://files.pythonhosted.org/packages/13/c7/378d78e0fd956370f2b120b209117384b5b98925c6d8210a33fd73db4a15/pyobjc_framework_fsevents-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:8b51d120b8f12a1ca94e28cf74113bf2bfd4c5aee7035b452e895518f4df7630", size = 13147, upload-time = "2025-06-14T20:49:33.022Z" }, { url = "https://files.pythonhosted.org/packages/18/dc/3b7e75b9f8284257740679509b54f61da2a114cf805d7d3523053e4c6c19/pyobjc_framework_fsevents-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:fad5ada269f137afabd622b5fc04884c668ae1c7914a8791bab73b1d972f7713", size = 13164, upload-time = "2025-06-14T20:49:33.751Z" }, { url = "https://files.pythonhosted.org/packages/dd/53/07d62a8642bfddee43cd96301abeed97e858757d363423cf6e383d91f900/pyobjc_framework_fsevents-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:ff064cfa9d9cffb5d4ab476fb5091604568744d961c670aced037b2b6f0d0185", size = 13525, upload-time = "2025-06-14T20:49:34.492Z" }, @@ -5143,11 +5562,12 @@ name = "pyobjc-framework-fskit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/46/47/d1f04c6115fa78936399a389cc5e0e443f8341c9a6c1c0df7f6fdbe51286/pyobjc_framework_fskit-11.1.tar.gz", hash = "sha256:9ded1eab19b4183cb04381e554bbbe679c1213fd58599d6fc6e135e93b51136f", size = 42091, upload-time = "2025-06-14T20:57:31.504Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/16/76/1152bd8121ef2c9a0ccdf10624d647095ce944d34f654f001b458edef668/pyobjc_framework_fskit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:59a939ac8442d648f73a3da75923aa3637ac4693850d995f1914260c8f4f7947", size = 19922, upload-time = "2025-06-14T20:49:38.424Z" }, { url = "https://files.pythonhosted.org/packages/59/8f/db8f03688db77bfa4b78e89af1d89e910c5e877e94d58bdb3e93cc302e5d/pyobjc_framework_fskit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:1e50b8f949f1386fada73b408463c87eb81ef7fd0b3482bacf0c206a73723013", size = 19948, upload-time = "2025-06-14T20:49:39.18Z" }, { url = "https://files.pythonhosted.org/packages/7a/31/0dd6ad9dfce080d6e567326fe7243261740ef1090f72409322040f55a426/pyobjc_framework_fskit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:cc2390934a23b6407aa7802b11978374301444c3135835ad3373f7b4930c24eb", size = 19959, upload-time = "2025-06-14T20:49:39.941Z" }, { url = "https://files.pythonhosted.org/packages/96/ba/8655c5959e28fc8b1806a0e0c0b6a47b615de586990efc8ff82a344177a3/pyobjc_framework_fskit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:44fe7b6781c8fd0552b13ab3d0ec21176cd7cd685a8a61d712f9e4e42eb2f736", size = 20201, upload-time = "2025-06-14T20:49:40.715Z" }, @@ -5160,11 +5580,12 @@ name = "pyobjc-framework-gamecenter" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/1b/8e/b594fd1dc32a59462fc68ad502be2bd87c70e6359b4e879a99bcc4beaf5b/pyobjc_framework_gamecenter-11.1.tar.gz", hash = "sha256:a1c4ed54e11a6e4efba6f2a21ace92bcf186e3fe5c74a385b31f6b1a515ec20c", size = 31981, upload-time = "2025-06-14T20:57:32.192Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/21/a8/8d9c2d0ff9f42a0951063a9eaff1e39c46c15e89ce4e5e274114340ca976/pyobjc_framework_gamecenter-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:81abe136292ea157acb6c54871915fe6d386146a9386179ded0b974ac435045c", size = 18601, upload-time = "2025-06-14T20:49:44.946Z" }, { url = "https://files.pythonhosted.org/packages/99/52/0e56f21a6660a4f43882ec641b9e19b7ea92dc7474cec48cda1c9bed9c49/pyobjc_framework_gamecenter-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:779cdf8f52348be7f64d16e3ea37fd621d5ee933c032db3a22a8ccad46d69c59", size = 18634, upload-time = "2025-06-14T20:49:45.737Z" }, { url = "https://files.pythonhosted.org/packages/3e/fc/64a1e9dc4874a75ceed6e70bb07d5e2a3460283c7737e639a0408ec1b365/pyobjc_framework_gamecenter-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:6ff8905a5a7bfd86cb2b95671b452be0836f79db065b8d8b3bb2a1a5750ffd0d", size = 18638, upload-time = "2025-06-14T20:49:46.826Z" }, { url = "https://files.pythonhosted.org/packages/d5/0b/5a8559056ee1cd2fea7405d3843de900b410a14134c33eb112b9fa42201d/pyobjc_framework_gamecenter-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:a73ca7027b2b827e26075b46551fe42425d4a68985022baa4413329a3a2c16ff", size = 18920, upload-time = "2025-06-14T20:49:47.61Z" }, @@ -5177,11 +5598,12 @@ name = "pyobjc-framework-gamecontroller" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/70/4c/1dd62103092a182f2ab8904c8a8e3922d2b0a80a7adab0c20e5fd0207d75/pyobjc_framework_gamecontroller-11.1.tar.gz", hash = "sha256:4d5346faf90e1ebe5602c0c480afbf528a35a7a1ad05f9b49991fdd2a97f105b", size = 115783, upload-time = "2025-06-14T20:57:32.879Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/e5/8e/09e73e03e9f57e77df58cf77f6069d3455a3c388a890ff815e86d036ae39/pyobjc_framework_gamecontroller-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:782779f080508acf869187c0cbd3a48c55ee059d3a14fe89ccd6349537923214", size = 20825, upload-time = "2025-06-14T20:49:51.565Z" }, { url = "https://files.pythonhosted.org/packages/40/e3/e35bccb0284046ef716db4897b70d061b8b16c91fb2c434b1e782322ef56/pyobjc_framework_gamecontroller-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:d2cbc0c6c7d9c63e6b5b0b124d0c2bad01bb4b136f3cbc305f27d31f8aab6083", size = 20850, upload-time = "2025-06-14T20:49:52.401Z" }, { url = "https://files.pythonhosted.org/packages/ae/eb/42469724725f5d0f11c197aadbb0c5db1647ba69579df4e8d13f553bed1c/pyobjc_framework_gamecontroller-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:4866b25df05f583af06095e7103ddd2fbb2484b0ac2c78fd2cd825f995e524fa", size = 20862, upload-time = "2025-06-14T20:49:53.47Z" }, { url = "https://files.pythonhosted.org/packages/c3/43/7430884d24989c07e4e9394c905b02b3aedee7397960dd329a3c44e29c22/pyobjc_framework_gamecontroller-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:98f3f7afcbbe473a53537da42b2cdc0363df2647289eb66e8c762e4b46c23e73", size = 21108, upload-time = "2025-06-14T20:49:54.226Z" }, @@ -5194,12 +5616,13 @@ name = "pyobjc-framework-gamekit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/5b/7b/ba141ec0f85ca816f493d1f6fe68c72d01092e5562e53c470a0111d9c34b/pyobjc_framework_gamekit-11.1.tar.gz", hash = "sha256:9b8db075da8866c4ef039a165af227bc29393dc11a617a40671bf6b3975ae269", size = 165397, upload-time = "2025-06-14T20:57:33.711Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/b4/2a/f206682b9ff76983bae14a479a9c8a9098e58efc3db31f88211d6ad4fd42/pyobjc_framework_gamekit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:5e07c25eab051905c6bd46f368d8b341ef8603dce588ff6dbd82d609dd4fbf71", size = 21932, upload-time = "2025-06-14T20:49:58.154Z" }, { url = "https://files.pythonhosted.org/packages/1f/23/094e4fe38f2de029365604f0b7dffde7b0edfc57c3d388294c20ed663de2/pyobjc_framework_gamekit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:f945c7cfe53c4a349a03a1272f2736cc5cf88fe9e7a7a407abb03899635d860c", size = 21952, upload-time = "2025-06-14T20:49:58.933Z" }, { url = "https://files.pythonhosted.org/packages/22/2c/9a35fb83a1df7588e2e60488aa425058ee7f01b5a9d4947f74f62a130bf3/pyobjc_framework_gamekit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:8c7f2bf7ecf44ca678cfdf76f23b32d9c2d03006a0af9ad8e60d9114d6be640a", size = 21968, upload-time = "2025-06-14T20:49:59.688Z" }, { url = "https://files.pythonhosted.org/packages/7f/23/205eb0532238e79a56bab54820b0e39aedc546429e054dc12d55ca44bb23/pyobjc_framework_gamekit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:a7c8fce8a2c4614e3dd88b002540e67423e3efd41aa26d576db2de0fc61651b9", size = 22246, upload-time = "2025-06-14T20:50:00.462Z" }, @@ -5212,12 +5635,13 @@ name = "pyobjc-framework-gameplaykit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-spritekit", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-spritekit" }, ] sdist = { url = "https://files.pythonhosted.org/packages/e0/07/f38b1d83eac10ea4f75c605ffc4850585740db89b90842d311e586ee36cd/pyobjc_framework_gameplaykit-11.1.tar.gz", hash = "sha256:9ae2bee69b0cc1afa0e210b4663c7cdbb3cc94be1374808df06f98f992e83639", size = 73399, upload-time = "2025-06-14T20:57:34.538Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/0f/29/df66f53f887990878b2b00b1336e451a15e360a384be74559acf47854bc3/pyobjc_framework_gameplaykit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:ac9f50941988c30175149af481a49b2026c56a9a497c6dbf2974ffb50ffe0af8", size = 13065, upload-time = "2025-06-14T20:50:05.243Z" }, { url = "https://files.pythonhosted.org/packages/e7/f5/65bdbefb9de7cbc2edf0b1f76286736536e31c216cfac1a5f84ea15f0fc1/pyobjc_framework_gameplaykit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:0e4f34db8177b8b4d89fd22a2a882a6c9f6e50cb438ea2fbbf96845481bcd80d", size = 13091, upload-time = "2025-06-14T20:50:05.962Z" }, { url = "https://files.pythonhosted.org/packages/25/4c/011e20a8e9ff1270d3efb6c470c3cd8af10dcd2b05042721b1a777aca7a6/pyobjc_framework_gameplaykit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:78c513bc53bafd996d896f6f4535f2700b4916013417f8b41f47045790c6208d", size = 13109, upload-time = "2025-06-14T20:50:06.7Z" }, { url = "https://files.pythonhosted.org/packages/50/a1/31a50e79dfb9983b53220d0a1148a05544062829af76a20febfa2def0b41/pyobjc_framework_gameplaykit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:30e15e4e8df9b1c0ca92bfabf79f6b12a286e544e67762b14dd3023c53e41978", size = 13316, upload-time = "2025-06-14T20:50:07.431Z" }, @@ -5230,11 +5654,12 @@ name = "pyobjc-framework-healthkit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/af/66/fa76f7c8e36e4c10677d42d91a8e220c135c610a06b759571db1abe26a32/pyobjc_framework_healthkit-11.1.tar.gz", hash = "sha256:20f59bd9e1ffafe5893b4eff5867fdfd20bd46c3d03bc4009219d82fc6815f76", size = 202009, upload-time = "2025-06-14T20:57:35.285Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/70/aa/c337d27dd98ffcbba2b1200126fcf624d1ccbeb7a4ed9205d48bfe2c1ca8/pyobjc_framework_healthkit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:34bce3d144c461af7e577fcf6bbb7739d0537bf42f081960122923a7ef2e06c0", size = 20301, upload-time = "2025-06-14T20:50:12.158Z" }, { url = "https://files.pythonhosted.org/packages/c7/08/12fca070ad2dc0b9c311df209b9b6d275ee192cb5ccbc94616d9ddd80d88/pyobjc_framework_healthkit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:ab4350f9fe65909107dd7992b367a6c8aac7dc31ed3d5b52eeb2310367d0eb0b", size = 20311, upload-time = "2025-06-14T20:50:13.271Z" }, { url = "https://files.pythonhosted.org/packages/5d/26/0337f1b4607a3a13a671a6b07468726943e0d28a462998fcd902f7df6fbf/pyobjc_framework_healthkit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:8b6c739e17362897f0b1ba4aa4dc395b3d0c3855b87423eaeb6a89f910adc43f", size = 20330, upload-time = "2025-06-14T20:50:14.042Z" }, { url = "https://files.pythonhosted.org/packages/f4/da/8681afc37504797f747c45be6780f2ef12b9c2a7703cda8f8cf9e48918ca/pyobjc_framework_healthkit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:2d1b76b04e9e33ac9441cafa695766938eac04f8c8c69f7efd93a6aceb6eca40", size = 20502, upload-time = "2025-06-14T20:50:14.788Z" }, @@ -5247,11 +5672,12 @@ name = "pyobjc-framework-imagecapturecore" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/7b/3b/f4edbc58a8c7394393f8d00d0e764f655545e743ee4e33917f27b8c68e7b/pyobjc_framework_imagecapturecore-11.1.tar.gz", hash = "sha256:a610ceb6726e385b132a1481a68ce85ccf56f94667b6d6e1c45a2cfab806a624", size = 100398, upload-time = "2025-06-14T20:57:36.503Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/50/72/465741d33757ef2162a1c9e12d6c8a41b5490949a92431c42a139c132303/pyobjc_framework_imagecapturecore-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:ede4c15da909a4d819c732a5554b8282a7b56a1b73d82aef908124147921945a", size = 15999, upload-time = "2025-06-14T20:50:18.742Z" }, { url = "https://files.pythonhosted.org/packages/61/62/54ed61e7cd3213549c8e98ca87a6b21afbb428d2c41948ae48ea019bf973/pyobjc_framework_imagecapturecore-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:ed296c23d3d8d1d9af96a6486d09fb8d294cc318e4a2152e6f134151c76065f8", size = 16021, upload-time = "2025-06-14T20:50:19.836Z" }, { url = "https://files.pythonhosted.org/packages/4e/91/71d48ec1b29d57112edd33ada86fcdbf1c9423ef2bdddadf8d37e8a03492/pyobjc_framework_imagecapturecore-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:ded8dc6a8c826a6ae1b6a6d0a31542bd1eb85345f86201689c54e51193b572dc", size = 16030, upload-time = "2025-06-14T20:50:20.568Z" }, { url = "https://files.pythonhosted.org/packages/c7/9d/7452fecf9b362b7a384b44256ca388b3e99905376e6f594565f2b2be0761/pyobjc_framework_imagecapturecore-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:254ae4502d651526c500533b8e2aee77ae7939f9acfd7d706dba2d464417deba", size = 16234, upload-time = "2025-06-14T20:50:21.341Z" }, @@ -5264,11 +5690,12 @@ name = "pyobjc-framework-inputmethodkit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/02/32/6a90bba682a31960ba1fc2d3b263e9be26043c4fb7aed273c13647c8b7d9/pyobjc_framework_inputmethodkit-11.1.tar.gz", hash = "sha256:7037579524041dcee71a649293c2660f9359800455a15e6a2f74a17b46d78496", size = 27203, upload-time = "2025-06-14T20:57:37.246Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/7f/23/a4226040eec8ed930c81073776064f30d627db03e9db5b24720aad8fd14d/pyobjc_framework_inputmethodkit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:9b0e47c3bc7f1e628c906436c1735041ed2e9aa7cba3f70084b6311c63c508be", size = 9480, upload-time = "2025-06-14T20:50:25.184Z" }, { url = "https://files.pythonhosted.org/packages/a8/0d/8a570072096fe339702e4ae9d98e59ee7c6c14124d4437c9a8c4482dda6d/pyobjc_framework_inputmethodkit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:dd0c591a9d26967018a781fa4638470147ef2a9af3ab4a28612f147573eeefba", size = 9489, upload-time = "2025-06-14T20:50:25.875Z" }, { url = "https://files.pythonhosted.org/packages/dc/a5/ce000bba1a52287c21d1d3aff6779a6bbb463da4337573cb17ecc9475939/pyobjc_framework_inputmethodkit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:5095005809a4108f362998b46994f99b5a57f9ba367c01141c1b9eaea311bc5b", size = 9508, upload-time = "2025-06-14T20:50:26.577Z" }, { url = "https://files.pythonhosted.org/packages/56/ad/bbdc9f4b91420a4d3cf0b633d1991d4ffb7bdeb78d01fa265bbd43fef929/pyobjc_framework_inputmethodkit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:013919a4d766a7e66045fa5dd5d819bfa0450ccb59baba2b89d7449bce637d6b", size = 9667, upload-time = "2025-06-14T20:50:27.617Z" }, @@ -5281,8 +5708,8 @@ name = "pyobjc-framework-installerplugins" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/4d/89/9a881e466476ca21f3ff3e8e87ccfba1aaad9b88f7eea4be6d3f05b07107/pyobjc_framework_installerplugins-11.1.tar.gz", hash = "sha256:363e59c7e05553d881f0facd41884f17b489ff443d7856e33dd0312064c746d9", size = 27451, upload-time = "2025-06-14T20:57:37.915Z" } wheels = [ @@ -5294,9 +5721,9 @@ name = "pyobjc-framework-instantmessage" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/9f/b9/5cec4dd0053b5f63c01211a60a286c47464d9f3e0c81bd682e6542dbff00/pyobjc_framework_instantmessage-11.1.tar.gz", hash = "sha256:c222aa61eb009704b333f6e63df01a0e690136e7e495907e5396882779bf9525", size = 33774, upload-time = "2025-06-14T20:57:38.553Z" } wheels = [ @@ -5308,11 +5735,12 @@ name = "pyobjc-framework-intents" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/4c/af/d7f260d06b79acca8028e373c2fe30bf0be014388ba612f538f40597d929/pyobjc_framework_intents-11.1.tar.gz", hash = "sha256:13185f206493f45d6bd2d4903c2136b1c4f8b9aa37628309ace6ff4a906b4695", size = 448459, upload-time = "2025-06-14T20:57:39.589Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/c5/1d/10fdbf3b8dd6451465ae147143ba3159397a50ff81aed1eb86c153e987b5/pyobjc_framework_intents-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:da2f11ee64c75cfbebb1c2be52a20b3618f32b6c47863809ff64c61e8a1dffb9", size = 32227, upload-time = "2025-06-14T20:50:34.303Z" }, { url = "https://files.pythonhosted.org/packages/8a/37/e6fa5737da42fb1265041bd3bd4f2be96f09294018fabf07139dd9dbc7b9/pyobjc_framework_intents-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:a663e2de1b7ae7b547de013f89773963f8180023e36f2cebfe8060395dc34c33", size = 32253, upload-time = "2025-06-14T20:50:35.028Z" }, { url = "https://files.pythonhosted.org/packages/f0/ff/f793a0c4b5ea87af3fc228d74e457c1594695b2745b3007a8ef4832ebeb7/pyobjc_framework_intents-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:9e21b3bc33de2d5f69b5c1d581e5c724a08686fe84ec324a4be365bef769e482", size = 32266, upload-time = "2025-06-14T20:50:35.775Z" }, { url = "https://files.pythonhosted.org/packages/52/e9/2725ae5f990faa7d7909e6ac14d14034d1e70028080ed602a03aa715b4bc/pyobjc_framework_intents-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:e008d542abe38fd374c9ada7c833ad6e34a2db92b4dcbfba0a59ff830b9093bc", size = 32499, upload-time = "2025-06-14T20:50:36.531Z" }, @@ -5325,11 +5753,12 @@ name = "pyobjc-framework-intentsui" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-intents", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-intents" }, ] sdist = { url = "https://files.pythonhosted.org/packages/86/46/20aae4a71efb514b096f36273a6129b48b01535bf501e5719d4a97fcb3a5/pyobjc_framework_intentsui-11.1.tar.gz", hash = "sha256:c8182155af4dce369c18d6e6ed9c25bbd8110c161ed5f1b4fb77cf5cdb99d135", size = 21305, upload-time = "2025-06-14T20:57:40.477Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/31/e3/db74fc161bb85bc442dfddf50321924613b67cf49288e2a8b335bf6d546a/pyobjc_framework_intentsui-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:252f7833fabb036cd56d59b445922b25cda1561b54c0989702618a5561d8e748", size = 8936, upload-time = "2025-06-14T20:50:40.522Z" }, { url = "https://files.pythonhosted.org/packages/43/7c/77fbd2a6f85eb905fbf27ba7540eaf2a026771ed5100fb1c01143cf47e9b/pyobjc_framework_intentsui-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:99a3ae40eb2a6ef1125955dd513c8acc88ce7d8d90130a8cdeaec8336e6fbec5", size = 8965, upload-time = "2025-06-14T20:50:41.281Z" }, { url = "https://files.pythonhosted.org/packages/9b/d6/ce8e2f6354bd77271b8f9f2a05920fb0a6de57ab5d97033021672853acb5/pyobjc_framework_intentsui-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:154fd92112184e8ef29ce81e685c377422dffcff4f7900ea6e5956a0e2be2268", size = 8983, upload-time = "2025-06-14T20:50:41.96Z" }, { url = "https://files.pythonhosted.org/packages/e1/2b/562785a91c30eccd3eea28ea02b31a029e04ecc5e994da7cd60205baf250/pyobjc_framework_intentsui-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:6d7d5402c05840a45047cf905fa550c2898cf5580cdee00a36bd35dd624c7542", size = 9154, upload-time = "2025-06-14T20:50:42.651Z" }, @@ -5342,11 +5771,12 @@ name = "pyobjc-framework-iobluetooth" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/93/e0/74b7b10c567b66c5f38b45ab240336325a4c889f43072d90f2b90aaeb7c0/pyobjc_framework_iobluetooth-11.1.tar.gz", hash = "sha256:094fd4be60cd1371b17cb4b33a3894e0d88a11b36683912be0540a7d51de76f1", size = 300992, upload-time = "2025-06-14T20:57:41.256Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/0a/13/31a514e48bd54880aadb1aac3a042fca5f499780628c18f4f54f06d4ece2/pyobjc_framework_iobluetooth-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:7d8858cf2e4b2ef5e8bf29b76c06d4f2e6a2264c325146d07dfab94c46633329", size = 40378, upload-time = "2025-06-14T20:50:46.298Z" }, { url = "https://files.pythonhosted.org/packages/da/94/eef57045762e955795a4e3312674045c52f8c506133acf9efe1b3370b93f/pyobjc_framework_iobluetooth-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:883781e7223cb0c63fab029d640721ded747f2e2b067645bc8b695ef02a4a4dd", size = 40406, upload-time = "2025-06-14T20:50:47.101Z" }, { url = "https://files.pythonhosted.org/packages/ed/f5/24476d6919c2d8d849c88740e81f620663181b3c97ac6e3aaeb1833277a5/pyobjc_framework_iobluetooth-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:4a8b1caba9ac51435f64a6cf9c1a2be867603161af8bebdd1676072ebed2fed9", size = 40428, upload-time = "2025-06-14T20:50:47.85Z" }, { url = "https://files.pythonhosted.org/packages/57/b6/ced1b076a86ea3d7a685155e8c61ab9ecf8037d2b5401d4aae65014789b3/pyobjc_framework_iobluetooth-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:2c99ade82a79263ea71c51d430696a2ad155beb01a67df59d52be63e181e0482", size = 40626, upload-time = "2025-06-14T20:50:48.655Z" }, @@ -5359,8 +5789,8 @@ name = "pyobjc-framework-iobluetoothui" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-iobluetooth", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-iobluetooth" }, ] sdist = { url = "https://files.pythonhosted.org/packages/dd/32/872272faeab6fe471eac6962c75db72ce65c3556e00b4edebdb41aaab7cb/pyobjc_framework_iobluetoothui-11.1.tar.gz", hash = "sha256:060c721f1cd8af4452493e8153b72b572edcd2a7e3b635d79d844f885afee860", size = 22835, upload-time = "2025-06-14T20:57:42.119Z" } wheels = [ @@ -5372,8 +5802,8 @@ name = "pyobjc-framework-iosurface" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/c5/ce/38ec17d860d0ee040bb737aad8ca7c7ff46bef6c9cffa47382d67682bb2d/pyobjc_framework_iosurface-11.1.tar.gz", hash = "sha256:a468b3a31e8cd70a2675a3ddc7176ab13aa521c035f11188b7a3af8fff8b148b", size = 20275, upload-time = "2025-06-14T20:57:42.742Z" } wheels = [ @@ -5385,8 +5815,8 @@ name = "pyobjc-framework-ituneslibrary" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/ee/43/aebefed774b434965752f9001685af0b19c02353aa7a12d2918af0948181/pyobjc_framework_ituneslibrary-11.1.tar.gz", hash = "sha256:e2212a9340e4328056ade3c2f9d4305c71f3f6af050204a135f9fa9aa3ba9c5e", size = 47388, upload-time = "2025-06-14T20:57:43.383Z" } wheels = [ @@ -5398,8 +5828,8 @@ name = "pyobjc-framework-kernelmanagement" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/1a/b6/708f10ac16425834cb5f8b71efdbe39b42c3b1009ac0c1796a42fc98cd36/pyobjc_framework_kernelmanagement-11.1.tar.gz", hash = "sha256:e934d1638cd89e38d6c6c5d4d9901b4295acee2d39cbfe0bd91aae9832961b44", size = 12543, upload-time = "2025-06-14T20:57:44.046Z" } wheels = [ @@ -5411,8 +5841,8 @@ name = "pyobjc-framework-latentsemanticmapping" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/db/8a/4e54ee2bc77d59d770b287daf73b629e2715a2b3b31264d164398131cbad/pyobjc_framework_latentsemanticmapping-11.1.tar.gz", hash = "sha256:c6c3142301e4d375c24a47dfaeebc2f3d0fc33128a1c0a755794865b9a371145", size = 17444, upload-time = "2025-06-14T20:57:44.643Z" } wheels = [ @@ -5424,8 +5854,8 @@ name = "pyobjc-framework-launchservices" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreservices", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-coreservices" }, ] sdist = { url = "https://files.pythonhosted.org/packages/2b/0a/a76b13109b8ab563fdb2d7182ca79515f132f82ac6e1c52351a6b02896a8/pyobjc_framework_launchservices-11.1.tar.gz", hash = "sha256:80b55368b1e208d6c2c58395cc7bc12a630a2a402e00e4930493e9bace22b7bb", size = 20446, upload-time = "2025-06-14T20:57:45.258Z" } wheels = [ @@ -5437,11 +5867,12 @@ name = "pyobjc-framework-libdispatch" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/be/89/7830c293ba71feb086cb1551455757f26a7e2abd12f360d375aae32a4d7d/pyobjc_framework_libdispatch-11.1.tar.gz", hash = "sha256:11a704e50a0b7dbfb01552b7d686473ffa63b5254100fdb271a1fe368dd08e87", size = 53942, upload-time = "2025-06-14T20:57:45.903Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/b0/cd/1010dee9f932a9686c27ce2e45e91d5b6875f5f18d2daafadea70090e111/pyobjc_framework_libdispatch-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:2ddca472c2cbc6bb192e05b8b501d528ce49333abe7ef0eef28df3133a8e18b7", size = 20441, upload-time = "2025-06-14T20:50:58.3Z" }, { url = "https://files.pythonhosted.org/packages/ac/92/ff9ceb14e1604193dcdb50643f2578e1010c68556711cd1a00eb25489c2b/pyobjc_framework_libdispatch-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:dc9a7b8c2e8a63789b7cf69563bb7247bde15353208ef1353fff0af61b281684", size = 15627, upload-time = "2025-06-14T20:50:59.055Z" }, { url = "https://files.pythonhosted.org/packages/0f/10/5851b68cd85b475ff1da08e908693819fd9a4ff07c079da9b0b6dbdaca9c/pyobjc_framework_libdispatch-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:c4e219849f5426745eb429f3aee58342a59f81e3144b37aa20e81dacc6177de1", size = 15648, upload-time = "2025-06-14T20:50:59.809Z" }, { url = "https://files.pythonhosted.org/packages/1b/79/f905f22b976e222a50d49e85fbd7f32d97e8790dd80a55f3f0c305305c32/pyobjc_framework_libdispatch-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:a9357736cb47b4a789f59f8fab9b0d10b0a9c84f9876367c398718d3de085888", size = 15912, upload-time = "2025-06-14T20:51:00.572Z" }, @@ -5454,11 +5885,12 @@ name = "pyobjc-framework-libxpc" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/6a/c9/7e15e38ac23f5bfb4e82bdf3b7ef88e2f56a8b4ad884009bc2d5267d2e1f/pyobjc_framework_libxpc-11.1.tar.gz", hash = "sha256:8fd7468aa520ff19915f6d793070b84be1498cb87224bee2bad1f01d8375273a", size = 49135, upload-time = "2025-06-14T20:57:46.59Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/39/01/f5fbc7627f838aea5960f3287b75cbda9233f76fc3ba82f088630d5d16cc/pyobjc_framework_libxpc-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:4ec8a7df24d85a561fc21d0eb0db89e8cddefeedec71c69bccf17f99804068ed", size = 19466, upload-time = "2025-06-14T20:51:05.138Z" }, { url = "https://files.pythonhosted.org/packages/be/8f/dfd8e1e1e461f857a1e50138e69b17c0e62a8dcaf7dea791cc158d2bf854/pyobjc_framework_libxpc-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:c29b2df8d74ff6f489afa7c39f7c848c5f3d0531a6bbe704571782ee6c820084", size = 19573, upload-time = "2025-06-14T20:51:05.902Z" }, { url = "https://files.pythonhosted.org/packages/00/fa/9ac86892294428a0eb532242a6fcbec565d0cf0e919924b6b7c064c8b196/pyobjc_framework_libxpc-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:6862e63f565823d4eeb56f18f90a3ee8682c52a8d4bcd486d3535c9959464eda", size = 19578, upload-time = "2025-06-14T20:51:06.659Z" }, { url = "https://files.pythonhosted.org/packages/44/2c/0b0bdc7847adf6ed653e846a98685346f70b1aaa187e37ddff2641cc54e2/pyobjc_framework_libxpc-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:2df539d11b65e229f8436a3660d0d1dce2cc7ba571054c5b91350b836db22576", size = 20167, upload-time = "2025-06-14T20:51:07.423Z" }, @@ -5471,9 +5903,9 @@ name = "pyobjc-framework-linkpresentation" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/b9/76/22873be73f12a3a11ae57af13167a1d2379e4e7eef584de137156a00f5ef/pyobjc_framework_linkpresentation-11.1.tar.gz", hash = "sha256:a785f393b01fdaada6d7d6d8de46b7173babba205b13b44f1dc884b3695c2fc9", size = 14987, upload-time = "2025-06-14T20:57:47.277Z" } wheels = [ @@ -5485,12 +5917,13 @@ name = "pyobjc-framework-localauthentication" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-security", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-security" }, ] sdist = { url = "https://files.pythonhosted.org/packages/e5/27/9e3195f3561574140e9b9071a36f7e0ebd18f50ade9261d23b5b9df8fccd/pyobjc_framework_localauthentication-11.1.tar.gz", hash = "sha256:3cd48907c794bd414ac68b8ac595d83c7e1453b63fc2cfc2d2035b690d31eaa1", size = 40700, upload-time = "2025-06-14T20:57:47.931Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/4e/9a/acc10d45041445db99a121950b0d4f4ff977dbe5e95ec154fe2e1740ff08/pyobjc_framework_localauthentication-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:1b6d52d07abd2240f7bc02b01ea1c630c280ed3fbc3fabe1e43b7444cfd41788", size = 10707, upload-time = "2025-06-14T20:51:12.436Z" }, { url = "https://files.pythonhosted.org/packages/91/db/59f118cc2658814c6b501b7360ca4fe6a82fd289ced5897b99787130ceef/pyobjc_framework_localauthentication-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:aa3815f936612d78e51b53beed9115c57ae2fd49500bb52c4030a35856e6569e", size = 10730, upload-time = "2025-06-14T20:51:13.487Z" }, { url = "https://files.pythonhosted.org/packages/9f/8b/544cadc6ecf75def347e96cdae4caa955bc23f2bc314779cffe1e6ba9475/pyobjc_framework_localauthentication-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:9c9446c017b13c8dcadf485b76ab1d7bc12099b504bf5c2df1aae33b5dc4ab2c", size = 10748, upload-time = "2025-06-14T20:51:14.198Z" }, { url = "https://files.pythonhosted.org/packages/44/f9/4095b2caa4453971bd790b6aeda05967c22743e1f80e5bf6cb63ec419288/pyobjc_framework_localauthentication-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:d5a2e1ea2fe8233dc244f6029d5d0c878102b2e0615cb4b81b2f30d9ee101fca", size = 10896, upload-time = "2025-06-14T20:51:14.892Z" }, @@ -5503,9 +5936,9 @@ name = "pyobjc-framework-localauthenticationembeddedui" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-localauthentication", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-localauthentication" }, ] sdist = { url = "https://files.pythonhosted.org/packages/29/7b/08c1e52487b07e9aee4c24a78f7c82a46695fa883113e3eece40f8e32d40/pyobjc_framework_localauthenticationembeddedui-11.1.tar.gz", hash = "sha256:22baf3aae606e5204e194f02bb205f244e27841ea7b4a4431303955475b4fa56", size = 14076, upload-time = "2025-06-14T20:57:48.557Z" } wheels = [ @@ -5517,8 +5950,8 @@ name = "pyobjc-framework-mailkit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/7e/7e/f22d733897e7618bd70a658b0353f5f897c583df04e7c5a2d68b99d43fbb/pyobjc_framework_mailkit-11.1.tar.gz", hash = "sha256:bf97dc44cb09b9eb9d591660dc0a41f077699976144b954caa4b9f0479211fd7", size = 32012, upload-time = "2025-06-14T20:57:49.173Z" } wheels = [ @@ -5530,13 +5963,14 @@ name = "pyobjc-framework-mapkit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-corelocation", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-corelocation" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/57/f0/505e074f49c783f2e65ca82174fd2d4348568f3f7281c1b81af816cf83bb/pyobjc_framework_mapkit-11.1.tar.gz", hash = "sha256:f3a5016f266091be313a118a42c0ea4f951c399b5259d93639eb643dacc626f1", size = 165614, upload-time = "2025-06-14T20:57:50.362Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/a0/dc/a7e03a9066e6eed9d1707ae45453a5332057950e16de6665402c804ae7af/pyobjc_framework_mapkit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:daee6bedc3acc23e62d1e7c3ab97e10425ca57e0c3cc47d2b212254705cc5c44", size = 22481, upload-time = "2025-06-14T20:51:20.694Z" }, { url = "https://files.pythonhosted.org/packages/30/0a/50aa2fba57499ff657cacb9ef1730006442e4f42d9a822dae46239603ecc/pyobjc_framework_mapkit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:91976c6dbc8cbb020e059a0ccdeab8933184712f77164dbad5a5526c1a49599d", size = 22515, upload-time = "2025-06-14T20:51:21.439Z" }, { url = "https://files.pythonhosted.org/packages/78/54/792f4d5848176753bfde8f10ac21b663981adf940243765edad45908cd55/pyobjc_framework_mapkit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:0b6fa1c4fffc3ae91adb965731a0cc943b3b6e82c8f21919a53a68b43a67b534", size = 22534, upload-time = "2025-06-14T20:51:22.199Z" }, { url = "https://files.pythonhosted.org/packages/07/0c/fd03986fc74c5e523e5ba824d3b4f0fd1f4a52720f28da93499787960317/pyobjc_framework_mapkit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:1dc27d315849ac96647d13c82eeefce5d1d2db8c64767ce10bd3e77cbaad2291", size = 22759, upload-time = "2025-06-14T20:51:23.269Z" }, @@ -5549,8 +5983,8 @@ name = "pyobjc-framework-mediaaccessibility" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/8d/81/60412b423c121de0fa0aa3ef679825e1e2fe8b00fceddec7d72333ef564b/pyobjc_framework_mediaaccessibility-11.1.tar.gz", hash = "sha256:52479a998fec3d079d2d4590a945fc78c41fe7ac8c76f1964c9d8156880565a4", size = 18440, upload-time = "2025-06-14T20:57:51.126Z" } wheels = [ @@ -5562,13 +5996,14 @@ name = "pyobjc-framework-mediaextension" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-avfoundation", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremedia", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-avfoundation" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coremedia" }, ] sdist = { url = "https://files.pythonhosted.org/packages/e1/09/fd214dc0cf3f3bc3f528815af4799c0cb7b4bf4032703b19ea63486a132b/pyobjc_framework_mediaextension-11.1.tar.gz", hash = "sha256:85a1c8a94e9175fb364c453066ef99b95752343fd113f08a3805cad56e2fa709", size = 58489, upload-time = "2025-06-14T20:57:51.796Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/ec/25/95315f730e9b73ef9e8936ed3ded636d3ac71b4d5653d4caf1d20a2314a8/pyobjc_framework_mediaextension-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:915c0cbb04913beb1f1ac8939dc0e615da8ddfba3927863a476af49f193415c5", size = 38858, upload-time = "2025-06-14T20:51:28.296Z" }, { url = "https://files.pythonhosted.org/packages/56/78/2c2d8265851f6060dbf4434c21bd67bf569b8c3071ba1f257e43aae563a8/pyobjc_framework_mediaextension-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:06cb19004413a4b08dd75cf1e5dadea7f2df8d15feeeb7adb529d0cf947fa789", size = 38859, upload-time = "2025-06-14T20:51:29.102Z" }, { url = "https://files.pythonhosted.org/packages/e7/6b/1d3761316ca7df57700a68b28f7c00cc4f050b3f6debac2305219506d6b1/pyobjc_framework_mediaextension-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:40f1440ccc8da6deb80810866f8c807c17567db67b53e1576ea3a3b1330c85f9", size = 38870, upload-time = "2025-06-14T20:51:29.862Z" }, { url = "https://files.pythonhosted.org/packages/15/e3/48f4ba724e31cb7adeaf5f9198ad5ab9cab45bcfc358b8af5759d8f79971/pyobjc_framework_mediaextension-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:29edab42d9ecd394ac26f2ae2dfd7e2118452fc60a5623843919c1e9659c9dbc", size = 39104, upload-time = "2025-06-14T20:51:30.956Z" }, @@ -5581,9 +6016,9 @@ name = "pyobjc-framework-medialibrary" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/2b/06/11ff622fb5fbdd557998a45cedd2b0a1c7ea5cc6c5cb015dd6e42ebd1c41/pyobjc_framework_medialibrary-11.1.tar.gz", hash = "sha256:102f4326f789734b7b2dfe689abd3840ca75a76fb8058bd3e4f85398ae2ce29d", size = 18706, upload-time = "2025-06-14T20:57:52.474Z" } wheels = [ @@ -5595,8 +6030,8 @@ name = "pyobjc-framework-mediaplayer" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-avfoundation", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-avfoundation" }, ] sdist = { url = "https://files.pythonhosted.org/packages/80/d5/daba26eb8c70af1f3823acfd7925356acc4dd75eeac4fc86dc95d94d0e15/pyobjc_framework_mediaplayer-11.1.tar.gz", hash = "sha256:d07a634b98e1b9eedd82d76f35e616525da096bd341051ea74f0971e0f2f2ddd", size = 93749, upload-time = "2025-06-14T20:57:53.165Z" } wheels = [ @@ -5608,11 +6043,12 @@ name = "pyobjc-framework-mediatoolbox" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/e1/68/cc230d2dfdeb974fdcfa828de655a43ce2bf4962023fd55bbb7ab0970100/pyobjc_framework_mediatoolbox-11.1.tar.gz", hash = "sha256:97834addc5179b3165c0d8cd74cc97ad43ed4c89547724216426348aca3b822a", size = 23568, upload-time = "2025-06-14T20:57:53.913Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/99/bc/6b69ca3c2bf1573b907be460c6a413ff2dfd1c037da53f46aec3bcdb3c73/pyobjc_framework_mediatoolbox-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:da60c0409b18dfb9fa60a60589881e1382c007700b99722926270feadcf3bfc1", size = 12630, upload-time = "2025-06-14T20:51:36.873Z" }, { url = "https://files.pythonhosted.org/packages/b5/23/6b5d999e1e71c42d5d116d992515955ac1bbc5cf4890072bb26f38eb9802/pyobjc_framework_mediatoolbox-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:2867c91645a335ee29b47e9c0e9fd3ea8c9daad0c0719c50b8bf244d76998056", size = 12785, upload-time = "2025-06-14T20:51:37.593Z" }, { url = "https://files.pythonhosted.org/packages/29/05/24d60869a816418771653057720727d6df2dd8485302a21f80cfcb694110/pyobjc_framework_mediatoolbox-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:bf26348d20caef38efb9cfc02d28af83c930b2f2c9581407f8ec04b3d8321a7a", size = 12794, upload-time = "2025-06-14T20:51:38.278Z" }, { url = "https://files.pythonhosted.org/packages/37/c5/7b2950c22187c1a2e4f492684c34dd0cd230b8be4c7749e4b223b7769def/pyobjc_framework_mediatoolbox-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:975de470af8e52104bd1548eb9b4b0ef98524f35a6263c0bb4182797b9c5975b", size = 13394, upload-time = "2025-06-14T20:51:39.001Z" }, @@ -5625,11 +6061,12 @@ name = "pyobjc-framework-metal" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/af/cf/29fea96fd49bf72946c5dac4c43ef50f26c15e9f76edd6f15580d556aa23/pyobjc_framework_metal-11.1.tar.gz", hash = "sha256:f9fd3b7574a824632ee9b7602973da30f172d2b575dd0c0f5ef76b44cfe9f6f9", size = 446549, upload-time = "2025-06-14T20:57:54.731Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/e9/e8/cd0621e246dc0dc06f55c50af3002573ad19208e30f6806ec997ac587886/pyobjc_framework_metal-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:157a0052be459ffb35a3687f77a96ea87b42caf4cdd0b9f7245242b100edb4f0", size = 58066, upload-time = "2025-06-14T20:51:44.243Z" }, { url = "https://files.pythonhosted.org/packages/4c/94/3d5a8bed000dec4a13e72dde175898b488192716b7256a05cc253c77020d/pyobjc_framework_metal-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:1f3aae0f9a4192a7f4f158dbee126ab5ef63a81bf9165ec63bc50c353c8d0e6f", size = 57969, upload-time = "2025-06-14T20:51:45.051Z" }, { url = "https://files.pythonhosted.org/packages/4f/af/b1f78770bb4b8d73d7a70140e39ca92daa2ba6b8de93d52b2ebf9db7d03e/pyobjc_framework_metal-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:d9b24d0ddb98b34a9a19755e5ca507c62fcef40ee5eae017e39be29650137f8c", size = 57994, upload-time = "2025-06-14T20:51:46.209Z" }, { url = "https://files.pythonhosted.org/packages/97/93/e680c0ece0e21cb20bc5d0504acd96ca6828fc766b8ed624d69230c1796d/pyobjc_framework_metal-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:de71b46062cb533be2c025cd6018fd4db9d7fd6a65bd67131d8e484c3616321a", size = 58381, upload-time = "2025-06-14T20:51:47.016Z" }, @@ -5642,11 +6079,12 @@ name = "pyobjc-framework-metalfx" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metal", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-metal" }, ] sdist = { url = "https://files.pythonhosted.org/packages/10/20/4c839a356b534c161fb97e06589f418fc78cc5a0808362bdecf4f9a61a8d/pyobjc_framework_metalfx-11.1.tar.gz", hash = "sha256:555c1b895d4ba31be43930f45e219a5d7bb0e531d148a78b6b75b677cc588fd8", size = 27002, upload-time = "2025-06-14T20:57:55.949Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/a2/f5/df29eeaaf053cd931fb74204a5f8827f88875a81c456b1e0fa24ea0bbcee/pyobjc_framework_metalfx-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:cbfca74f437fcde89de85d14de33c2e617d3084f5fc2b4d614a700e516324f55", size = 10091, upload-time = "2025-06-14T20:51:51.084Z" }, { url = "https://files.pythonhosted.org/packages/36/73/a8df8fa445a09fbc917a495a30b13fbcf224b5576c1e464d5ece9824a493/pyobjc_framework_metalfx-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:60e1dcdf133d2504d810c3a9ba5a02781c9d54c2112a9238de8e3ca4e8debf31", size = 10107, upload-time = "2025-06-14T20:51:51.783Z" }, { url = "https://files.pythonhosted.org/packages/8e/7b/4d925bf5f1f0b0d254b3167999987ecafb251f589cd863bdbaf96eb4ad2a/pyobjc_framework_metalfx-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:fdced91f6b2012c556db954de0e17f6d7985d52b4af83262f4d083bcd87aa01c", size = 10122, upload-time = "2025-06-14T20:51:52.473Z" }, { url = "https://files.pythonhosted.org/packages/0c/b3/633bbd87f9380f8e288d02b44e70845453daf640602d15c4e167536c4b45/pyobjc_framework_metalfx-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:e1b2819bd6a66ba55fb7019b45d38a803ea21b8258fa41c8e9ad7c28cfe74092", size = 10284, upload-time = "2025-06-14T20:51:53.193Z" }, @@ -5659,12 +6097,13 @@ name = "pyobjc-framework-metalkit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metal", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-metal" }, ] sdist = { url = "https://files.pythonhosted.org/packages/45/cb/7e01bc61625c7a6fea9c9888c9ed35aa6bbc47cda2fcd02b6525757bc2b8/pyobjc_framework_metalkit-11.1.tar.gz", hash = "sha256:8811cd81ee9583b9330df4f2499a73dcc53f3359cb92767b409acaec9e4faa1e", size = 45135, upload-time = "2025-06-14T20:57:56.601Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/2a/eb/fd5640015fc91b16e23cafe3a84508775344cd13f621e62b9c32d1750a83/pyobjc_framework_metalkit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:95abb993d17be7a9d1174701594cc040e557983d0a0e9f49b1dfa9868ef20ed6", size = 8711, upload-time = "2025-06-14T20:51:56.765Z" }, { url = "https://files.pythonhosted.org/packages/87/0c/516b6d7a67a170b7d2316701d5288797a19dd283fcc2f73b7b78973e1392/pyobjc_framework_metalkit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:4854cf74fccf6ce516b49bf7cf8fc7c22da9a3743914a2f4b00f336206ad47ec", size = 8730, upload-time = "2025-06-14T20:51:57.824Z" }, { url = "https://files.pythonhosted.org/packages/11/2a/5c55d1e57d8e90613fbce4b204b7d94a9ae7019a0928cb50cbd60bfa8191/pyobjc_framework_metalkit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:62e261b7798b276fee1fee065030a5d19d173863e9c697a80d1fc9a22258ec2c", size = 8749, upload-time = "2025-06-14T20:51:58.538Z" }, { url = "https://files.pythonhosted.org/packages/b6/e4/7b7b61d72fa235c9e364117a595c621c427217567d300da21d7417668c46/pyobjc_framework_metalkit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:b8a378135566e3c48838c19044e17ed2598a4050516ee1c23eee7d42439ef3c8", size = 8903, upload-time = "2025-06-14T20:51:59.392Z" }, @@ -5677,11 +6116,12 @@ name = "pyobjc-framework-metalperformanceshaders" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metal", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-metal" }, ] sdist = { url = "https://files.pythonhosted.org/packages/d0/11/5df398a158a6efe2c87ac5cae121ef2788242afe5d4302d703147b9fcd91/pyobjc_framework_metalperformanceshaders-11.1.tar.gz", hash = "sha256:8a312d090a0f51651e63d9001e6cc7c1aa04ceccf23b494cbf84b7fd3d122071", size = 302113, upload-time = "2025-06-14T20:57:57.407Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/64/ce/bbcf26f8aa94fb6edcf1a71ef23cd8df2afd4b5c2be451432211827c2ab0/pyobjc_framework_metalperformanceshaders-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:81ec1f85c55d11529008e6a0fb1329d5184620f04d89751c11bf14d7dd9798ee", size = 32650, upload-time = "2025-06-14T20:52:04.451Z" }, { url = "https://files.pythonhosted.org/packages/89/df/f844516a54ef0fa1d047fe5fd94b63bc8b1218c09f7d4309b2a67a79708d/pyobjc_framework_metalperformanceshaders-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:06b2a4e446fe859e30f7efc7ccfbaefd443225a6ec53d949a113a6a4acc16c4c", size = 32888, upload-time = "2025-06-14T20:52:05.225Z" }, { url = "https://files.pythonhosted.org/packages/b5/a2/5387ab012a20afb7252b3938a8fb5319c946a3faaa9166b79b51ab3c0bf6/pyobjc_framework_metalperformanceshaders-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:97be4bd0ded06c663205bd1cf821e148352346f147da48dba44cf7680f0ea23b", size = 32903, upload-time = "2025-06-14T20:52:06.31Z" }, { url = "https://files.pythonhosted.org/packages/ee/8c/5f10387b638a92ffbc3ccd04bac73c68a5119672b908b6dc90d46e30fd40/pyobjc_framework_metalperformanceshaders-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:c905a3f5a34a95c1fd26bf07da505ed84b9b0a0c88a8f004914d9173f5037142", size = 33093, upload-time = "2025-06-14T20:52:07.055Z" }, @@ -5694,8 +6134,8 @@ name = "pyobjc-framework-metalperformanceshadersgraph" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-metalperformanceshaders", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-metalperformanceshaders" }, ] sdist = { url = "https://files.pythonhosted.org/packages/32/c3/8d98661f7eecd1f1b0d80a80961069081b88efd3a82fbbed2d7e6050c0ad/pyobjc_framework_metalperformanceshadersgraph-11.1.tar.gz", hash = "sha256:d25225aab4edc6f786b29fe3d9badc4f3e2d0caeab1054cd4f224258c1b6dbe2", size = 105098, upload-time = "2025-06-14T20:57:58.273Z" } wheels = [ @@ -5707,11 +6147,12 @@ name = "pyobjc-framework-metrickit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/bd/48/8ae969a51a91864000e39c1de74627b12ff587b1dbad9406f7a30dfe71f8/pyobjc_framework_metrickit-11.1.tar.gz", hash = "sha256:a79d37575489916c35840e6a07edd958be578d3be7a3d621684d028d721f0b85", size = 40952, upload-time = "2025-06-14T20:57:58.996Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/3b/cd/e459511c194d25c4acd31cbdb5c118215795785840861d55dbc8bd55cf35/pyobjc_framework_metrickit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:a5d2b394f7acadd17d8947d188106424f59393b45dd4a842ac3cc50935170e3e", size = 8063, upload-time = "2025-06-14T20:52:12.696Z" }, { url = "https://files.pythonhosted.org/packages/55/d1/aea4655e7eaa9ab19da8fe78ab363270443059c8a542b8f8a071b4988b57/pyobjc_framework_metrickit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:a034e6b982e915da881edef87d71b063e596511d52aef7a32c683571f364156e", size = 8081, upload-time = "2025-06-14T20:52:13.72Z" }, { url = "https://files.pythonhosted.org/packages/d9/d2/1f70e7524f6aca2e7aa7a99c4024d8c7e7cdd2ae9b338d2958548ee432c0/pyobjc_framework_metrickit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:95e98e96b8f122b0141e84f13ae9e0f91d09d0803b1c093fdc7d19123f000f9e", size = 8104, upload-time = "2025-06-14T20:52:14.405Z" }, { url = "https://files.pythonhosted.org/packages/aa/26/d875ea9da12be79e5336e7aa9134db97eb917c968f8237235e5a70da0b72/pyobjc_framework_metrickit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:14de8dcaa107fe15546df91b1f7d51dc398169c3d1b06e02291fdb8722c6bf41", size = 8247, upload-time = "2025-06-14T20:52:15.469Z" }, @@ -5724,8 +6165,8 @@ name = "pyobjc-framework-mlcompute" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/8b/e6/f064dec650fb1209f41aba0c3074416cb9b975a7cf4d05d93036e3d917f0/pyobjc_framework_mlcompute-11.1.tar.gz", hash = "sha256:f6c4c3ea6a62e4e3927abf9783c40495aa8bb9a8c89def744b0822da58c2354b", size = 89021, upload-time = "2025-06-14T20:57:59.997Z" } wheels = [ @@ -5737,12 +6178,13 @@ name = "pyobjc-framework-modelio" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/a0/27/140bf75706332729de252cc4141e8c8afe16a0e9e5818b5a23155aa3473c/pyobjc_framework_modelio-11.1.tar.gz", hash = "sha256:fad0fa2c09d468ac7e49848e144f7bbce6826f2178b3120add8960a83e5bfcb7", size = 123203, upload-time = "2025-06-14T20:58:01.035Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/6c/66/8109e52c7d97a108d4852a2032c9d7a7ecd27c6085bd7b2920b2ab575df4/pyobjc_framework_modelio-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:4365fb96eb42b71c12efdfa2ff9d44755d5c292b8d1c78b947833d84271e359f", size = 20142, upload-time = "2025-06-14T20:52:21.582Z" }, { url = "https://files.pythonhosted.org/packages/18/84/5f223b82894777388ef1aa09579d9c044044877a72075213741c97adc901/pyobjc_framework_modelio-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:5d5e11389bde0852490b2a37896aaf9eb674b2a3586f2c572f9101cecb7bc576", size = 20172, upload-time = "2025-06-14T20:52:22.327Z" }, { url = "https://files.pythonhosted.org/packages/00/8b/7c8b93d99d2102800834011f58d6e5cbb56d24c112c2e45c4730b103e4a3/pyobjc_framework_modelio-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:34fabde55d28aa8a12dd4476ad40182513cf87ee2fa928043aa6702961de302b", size = 20182, upload-time = "2025-06-14T20:52:23.063Z" }, { url = "https://files.pythonhosted.org/packages/4d/c1/4d7830a8bd4e5b077e03e72eb8b92a336f689d5203228ecab9900d58d3c3/pyobjc_framework_modelio-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:327e1f3020001fd15bfbf4d4228581a8f64bd85872fd697b7c306343c11e25a6", size = 20408, upload-time = "2025-06-14T20:52:23.813Z" }, @@ -5755,11 +6197,12 @@ name = "pyobjc-framework-multipeerconnectivity" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/73/99/75bf6170e282d9e546b353b65af7859de8b1b27ddc431fc4afbf15423d01/pyobjc_framework_multipeerconnectivity-11.1.tar.gz", hash = "sha256:a3dacca5e6e2f1960dd2d1107d98399ff81ecf54a9852baa8ec8767dbfdbf54b", size = 26149, upload-time = "2025-06-14T20:58:01.793Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/8d/fc/a3fc2514879a39673202f7ea5e835135255c5e510d30c58a43239ec1d9e0/pyobjc_framework_multipeerconnectivity-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:b3c9d4d36e0c142b4ce91033740ed5bca19fe7ec96870d90610d2942ecd3cd39", size = 11955, upload-time = "2025-06-14T20:52:28.392Z" }, { url = "https://files.pythonhosted.org/packages/b4/fe/5c29c227f6ed81147ec6ec3e681fc680a7ffe0360f96901371435ea68570/pyobjc_framework_multipeerconnectivity-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:970031deb3dbf8da1fcb04e785d4bd2eeedae8f6677db92881df6d92b05c31d6", size = 11981, upload-time = "2025-06-14T20:52:29.406Z" }, { url = "https://files.pythonhosted.org/packages/d3/ea/f8d928235a67feeefec80e1f679bdb0c05f94e718a9aa22b4968ad65c6d1/pyobjc_framework_multipeerconnectivity-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:c92c95ea611d5272ab37fd73bc8e68c3d8fde515a75b97d8b22dafa8acbc7daf", size = 11992, upload-time = "2025-06-14T20:52:30.148Z" }, { url = "https://files.pythonhosted.org/packages/5a/ff/e60c8681d5c916f68fc78276d9243a91efc94a0e98717b535ce0b16e9db0/pyobjc_framework_multipeerconnectivity-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:296e10d289887cc4141c660f884cced1ec4ce64a19b3e406f13f6ce453a9425f", size = 12172, upload-time = "2025-06-14T20:52:30.857Z" }, @@ -5772,8 +6215,8 @@ name = "pyobjc-framework-naturallanguage" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/a2/e9/5352fbf09c5d5360405dea49fb77e53ed55acd572a94ce9a0d05f64d2b70/pyobjc_framework_naturallanguage-11.1.tar.gz", hash = "sha256:ab1fc711713aa29c32719774fc623bf2d32168aed21883970d4896e901ff4b41", size = 46120, upload-time = "2025-06-14T20:58:02.808Z" } wheels = [ @@ -5785,8 +6228,8 @@ name = "pyobjc-framework-netfs" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/68/5d/d68cc59a1c1ea61f227ed58e7b185a444d560655320b53ced155076f5b78/pyobjc_framework_netfs-11.1.tar.gz", hash = "sha256:9c49f050c8171dc37e54d05dd12a63979c8b6b565c10f05092923a2250446f50", size = 15910, upload-time = "2025-06-14T20:58:03.811Z" } wheels = [ @@ -5798,11 +6241,12 @@ name = "pyobjc-framework-network" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/0a/ee/5ea93e48eca341b274027e1532bd8629fd55d609cd9c39c2c3acf26158c3/pyobjc_framework_network-11.1.tar.gz", hash = "sha256:f6df7a58a1279bbc976fd7e2efe813afbbb18427df40463e6e2ee28fba07d2df", size = 124670, upload-time = "2025-06-14T20:58:05.491Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/17/e9/a54f32daa0365bf000b739fc386d4783432273a9075337aa57a3808af65d/pyobjc_framework_network-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:e56691507584c09cdb50f1cd69b5f57b42fd55c396e8c34fab8c5b81b44d36ed", size = 19499, upload-time = "2025-06-14T20:52:37.158Z" }, { url = "https://files.pythonhosted.org/packages/15/c2/3c6626fdb3616fde2c173d313d15caea22d141abcc2fbf3b615f8555abe3/pyobjc_framework_network-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:8cdc9be8ec3b0ae95e5c649e4bbcdf502cffd357dacc566223be707bdd5ac271", size = 19513, upload-time = "2025-06-14T20:52:38.423Z" }, { url = "https://files.pythonhosted.org/packages/91/96/0824455bab6d321ccb5a38907ab8593e1c83b283ec850abee494278f1c96/pyobjc_framework_network-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:04582fef567392c2a10dcee9519356b79b17ab73ded050d14592da938d95b01a", size = 19537, upload-time = "2025-06-14T20:52:39.181Z" }, { url = "https://files.pythonhosted.org/packages/5d/77/a088cfef5daf5841274b49fc57f5c5f70954c4a60b9a26160cb7beeb3e3a/pyobjc_framework_network-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:acf16738ab447a31a9f6167171b2a00d65a9370a8e84482d435b2b31c58eed94", size = 19600, upload-time = "2025-06-14T20:52:39.95Z" }, @@ -5815,11 +6259,12 @@ name = "pyobjc-framework-networkextension" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/71/30/d1eee738d702bbca78effdaa346a2b05359ab8a96d961b7cb44838e236ca/pyobjc_framework_networkextension-11.1.tar.gz", hash = "sha256:2b74b430ca651293e5aa90a1e7571b200d0acbf42803af87306ac8a1c70b0d4b", size = 217252, upload-time = "2025-06-14T20:58:06.311Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/76/d7/b10aa191d37900ade78f1b7806d17ff29fa95f40ce7aeecce6f15ec94ac9/pyobjc_framework_networkextension-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:55e5ca70c81a864896b603cfcabf4c065783f64395460d16fe16db2bf0866d60", size = 14101, upload-time = "2025-06-14T20:52:44.527Z" }, { url = "https://files.pythonhosted.org/packages/b6/26/526cd9f63e390e9c2153c41dc0982231b0b1ca88865deb538b77e1c3513d/pyobjc_framework_networkextension-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:853458aae8b43634461f6c44759750e2dc784c9aba561f9468ab14529b5a7fbe", size = 14114, upload-time = "2025-06-14T20:52:45.274Z" }, { url = "https://files.pythonhosted.org/packages/06/30/ab050541fda285e2ce6b6ba0f1f5215809bd5ec75f71de8057ff8135737a/pyobjc_framework_networkextension-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:d3d6e9810cb01c3a8f99aed5ee2d75f6f785204338b99b32e5f64370a18cc9dd", size = 14128, upload-time = "2025-06-14T20:52:46.328Z" }, { url = "https://files.pythonhosted.org/packages/07/36/3980a3ee5fe4be7c442cb4ddcf03f63406055da3f5ad58640fb573ecd77c/pyobjc_framework_networkextension-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:7dea914e7b26e28c6e4f8ffd03dd8fce612d38876043944fb0cf191774634566", size = 14275, upload-time = "2025-06-14T20:52:47.019Z" }, @@ -5832,11 +6277,12 @@ name = "pyobjc-framework-notificationcenter" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/a8/4a/d3529b9bd7aae2c89d258ebc234673c5435e217a5136abd8c0aba37b916b/pyobjc_framework_notificationcenter-11.1.tar.gz", hash = "sha256:0b938053f2d6b1cea9db79313639d7eb9ddd5b2a5436a346be0887e75101e717", size = 23389, upload-time = "2025-06-14T20:58:07.136Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/ea/ed/3beb825e2b80de45b90e7cd510ad52890ac4a5a4de88cd9a5291235519fb/pyobjc_framework_notificationcenter-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:3d44413818e7fa3662f784cdcf0730c86676dd7333b7d24a7da13d4ffcde491b", size = 9859, upload-time = "2025-06-14T20:52:51.744Z" }, { url = "https://files.pythonhosted.org/packages/6d/92/cd00fe5e54a191fb77611fe728a8c8a0a6edb229857d32f27806582406ca/pyobjc_framework_notificationcenter-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:65fc67374a471890245c7a1d60cf67dcf160075a9c048a5d89608a8290f33b03", size = 9880, upload-time = "2025-06-14T20:52:52.406Z" }, { url = "https://files.pythonhosted.org/packages/40/e4/1bc444c5ee828a042e951c264ce597207e192fb6701c380db5ba05486955/pyobjc_framework_notificationcenter-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:f5ce98882e301adef07651ba495ddd57b661d4c0398afd39f4591c1b44673cca", size = 9895, upload-time = "2025-06-14T20:52:53.105Z" }, { url = "https://files.pythonhosted.org/packages/13/b9/b98d74bcc9e1694494b81dd1bfeb28e2f004041db4945b7451c0c6c64b1e/pyobjc_framework_notificationcenter-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:e46285290d04e84c167606ccfcb9a20c2567f5a2a6a9c6e96760fc9d561c2740", size = 10090, upload-time = "2025-06-14T20:52:53.814Z" }, @@ -5849,8 +6295,8 @@ name = "pyobjc-framework-opendirectory" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/9d/02/ac56c56fdfbc24cdf87f4a624f81bbe2e371d0983529b211a18c6170e932/pyobjc_framework_opendirectory-11.1.tar.gz", hash = "sha256:319ac3424ed0350be458b78148914468a8fc13a069d62e7869e3079108e4f118", size = 188880, upload-time = "2025-06-14T20:58:08.003Z" } wheels = [ @@ -5862,8 +6308,8 @@ name = "pyobjc-framework-osakit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/56/22/f9cdfb5de255b335f99e61a3284be7cb1552a43ed1dfe7c22cc868c23819/pyobjc_framework_osakit-11.1.tar.gz", hash = "sha256:920987da78b67578367c315d208f87e8fab01dd35825d72242909f29fb43c820", size = 22290, upload-time = "2025-06-14T20:58:09.103Z" } wheels = [ @@ -5875,13 +6321,14 @@ name = "pyobjc-framework-oslog" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremedia", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coremedia" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/79/93/3feb7f6150b50165524750a424f5434448392123420cb4673db766c3f54a/pyobjc_framework_oslog-11.1.tar.gz", hash = "sha256:b2af409617e6b68fa1f1467c5a5679ebf59afd0cdc4b4528e1616059959a7979", size = 24689, upload-time = "2025-06-14T20:58:09.739Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/66/7a/2db26fc24e16c84312a0de432bab16ca586223fd6c5ba08e49c192ae95f6/pyobjc_framework_oslog-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:5dab25ef1cde4237cd2957c1f61c2888968e924304f7b9d9699eceeb330e9817", size = 7793, upload-time = "2025-06-14T20:52:59.132Z" }, { url = "https://files.pythonhosted.org/packages/40/da/fd3bd62899cd679743056aa2c28bc821c2688682a17ddde1a08d6d9d67fc/pyobjc_framework_oslog-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:7ae29c31ce51c476d3a37ca303465dd8bdfa98df2f6f951cf14c497e984a1ba9", size = 7799, upload-time = "2025-06-14T20:52:59.935Z" }, { url = "https://files.pythonhosted.org/packages/9d/a9/d26bb3ec7ab2a3ef843c1697b6084dbd4a4a98d90ff8e29f4c227ade425e/pyobjc_framework_oslog-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:7174ca2cdc073e555d5f5aea3baa7410c61a83a3741eaec23e8581340037680e", size = 7811, upload-time = "2025-06-14T20:53:00.621Z" }, { url = "https://files.pythonhosted.org/packages/44/60/2f57ee052e9df2700b21032774146ae622af0a88a8dff97158dc5850a0ec/pyobjc_framework_oslog-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:f03789f8d5638e1075652b331b8ebf98c03dfa809c57545f0313583a7688bb86", size = 7995, upload-time = "2025-06-14T20:53:01.316Z" }, @@ -5894,11 +6341,12 @@ name = "pyobjc-framework-passkit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/5c/05/063db500e7df70e39cbb5518a5a03c2acc06a1ca90b057061daea00129f3/pyobjc_framework_passkit-11.1.tar.gz", hash = "sha256:d2408b58960fca66607b483353c1ffbd751ef0bef394a1853ec414a34029566f", size = 144859, upload-time = "2025-06-14T20:58:10.761Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/80/18/343eb846e62704fbd64e178e0cbf75b121955c1973bf51ddd0871a42910a/pyobjc_framework_passkit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:67b7b1ee9454919c073c2cba7bdba444a766a4e1dd15a5e906f4fa0c61525347", size = 13949, upload-time = "2025-06-14T20:53:04.98Z" }, { url = "https://files.pythonhosted.org/packages/9d/ba/9e52213e0c0100079e4ef397cf4fd5ba8939fa4de19339755d1a373407a8/pyobjc_framework_passkit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:779eaea4e1931cfda4c8701e1111307b14bf9067b359a319fc992b6848a86932", size = 13959, upload-time = "2025-06-14T20:53:05.694Z" }, { url = "https://files.pythonhosted.org/packages/d1/4f/e29dc665382e22cd6b4ebb1c5707a1b2059018a6462c81a7c344a9c40dba/pyobjc_framework_passkit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:a6306dda724ca812dca70154d40f32ec9bbdaff765a12f3cc45391723efe147e", size = 13971, upload-time = "2025-06-14T20:53:06.413Z" }, { url = "https://files.pythonhosted.org/packages/f4/ec/ef03f62924b288302e41373c4c292cadf4c393519828a9986d8573b72bcc/pyobjc_framework_passkit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:d7948d5b3369b60808a85dcadffdebb0a44e8d2c4716edc10b78cb76fa762070", size = 14130, upload-time = "2025-06-14T20:53:07.169Z" }, @@ -5911,8 +6359,8 @@ name = "pyobjc-framework-pencilkit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/75/d0/bbbe9dadcfc37e33a63d43b381a8d9a64eca27559df38efb74d524fa6260/pyobjc_framework_pencilkit-11.1.tar.gz", hash = "sha256:9c173e0fe70179feadc3558de113a8baad61b584fe70789b263af202bfa4c6be", size = 22570, upload-time = "2025-06-14T20:58:11.538Z" } wheels = [ @@ -5924,8 +6372,8 @@ name = "pyobjc-framework-phase" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-avfoundation", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-avfoundation" }, ] sdist = { url = "https://files.pythonhosted.org/packages/c6/d2/e9384b5b3fbcc79e8176cb39fcdd48b77f60cd1cb64f9ee4353762b037dc/pyobjc_framework_phase-11.1.tar.gz", hash = "sha256:a940d81ac5c393ae3da94144cf40af33932e0a9731244e2cfd5c9c8eb851e3fc", size = 58986, upload-time = "2025-06-14T20:58:12.196Z" } wheels = [ @@ -5937,11 +6385,12 @@ name = "pyobjc-framework-photos" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/78/b0/576652ecd05c26026ab4e75e0d81466edd570d060ce7df3d6bd812eb90d0/pyobjc_framework_photos-11.1.tar.gz", hash = "sha256:c8c3b25b14a2305047f72c7c081ff3655b3d051f7ed531476c03246798f8156d", size = 92569, upload-time = "2025-06-14T20:58:12.939Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/df/25/ec3b0234d20948816791399e580f6dd83c0d50a24219c954708f755742c4/pyobjc_framework_photos-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:959dfc82f20513366b85cd37d8541bb0a6ab4f3bfa2f8094e9758a5245032d67", size = 12198, upload-time = "2025-06-14T20:53:13.563Z" }, { url = "https://files.pythonhosted.org/packages/fa/24/2400e6b738d3ed622c61a7cc6604eec769f398071a1eb6a16dfdf3a9ceea/pyobjc_framework_photos-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:8dbfffd29cfa63a8396ede0030785c15a5bc36065d3dd98fc6176a59e7abb3d3", size = 12224, upload-time = "2025-06-14T20:53:14.793Z" }, { url = "https://files.pythonhosted.org/packages/70/60/cc575ee4287b250a42406e9b335f3293840996a840152cf93d1ce73790c5/pyobjc_framework_photos-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:541d8fafdb2f111f2f298e1aa0542f2d5871ce1dd481c3e9be4ed33916b38c3a", size = 12241, upload-time = "2025-06-14T20:53:15.469Z" }, { url = "https://files.pythonhosted.org/packages/8c/3b/d9c4c5b156e7805495a8864dd06a3439c3b4267e5887d9094ac45a4ca907/pyobjc_framework_photos-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:7cded282eaebd77645a4262f6fb63379c7a226d20f8f1763910b19927709aea2", size = 12426, upload-time = "2025-06-14T20:53:16.207Z" }, @@ -5954,11 +6403,12 @@ name = "pyobjc-framework-photosui" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/20/bb/e6de720efde2e9718677c95c6ae3f97047be437cda7a0f050cd1d6d2a434/pyobjc_framework_photosui-11.1.tar.gz", hash = "sha256:1c7ffab4860ce3e2b50feeed4f1d84488a9e38546db0bec09484d8d141c650df", size = 48443, upload-time = "2025-06-14T20:58:13.626Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/af/c1/3d67c2af53fe91feb6f64dbc501bbcfd5d325b7f0f0ffffd5d033334cb03/pyobjc_framework_photosui-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:d93722aeb8c134569035fd7e6632d0247e1bcb18c3cc4e0a288664218f241b85", size = 11667, upload-time = "2025-06-14T20:53:20.464Z" }, { url = "https://files.pythonhosted.org/packages/f8/c1/a5c84c1695e7a066743d63d10b219d94f3c07d706871682e42f7db389f5c/pyobjc_framework_photosui-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:b2f278f569dfd596a32468351411518a651d12cb91e60620094e852c525a5f10", size = 11682, upload-time = "2025-06-14T20:53:21.162Z" }, { url = "https://files.pythonhosted.org/packages/33/10/506af430a9e7d356302b6bbee6672e03a4dfbc9a2f3a90fa79607d06387d/pyobjc_framework_photosui-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:6f0fa9c9e363c0db54957dfe4e26214379f2698caaba1e4ff4c9e3eba5e690d9", size = 11697, upload-time = "2025-06-14T20:53:21.855Z" }, { url = "https://files.pythonhosted.org/packages/9f/f8/ada0d54136f14b071e784e7f86e0a1e2190e2e898a7f4172b53e1fec5f7c/pyobjc_framework_photosui-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:91aff7caae16a7a7f25e35692aa92b796155510b8a0575668e75f351fbf63a68", size = 11894, upload-time = "2025-06-14T20:53:22.536Z" }, @@ -5971,8 +6421,8 @@ name = "pyobjc-framework-preferencepanes" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/34/ac/9324602daf9916308ebf1935b8a4b91c93b9ae993dcd0da731c0619c2836/pyobjc_framework_preferencepanes-11.1.tar.gz", hash = "sha256:6e4a55195ec9fc921e0eaad6b3038d0ab91f0bb2f39206aa6fccd24b14a0f1d8", size = 26212, upload-time = "2025-06-14T20:58:14.361Z" } wheels = [ @@ -5984,11 +6434,12 @@ name = "pyobjc-framework-pushkit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/9f/f0/92d0eb26bf8af8ebf6b5b88df77e70b807de11f01af0162e0a429fcfb892/pyobjc_framework_pushkit-11.1.tar.gz", hash = "sha256:540769a4aadc3c9f08beca8496fe305372501eb28fdbca078db904a07b8e10f4", size = 21362, upload-time = "2025-06-14T20:58:15.642Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/d9/dc/415d6d7e3ed04d8b2f8dc6d458e7c6db3f503737b092d71b4856bf1607f7/pyobjc_framework_pushkit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:5e2f08b667035df6b11a0a26f038610df1eebbedf9f3f111c241b5afaaf7c5fd", size = 8149, upload-time = "2025-06-14T20:53:28.096Z" }, { url = "https://files.pythonhosted.org/packages/31/65/260014c5d13c54bd359221b0a890cbffdb99eecff3703f253cf648e45036/pyobjc_framework_pushkit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:21993b7e9127b05575a954faa68e85301c6a4c04e34e38aff9050f67a05c562a", size = 8174, upload-time = "2025-06-14T20:53:28.805Z" }, { url = "https://files.pythonhosted.org/packages/b4/b2/08514fa6be83a359bb6d72f9009f17f16f7efc0fe802029d1f6f0c4fc5c9/pyobjc_framework_pushkit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:bac3ee77dfbe936998f207c1579e346993485bab8849db537ed250261cf12ab3", size = 8190, upload-time = "2025-06-14T20:53:29.651Z" }, { url = "https://files.pythonhosted.org/packages/46/d0/cbe99c9bf3b9fb2679c08f4051aaa44dcfbfa9e762f0ef4c7fc5ad2e147e/pyobjc_framework_pushkit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:68c4f44354eab84cb54d43310fa65ca3a5ba68299c868378764cc50803cf2adc", size = 8314, upload-time = "2025-06-14T20:53:31.178Z" }, @@ -6001,11 +6452,12 @@ name = "pyobjc-framework-quartz" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/c7/ac/6308fec6c9ffeda9942fef72724f4094c6df4933560f512e63eac37ebd30/pyobjc_framework_quartz-11.1.tar.gz", hash = "sha256:a57f35ccfc22ad48c87c5932818e583777ff7276605fef6afad0ac0741169f75", size = 3953275, upload-time = "2025-06-14T20:58:17.924Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/77/cb/38172fdb350b3f47e18d87c5760e50f4efbb4da6308182b5e1310ff0cde4/pyobjc_framework_quartz-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:2d501fe95ef15d8acf587cb7dc4ab4be3c5a84e2252017da8dbb7df1bbe7a72a", size = 215565, upload-time = "2025-06-14T20:53:35.262Z" }, { url = "https://files.pythonhosted.org/packages/9b/37/ee6e0bdd31b3b277fec00e5ee84d30eb1b5b8b0e025095e24ddc561697d0/pyobjc_framework_quartz-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:9ac806067541917d6119b98d90390a6944e7d9bd737f5c0a79884202327c9204", size = 216410, upload-time = "2025-06-14T20:53:36.346Z" }, { url = "https://files.pythonhosted.org/packages/bd/27/4f4fc0e6a0652318c2844608dd7c41e49ba6006ee5fb60c7ae417c338357/pyobjc_framework_quartz-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:43a1138280571bbf44df27a7eef519184b5c4183a588598ebaaeb887b9e73e76", size = 216816, upload-time = "2025-06-14T20:53:37.358Z" }, { url = "https://files.pythonhosted.org/packages/b8/8a/1d15e42496bef31246f7401aad1ebf0f9e11566ce0de41c18431715aafbc/pyobjc_framework_quartz-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:b23d81c30c564adf6336e00b357f355b35aad10075dd7e837cfd52a9912863e5", size = 221941, upload-time = "2025-06-14T20:53:38.34Z" }, @@ -6018,9 +6470,9 @@ name = "pyobjc-framework-quicklookthumbnailing" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/aa/98/6e87f360c2dfc870ae7870b8a25fdea8ddf1d62092c755686cebe7ec1a07/pyobjc_framework_quicklookthumbnailing-11.1.tar.gz", hash = "sha256:1614dc108c1d45bbf899ea84b8691288a5b1d25f2d6f0c57dfffa962b7a478c3", size = 16527, upload-time = "2025-06-14T20:58:20.811Z" } wheels = [ @@ -6032,11 +6484,12 @@ name = "pyobjc-framework-replaykit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/c8/4f/014e95f0fd6842d7fcc3d443feb6ee65ac69d06c66ffa9327fc33ceb7c27/pyobjc_framework_replaykit-11.1.tar.gz", hash = "sha256:6919baa123a6d8aad769769fcff87369e13ee7bae11b955a8185a406a651061b", size = 26132, upload-time = "2025-06-14T20:58:21.853Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/72/97/2b4fbd52c6727977c0fdbde2b4a15226a9beb836248c289781e4129394e4/pyobjc_framework_replaykit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:4d88c3867349865d8a3a06ea064f15aed7e5be20d22882ac8a647d9b6959594e", size = 10066, upload-time = "2025-06-14T20:53:45.555Z" }, { url = "https://files.pythonhosted.org/packages/b9/73/846cebb36fc279df18f10dc3a27cba8fe2e47e95350a3651147e4d454719/pyobjc_framework_replaykit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:22c6d09be9a6e758426d723a6c3658ad6bbb66f97ba9a1909bfcf29a91d99921", size = 10087, upload-time = "2025-06-14T20:53:46.242Z" }, { url = "https://files.pythonhosted.org/packages/bf/2e/996764cd045b6c9e033167e573c9fe67c4e867eb6ab49c2d4fde005cd4a7/pyobjc_framework_replaykit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:7742ee18c8c9b61f5668698a05b88d25d34461fcdd95a8f669ecdfd8db8c4d42", size = 10108, upload-time = "2025-06-14T20:53:47.293Z" }, { url = "https://files.pythonhosted.org/packages/d6/f9/1013a88f655b9eaf6fc81a5da48403724435cf2f87c147038dfa733e6213/pyobjc_framework_replaykit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:b503fabc33ee02117fd82c78db18cba3f0be90dea652f5553101a45185100402", size = 10298, upload-time = "2025-06-14T20:53:47.992Z" }, @@ -6049,11 +6502,12 @@ name = "pyobjc-framework-safariservices" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/1a/fc/c47d2abf3c1de6db21d685cace76a0931d594aa369e3d090260295273f6e/pyobjc_framework_safariservices-11.1.tar.gz", hash = "sha256:39a17df1a8e1c339457f3acbff0dc0eae4681d158f9d783a11995cf484aa9cd0", size = 34905, upload-time = "2025-06-14T20:58:22.492Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/c9/aa/0c9f3456a57dbee711210a0ac3fe58aff9bf881ab7c65727b885193eb8af/pyobjc_framework_safariservices-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:a441a2e99f7d6475bea00c3d53de924143b8f90052be226aee16f1f6d9cfdc8c", size = 7262, upload-time = "2025-06-14T20:53:52.057Z" }, { url = "https://files.pythonhosted.org/packages/d7/13/9636e9d3dc362daaaa025b2aa4e28606a1e197dfc6506d3a246be8315f8a/pyobjc_framework_safariservices-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:c92eb9e35f98368ea1bfaa8cdd41138ca8b004ea5a85833390a44e5626ca5061", size = 7275, upload-time = "2025-06-14T20:53:53.075Z" }, { url = "https://files.pythonhosted.org/packages/de/cd/9ed0083373be3bf6da2450a6800b54965fea95b2452473ee0e36ddc72573/pyobjc_framework_safariservices-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:8b4d4169dd21e69246d90a42f872b7148064b63de6bbbf6bc6ddabe33f143843", size = 7290, upload-time = "2025-06-14T20:53:53.816Z" }, { url = "https://files.pythonhosted.org/packages/42/ed/3eaec77c81395410441466f66c8920664ba72f62099306f0e9b878b0b203/pyobjc_framework_safariservices-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:8a4371d64052a3ffe9993a89c45f9731f86e7b6c21fd1d968815fd7930ff501a", size = 7293, upload-time = "2025-06-14T20:53:54.508Z" }, @@ -6066,12 +6520,13 @@ name = "pyobjc-framework-safetykit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/28/cc/f6aa5d6f45179bd084416511be4e5b0dd0752cb76daa93869e6edb806096/pyobjc_framework_safetykit-11.1.tar.gz", hash = "sha256:c6b44e0cf69e27584ac3ef3d8b771d19a7c2ccd9c6de4138d091358e036322d4", size = 21240, upload-time = "2025-06-14T20:58:23.132Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/a3/ad/1e9c661510cc4cd96f2beffc7ba39af36064c742e265303c689e85aaa0ad/pyobjc_framework_safetykit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:3333e8e53a1e8c8133936684813a2254e5d1b4fe313333a3d0273e31b9158cf7", size = 8513, upload-time = "2025-06-14T20:53:58.413Z" }, { url = "https://files.pythonhosted.org/packages/9c/8f/6f4c833e31526a81faef9bf19695b332ba8d2fa53d92640abd6fb3ac1d78/pyobjc_framework_safetykit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:b76fccdb970d3d751a540c47712e9110afac9abea952cb9b7bc0d5867db896e3", size = 8523, upload-time = "2025-06-14T20:53:59.443Z" }, { url = "https://files.pythonhosted.org/packages/85/3d/782e1738f2eb4b276baabd85a8b263bf75b2c4e990fd5950eeadfb59ebeb/pyobjc_framework_safetykit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:8130de57f701dbccb1d84c76ec007fe04992da58cbf0eb906324393eeac3d08d", size = 8541, upload-time = "2025-06-14T20:54:00.461Z" }, { url = "https://files.pythonhosted.org/packages/be/2c/411d525a2110777dd22888e46a48dcff2ae15ff08ab2f739eab44ee740cb/pyobjc_framework_safetykit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:cd8091c902037eac4a403d8462424afd711f43206af3548a34bebe1f59d2c340", size = 8701, upload-time = "2025-06-14T20:54:01.156Z" }, @@ -6084,12 +6539,13 @@ name = "pyobjc-framework-scenekit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/64/cf/2d89777120d2812e7ee53c703bf6fc8968606c29ddc1351bc63f0a2a5692/pyobjc_framework_scenekit-11.1.tar.gz", hash = "sha256:82941f1e5040114d6e2c9fd35507244e102ef561c637686091b71a7ad0f31306", size = 214118, upload-time = "2025-06-14T20:58:24.003Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/51/46/d011b5a88e45d78265f5df144759ff57e50d361d44c9adb68c2fb58b276d/pyobjc_framework_scenekit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:3e777dacb563946ad0c2351e6cfe3f16b8587a65772ec0654e2be9f75764d234", size = 33490, upload-time = "2025-06-14T20:54:04.845Z" }, { url = "https://files.pythonhosted.org/packages/e0/f9/bdcd8a4bc6c387ef07f3e2190cea6a03d4f7ed761784f492b01323e8d900/pyobjc_framework_scenekit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:c803d95b30c4ce49f46ff7174806f5eb84e4c3a152f8f580c5da0313c5c67041", size = 33558, upload-time = "2025-06-14T20:54:05.59Z" }, { url = "https://files.pythonhosted.org/packages/ce/5e/9bb308fd68b56a8cf9ea5213e6c988232ce6ae4e6ccd4cf53b38f0018deb/pyobjc_framework_scenekit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:2f347d5ae42af8acddb86a45f965046bb91f8d83d33851390954439961e2a7b7", size = 33577, upload-time = "2025-06-14T20:54:06.69Z" }, { url = "https://files.pythonhosted.org/packages/e0/96/c960c553de8e70f0bff275e19295b6254127f3f6d1da4e5dd80fd7037d49/pyobjc_framework_scenekit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:ea2f02eea982872994d7c366f6a51060a90cc17b994c017f85c094e2bc346847", size = 33912, upload-time = "2025-06-14T20:54:07.456Z" }, @@ -6102,12 +6558,13 @@ name = "pyobjc-framework-screencapturekit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremedia", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coremedia" }, ] sdist = { url = "https://files.pythonhosted.org/packages/32/a5/9bd1f1ad1773a1304ccde934ff39e0f0a0b0034441bf89166aea649606de/pyobjc_framework_screencapturekit-11.1.tar.gz", hash = "sha256:11443781a30ed446f2d892c9e6642ca4897eb45f1a1411136ca584997fa739e0", size = 53548, upload-time = "2025-06-14T20:58:24.837Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/7e/e0/fd1957e962c4a1624171dbbda4e425615848a7bcc9b45a524018dc449874/pyobjc_framework_screencapturekit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:7203108d28d7373501c455cd4a8bbcd2eb7849906dbc7859ac17a350b141553c", size = 11280, upload-time = "2025-06-14T20:54:11.699Z" }, { url = "https://files.pythonhosted.org/packages/98/37/840f306dcf01dd2bd092ae8dcf371a3bad3a0f88f0780d0840f899a8c047/pyobjc_framework_screencapturekit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:641fa7834f54558859209e174c83551d5fa239ca6943ace52665f7d45e562ff2", size = 11308, upload-time = "2025-06-14T20:54:12.382Z" }, { url = "https://files.pythonhosted.org/packages/1b/9e/de4c2e3ae834c2f60c9e78d95e1f2488b679b4cf74fa5bfba7f065fb827b/pyobjc_framework_screencapturekit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:1119d6258d6c668564ab39154cfc745fd2bb8b3beeaa4f9b2a8a4c93926678c0", size = 11324, upload-time = "2025-06-14T20:54:13.104Z" }, { url = "https://files.pythonhosted.org/packages/4c/49/fa1680b8453fb5c4bbe92b2bfef145fd90b3cd9c2ee24c1eb786b7655cd3/pyobjc_framework_screencapturekit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:f93f8198741bd904d423a7b1ef941445246bdf6cb119597d981e61a13cc479a4", size = 11517, upload-time = "2025-06-14T20:54:13.829Z" }, @@ -6120,11 +6577,12 @@ name = "pyobjc-framework-screensaver" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/7c/f6/f2d48583b29fc67b64aa1f415fd51faf003d045cdb1f3acab039b9a3f59f/pyobjc_framework_screensaver-11.1.tar.gz", hash = "sha256:d5fbc9dc076cc574ead183d521840b56be0c160415e43cb8e01cfddd6d6372c2", size = 24302, upload-time = "2025-06-14T20:58:25.52Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/f0/8c/2236e5796f329a92ce7664036da91e91d63d86217972dc2939261ce88dde/pyobjc_framework_screensaver-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:8b959761fddf06d9fb3fed6cd0cea6009d60473317e11490f66dcf0444011d5f", size = 8466, upload-time = "2025-06-14T20:54:18.329Z" }, { url = "https://files.pythonhosted.org/packages/76/f9/4ae982c7a1387b64954130b72187e140329b73c647acb4d6b6eb3c033d8d/pyobjc_framework_screensaver-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:f2d22293cf9d715e4692267a1678096afd6793c0519d9417cf77c8a6c706a543", size = 8402, upload-time = "2025-06-14T20:54:19.044Z" }, { url = "https://files.pythonhosted.org/packages/dc/ff/c2e83551474d3c401181ce1d859ebd0e0b1986ab8ee932d647debebbe7eb/pyobjc_framework_screensaver-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:46d65c1e14d35f287e7be351e2f98daf9489e31e7ca0d306e6102904ce6c40fb", size = 8419, upload-time = "2025-06-14T20:54:19.741Z" }, { url = "https://files.pythonhosted.org/packages/7a/b7/e633cd8e07bcfcd675155c7fd00f82cab0d09ca3edee0f568bcfc0ae8ea4/pyobjc_framework_screensaver-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:2c01a9646bc118445cbb117e7016bd1df9fe93a65db991ab5496d59b1a7bc66d", size = 8423, upload-time = "2025-06-14T20:54:20.447Z" }, @@ -6137,8 +6595,8 @@ name = "pyobjc-framework-screentime" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/82/33/ebed70a1de134de936bb9a12d5c76f24e1e335ff4964f9bb0af9b09607f1/pyobjc_framework_screentime-11.1.tar.gz", hash = "sha256:9bb8269456bbb674e1421182efe49f9168ceefd4e7c497047c7bf63e2f510a34", size = 14875, upload-time = "2025-06-14T20:58:26.179Z" } wheels = [ @@ -6150,11 +6608,12 @@ name = "pyobjc-framework-scriptingbridge" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/8e/c1/5b1dd01ff173df4c6676f97405113458918819cb2064c1735b61948e8800/pyobjc_framework_scriptingbridge-11.1.tar.gz", hash = "sha256:604445c759210a35d86d3e0dfcde0aac8e5e3e9d9e35759e0723952138843699", size = 23155, upload-time = "2025-06-14T20:58:26.812Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/e6/76/e173ca0b121693bdc6ac5797b30fd5771f31a682d15fd46402dc6f9ca3d1/pyobjc_framework_scriptingbridge-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:d6020c69c14872105852ff99aab7cd2b2671e61ded3faefb071dc40a8916c527", size = 8301, upload-time = "2025-06-14T20:54:29.082Z" }, { url = "https://files.pythonhosted.org/packages/c1/64/31849063e3e81b4c312ce838dc98f0409c09eb33bc79dbb5261cb994a4c4/pyobjc_framework_scriptingbridge-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:226ba12d9cbd504411b702323b0507dd1690e81b4ce657c5f0d8b998c46cf374", size = 8323, upload-time = "2025-06-14T20:54:30.105Z" }, { url = "https://files.pythonhosted.org/packages/d8/19/3003d4a137ce84fa8cb42a9c84f8c04e83c89749ab9cf93bc755016434b7/pyobjc_framework_scriptingbridge-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:c2ba0ad3d3e4e3c6a43fe3e84ab02c5c4e74000bb6f130ae47bf82a3dcd4af98", size = 8337, upload-time = "2025-06-14T20:54:30.81Z" }, { url = "https://files.pythonhosted.org/packages/e3/1c/0b90b4bcef7ea8fb80cb5f6fa0b73be075f2dffa2ba03580b37592dc8dad/pyobjc_framework_scriptingbridge-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:57f5401826e3a008d9cfb7c164187859cadc1b1f96194dc0a7c596f502548c26", size = 8485, upload-time = "2025-06-14T20:54:31.518Z" }, @@ -6167,8 +6626,8 @@ name = "pyobjc-framework-searchkit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreservices", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-coreservices" }, ] sdist = { url = "https://files.pythonhosted.org/packages/6e/20/61b73fddae0d1a94f5defb0cd4b4f391ec03bfcce7ebe830cb827d5e208a/pyobjc_framework_searchkit-11.1.tar.gz", hash = "sha256:13a194eefcf1359ce9972cd92f2aadddf103f3efb1b18fd578ba5367dff3c10c", size = 30918, upload-time = "2025-06-14T20:58:27.447Z" } wheels = [ @@ -6180,11 +6639,12 @@ name = "pyobjc-framework-security" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/ee/6f/ba50ed2d9c1192c67590a7cfefa44fc5f85c776d1e25beb224dec32081f6/pyobjc_framework_security-11.1.tar.gz", hash = "sha256:dabcee6987c6bae575e2d1ef0fcbe437678c4f49f1c25a4b131a5e960f31a2da", size = 302291, upload-time = "2025-06-14T20:58:28.506Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/ac/ae/1679770d9a1cf5f2fe532a3567a51f0c5ee09054ae2c4003ae8f3e11eea4/pyobjc_framework_security-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:d361231697486e97cfdafadf56709190696ab26a6a086dbba5f170e042e13daa", size = 41202, upload-time = "2025-06-14T20:54:36.255Z" }, { url = "https://files.pythonhosted.org/packages/35/16/7fc52ab1364ada5885bf9b4c9ea9da3ad892b847c9b86aa59e086b16fc11/pyobjc_framework_security-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:2eb4ba6d8b221b9ad5d010e026247e8aa26ee43dcaf327e848340ed227d22d7e", size = 41222, upload-time = "2025-06-14T20:54:37.032Z" }, { url = "https://files.pythonhosted.org/packages/3f/d8/cb20b4c4d15b2bdc7e39481159e50a933ddb87e4702d35060c254b316055/pyobjc_framework_security-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:158da3b2474e2567fd269531c4ee9f35b8ba4f1eccbd1fb4a37c85a18bf1243c", size = 41221, upload-time = "2025-06-14T20:54:37.803Z" }, { url = "https://files.pythonhosted.org/packages/cb/3c/d13d6870f5d66f5379565887b332f86f16d666dc50a1944d7e3a1462e76c/pyobjc_framework_security-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:141cc3ee08627ae0698264efc3dbbaf28d2255e0fe690e336eb8f0f387c4af01", size = 42099, upload-time = "2025-06-14T20:54:38.627Z" }, @@ -6197,9 +6657,9 @@ name = "pyobjc-framework-securityfoundation" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-security", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-security" }, ] sdist = { url = "https://files.pythonhosted.org/packages/5c/d4/19591dd0938a45b6d8711ef9ae5375b87c37a55b45d79c52d6f83a8d991f/pyobjc_framework_securityfoundation-11.1.tar.gz", hash = "sha256:b3c4cf70735a93e9df40f3a14478143959c415778f27be8c0dc9ae0c5b696b92", size = 13270, upload-time = "2025-06-14T20:58:29.304Z" } wheels = [ @@ -6211,12 +6671,13 @@ name = "pyobjc-framework-securityinterface" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-security", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-security" }, ] sdist = { url = "https://files.pythonhosted.org/packages/a1/be/c846651c3e7f38a637c40ae1bcda9f14237c2395637c3a188df4f733c727/pyobjc_framework_securityinterface-11.1.tar.gz", hash = "sha256:e7aa6373e525f3ae05d71276e821a6348c53fec9f812b90eec1dbadfcb507bc9", size = 37648, upload-time = "2025-06-14T20:58:29.932Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/1c/ec/8073f37f56870efb039970f1cc4536f279c5d476abab2e8654129789277f/pyobjc_framework_securityinterface-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:3e884620b22918d462764f0665f6ac0cbb8142bb160fcd27c4f4357f81da73b7", size = 10769, upload-time = "2025-06-14T20:54:43.344Z" }, { url = "https://files.pythonhosted.org/packages/6f/ab/48b8027a24f3f8924f5be5f97217961b4ed23e6be49b3bd94ee8a0d56a1e/pyobjc_framework_securityinterface-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:26056441b325029da06a7c7b8dd1a0c9a4ad7d980596c1b04d132a502b4cacc0", size = 10837, upload-time = "2025-06-14T20:54:44.052Z" }, { url = "https://files.pythonhosted.org/packages/31/2e/de226a3caa47b4a800c8e6289b9fe30c71f10985dbc37379d5bd0781b470/pyobjc_framework_securityinterface-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:708dd1d65309f3d4043ecaf152591c240601a5d3da7ae7a500f511c54317537b", size = 10851, upload-time = "2025-06-14T20:54:45.254Z" }, { url = "https://files.pythonhosted.org/packages/2a/9f/2d0c41ded78f9dc1e58d63b9d7ed55666b0d0d6ec78ce8938c7c4accdf59/pyobjc_framework_securityinterface-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:e9ebfb32177eb06f5c894be97c6af3802f09b9890fce8e0956cc0e680af4eafd", size = 11183, upload-time = "2025-06-14T20:54:46.325Z" }, @@ -6229,9 +6690,9 @@ name = "pyobjc-framework-securityui" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-security", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-security" }, ] sdist = { url = "https://files.pythonhosted.org/packages/07/5b/3b5585d56e0bcaba82e0661224bbc7aaf29fba6b10498971dbe08b2b490a/pyobjc_framework_securityui-11.1.tar.gz", hash = "sha256:e80c93e8a56bf89e4c0333047b9f8219752dd6de290681e9e2e2b2e26d69e92d", size = 12179, upload-time = "2025-06-14T20:58:30.928Z" } wheels = [ @@ -6243,9 +6704,9 @@ name = "pyobjc-framework-sensitivecontentanalysis" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/56/7b/e28f6b30d99e9d464427a07ada82b33cd3292f310bf478a1824051d066b9/pyobjc_framework_sensitivecontentanalysis-11.1.tar.gz", hash = "sha256:5b310515c7386f7afaf13e4632d7d9590688182bb7b563f8026c304bdf317308", size = 12796, upload-time = "2025-06-14T20:58:31.488Z" } wheels = [ @@ -6257,8 +6718,8 @@ name = "pyobjc-framework-servicemanagement" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/20/c6/32e11599d9d232311607b79eb2d1d21c52eaaf001599ea85f8771a933fa2/pyobjc_framework_servicemanagement-11.1.tar.gz", hash = "sha256:90a07164da49338480e0e135b445acc6ae7c08549a2037d1e512d2605fedd80a", size = 16645, upload-time = "2025-06-14T20:58:32.062Z" } wheels = [ @@ -6270,11 +6731,12 @@ name = "pyobjc-framework-sharedwithyou" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-sharedwithyoucore", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-sharedwithyoucore" }, ] sdist = { url = "https://files.pythonhosted.org/packages/fe/a5/e299fbd0c13d4fac9356459f21372f6eef4279d0fbc99ba316d88dfbbfb4/pyobjc_framework_sharedwithyou-11.1.tar.gz", hash = "sha256:ece3a28a3083d0bcad0ac95b01f0eb699b9d2d0c02c61305bfd402678753ff6e", size = 34216, upload-time = "2025-06-14T20:58:32.75Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/2e/23/7caefaddc58702da830d1cc4eb3c45ae82dcd605ea362126ab47ebd54f7d/pyobjc_framework_sharedwithyou-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:ce1c37d5f8cf5b0fe8a261e4e7256da677162fd5aa7b724e83532cdfe58d8f94", size = 8725, upload-time = "2025-06-14T20:54:53.179Z" }, { url = "https://files.pythonhosted.org/packages/57/44/211e1f18676e85d3656671fc0c954ced2cd007e55f1b0b6b2e4d0a0852eb/pyobjc_framework_sharedwithyou-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:99e1749187ae370be7b9c55dd076d1b8143f0d8db3e83f52540586f32e7abb33", size = 8740, upload-time = "2025-06-14T20:54:53.879Z" }, { url = "https://files.pythonhosted.org/packages/6f/da/1a2f2ae024e0206e1bcaba27aac2ebadf8bceb0ee05d03be2250e8c3d1a3/pyobjc_framework_sharedwithyou-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:c1a1770aa2c417f17010623414fb12943570baa726d8780dd7446ba5bcee8c3d", size = 8759, upload-time = "2025-06-14T20:54:54.631Z" }, { url = "https://files.pythonhosted.org/packages/48/85/d54efa902f5dd18a99478eb4fd0befda07dcd2672b1c3ed00ec88280fed0/pyobjc_framework_sharedwithyou-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:63b1cb673b844ebfeddc032d0539f913bbd6b67ab2a310a1fcff7842dba9c714", size = 8909, upload-time = "2025-06-14T20:54:55.359Z" }, @@ -6287,11 +6749,12 @@ name = "pyobjc-framework-sharedwithyoucore" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/79/a3/1ca6ff1b785772c7c5a38a7c017c6f971b1eda638d6a0aab3bbde18ac086/pyobjc_framework_sharedwithyoucore-11.1.tar.gz", hash = "sha256:790050d25f47bda662a9f008b17ca640ac2460f2559a56b17995e53f2f44ed73", size = 29459, upload-time = "2025-06-14T20:58:33.422Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/7a/df/08cfa01dcdb4655514b7a10eb7c40da2bdb7866078c761d6ed26c9f464f7/pyobjc_framework_sharedwithyoucore-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:9a7fe5ffcc65093ef7cd25903769ad557c3d3c5a59155a31f3f934cf555101e6", size = 8489, upload-time = "2025-06-14T20:54:59.631Z" }, { url = "https://files.pythonhosted.org/packages/b9/70/3b2e13fcf393aa434b1cf5c29c6aaf65ee5b8361254df3a920ed436bb5e4/pyobjc_framework_sharedwithyoucore-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:dd18c588b29de322c25821934d6aa6d2bbbdbb89b6a4efacdb248b4115fc488d", size = 8512, upload-time = "2025-06-14T20:55:00.411Z" }, { url = "https://files.pythonhosted.org/packages/b7/fc/feb2912fb9c7bbeb2099d2cb42ad28055c6e29504fcb92bd8a011fcba66a/pyobjc_framework_sharedwithyoucore-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:a3fb0e745fd022fed48cc9a5e0dcbf8d1abcb5bfc192150e3a2584f4351791fc", size = 8527, upload-time = "2025-06-14T20:55:01.112Z" }, { url = "https://files.pythonhosted.org/packages/f1/3f/0a8aa5d1b0eb07508c42e900d82a89e096b79fcafcd55e966d4d45476ae5/pyobjc_framework_sharedwithyoucore-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:6aee3df8bed97a74e1f79609f9884edcaab2d305db20bdcae39e47b3e513c559", size = 8672, upload-time = "2025-06-14T20:55:01.801Z" }, @@ -6304,11 +6767,12 @@ name = "pyobjc-framework-shazamkit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/de/08/ba739b97f1e441653bae8da5dd1e441bbbfa43940018d21edb60da7dd163/pyobjc_framework_shazamkit-11.1.tar.gz", hash = "sha256:c6e3c9ab8744d9319a89b78ae6f185bb5704efb68509e66d77bcd1f84a9446d6", size = 25797, upload-time = "2025-06-14T20:58:34.086Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/f8/b6/c03bc9aad7f15979b5d7f144baf5161c3c40e0bca194cce82e1bce0804a9/pyobjc_framework_shazamkit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:2fe6990d0ec1b40d4efd0d0e49c2deb65198f49b963e6215c608c140b3149151", size = 8540, upload-time = "2025-06-14T20:55:05.978Z" }, { url = "https://files.pythonhosted.org/packages/89/b7/594b8bdc406603a7a07cdb33f2be483fed16aebc35aeb087385fc9eca844/pyobjc_framework_shazamkit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:b323f5409b01711aa2b6e2113306084fab2cc83fa57a0c3d55bd5876358b68d8", size = 8560, upload-time = "2025-06-14T20:55:07.564Z" }, { url = "https://files.pythonhosted.org/packages/8c/fa/49ba8d1f9e257a12267773d6682e170fba441c7ea72d6fe58da9f4bf6f10/pyobjc_framework_shazamkit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:8bac17f285742e0f13a54c7085ef3035d8034ffc43d18d3d68fb41283c5064ff", size = 8573, upload-time = "2025-06-14T20:55:08.42Z" }, { url = "https://files.pythonhosted.org/packages/22/47/eeae6a31a41cbaf29081145b8f54ddebf68a5eba19626dd9ba2c00fdc92b/pyobjc_framework_shazamkit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:b3304c3a67e3722b895d874f215dd4277b49cedddb72fa780a791ef79e5c3d45", size = 8726, upload-time = "2025-06-14T20:55:09.447Z" }, @@ -6321,8 +6785,8 @@ name = "pyobjc-framework-social" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/07/2e/cc7707b7a40df392c579087947049f3e1f0e00597e7151ec411f654d8bef/pyobjc_framework_social-11.1.tar.gz", hash = "sha256:fbc09d7b00dad45b547f9b2329f4dcee3f5a50e2348de1870de0bd7be853a5b7", size = 14540, upload-time = "2025-06-14T20:58:35.116Z" } wheels = [ @@ -6334,8 +6798,8 @@ name = "pyobjc-framework-soundanalysis" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/e0/d4/b9497dbb57afdf0d22f61bb6e776a6f46cf9294c890448acde5b46dd61f3/pyobjc_framework_soundanalysis-11.1.tar.gz", hash = "sha256:42cd25b7e0f343d8b59367f72b5dae96cf65696bdb8eeead8d7424ed37aa1434", size = 16539, upload-time = "2025-06-14T20:58:35.813Z" } wheels = [ @@ -6347,11 +6811,12 @@ name = "pyobjc-framework-speech" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/67/76/2a1fd7637b2c662349ede09806e159306afeebfba18fb062ad053b41d811/pyobjc_framework_speech-11.1.tar.gz", hash = "sha256:d382977208c3710eacea89e05eae4578f1638bb5a7b667c06971e3d34e96845c", size = 41179, upload-time = "2025-06-14T20:58:36.43Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/b5/d3/c3b1d542c5ddc816924f02edf2ececcda226f35c91e95ed80f2632fbd91c/pyobjc_framework_speech-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:d3e0276a66d2fa4357959a6f6fb5def03f8e0fd3aa43711d6a81ab2573b9415f", size = 9171, upload-time = "2025-06-14T20:55:15.316Z" }, { url = "https://files.pythonhosted.org/packages/78/59/267f4699055beb39723ccbff70909ec3851e4adf17386f6ad85e5d983780/pyobjc_framework_speech-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:7726eff52cfa9cc7178ddcd1285cbc23b5f89ee55b4b850b0d2e90bb4f8e044b", size = 9180, upload-time = "2025-06-14T20:55:16.556Z" }, { url = "https://files.pythonhosted.org/packages/ea/a6/c394c3973c42d86c7b0c5c673c5ce65d10671e59e174f1ba4e7ab61ae5df/pyobjc_framework_speech-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:3c80670dbad921bf1d4954a9de29525acb53ee84e064a95fbbdfddff1db2f14f", size = 9198, upload-time = "2025-06-14T20:55:17.581Z" }, { url = "https://files.pythonhosted.org/packages/95/e9/3e47e2e3337080e45dd9153c7f465d16c40ce74b11ac53c4663554dab0bd/pyobjc_framework_speech-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:f19778a4ace37c538a34a10ac1f595c80b83489210e6fa60c703399aee264c7e", size = 9355, upload-time = "2025-06-14T20:55:18.27Z" }, @@ -6364,12 +6829,13 @@ name = "pyobjc-framework-spritekit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/16/02/2e253ba4f7fad6efe05fd5fcf44aede093f6c438d608d67c6c6623a1846d/pyobjc_framework_spritekit-11.1.tar.gz", hash = "sha256:914da6e846573cac8db5e403dec9a3e6f6edf5211f9b7e429734924d00f65108", size = 130297, upload-time = "2025-06-14T20:58:37.113Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/8f/83/1c874cffba691cf8c103e0fdf55b53d9749577794efb9fc30e4394ffef41/pyobjc_framework_spritekit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:1c8c94d37c054b6e3c22c237f6458c12649776e5ac921d066ab99dee2e580909", size = 17718, upload-time = "2025-06-14T20:55:22.543Z" }, { url = "https://files.pythonhosted.org/packages/f1/fe/39d92bf40ec7a6116f89fd95053321f7c00c50c10d82b9adfa0f9ebdb10c/pyobjc_framework_spritekit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:8b470a890db69e70ef428dfff88da499500fca9b2d44da7120dc588d13a2dbdb", size = 17776, upload-time = "2025-06-14T20:55:23.639Z" }, { url = "https://files.pythonhosted.org/packages/3f/c1/56490cce24e34e8c4c8c6a0f4746cd3a8bb5c2403e243c99f4dfa0cd147f/pyobjc_framework_spritekit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:2277e74d7be426181ae5ca7dd9d6c776426e8e825ad83b6046a7cb999015f27d", size = 17798, upload-time = "2025-06-14T20:55:24.407Z" }, { url = "https://files.pythonhosted.org/packages/75/dc/2ddd3aec417ebb92fd37f687c3e41e051d5e8b761bf2af63b1eb21e20cf4/pyobjc_framework_spritekit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:d6ea27fc202b40945729db50fdc6f75a0a11a07149febf4b99e14caf96ef33b0", size = 18068, upload-time = "2025-06-14T20:55:25.541Z" }, @@ -6382,11 +6848,12 @@ name = "pyobjc-framework-storekit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/44/a0/58cab9ebc9ac9282e1d4734b1987d1c3cd652b415ec3e678fcc5e735d279/pyobjc_framework_storekit-11.1.tar.gz", hash = "sha256:85acc30c0bfa120b37c3c5ac693fe9ad2c2e351ee7a1f9ea6f976b0c311ff164", size = 76421, upload-time = "2025-06-14T20:58:37.86Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/d4/30/7549a7bd2b068cd460792e09a66d88465aab2ac6fb2ddcf77b7bf5712eee/pyobjc_framework_storekit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:624105bd26a9ce5a097b3f96653e2700d33bb095828ed65ee0f4679b34d9f1e1", size = 11841, upload-time = "2025-06-14T20:55:29.735Z" }, { url = "https://files.pythonhosted.org/packages/ac/61/6404aac6857ea43798882333bcc26bfd3c9c3a1efc7a575cbf3e53538e2a/pyobjc_framework_storekit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:5ca3373272b6989917c88571ca170ce6d771180fe1a2b44c7643fe084569b93e", size = 11868, upload-time = "2025-06-14T20:55:30.454Z" }, { url = "https://files.pythonhosted.org/packages/6b/52/23acdf128a5b04059b2a3b38928afbff0afb50da439b597e25cdff1e9148/pyobjc_framework_storekit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:2e2607116b0d53d7fda2fc48e37b1deb1d26a60e7b723a6b7c391a3f48b2ac3b", size = 11882, upload-time = "2025-06-14T20:55:31.523Z" }, { url = "https://files.pythonhosted.org/packages/48/04/e7407f5c11a56c9a3a6b4328ec95dbf01ea6f88ac0ff5dc5089e9c8d0a61/pyobjc_framework_storekit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:4944bd1fd01f486623453b68accf4445d3c5686714820c8329a0c4e4672d6fff", size = 12129, upload-time = "2025-06-14T20:55:32.213Z" }, @@ -6399,8 +6866,8 @@ name = "pyobjc-framework-symbols" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/cd/af/7191276204bd3e7db1d0a3e490a869956606f77f7a303a04d92a5d0c3f7b/pyobjc_framework_symbols-11.1.tar.gz", hash = "sha256:0e09b7813ef2ebdca7567d3179807444dd60f3f393202b35b755d4e1baf99982", size = 13377, upload-time = "2025-06-14T20:58:38.542Z" } wheels = [ @@ -6412,12 +6879,13 @@ name = "pyobjc-framework-syncservices" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coredata", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coredata" }, ] sdist = { url = "https://files.pythonhosted.org/packages/69/45/cd9fa83ed1d75be7130fb8e41c375f05b5d6621737ec37e9d8da78676613/pyobjc_framework_syncservices-11.1.tar.gz", hash = "sha256:0f141d717256b98c17ec2eddbc983c4bd39dfa00dc0c31b4174742e73a8447fe", size = 57996, upload-time = "2025-06-14T20:58:39.146Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/f5/7e/60e184beafca85571cfa68d46a8f453a54edbc7d2eceb18163cfec438438/pyobjc_framework_syncservices-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:bc6159bda4597149c6999b052a35ffd9fc4817988293da6e54a1e073fa571653", size = 13464, upload-time = "2025-06-14T20:55:37.117Z" }, { url = "https://files.pythonhosted.org/packages/01/2b/6d7d65c08a9c51eed12eb7f83eaa48deaed621036f77221b3b0346c3f6c2/pyobjc_framework_syncservices-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:03124c8c7c7ce837f51e1c9bdcf84c6f1d5201f92c8a1c172ec34908d5e57415", size = 13496, upload-time = "2025-06-14T20:55:37.83Z" }, { url = "https://files.pythonhosted.org/packages/99/7b/88e89b81b5a6ee7da3b452c1619ec22936a8dd4384afd67f6019472655b8/pyobjc_framework_syncservices-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:711d493c7967682bee605c5909a49d268d9b3dd3cb7a71d8ab5dbe01a069eb44", size = 13511, upload-time = "2025-06-14T20:55:38.55Z" }, { url = "https://files.pythonhosted.org/packages/bf/3c/6056913cea9fce52f77649b81c54c6282f2eb1b26e7ca17c5c1015123375/pyobjc_framework_syncservices-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:a0ff222472b2cb5c345c92ae4bde245f4181843379f4fd9462cd5c096ed7b2f1", size = 13681, upload-time = "2025-06-14T20:55:39.279Z" }, @@ -6430,11 +6898,12 @@ name = "pyobjc-framework-systemconfiguration" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/e2/3d/41590c0afc72e93d911348fbde0c9c1071ff53c6f86df42df64b21174bb9/pyobjc_framework_systemconfiguration-11.1.tar.gz", hash = "sha256:f30ed0e9a8233fecb06522e67795918ab230ddcc4a18e15494eff7532f4c3ae1", size = 143410, upload-time = "2025-06-14T20:58:39.917Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/64/9b/8fe26a9ac85898fa58f6206f357745ec44cd95b63786503ce05c382344ce/pyobjc_framework_systemconfiguration-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:d12d5078611c905162bc951dffbb2a989b0dfd156952ba1884736c8dcbe38f7f", size = 21732, upload-time = "2025-06-14T20:55:43.951Z" }, { url = "https://files.pythonhosted.org/packages/b9/61/0e9841bf1c7597f380a6dcefcc9335b6a909f20d9bdf07910cddc8552b42/pyobjc_framework_systemconfiguration-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:6881929b828a566bf1349f09db4943e96a2b33f42556e1f7f6f28b192420f6fc", size = 21639, upload-time = "2025-06-14T20:55:44.678Z" }, { url = "https://files.pythonhosted.org/packages/1c/eb/4480a1ab5baba4b9e75bb7f4f667073db5702cf521ddc99941575167585d/pyobjc_framework_systemconfiguration-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:ab2ff52e4228f42182b7ef398d0da504f9f8f4a889963422af9aa1f495668db2", size = 21646, upload-time = "2025-06-14T20:55:45.426Z" }, { url = "https://files.pythonhosted.org/packages/b7/00/40d433a160c4d3c156008d375aa0279f46343c69cecb464e59ab1a0b3063/pyobjc_framework_systemconfiguration-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:c236f19cadc9fff56c0afb3e4ad6f8c8e11c5679e31ed413fe6876bf2ea73353", size = 22059, upload-time = "2025-06-14T20:55:46.203Z" }, @@ -6447,11 +6916,12 @@ name = "pyobjc-framework-systemextensions" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/b4/57/4609fd9183383616b1e643c2489ad774335f679523a974b9ce346a6d4d5b/pyobjc_framework_systemextensions-11.1.tar.gz", hash = "sha256:8ff9f0aad14dcdd07dd47545c1dd20df7a286306967b0a0232c81fcc382babe6", size = 23062, upload-time = "2025-06-14T20:58:40.686Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/10/53/0fb6a200383fa98001ffa66b4f6344c68ccd092506699a353b30f18d7094/pyobjc_framework_systemextensions-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:7e742ae51cdd86c0e609fe47189ea446de98d13b235b0a138a3f2e37e98cd359", size = 9125, upload-time = "2025-06-14T20:55:50.431Z" }, { url = "https://files.pythonhosted.org/packages/76/40/d9be444b39ec12d68b5e4f712b71d6c00d654936ff5744ea380c1bfabf06/pyobjc_framework_systemextensions-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:3a2b1e84e4a118bfe13efb9f2888b065dc937e2a7e60afd4d0a82b51b8301a10", size = 9130, upload-time = "2025-06-14T20:55:51.127Z" }, { url = "https://files.pythonhosted.org/packages/7d/23/f615d69b3a86e75af234149fc12c8dfde8f346148e4eb185696a9c87e824/pyobjc_framework_systemextensions-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:2ed65857244f18b88107e5d3ea8ea21c9da662490895b430e376423ee7c0b963", size = 9154, upload-time = "2025-06-14T20:55:51.798Z" }, { url = "https://files.pythonhosted.org/packages/3c/08/2719c95d57f404d880c80da4250ff122ff318307e7a9b8ceef54d56fdb7f/pyobjc_framework_systemextensions-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:9aa7595de4f8f6a252c50419c0343f7326c6a4de47da5b933a17880d1cadfa36", size = 9315, upload-time = "2025-06-14T20:55:52.494Z" }, @@ -6464,8 +6934,8 @@ name = "pyobjc-framework-threadnetwork" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/e7/a4/5400a222ced0e4f077a8f4dd0188e08e2af4762e72ed0ed39f9d27feefc9/pyobjc_framework_threadnetwork-11.1.tar.gz", hash = "sha256:73a32782f44b61ca0f8a4a9811c36b1ca1cdcf96c8a3ba4de35d8e8e58a86ad5", size = 13572, upload-time = "2025-06-14T20:58:41.311Z" } wheels = [ @@ -6477,8 +6947,8 @@ name = "pyobjc-framework-uniformtypeidentifiers" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/c5/4f/066ed1c69352ccc29165f45afb302f8c9c2b5c6f33ee3abfa41b873c07e5/pyobjc_framework_uniformtypeidentifiers-11.1.tar.gz", hash = "sha256:86c499bec8953aeb0c95af39b63f2592832384f09f12523405650b5d5f1ed5e9", size = 20599, upload-time = "2025-06-14T20:58:41.945Z" } wheels = [ @@ -6490,11 +6960,12 @@ name = "pyobjc-framework-usernotifications" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/b4/4c/e7e180fcd06c246c37f218bcb01c40ea0213fde5ace3c09d359e60dcaafd/pyobjc_framework_usernotifications-11.1.tar.gz", hash = "sha256:38fc763afa7854b41ddfca8803f679a7305d278af8a7ad02044adc1265699996", size = 55428, upload-time = "2025-06-14T20:58:42.572Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/c1/bb/ae9c9301a86b7c0c26583c59ac761374cb6928c3d34cae514939e93e44b1/pyobjc_framework_usernotifications-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:7140d337dd9dc3635add2177086429fdd6ef24970935b22fffdc5ec7f02ebf60", size = 9599, upload-time = "2025-06-14T20:55:58.051Z" }, { url = "https://files.pythonhosted.org/packages/03/af/a54e343a7226dc65a65f7a561c060f8c96cb9f92f41ce2242d20d82ae594/pyobjc_framework_usernotifications-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:ce6006989fd4a59ec355f6797ccdc9946014ea5241ff7875854799934dbba901", size = 9606, upload-time = "2025-06-14T20:55:59.088Z" }, { url = "https://files.pythonhosted.org/packages/d1/fb/ae1ea7f7c511714c1502fa9c4856c6b3dfe110ff7cc094070fec5ad496b8/pyobjc_framework_usernotifications-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:9efa3004059a8fe3f3c52f638f0401dbcdbc7b2f539587c8868da2486a64d674", size = 9628, upload-time = "2025-06-14T20:55:59.807Z" }, { url = "https://files.pythonhosted.org/packages/e5/46/4934930848d74aeea32435378154501fcb3dbd77f759c4aa09b99e094310/pyobjc_framework_usernotifications-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:62a4bd242b761a6f00a4374a369391346d225d68be07691e042ec7db452084c8", size = 9793, upload-time = "2025-06-14T20:56:00.496Z" }, @@ -6507,9 +6978,9 @@ name = "pyobjc-framework-usernotificationsui" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-usernotifications", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-usernotifications" }, ] sdist = { url = "https://files.pythonhosted.org/packages/d2/c4/03d97bd3adcee9b857533cb42967df0d019f6a034adcdbcfca2569d415b2/pyobjc_framework_usernotificationsui-11.1.tar.gz", hash = "sha256:18e0182bddd10381884530d6a28634ebb3280912592f8f2ad5bac2a9308c6a65", size = 14123, upload-time = "2025-06-14T20:58:43.267Z" } wheels = [ @@ -6521,8 +6992,8 @@ name = "pyobjc-framework-videosubscriberaccount" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/aa/00/cd9d93d06204bbb7fe68fb97022b0dd4ecdf8af3adb6d70a41e22c860d55/pyobjc_framework_videosubscriberaccount-11.1.tar.gz", hash = "sha256:2dd78586260fcee51044e129197e8bf2e157176e02babeec2f873afa4235d8c6", size = 28856, upload-time = "2025-06-14T20:58:43.903Z" } wheels = [ @@ -6534,13 +7005,14 @@ name = "pyobjc-framework-videotoolbox" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coremedia", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coremedia" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/e5/e3/df9096f54ae1f27cab8f922ee70cbda5d80f8c1d12734c38580829858133/pyobjc_framework_videotoolbox-11.1.tar.gz", hash = "sha256:a27985656e1b639cdb102fcc727ebc39f71bb1a44cdb751c8c80cc9fe938f3a9", size = 88551, upload-time = "2025-06-14T20:58:44.566Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/0b/41/fda951f1c734a68d7bf46ecc03bfff376a690ad771029c4289ba0423a52e/pyobjc_framework_videotoolbox-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:94c17bffe0f4692db2e7641390dfdcd0f73ddbb0afa6c81ef504219be0777930", size = 17325, upload-time = "2025-06-14T20:56:07.719Z" }, { url = "https://files.pythonhosted.org/packages/1f/cf/569babadbf1f9598f62c400ee02da19d4ab5f36276978c81080999399df9/pyobjc_framework_videotoolbox-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:c55285c3c78183fd2a092d582e30b562777a82985cccca9e7e99a0aff2601591", size = 17432, upload-time = "2025-06-14T20:56:08.457Z" }, { url = "https://files.pythonhosted.org/packages/b1/32/1a3d1a448d3cbcaf5c2a4ceaaad32817df21739099e187bbe6e3fd03d6fd/pyobjc_framework_videotoolbox-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:65a96385e80cb9ad3eab7d1f3156452ff805a925c9ca287ff1491a97cca191ba", size = 17450, upload-time = "2025-06-14T20:56:09.239Z" }, { url = "https://files.pythonhosted.org/packages/64/d9/530b561bea7b8690ca976570466e42fa226fc60fe3fef3d14beaf719dc99/pyobjc_framework_videotoolbox-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:e282cb07f6a51647ac19a3b5d31e26f1619285bac24171e403921d671e4756d9", size = 17668, upload-time = "2025-06-14T20:56:09.98Z" }, @@ -6553,11 +7025,12 @@ name = "pyobjc-framework-virtualization" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/f1/ff/57214e8f42755eeaad516a7e673dae4341b8742005d368ecc22c7a790b0b/pyobjc_framework_virtualization-11.1.tar.gz", hash = "sha256:4221ee5eb669e43a2ff46e04178bec149af2d65205deb5d4db5fa62ea060e022", size = 78633, upload-time = "2025-06-14T20:58:45.358Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/64/8b/5eeabfd08d5e6801010496969c1b67517bbda348ff0578ca5f075aa58926/pyobjc_framework_virtualization-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:c2a812da4c995e1f8076678130d0b0a63042aa48219f8fb43b70e13eabcbdbc2", size = 13054, upload-time = "2025-06-14T20:56:13.866Z" }, { url = "https://files.pythonhosted.org/packages/c8/4f/fe1930f4ce2c7d2f4c34bb53adf43f412bc91364e8e4cb450a7c8a6b8b59/pyobjc_framework_virtualization-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:59df6702b3e63200752be7d9c0dc590cb4c3b699c886f9a8634dd224c74b3c3c", size = 13084, upload-time = "2025-06-14T20:56:14.617Z" }, { url = "https://files.pythonhosted.org/packages/4f/33/6d9f4177983d8894d217b212c25cbb91004cb1103c865961f03360aff68b/pyobjc_framework_virtualization-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:12a5ef32d2b7a56b675ea34fcb68bb9dddb7cf2c0a5ac5131f35551767bdacf1", size = 13093, upload-time = "2025-06-14T20:56:15.322Z" }, { url = "https://files.pythonhosted.org/packages/78/af/b9e1b6fa9afb4a6557e3bc1e7e8409108ecf416db5a8a9c6ef4d25dd16af/pyobjc_framework_virtualization-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:790bd2e42e8c5890319f8c576d5e171f87f95655e6fc55cf19a5f85f9e23558a", size = 13284, upload-time = "2025-06-14T20:56:16.052Z" }, @@ -6570,13 +7043,14 @@ name = "pyobjc-framework-vision" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-coreml", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-quartz", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, + { name = "pyobjc-framework-coreml" }, + { name = "pyobjc-framework-quartz" }, ] sdist = { url = "https://files.pythonhosted.org/packages/40/a8/7128da4d0a0103cabe58910a7233e2f98d18c590b1d36d4b3efaaedba6b9/pyobjc_framework_vision-11.1.tar.gz", hash = "sha256:26590512ee7758da3056499062a344b8a351b178be66d4b719327884dde4216b", size = 133721, upload-time = "2025-06-14T20:58:46.095Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/10/69/a745a5491d7af6034ac9e0d627e7b41b42978df0a469b86cdf372ba8917f/pyobjc_framework_vision-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:bfbde43c9d4296e1d26548b6d30ae413e2029425968cd8bce96d3c5a735e8f2c", size = 21657, upload-time = "2025-06-14T20:56:20.265Z" }, { url = "https://files.pythonhosted.org/packages/a2/b5/54c0227a695557ea3065bc035b20a5c256f6f3b861e095eee1ec4b4d8cee/pyobjc_framework_vision-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:df076c3e3e672887182953efc934c1f9683304737e792ec09a29bfee90d2e26a", size = 16829, upload-time = "2025-06-14T20:56:21.355Z" }, { url = "https://files.pythonhosted.org/packages/20/cf/58ace43525ab073b39df9a740e855ebe83ed78f041d619644af3c60d9013/pyobjc_framework_vision-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:1e5617e37dd2a7cff5e69e9aab039ea74b39ccdc528f6c828f2b60c1254e61e5", size = 16852, upload-time = "2025-06-14T20:56:22.081Z" }, { url = "https://files.pythonhosted.org/packages/99/c3/4aeaac1d53766125870aadbe3a4a02d4bca373b18753d32281f77e095976/pyobjc_framework_vision-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:dfd148a6df30ac70a9c41dd90a6c8f8c7f339bd9ca6829629a902f272e02b6b4", size = 16993, upload-time = "2025-06-14T20:56:22.818Z" }, @@ -6589,11 +7063,12 @@ name = "pyobjc-framework-webkit" version = "11.1" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "pyobjc-core", marker = "sys_platform == 'darwin'" }, - { name = "pyobjc-framework-cocoa", marker = "sys_platform == 'darwin'" }, + { name = "pyobjc-core" }, + { name = "pyobjc-framework-cocoa" }, ] sdist = { url = "https://files.pythonhosted.org/packages/92/04/fb3d0b68994f7e657ef00c1ac5fc1c04ae2fc7ea581d647f5ae1f6739b14/pyobjc_framework_webkit-11.1.tar.gz", hash = "sha256:27e701c7aaf4f24fc7e601a128e2ef14f2773f4ab071b9db7438dc5afb5053ae", size = 717102, upload-time = "2025-06-14T20:58:47.461Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/8d/b6/d62c01a83c22619edf2379a6941c9f6b7aee01c565b9c1170696f85cba95/pyobjc_framework_webkit-11.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:10ec89d727af8f216ba5911ff5553f84a5b660f5ddf75b07788e3a439c281165", size = 51406, upload-time = "2025-06-14T20:56:26.845Z" }, { url = "https://files.pythonhosted.org/packages/8a/7e/fa2c18c0c0f9321e5036e54b9da7a196956b531e50fe1a76e7dfdbe8fac2/pyobjc_framework_webkit-11.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:1a6e6f64ca53c4953f17e808ecac11da288d9a6ade738156ba161732a5e0c96a", size = 51464, upload-time = "2025-06-14T20:56:27.653Z" }, { url = "https://files.pythonhosted.org/packages/7a/8d/66561d95b00b8e57a9d5725ae34a8d9ca7ebeb776f13add989421ff90279/pyobjc_framework_webkit-11.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:1d01008756c3912b02b7c02f62432467fbee90a93e3b8e31fa351b4ca97c9c98", size = 51495, upload-time = "2025-06-14T20:56:28.464Z" }, { url = "https://files.pythonhosted.org/packages/db/c3/e790b518f84ea8dfbe32a9dcb4d8611b532de08057d19f853c1890110938/pyobjc_framework_webkit-11.1-cp313-cp313t-macosx_10_13_universal2.whl", hash = "sha256:864f9867a2caaeaeb83e5c0fa3dcf78169622233cf93a9a5eeb7012ced3b8076", size = 51985, upload-time = "2025-06-14T20:56:29.303Z" }, @@ -6792,6 +7267,9 @@ name = "pywin32" version = "311" source = { registry = "https://pypi.org/simple" } wheels = [ + { url = "https://files.pythonhosted.org/packages/7c/af/449a6a91e5d6db51420875c54f6aff7c97a86a3b13a0b4f1a5c13b988de3/pywin32-311-cp311-cp311-win32.whl", hash = "sha256:184eb5e436dea364dcd3d2316d577d625c0351bf237c4e9a5fabbcfa5a58b151", size = 8697031, upload-time = "2025-07-14T20:13:13.266Z" }, + { url = "https://files.pythonhosted.org/packages/51/8f/9bb81dd5bb77d22243d33c8397f09377056d5c687aa6d4042bea7fbf8364/pywin32-311-cp311-cp311-win_amd64.whl", hash = "sha256:3ce80b34b22b17ccbd937a6e78e7225d80c52f5ab9940fe0506a1a16f3dab503", size = 9508308, upload-time = "2025-07-14T20:13:15.147Z" }, + { url = "https://files.pythonhosted.org/packages/44/7b/9c2ab54f74a138c491aba1b1cd0795ba61f144c711daea84a88b63dc0f6c/pywin32-311-cp311-cp311-win_arm64.whl", hash = "sha256:a733f1388e1a842abb67ffa8e7aad0e70ac519e09b0f6a784e65a136ec7cefd2", size = 8703930, upload-time = "2025-07-14T20:13:16.945Z" }, { url = "https://files.pythonhosted.org/packages/e7/ab/01ea1943d4eba0f850c3c61e78e8dd59757ff815ff3ccd0a84de5f541f42/pywin32-311-cp312-cp312-win32.whl", hash = "sha256:750ec6e621af2b948540032557b10a2d43b0cee2ae9758c54154d711cc852d31", size = 8706543, upload-time = "2025-07-14T20:13:20.765Z" }, { url = "https://files.pythonhosted.org/packages/d1/a8/a0e8d07d4d051ec7502cd58b291ec98dcc0c3fff027caad0470b72cfcc2f/pywin32-311-cp312-cp312-win_amd64.whl", hash = "sha256:b8c095edad5c211ff31c05223658e71bf7116daa0ecf3ad85f3201ea3190d067", size = 9495040, upload-time = "2025-07-14T20:13:22.543Z" }, { url = "https://files.pythonhosted.org/packages/ba/3a/2ae996277b4b50f17d61f0603efd8253cb2d79cc7ae159468007b586396d/pywin32-311-cp312-cp312-win_arm64.whl", hash = "sha256:e286f46a9a39c4a18b319c28f59b61de793654af2f395c102b4f819e584b5852", size = 8710102, upload-time = "2025-07-14T20:13:24.682Z" }, @@ -6809,6 +7287,7 @@ version = "3.0.2" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/f3/bb/a7cc2967c5c4eceb6cc49cfe39447d4bfc56e6c865e7c2249b6eb978935f/pywinpty-3.0.2.tar.gz", hash = "sha256:1505cc4cb248af42cb6285a65c9c2086ee9e7e574078ee60933d5d7fa86fb004", size = 30669, upload-time = "2025-10-03T21:16:29.205Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/a6/a1/409c1651c9f874d598c10f51ff586c416625601df4bca315d08baec4c3e3/pywinpty-3.0.2-cp311-cp311-win_amd64.whl", hash = "sha256:327790d70e4c841ebd9d0f295a780177149aeb405bca44c7115a3de5c2054b23", size = 2050304, upload-time = "2025-10-03T21:19:29.466Z" }, { url = "https://files.pythonhosted.org/packages/02/4e/1098484e042c9485f56f16eb2b69b43b874bd526044ee401512234cf9e04/pywinpty-3.0.2-cp312-cp312-win_amd64.whl", hash = "sha256:99fdd9b455f0ad6419aba6731a7a0d2f88ced83c3c94a80ff9533d95fa8d8a9e", size = 2050391, upload-time = "2025-10-03T21:19:01.642Z" }, { url = "https://files.pythonhosted.org/packages/fc/19/b757fe28008236a4a713e813283721b8a40aa60cd7d3f83549f2e25a3155/pywinpty-3.0.2-cp313-cp313-win_amd64.whl", hash = "sha256:18f78b81e4cfee6aabe7ea8688441d30247b73e52cd9657138015c5f4ee13a51", size = 2050057, upload-time = "2025-10-03T21:19:26.732Z" }, { url = "https://files.pythonhosted.org/packages/cb/44/cbae12ecf6f4fa4129c36871fd09c6bef4f98d5f625ecefb5e2449765508/pywinpty-3.0.2-cp313-cp313t-win_amd64.whl", hash = "sha256:663383ecfab7fc382cc97ea5c4f7f0bb32c2f889259855df6ea34e5df42d305b", size = 2049874, upload-time = "2025-10-03T21:18:53.923Z" }, @@ -6822,6 +7301,15 @@ version = "6.0.3" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/05/8e/961c0007c59b8dd7729d542c61a4d537767a59645b82a0b521206e1e25c2/pyyaml-6.0.3.tar.gz", hash = "sha256:d76623373421df22fb4cf8817020cbb7ef15c725b9d5e45f17e189bfc384190f", size = 130960, upload-time = "2025-09-25T21:33:16.546Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/6d/16/a95b6757765b7b031c9374925bb718d55e0a9ba8a1b6a12d25962ea44347/pyyaml-6.0.3-cp311-cp311-macosx_10_13_x86_64.whl", hash = "sha256:44edc647873928551a01e7a563d7452ccdebee747728c1080d881d68af7b997e", size = 185826, upload-time = "2025-09-25T21:31:58.655Z" }, + { url = "https://files.pythonhosted.org/packages/16/19/13de8e4377ed53079ee996e1ab0a9c33ec2faf808a4647b7b4c0d46dd239/pyyaml-6.0.3-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:652cb6edd41e718550aad172851962662ff2681490a8a711af6a4d288dd96824", size = 175577, upload-time = "2025-09-25T21:32:00.088Z" }, + { url = "https://files.pythonhosted.org/packages/0c/62/d2eb46264d4b157dae1275b573017abec435397aa59cbcdab6fc978a8af4/pyyaml-6.0.3-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:10892704fc220243f5305762e276552a0395f7beb4dbf9b14ec8fd43b57f126c", size = 775556, upload-time = "2025-09-25T21:32:01.31Z" }, + { url = "https://files.pythonhosted.org/packages/10/cb/16c3f2cf3266edd25aaa00d6c4350381c8b012ed6f5276675b9eba8d9ff4/pyyaml-6.0.3-cp311-cp311-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:850774a7879607d3a6f50d36d04f00ee69e7fc816450e5f7e58d7f17f1ae5c00", size = 882114, upload-time = "2025-09-25T21:32:03.376Z" }, + { url = "https://files.pythonhosted.org/packages/71/60/917329f640924b18ff085ab889a11c763e0b573da888e8404ff486657602/pyyaml-6.0.3-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:b8bb0864c5a28024fac8a632c443c87c5aa6f215c0b126c449ae1a150412f31d", size = 806638, upload-time = "2025-09-25T21:32:04.553Z" }, + { url = "https://files.pythonhosted.org/packages/dd/6f/529b0f316a9fd167281a6c3826b5583e6192dba792dd55e3203d3f8e655a/pyyaml-6.0.3-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:1d37d57ad971609cf3c53ba6a7e365e40660e3be0e5175fa9f2365a379d6095a", size = 767463, upload-time = "2025-09-25T21:32:06.152Z" }, + { url = "https://files.pythonhosted.org/packages/f2/6a/b627b4e0c1dd03718543519ffb2f1deea4a1e6d42fbab8021936a4d22589/pyyaml-6.0.3-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:37503bfbfc9d2c40b344d06b2199cf0e96e97957ab1c1b546fd4f87e53e5d3e4", size = 794986, upload-time = "2025-09-25T21:32:07.367Z" }, + { url = "https://files.pythonhosted.org/packages/45/91/47a6e1c42d9ee337c4839208f30d9f09caa9f720ec7582917b264defc875/pyyaml-6.0.3-cp311-cp311-win32.whl", hash = "sha256:8098f252adfa6c80ab48096053f512f2321f0b998f98150cea9bd23d83e1467b", size = 142543, upload-time = "2025-09-25T21:32:08.95Z" }, + { url = "https://files.pythonhosted.org/packages/da/e3/ea007450a105ae919a72393cb06f122f288ef60bba2dc64b26e2646fa315/pyyaml-6.0.3-cp311-cp311-win_amd64.whl", hash = "sha256:9f3bfb4965eb874431221a3ff3fdcddc7e74e3b07799e0e84ca4a0f867d449bf", size = 158763, upload-time = "2025-09-25T21:32:09.96Z" }, { url = "https://files.pythonhosted.org/packages/d1/33/422b98d2195232ca1826284a76852ad5a86fe23e31b009c9886b2d0fb8b2/pyyaml-6.0.3-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:7f047e29dcae44602496db43be01ad42fc6f1cc0d8cd6c83d342306c32270196", size = 182063, upload-time = "2025-09-25T21:32:11.445Z" }, { url = "https://files.pythonhosted.org/packages/89/a0/6cf41a19a1f2f3feab0e9c0b74134aa2ce6849093d5517a0c550fe37a648/pyyaml-6.0.3-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:fc09d0aa354569bc501d4e787133afc08552722d3ab34836a80547331bb5d4a0", size = 173973, upload-time = "2025-09-25T21:32:12.492Z" }, { url = "https://files.pythonhosted.org/packages/ed/23/7a778b6bd0b9a8039df8b1b1d80e2e2ad78aa04171592c8a5c43a56a6af4/pyyaml-6.0.3-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:9149cad251584d5fb4981be1ecde53a1ca46c891a79788c0df828d2f166bda28", size = 775116, upload-time = "2025-09-25T21:32:13.652Z" }, @@ -6871,6 +7359,16 @@ dependencies = [ ] sdist = { url = "https://files.pythonhosted.org/packages/04/0b/3c9baedbdf613ecaa7aa07027780b8867f57b6293b6ee50de316c9f3222b/pyzmq-27.1.0.tar.gz", hash = "sha256:ac0765e3d44455adb6ddbf4417dcce460fc40a05978c08efdf2948072f6db540", size = 281750, upload-time = "2025-09-08T23:10:18.157Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/06/5d/305323ba86b284e6fcb0d842d6adaa2999035f70f8c38a9b6d21ad28c3d4/pyzmq-27.1.0-cp311-cp311-macosx_10_15_universal2.whl", hash = "sha256:226b091818d461a3bef763805e75685e478ac17e9008f49fce2d3e52b3d58b86", size = 1333328, upload-time = "2025-09-08T23:07:45.946Z" }, + { url = "https://files.pythonhosted.org/packages/bd/a0/fc7e78a23748ad5443ac3275943457e8452da67fda347e05260261108cbc/pyzmq-27.1.0-cp311-cp311-manylinux2014_i686.manylinux_2_17_i686.whl", hash = "sha256:0790a0161c281ca9723f804871b4027f2e8b5a528d357c8952d08cd1a9c15581", size = 908803, upload-time = "2025-09-08T23:07:47.551Z" }, + { url = "https://files.pythonhosted.org/packages/7e/22/37d15eb05f3bdfa4abea6f6d96eb3bb58585fbd3e4e0ded4e743bc650c97/pyzmq-27.1.0-cp311-cp311-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:c895a6f35476b0c3a54e3eb6ccf41bf3018de937016e6e18748317f25d4e925f", size = 668836, upload-time = "2025-09-08T23:07:49.436Z" }, + { url = "https://files.pythonhosted.org/packages/b1/c4/2a6fe5111a01005fc7af3878259ce17684fabb8852815eda6225620f3c59/pyzmq-27.1.0-cp311-cp311-manylinux_2_26_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:5bbf8d3630bf96550b3be8e1fc0fea5cbdc8d5466c1192887bd94869da17a63e", size = 857038, upload-time = "2025-09-08T23:07:51.234Z" }, + { url = "https://files.pythonhosted.org/packages/cb/eb/bfdcb41d0db9cd233d6fb22dc131583774135505ada800ebf14dfb0a7c40/pyzmq-27.1.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:15c8bd0fe0dabf808e2d7a681398c4e5ded70a551ab47482067a572c054c8e2e", size = 1657531, upload-time = "2025-09-08T23:07:52.795Z" }, + { url = "https://files.pythonhosted.org/packages/ab/21/e3180ca269ed4a0de5c34417dfe71a8ae80421198be83ee619a8a485b0c7/pyzmq-27.1.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:bafcb3dd171b4ae9f19ee6380dfc71ce0390fefaf26b504c0e5f628d7c8c54f2", size = 2034786, upload-time = "2025-09-08T23:07:55.047Z" }, + { url = "https://files.pythonhosted.org/packages/3b/b1/5e21d0b517434b7f33588ff76c177c5a167858cc38ef740608898cd329f2/pyzmq-27.1.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:e829529fcaa09937189178115c49c504e69289abd39967cd8a4c215761373394", size = 1894220, upload-time = "2025-09-08T23:07:57.172Z" }, + { url = "https://files.pythonhosted.org/packages/03/f2/44913a6ff6941905efc24a1acf3d3cb6146b636c546c7406c38c49c403d4/pyzmq-27.1.0-cp311-cp311-win32.whl", hash = "sha256:6df079c47d5902af6db298ec92151db82ecb557af663098b92f2508c398bb54f", size = 567155, upload-time = "2025-09-08T23:07:59.05Z" }, + { url = "https://files.pythonhosted.org/packages/23/6d/d8d92a0eb270a925c9b4dd039c0b4dc10abc2fcbc48331788824ef113935/pyzmq-27.1.0-cp311-cp311-win_amd64.whl", hash = "sha256:190cbf120fbc0fc4957b56866830def56628934a9d112aec0e2507aa6a032b97", size = 633428, upload-time = "2025-09-08T23:08:00.663Z" }, + { url = "https://files.pythonhosted.org/packages/ae/14/01afebc96c5abbbd713ecfc7469cfb1bc801c819a74ed5c9fad9a48801cb/pyzmq-27.1.0-cp311-cp311-win_arm64.whl", hash = "sha256:eca6b47df11a132d1745eb3b5b5e557a7dae2c303277aa0e69c6ba91b8736e07", size = 559497, upload-time = "2025-09-08T23:08:02.15Z" }, { url = "https://files.pythonhosted.org/packages/92/e7/038aab64a946d535901103da16b953c8c9cc9c961dadcbf3609ed6428d23/pyzmq-27.1.0-cp312-abi3-macosx_10_15_universal2.whl", hash = "sha256:452631b640340c928fa343801b0d07eb0c3789a5ffa843f6e1a9cee0ba4eb4fc", size = 1306279, upload-time = "2025-09-08T23:08:03.807Z" }, { url = "https://files.pythonhosted.org/packages/e8/5e/c3c49fdd0f535ef45eefcc16934648e9e59dace4a37ee88fc53f6cd8e641/pyzmq-27.1.0-cp312-abi3-manylinux2014_i686.manylinux_2_17_i686.whl", hash = "sha256:1c179799b118e554b66da67d88ed66cd37a169f1f23b5d9f0a231b4e8d44a113", size = 895645, upload-time = "2025-09-08T23:08:05.301Z" }, { url = "https://files.pythonhosted.org/packages/f8/e5/b0b2504cb4e903a74dcf1ebae157f9e20ebb6ea76095f6cfffea28c42ecd/pyzmq-27.1.0-cp312-abi3-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:3837439b7f99e60312f0c926a6ad437b067356dc2bc2ec96eb395fd0fe804233", size = 652574, upload-time = "2025-09-08T23:08:06.828Z" }, @@ -6903,6 +7401,11 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/c4/59/a5f38970f9bf07cee96128de79590bb354917914a9be11272cfc7ff26af0/pyzmq-27.1.0-cp314-cp314t-win32.whl", hash = "sha256:1f0b2a577fd770aa6f053211a55d1c47901f4d537389a034c690291485e5fe92", size = 587472, upload-time = "2025-09-08T23:08:58.18Z" }, { url = "https://files.pythonhosted.org/packages/70/d8/78b1bad170f93fcf5e3536e70e8fadac55030002275c9a29e8f5719185de/pyzmq-27.1.0-cp314-cp314t-win_amd64.whl", hash = "sha256:19c9468ae0437f8074af379e986c5d3d7d7bfe033506af442e8c879732bedbe0", size = 661401, upload-time = "2025-09-08T23:08:59.802Z" }, { url = "https://files.pythonhosted.org/packages/81/d6/4bfbb40c9a0b42fc53c7cf442f6385db70b40f74a783130c5d0a5aa62228/pyzmq-27.1.0-cp314-cp314t-win_arm64.whl", hash = "sha256:dc5dbf68a7857b59473f7df42650c621d7e8923fb03fa74a526890f4d33cc4d7", size = 575170, upload-time = "2025-09-08T23:09:01.418Z" }, + { url = "https://files.pythonhosted.org/packages/4c/c6/c4dcdecdbaa70969ee1fdced6d7b8f60cfabe64d25361f27ac4665a70620/pyzmq-27.1.0-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:18770c8d3563715387139060d37859c02ce40718d1faf299abddcdcc6a649066", size = 836265, upload-time = "2025-09-08T23:09:49.376Z" }, + { url = "https://files.pythonhosted.org/packages/3e/79/f38c92eeaeb03a2ccc2ba9866f0439593bb08c5e3b714ac1d553e5c96e25/pyzmq-27.1.0-pp311-pypy311_pp73-manylinux2014_i686.manylinux_2_17_i686.whl", hash = "sha256:ac25465d42f92e990f8d8b0546b01c391ad431c3bf447683fdc40565941d0604", size = 800208, upload-time = "2025-09-08T23:09:51.073Z" }, + { url = "https://files.pythonhosted.org/packages/49/0e/3f0d0d335c6b3abb9b7b723776d0b21fa7f3a6c819a0db6097059aada160/pyzmq-27.1.0-pp311-pypy311_pp73-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:53b40f8ae006f2734ee7608d59ed661419f087521edbfc2149c3932e9c14808c", size = 567747, upload-time = "2025-09-08T23:09:52.698Z" }, + { url = "https://files.pythonhosted.org/packages/a1/cf/f2b3784d536250ffd4be70e049f3b60981235d70c6e8ce7e3ef21e1adb25/pyzmq-27.1.0-pp311-pypy311_pp73-manylinux_2_26_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:f605d884e7c8be8fe1aa94e0a783bf3f591b84c24e4bc4f3e7564c82ac25e271", size = 747371, upload-time = "2025-09-08T23:09:54.563Z" }, + { url = "https://files.pythonhosted.org/packages/01/1b/5dbe84eefc86f48473947e2f41711aded97eecef1231f4558f1f02713c12/pyzmq-27.1.0-pp311-pypy311_pp73-win_amd64.whl", hash = "sha256:c9f7f6e13dff2e44a6afeaf2cf54cee5929ad64afaf4d40b50f93c58fc687355", size = 544862, upload-time = "2025-09-08T23:09:56.509Z" }, ] [[package]] @@ -6920,6 +7423,10 @@ dependencies = [ { name = "requests" }, ] wheels = [ + { url = "https://files.pythonhosted.org/packages/bf/64/d5c29a4b014d8b9a624203a88b67630072c1d6960425dbf7a1f0fa5d6b74/ray-2.53.0-cp311-cp311-macosx_12_0_arm64.whl", hash = "sha256:bd3ec4c342776ddac23ae2b108c64f5939f417ccc4875900d586c7c978463269", size = 69479296, upload-time = "2025-12-20T16:06:05.111Z" }, + { url = "https://files.pythonhosted.org/packages/c6/41/9e19d1e5d9458a5ba157c36642e2874bcb22fddbd7c1e77b668e5afc3f3d/ray-2.53.0-cp311-cp311-manylinux2014_aarch64.whl", hash = "sha256:a0bbb98b0b0f25a3ee075ca10171e1260e70b6bc690cd509ecd7ce1228af854d", size = 71463449, upload-time = "2025-12-20T16:06:10.983Z" }, + { url = "https://files.pythonhosted.org/packages/63/de/58c19906b0dd16ea06b4f2465b7327f5f180e6b6e1c8c9b610d7c589ea5f/ray-2.53.0-cp311-cp311-manylinux2014_x86_64.whl", hash = "sha256:eb000c17f7301071fdd15c44c4cd3ac0f7953bb4c7c227e61719fe7048195bcd", size = 72305102, upload-time = "2025-12-20T16:06:17.989Z" }, + { url = "https://files.pythonhosted.org/packages/b1/43/72cc1cfe17d26abe62a793eab10445f9546dce24192b85a6cd0cdc47ed86/ray-2.53.0-cp311-cp311-win_amd64.whl", hash = "sha256:4a1bb3fe09ab4cd0d16ddc96b9f60c9ed83b3f93b87aa8506e0d3b746fd4e825", size = 27194174, upload-time = "2025-12-20T16:06:23.042Z" }, { url = "https://files.pythonhosted.org/packages/b2/44/562718a634e63e8ef7985285288a167d4af62bc2a7decce3300cf937776a/ray-2.53.0-cp312-cp312-macosx_12_0_arm64.whl", hash = "sha256:d8b95d047d947493803fb8417aea31225dcacdab15afdc75b8a238901949d457", size = 69463763, upload-time = "2025-12-20T16:06:28.685Z" }, { url = "https://files.pythonhosted.org/packages/38/68/8e59b8413f3751fe7ce8b98ee8787d13964b47a4043587950790a9dd2151/ray-2.53.0-cp312-cp312-manylinux2014_aarch64.whl", hash = "sha256:65e2ce58d3dc6baa3cf45824d889c1968ebde565ee54dfd80a98af8f31af8e4a", size = 71504450, upload-time = "2025-12-20T16:06:34.922Z" }, { url = "https://files.pythonhosted.org/packages/2a/db/978a50d264565ca42e2a4bf115ec9a1f04f19ca5e620e6aa2f280747b644/ray-2.53.0-cp312-cp312-manylinux2014_x86_64.whl", hash = "sha256:14f46363e9b4cf0c1c8b4d8623ec337c5bd408377831b5e5b50067930137bbca", size = 72370424, upload-time = "2025-12-20T16:06:40.821Z" }, @@ -7023,6 +7530,21 @@ version = "0.27.1" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/e9/dd/2c0cbe774744272b0ae725f44032c77bdcab6e8bcf544bffa3b6e70c8dba/rpds_py-0.27.1.tar.gz", hash = "sha256:26a1c73171d10b7acccbded82bf6a586ab8203601e565badc74bbbf8bc5a10f8", size = 27479, upload-time = "2025-08-27T12:16:36.024Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/b5/c1/7907329fbef97cbd49db6f7303893bd1dd5a4a3eae415839ffdfb0762cae/rpds_py-0.27.1-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:be898f271f851f68b318872ce6ebebbc62f303b654e43bf72683dbdc25b7c881", size = 371063, upload-time = "2025-08-27T12:12:47.856Z" }, + { url = "https://files.pythonhosted.org/packages/11/94/2aab4bc86228bcf7c48760990273653a4900de89c7537ffe1b0d6097ed39/rpds_py-0.27.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:62ac3d4e3e07b58ee0ddecd71d6ce3b1637de2d373501412df395a0ec5f9beb5", size = 353210, upload-time = "2025-08-27T12:12:49.187Z" }, + { url = "https://files.pythonhosted.org/packages/3a/57/f5eb3ecf434342f4f1a46009530e93fd201a0b5b83379034ebdb1d7c1a58/rpds_py-0.27.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4708c5c0ceb2d034f9991623631d3d23cb16e65c83736ea020cdbe28d57c0a0e", size = 381636, upload-time = "2025-08-27T12:12:50.492Z" }, + { url = "https://files.pythonhosted.org/packages/ae/f4/ef95c5945e2ceb5119571b184dd5a1cc4b8541bbdf67461998cfeac9cb1e/rpds_py-0.27.1-cp311-cp311-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:abfa1171a9952d2e0002aba2ad3780820b00cc3d9c98c6630f2e93271501f66c", size = 394341, upload-time = "2025-08-27T12:12:52.024Z" }, + { url = "https://files.pythonhosted.org/packages/5a/7e/4bd610754bf492d398b61725eb9598ddd5eb86b07d7d9483dbcd810e20bc/rpds_py-0.27.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:4b507d19f817ebaca79574b16eb2ae412e5c0835542c93fe9983f1e432aca195", size = 523428, upload-time = "2025-08-27T12:12:53.779Z" }, + { url = "https://files.pythonhosted.org/packages/9f/e5/059b9f65a8c9149361a8b75094864ab83b94718344db511fd6117936ed2a/rpds_py-0.27.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:168b025f8fd8d8d10957405f3fdcef3dc20f5982d398f90851f4abc58c566c52", size = 402923, upload-time = "2025-08-27T12:12:55.15Z" }, + { url = "https://files.pythonhosted.org/packages/f5/48/64cabb7daced2968dd08e8a1b7988bf358d7bd5bcd5dc89a652f4668543c/rpds_py-0.27.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:cb56c6210ef77caa58e16e8c17d35c63fe3f5b60fd9ba9d424470c3400bcf9ed", size = 384094, upload-time = "2025-08-27T12:12:57.194Z" }, + { url = "https://files.pythonhosted.org/packages/ae/e1/dc9094d6ff566bff87add8a510c89b9e158ad2ecd97ee26e677da29a9e1b/rpds_py-0.27.1-cp311-cp311-manylinux_2_31_riscv64.whl", hash = "sha256:d252f2d8ca0195faa707f8eb9368955760880b2b42a8ee16d382bf5dd807f89a", size = 401093, upload-time = "2025-08-27T12:12:58.985Z" }, + { url = "https://files.pythonhosted.org/packages/37/8e/ac8577e3ecdd5593e283d46907d7011618994e1d7ab992711ae0f78b9937/rpds_py-0.27.1-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:6e5e54da1e74b91dbc7996b56640f79b195d5925c2b78efaa8c5d53e1d88edde", size = 417969, upload-time = "2025-08-27T12:13:00.367Z" }, + { url = "https://files.pythonhosted.org/packages/66/6d/87507430a8f74a93556fe55c6485ba9c259949a853ce407b1e23fea5ba31/rpds_py-0.27.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:ffce0481cc6e95e5b3f0a47ee17ffbd234399e6d532f394c8dce320c3b089c21", size = 558302, upload-time = "2025-08-27T12:13:01.737Z" }, + { url = "https://files.pythonhosted.org/packages/3a/bb/1db4781ce1dda3eecc735e3152659a27b90a02ca62bfeea17aee45cc0fbc/rpds_py-0.27.1-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:a205fdfe55c90c2cd8e540ca9ceba65cbe6629b443bc05db1f590a3db8189ff9", size = 589259, upload-time = "2025-08-27T12:13:03.127Z" }, + { url = "https://files.pythonhosted.org/packages/7b/0e/ae1c8943d11a814d01b482e1f8da903f88047a962dff9bbdadf3bd6e6fd1/rpds_py-0.27.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:689fb5200a749db0415b092972e8eba85847c23885c8543a8b0f5c009b1a5948", size = 554983, upload-time = "2025-08-27T12:13:04.516Z" }, + { url = "https://files.pythonhosted.org/packages/b2/d5/0b2a55415931db4f112bdab072443ff76131b5ac4f4dc98d10d2d357eb03/rpds_py-0.27.1-cp311-cp311-win32.whl", hash = "sha256:3182af66048c00a075010bc7f4860f33913528a4b6fc09094a6e7598e462fe39", size = 217154, upload-time = "2025-08-27T12:13:06.278Z" }, + { url = "https://files.pythonhosted.org/packages/24/75/3b7ffe0d50dc86a6a964af0d1cc3a4a2cdf437cb7b099a4747bbb96d1819/rpds_py-0.27.1-cp311-cp311-win_amd64.whl", hash = "sha256:b4938466c6b257b2f5c4ff98acd8128ec36b5059e5c8f8372d79316b1c36bb15", size = 228627, upload-time = "2025-08-27T12:13:07.625Z" }, + { url = "https://files.pythonhosted.org/packages/8d/3f/4fd04c32abc02c710f09a72a30c9a55ea3cc154ef8099078fd50a0596f8e/rpds_py-0.27.1-cp311-cp311-win_arm64.whl", hash = "sha256:2f57af9b4d0793e53266ee4325535a31ba48e2f875da81a9177c9926dfa60746", size = 220998, upload-time = "2025-08-27T12:13:08.972Z" }, { url = "https://files.pythonhosted.org/packages/bd/fe/38de28dee5df58b8198c743fe2bea0c785c6d40941b9950bac4cdb71a014/rpds_py-0.27.1-cp312-cp312-macosx_10_12_x86_64.whl", hash = "sha256:ae2775c1973e3c30316892737b91f9283f9908e3cc7625b9331271eaaed7dc90", size = 361887, upload-time = "2025-08-27T12:13:10.233Z" }, { url = "https://files.pythonhosted.org/packages/7c/9a/4b6c7eedc7dd90986bf0fab6ea2a091ec11c01b15f8ba0a14d3f80450468/rpds_py-0.27.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:2643400120f55c8a96f7c9d858f7be0c88d383cd4653ae2cf0d0c88f668073e5", size = 345795, upload-time = "2025-08-27T12:13:11.65Z" }, { url = "https://files.pythonhosted.org/packages/6f/0e/e650e1b81922847a09cca820237b0edee69416a01268b7754d506ade11ad/rpds_py-0.27.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:16323f674c089b0360674a4abd28d5042947d54ba620f72514d69be4ff64845e", size = 385121, upload-time = "2025-08-27T12:13:13.008Z" }, @@ -7096,6 +7618,18 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/dd/10/6b283707780a81919f71625351182b4f98932ac89a09023cb61865136244/rpds_py-0.27.1-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:f39f58a27cc6e59f432b568ed8429c7e1641324fbe38131de852cd77b2d534b0", size = 555813, upload-time = "2025-08-27T12:15:00.334Z" }, { url = "https://files.pythonhosted.org/packages/04/2e/30b5ea18c01379da6272a92825dd7e53dc9d15c88a19e97932d35d430ef7/rpds_py-0.27.1-cp314-cp314t-win32.whl", hash = "sha256:d5fa0ee122dc09e23607a28e6d7b150da16c662e66409bbe85230e4c85bb528a", size = 217385, upload-time = "2025-08-27T12:15:01.937Z" }, { url = "https://files.pythonhosted.org/packages/32/7d/97119da51cb1dd3f2f3c0805f155a3aa4a95fa44fe7d78ae15e69edf4f34/rpds_py-0.27.1-cp314-cp314t-win_amd64.whl", hash = "sha256:6567d2bb951e21232c2f660c24cf3470bb96de56cdcb3f071a83feeaff8a2772", size = 230097, upload-time = "2025-08-27T12:15:03.961Z" }, + { url = "https://files.pythonhosted.org/packages/0c/ed/e1fba02de17f4f76318b834425257c8ea297e415e12c68b4361f63e8ae92/rpds_py-0.27.1-pp311-pypy311_pp73-macosx_10_12_x86_64.whl", hash = "sha256:cdfe4bb2f9fe7458b7453ad3c33e726d6d1c7c0a72960bcc23800d77384e42df", size = 371402, upload-time = "2025-08-27T12:15:51.561Z" }, + { url = "https://files.pythonhosted.org/packages/af/7c/e16b959b316048b55585a697e94add55a4ae0d984434d279ea83442e460d/rpds_py-0.27.1-pp311-pypy311_pp73-macosx_11_0_arm64.whl", hash = "sha256:8fabb8fd848a5f75a2324e4a84501ee3a5e3c78d8603f83475441866e60b94a3", size = 354084, upload-time = "2025-08-27T12:15:53.219Z" }, + { url = "https://files.pythonhosted.org/packages/de/c1/ade645f55de76799fdd08682d51ae6724cb46f318573f18be49b1e040428/rpds_py-0.27.1-pp311-pypy311_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:eda8719d598f2f7f3e0f885cba8646644b55a187762bec091fa14a2b819746a9", size = 383090, upload-time = "2025-08-27T12:15:55.158Z" }, + { url = "https://files.pythonhosted.org/packages/1f/27/89070ca9b856e52960da1472efcb6c20ba27cfe902f4f23ed095b9cfc61d/rpds_py-0.27.1-pp311-pypy311_pp73-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:3c64d07e95606ec402a0a1c511fe003873fa6af630bda59bac77fac8b4318ebc", size = 394519, upload-time = "2025-08-27T12:15:57.238Z" }, + { url = "https://files.pythonhosted.org/packages/b3/28/be120586874ef906aa5aeeae95ae8df4184bc757e5b6bd1c729ccff45ed5/rpds_py-0.27.1-pp311-pypy311_pp73-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:93a2ed40de81bcff59aabebb626562d48332f3d028ca2036f1d23cbb52750be4", size = 523817, upload-time = "2025-08-27T12:15:59.237Z" }, + { url = "https://files.pythonhosted.org/packages/a8/ef/70cc197bc11cfcde02a86f36ac1eed15c56667c2ebddbdb76a47e90306da/rpds_py-0.27.1-pp311-pypy311_pp73-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:387ce8c44ae94e0ec50532d9cb0edce17311024c9794eb196b90e1058aadeb66", size = 403240, upload-time = "2025-08-27T12:16:00.923Z" }, + { url = "https://files.pythonhosted.org/packages/cf/35/46936cca449f7f518f2f4996e0e8344db4b57e2081e752441154089d2a5f/rpds_py-0.27.1-pp311-pypy311_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:aaf94f812c95b5e60ebaf8bfb1898a7d7cb9c1af5744d4a67fa47796e0465d4e", size = 385194, upload-time = "2025-08-27T12:16:02.802Z" }, + { url = "https://files.pythonhosted.org/packages/e1/62/29c0d3e5125c3270b51415af7cbff1ec587379c84f55a5761cc9efa8cd06/rpds_py-0.27.1-pp311-pypy311_pp73-manylinux_2_31_riscv64.whl", hash = "sha256:4848ca84d6ded9b58e474dfdbad4b8bfb450344c0551ddc8d958bf4b36aa837c", size = 402086, upload-time = "2025-08-27T12:16:04.806Z" }, + { url = "https://files.pythonhosted.org/packages/8f/66/03e1087679227785474466fdd04157fb793b3b76e3fcf01cbf4c693c1949/rpds_py-0.27.1-pp311-pypy311_pp73-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:2bde09cbcf2248b73c7c323be49b280180ff39fadcfe04e7b6f54a678d02a7cf", size = 419272, upload-time = "2025-08-27T12:16:06.471Z" }, + { url = "https://files.pythonhosted.org/packages/6a/24/e3e72d265121e00b063aef3e3501e5b2473cf1b23511d56e529531acf01e/rpds_py-0.27.1-pp311-pypy311_pp73-musllinux_1_2_aarch64.whl", hash = "sha256:94c44ee01fd21c9058f124d2d4f0c9dc7634bec93cd4b38eefc385dabe71acbf", size = 560003, upload-time = "2025-08-27T12:16:08.06Z" }, + { url = "https://files.pythonhosted.org/packages/26/ca/f5a344c534214cc2d41118c0699fffbdc2c1bc7046f2a2b9609765ab9c92/rpds_py-0.27.1-pp311-pypy311_pp73-musllinux_1_2_i686.whl", hash = "sha256:df8b74962e35c9249425d90144e721eed198e6555a0e22a563d29fe4486b51f6", size = 590482, upload-time = "2025-08-27T12:16:10.137Z" }, + { url = "https://files.pythonhosted.org/packages/ce/08/4349bdd5c64d9d193c360aa9db89adeee6f6682ab8825dca0a3f535f434f/rpds_py-0.27.1-pp311-pypy311_pp73-musllinux_1_2_x86_64.whl", hash = "sha256:dc23e6820e3b40847e2f4a7726462ba0cf53089512abe9ee16318c366494c17a", size = 556523, upload-time = "2025-08-27T12:16:12.188Z" }, ] [[package]] @@ -7124,15 +7658,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/c6/2a/65880dfd0e13f7f13a775998f34703674a4554906167dce02daf7865b954/ruff-0.14.0-py3-none-win_arm64.whl", hash = "sha256:f42c9495f5c13ff841b1da4cb3c2a42075409592825dada7c5885c2c844ac730", size = 12565142, upload-time = "2025-10-07T18:21:53.577Z" }, ] -[[package]] -name = "runtype" -version = "0.5.3" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/60/76/d8a0f754c834c3d71a0896b1d40a1938244aab4bb5b4bab0b21d21525694/runtype-0.5.3.tar.gz", hash = "sha256:ccaec05c74f8d213342b9fc25e304560d114bc4d72ec117639cd1e7af9c5db1f", size = 30223, upload-time = "2025-03-03T08:39:00.081Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/80/db/879902580d720925092c86eaab2ceee7493e2fadbb5b718f54289b04d277/runtype-0.5.3-py3-none-any.whl", hash = "sha256:ea8cc6828217ebfda5c159dce969e832efd865a09d6ad1fc993f5bf5e1a627ee", size = 31944, upload-time = "2025-03-03T08:38:58.329Z" }, -] - [[package]] name = "scikit-learn" version = "1.7.2" @@ -7145,6 +7670,11 @@ dependencies = [ ] sdist = { url = "https://files.pythonhosted.org/packages/98/c2/a7855e41c9d285dfe86dc50b250978105dce513d6e459ea66a6aeb0e1e0c/scikit_learn-1.7.2.tar.gz", hash = "sha256:20e9e49ecd130598f1ca38a1d85090e1a600147b9c02fa6f15d69cb53d968fda", size = 7193136, upload-time = "2025-09-09T08:21:29.075Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/43/83/564e141eef908a5863a54da8ca342a137f45a0bfb71d1d79704c9894c9d1/scikit_learn-1.7.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:c7509693451651cd7361d30ce4e86a1347493554f172b1c72a39300fa2aea79e", size = 9331967, upload-time = "2025-09-09T08:20:32.421Z" }, + { url = "https://files.pythonhosted.org/packages/18/d6/ba863a4171ac9d7314c4d3fc251f015704a2caeee41ced89f321c049ed83/scikit_learn-1.7.2-cp311-cp311-macosx_12_0_arm64.whl", hash = "sha256:0486c8f827c2e7b64837c731c8feff72c0bd2b998067a8a9cbc10643c31f0fe1", size = 8648645, upload-time = "2025-09-09T08:20:34.436Z" }, + { url = "https://files.pythonhosted.org/packages/ef/0e/97dbca66347b8cf0ea8b529e6bb9367e337ba2e8be0ef5c1a545232abfde/scikit_learn-1.7.2-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:89877e19a80c7b11a2891a27c21c4894fb18e2c2e077815bcade10d34287b20d", size = 9715424, upload-time = "2025-09-09T08:20:36.776Z" }, + { url = "https://files.pythonhosted.org/packages/f7/32/1f3b22e3207e1d2c883a7e09abb956362e7d1bd2f14458c7de258a26ac15/scikit_learn-1.7.2-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:8da8bf89d4d79aaec192d2bda62f9b56ae4e5b4ef93b6a56b5de4977e375c1f1", size = 9509234, upload-time = "2025-09-09T08:20:38.957Z" }, + { url = "https://files.pythonhosted.org/packages/9f/71/34ddbd21f1da67c7a768146968b4d0220ee6831e4bcbad3e03dd3eae88b6/scikit_learn-1.7.2-cp311-cp311-win_amd64.whl", hash = "sha256:9b7ed8d58725030568523e937c43e56bc01cadb478fc43c042a9aca1dacb3ba1", size = 8894244, upload-time = "2025-09-09T08:20:41.166Z" }, { url = "https://files.pythonhosted.org/packages/a7/aa/3996e2196075689afb9fce0410ebdb4a09099d7964d061d7213700204409/scikit_learn-1.7.2-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:8d91a97fa2b706943822398ab943cde71858a50245e31bc71dba62aab1d60a96", size = 9259818, upload-time = "2025-09-09T08:20:43.19Z" }, { url = "https://files.pythonhosted.org/packages/43/5d/779320063e88af9c4a7c2cf463ff11c21ac9c8bd730c4a294b0000b666c9/scikit_learn-1.7.2-cp312-cp312-macosx_12_0_arm64.whl", hash = "sha256:acbc0f5fd2edd3432a22c69bed78e837c70cf896cd7993d71d51ba6708507476", size = 8636997, upload-time = "2025-09-09T08:20:45.468Z" }, { url = "https://files.pythonhosted.org/packages/5c/d0/0c577d9325b05594fdd33aa970bf53fb673f051a45496842caee13cfd7fe/scikit_learn-1.7.2-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:e5bf3d930aee75a65478df91ac1225ff89cd28e9ac7bd1196853a9229b6adb0b", size = 9478381, upload-time = "2025-09-09T08:20:47.982Z" }, @@ -7176,6 +7706,16 @@ dependencies = [ ] sdist = { url = "https://files.pythonhosted.org/packages/4c/3b/546a6f0bfe791bbb7f8d591613454d15097e53f906308ec6f7c1ce588e8e/scipy-1.16.2.tar.gz", hash = "sha256:af029b153d243a80afb6eabe40b0a07f8e35c9adc269c019f364ad747f826a6b", size = 30580599, upload-time = "2025-09-11T17:48:08.271Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/0b/ef/37ed4b213d64b48422df92560af7300e10fe30b5d665dd79932baebee0c6/scipy-1.16.2-cp311-cp311-macosx_10_14_x86_64.whl", hash = "sha256:6ab88ea43a57da1af33292ebd04b417e8e2eaf9d5aa05700be8d6e1b6501cd92", size = 36619956, upload-time = "2025-09-11T17:39:20.5Z" }, + { url = "https://files.pythonhosted.org/packages/85/ab/5c2eba89b9416961a982346a4d6a647d78c91ec96ab94ed522b3b6baf444/scipy-1.16.2-cp311-cp311-macosx_12_0_arm64.whl", hash = "sha256:c95e96c7305c96ede73a7389f46ccd6c659c4da5ef1b2789466baeaed3622b6e", size = 28931117, upload-time = "2025-09-11T17:39:29.06Z" }, + { url = "https://files.pythonhosted.org/packages/80/d1/eed51ab64d227fe60229a2d57fb60ca5898cfa50ba27d4f573e9e5f0b430/scipy-1.16.2-cp311-cp311-macosx_14_0_arm64.whl", hash = "sha256:87eb178db04ece7c698220d523c170125dbffebb7af0345e66c3554f6f60c173", size = 20921997, upload-time = "2025-09-11T17:39:34.892Z" }, + { url = "https://files.pythonhosted.org/packages/be/7c/33ea3e23bbadde96726edba6bf9111fb1969d14d9d477ffa202c67bec9da/scipy-1.16.2-cp311-cp311-macosx_14_0_x86_64.whl", hash = "sha256:4e409eac067dcee96a57fbcf424c13f428037827ec7ee3cb671ff525ca4fc34d", size = 23523374, upload-time = "2025-09-11T17:39:40.846Z" }, + { url = "https://files.pythonhosted.org/packages/96/0b/7399dc96e1e3f9a05e258c98d716196a34f528eef2ec55aad651ed136d03/scipy-1.16.2-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:e574be127bb760f0dad24ff6e217c80213d153058372362ccb9555a10fc5e8d2", size = 33583702, upload-time = "2025-09-11T17:39:49.011Z" }, + { url = "https://files.pythonhosted.org/packages/1a/bc/a5c75095089b96ea72c1bd37a4497c24b581ec73db4ef58ebee142ad2d14/scipy-1.16.2-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:f5db5ba6188d698ba7abab982ad6973265b74bb40a1efe1821b58c87f73892b9", size = 35883427, upload-time = "2025-09-11T17:39:57.406Z" }, + { url = "https://files.pythonhosted.org/packages/ab/66/e25705ca3d2b87b97fe0a278a24b7f477b4023a926847935a1a71488a6a6/scipy-1.16.2-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:ec6e74c4e884104ae006d34110677bfe0098203a3fec2f3faf349f4cb05165e3", size = 36212940, upload-time = "2025-09-11T17:40:06.013Z" }, + { url = "https://files.pythonhosted.org/packages/d6/fd/0bb911585e12f3abdd603d721d83fc1c7492835e1401a0e6d498d7822b4b/scipy-1.16.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:912f46667d2d3834bc3d57361f854226475f695eb08c08a904aadb1c936b6a88", size = 38865092, upload-time = "2025-09-11T17:40:15.143Z" }, + { url = "https://files.pythonhosted.org/packages/d6/73/c449a7d56ba6e6f874183759f8483cde21f900a8be117d67ffbb670c2958/scipy-1.16.2-cp311-cp311-win_amd64.whl", hash = "sha256:91e9e8a37befa5a69e9cacbe0bcb79ae5afb4a0b130fd6db6ee6cc0d491695fa", size = 38687626, upload-time = "2025-09-11T17:40:24.041Z" }, + { url = "https://files.pythonhosted.org/packages/68/72/02f37316adf95307f5d9e579023c6899f89ff3a051fa079dbd6faafc48e5/scipy-1.16.2-cp311-cp311-win_arm64.whl", hash = "sha256:f3bf75a6dcecab62afde4d1f973f1692be013110cad5338007927db8da73249c", size = 25503506, upload-time = "2025-09-11T17:40:30.703Z" }, { url = "https://files.pythonhosted.org/packages/b7/8d/6396e00db1282279a4ddd507c5f5e11f606812b608ee58517ce8abbf883f/scipy-1.16.2-cp312-cp312-macosx_10_14_x86_64.whl", hash = "sha256:89d6c100fa5c48472047632e06f0876b3c4931aac1f4291afc81a3644316bb0d", size = 36646259, upload-time = "2025-09-11T17:40:39.329Z" }, { url = "https://files.pythonhosted.org/packages/3b/93/ea9edd7e193fceb8eef149804491890bde73fb169c896b61aa3e2d1e4e77/scipy-1.16.2-cp312-cp312-macosx_12_0_arm64.whl", hash = "sha256:ca748936cd579d3f01928b30a17dc474550b01272d8046e3e1ee593f23620371", size = 28888976, upload-time = "2025-09-11T17:40:46.82Z" }, { url = "https://files.pythonhosted.org/packages/91/4d/281fddc3d80fd738ba86fd3aed9202331180b01e2c78eaae0642f22f7e83/scipy-1.16.2-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:fac4f8ce2ddb40e2e3d0f7ec36d2a1e7f92559a2471e59aec37bd8d9de01fec0", size = 20879905, upload-time = "2025-09-11T17:40:52.545Z" }, @@ -7298,6 +7838,19 @@ version = "3.20.2" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/41/f4/a1ac5ed32f7ed9a088d62a59d410d4c204b3b3815722e2ccfb491fa8251b/simplejson-3.20.2.tar.gz", hash = "sha256:5fe7a6ce14d1c300d80d08695b7f7e633de6cd72c80644021874d985b3393649", size = 85784, upload-time = "2025-09-26T16:29:36.64Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/b9/3e/96898c6c66d9dca3f9bd14d7487bf783b4acc77471b42f979babbb68d4ca/simplejson-3.20.2-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:06190b33cd7849efc413a5738d3da00b90e4a5382fd3d584c841ac20fb828c6f", size = 92633, upload-time = "2025-09-26T16:27:45.028Z" }, + { url = "https://files.pythonhosted.org/packages/6b/a2/cd2e10b880368305d89dd540685b8bdcc136df2b3c76b5ddd72596254539/simplejson-3.20.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:4ad4eac7d858947a30d2c404e61f16b84d16be79eb6fb316341885bdde864fa8", size = 75309, upload-time = "2025-09-26T16:27:46.142Z" }, + { url = "https://files.pythonhosted.org/packages/5d/02/290f7282eaa6ebe945d35c47e6534348af97472446951dce0d144e013f4c/simplejson-3.20.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:b392e11c6165d4a0fde41754a0e13e1d88a5ad782b245a973dd4b2bdb4e5076a", size = 75308, upload-time = "2025-09-26T16:27:47.542Z" }, + { url = "https://files.pythonhosted.org/packages/43/91/43695f17b69e70c4b0b03247aa47fb3989d338a70c4b726bbdc2da184160/simplejson-3.20.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:51eccc4e353eed3c50e0ea2326173acdc05e58f0c110405920b989d481287e51", size = 143733, upload-time = "2025-09-26T16:27:48.673Z" }, + { url = "https://files.pythonhosted.org/packages/9b/4b/fdcaf444ac1c3cbf1c52bf00320c499e1cf05d373a58a3731ae627ba5e2d/simplejson-3.20.2-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:306e83d7c331ad833d2d43c76a67f476c4b80c4a13334f6e34bb110e6105b3bd", size = 153397, upload-time = "2025-09-26T16:27:49.89Z" }, + { url = "https://files.pythonhosted.org/packages/c4/83/21550f81a50cd03599f048a2d588ffb7f4c4d8064ae091511e8e5848eeaa/simplejson-3.20.2-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f820a6ac2ef0bc338ae4963f4f82ccebdb0824fe9caf6d660670c578abe01013", size = 141654, upload-time = "2025-09-26T16:27:51.168Z" }, + { url = "https://files.pythonhosted.org/packages/cf/54/d76c0e72ad02450a3e723b65b04f49001d0e73218ef6a220b158a64639cb/simplejson-3.20.2-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:21e7a066528a5451433eb3418184f05682ea0493d14e9aae690499b7e1eb6b81", size = 144913, upload-time = "2025-09-26T16:27:52.331Z" }, + { url = "https://files.pythonhosted.org/packages/3f/49/976f59b42a6956d4aeb075ada16ad64448a985704bc69cd427a2245ce835/simplejson-3.20.2-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:438680ddde57ea87161a4824e8de04387b328ad51cfdf1eaf723623a3014b7aa", size = 144568, upload-time = "2025-09-26T16:27:53.41Z" }, + { url = "https://files.pythonhosted.org/packages/60/c7/30bae30424ace8cd791ca660fed454ed9479233810fe25c3f3eab3d9dc7b/simplejson-3.20.2-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:cac78470ae68b8d8c41b6fca97f5bf8e024ca80d5878c7724e024540f5cdaadb", size = 146239, upload-time = "2025-09-26T16:27:54.502Z" }, + { url = "https://files.pythonhosted.org/packages/79/3e/7f3b7b97351c53746e7b996fcd106986cda1954ab556fd665314756618d2/simplejson-3.20.2-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:7524e19c2da5ef281860a3d74668050c6986be15c9dd99966034ba47c68828c2", size = 154497, upload-time = "2025-09-26T16:27:55.885Z" }, + { url = "https://files.pythonhosted.org/packages/1d/48/7241daa91d0bf19126589f6a8dcbe8287f4ed3d734e76fd4a092708947be/simplejson-3.20.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:0e9b6d845a603b2eef3394eb5e21edb8626cd9ae9a8361d14e267eb969dbe413", size = 148069, upload-time = "2025-09-26T16:27:57.039Z" }, + { url = "https://files.pythonhosted.org/packages/e6/f4/ef18d2962fe53e7be5123d3784e623859eec7ed97060c9c8536c69d34836/simplejson-3.20.2-cp311-cp311-win32.whl", hash = "sha256:47d8927e5ac927fdd34c99cc617938abb3624b06ff86e8e219740a86507eb961", size = 74158, upload-time = "2025-09-26T16:27:58.265Z" }, + { url = "https://files.pythonhosted.org/packages/35/fd/3d1158ecdc573fdad81bf3cc78df04522bf3959758bba6597ba4c956c74d/simplejson-3.20.2-cp311-cp311-win_amd64.whl", hash = "sha256:ba4edf3be8e97e4713d06c3d302cba1ff5c49d16e9d24c209884ac1b8455520c", size = 75911, upload-time = "2025-09-26T16:27:59.292Z" }, { url = "https://files.pythonhosted.org/packages/9d/9e/1a91e7614db0416885eab4136d49b7303de20528860ffdd798ce04d054db/simplejson-3.20.2-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:4376d5acae0d1e91e78baeba4ee3cf22fbf6509d81539d01b94e0951d28ec2b6", size = 93523, upload-time = "2025-09-26T16:28:00.356Z" }, { url = "https://files.pythonhosted.org/packages/5e/2b/d2413f5218fc25608739e3d63fe321dfa85c5f097aa6648dbe72513a5f12/simplejson-3.20.2-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:f8fe6de652fcddae6dec8f281cc1e77e4e8f3575249e1800090aab48f73b4259", size = 75844, upload-time = "2025-09-26T16:28:01.756Z" }, { url = "https://files.pythonhosted.org/packages/ad/f1/efd09efcc1e26629e120fef59be059ce7841cc6e1f949a4db94f1ae8a918/simplejson-3.20.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:25ca2663d99328d51e5a138f22018e54c9162438d831e26cfc3458688616eca8", size = 75655, upload-time = "2025-09-26T16:28:03.037Z" }, @@ -7561,6 +8114,14 @@ dependencies = [ ] sdist = { url = "https://files.pythonhosted.org/packages/d7/bc/d59b5d97d27229b0e009bd9098cd81af71c2fa5549c580a0a67b9bed0496/sqlalchemy-2.0.43.tar.gz", hash = "sha256:788bfcef6787a7764169cfe9859fe425bf44559619e1d9f56f5bddf2ebf6f417", size = 9762949, upload-time = "2025-08-11T14:24:58.438Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/9d/77/fa7189fe44114658002566c6fe443d3ed0ec1fa782feb72af6ef7fbe98e7/sqlalchemy-2.0.43-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:52d9b73b8fb3e9da34c2b31e6d99d60f5f99fd8c1225c9dad24aeb74a91e1d29", size = 2136472, upload-time = "2025-08-11T15:52:21.789Z" }, + { url = "https://files.pythonhosted.org/packages/99/ea/92ac27f2fbc2e6c1766bb807084ca455265707e041ba027c09c17d697867/sqlalchemy-2.0.43-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:f42f23e152e4545157fa367b2435a1ace7571cab016ca26038867eb7df2c3631", size = 2126535, upload-time = "2025-08-11T15:52:23.109Z" }, + { url = "https://files.pythonhosted.org/packages/94/12/536ede80163e295dc57fff69724caf68f91bb40578b6ac6583a293534849/sqlalchemy-2.0.43-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4fb1a8c5438e0c5ea51afe9c6564f951525795cf432bed0c028c1cb081276685", size = 3297521, upload-time = "2025-08-11T15:50:33.536Z" }, + { url = "https://files.pythonhosted.org/packages/03/b5/cacf432e6f1fc9d156eca0560ac61d4355d2181e751ba8c0cd9cb232c8c1/sqlalchemy-2.0.43-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:db691fa174e8f7036afefe3061bc40ac2b770718be2862bfb03aabae09051aca", size = 3297343, upload-time = "2025-08-11T15:57:51.186Z" }, + { url = "https://files.pythonhosted.org/packages/ca/ba/d4c9b526f18457667de4c024ffbc3a0920c34237b9e9dd298e44c7c00ee5/sqlalchemy-2.0.43-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:fe2b3b4927d0bc03d02ad883f402d5de201dbc8894ac87d2e981e7d87430e60d", size = 3232113, upload-time = "2025-08-11T15:50:34.949Z" }, + { url = "https://files.pythonhosted.org/packages/aa/79/c0121b12b1b114e2c8a10ea297a8a6d5367bc59081b2be896815154b1163/sqlalchemy-2.0.43-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:4d3d9b904ad4a6b175a2de0738248822f5ac410f52c2fd389ada0b5262d6a1e3", size = 3258240, upload-time = "2025-08-11T15:57:52.983Z" }, + { url = "https://files.pythonhosted.org/packages/79/99/a2f9be96fb382f3ba027ad42f00dbe30fdb6ba28cda5f11412eee346bec5/sqlalchemy-2.0.43-cp311-cp311-win32.whl", hash = "sha256:5cda6b51faff2639296e276591808c1726c4a77929cfaa0f514f30a5f6156921", size = 2101248, upload-time = "2025-08-11T15:55:01.855Z" }, + { url = "https://files.pythonhosted.org/packages/ee/13/744a32ebe3b4a7a9c7ea4e57babae7aa22070d47acf330d8e5a1359607f1/sqlalchemy-2.0.43-cp311-cp311-win_amd64.whl", hash = "sha256:c5d1730b25d9a07727d20ad74bc1039bbbb0a6ca24e6769861c1aa5bf2c4c4a8", size = 2126109, upload-time = "2025-08-11T15:55:04.092Z" }, { url = "https://files.pythonhosted.org/packages/61/db/20c78f1081446095450bdc6ee6cc10045fce67a8e003a5876b6eaafc5cc4/sqlalchemy-2.0.43-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:20d81fc2736509d7a2bd33292e489b056cbae543661bb7de7ce9f1c0cd6e7f24", size = 2134891, upload-time = "2025-08-11T15:51:13.019Z" }, { url = "https://files.pythonhosted.org/packages/45/0a/3d89034ae62b200b4396f0f95319f7d86e9945ee64d2343dcad857150fa2/sqlalchemy-2.0.43-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:25b9fc27650ff5a2c9d490c13c14906b918b0de1f8fcbb4c992712d8caf40e83", size = 2123061, upload-time = "2025-08-11T15:51:14.319Z" }, { url = "https://files.pythonhosted.org/packages/cb/10/2711f7ff1805919221ad5bee205971254845c069ee2e7036847103ca1e4c/sqlalchemy-2.0.43-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6772e3ca8a43a65a37c88e2f3e2adfd511b0b1da37ef11ed78dea16aeae85bd9", size = 3320384, upload-time = "2025-08-11T15:52:35.088Z" }, @@ -7593,6 +8154,23 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/8c/92/c35e036151fe53822893979f8a13e6f235ae8191f4164a79ae60a95d66aa/sqlmodel-0.0.27-py3-none-any.whl", hash = "sha256:667fe10aa8ff5438134668228dc7d7a08306f4c5c4c7e6ad3ad68defa0e7aa49", size = 29131, upload-time = "2025-10-08T16:39:10.917Z" }, ] +[[package]] +name = "stable-baselines3" +version = "2.8.0" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "cloudpickle" }, + { name = "gymnasium" }, + { name = "matplotlib" }, + { name = "numpy" }, + { name = "pandas" }, + { name = "torch" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/e2/07/01a2aa6a6a58f911085981dad1af2f1877d04886768c0df33930945fb98c/stable_baselines3-2.8.0.tar.gz", hash = "sha256:fe976d102b596c8001ca619638901721bcf97e8934a397e235b2d277fa9216c2", size = 220224, upload-time = "2026-04-01T10:49:29.738Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/85/1b/8046baf1e7756006eab991cd3260c4342c515dd6b536bc2d03df4b6f35aa/stable_baselines3-2.8.0-py3-none-any.whl", hash = "sha256:8c19d960b534a909f46dac5227662fc2d6be380e5c66cb04e1ad23edb23dc5a2", size = 187458, upload-time = "2026-04-01T10:49:28.132Z" }, +] + [[package]] name = "stack-data" version = "0.6.3" @@ -7690,12 +8268,16 @@ dependencies = [ { name = "nvidia-nccl-cu12", marker = "platform_machine == 'x86_64' and sys_platform == 'linux'" }, { name = "nvidia-nvjitlink-cu12", marker = "platform_machine == 'x86_64' and sys_platform == 'linux'" }, { name = "nvidia-nvtx-cu12", marker = "platform_machine == 'x86_64' and sys_platform == 'linux'" }, - { name = "setuptools" }, + { name = "setuptools", marker = "python_full_version >= '3.12'" }, { name = "sympy" }, { name = "triton", marker = "platform_machine == 'x86_64' and sys_platform == 'linux'" }, { name = "typing-extensions" }, ] wheels = [ + { url = "https://files.pythonhosted.org/packages/8f/c4/3e7a3887eba14e815e614db70b3b529112d1513d9dae6f4d43e373360b7f/torch-2.8.0-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:220a06fd7af8b653c35d359dfe1aaf32f65aa85befa342629f716acb134b9710", size = 102073391, upload-time = "2025-08-06T14:53:20.937Z" }, + { url = "https://files.pythonhosted.org/packages/5a/63/4fdc45a0304536e75a5e1b1bbfb1b56dd0e2743c48ee83ca729f7ce44162/torch-2.8.0-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:c12fa219f51a933d5f80eeb3a7a5d0cbe9168c0a14bbb4055f1979431660879b", size = 888063640, upload-time = "2025-08-06T14:55:05.325Z" }, + { url = "https://files.pythonhosted.org/packages/84/57/2f64161769610cf6b1c5ed782bd8a780e18a3c9d48931319f2887fa9d0b1/torch-2.8.0-cp311-cp311-win_amd64.whl", hash = "sha256:8c7ef765e27551b2fbfc0f41bcf270e1292d9bf79f8e0724848b1682be6e80aa", size = 241366752, upload-time = "2025-08-06T14:53:38.692Z" }, + { url = "https://files.pythonhosted.org/packages/a4/5e/05a5c46085d9b97e928f3f037081d3d2b87fb4b4195030fc099aaec5effc/torch-2.8.0-cp311-none-macosx_11_0_arm64.whl", hash = "sha256:5ae0524688fb6707c57a530c2325e13bb0090b745ba7b4a2cd6a3ce262572916", size = 73621174, upload-time = "2025-08-06T14:53:25.44Z" }, { url = "https://files.pythonhosted.org/packages/49/0c/2fd4df0d83a495bb5e54dca4474c4ec5f9c62db185421563deeb5dabf609/torch-2.8.0-cp312-cp312-manylinux_2_28_aarch64.whl", hash = "sha256:e2fab4153768d433f8ed9279c8133a114a034a61e77a3a104dcdf54388838705", size = 101906089, upload-time = "2025-08-06T14:53:52.631Z" }, { url = "https://files.pythonhosted.org/packages/99/a8/6acf48d48838fb8fe480597d98a0668c2beb02ee4755cc136de92a0a956f/torch-2.8.0-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:b2aca0939fb7e4d842561febbd4ffda67a8e958ff725c1c27e244e85e982173c", size = 887913624, upload-time = "2025-08-06T14:56:44.33Z" }, { url = "https://files.pythonhosted.org/packages/af/8a/5c87f08e3abd825c7dfecef5a0f1d9aa5df5dd0e3fd1fa2f490a8e512402/torch-2.8.0-cp312-cp312-win_amd64.whl", hash = "sha256:2f4ac52f0130275d7517b03a33d2493bab3693c83dcfadf4f81688ea82147d2e", size = 241326087, upload-time = "2025-08-06T14:53:46.503Z" }, @@ -7720,6 +8302,10 @@ dependencies = [ { name = "torch" }, ] wheels = [ + { url = "https://files.pythonhosted.org/packages/f0/d7/15d3d7bd8d0239211b21673d1bac7bc345a4ad904a8e25bb3fd8a9cf1fbc/torchvision-0.23.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:49aa20e21f0c2bd458c71d7b449776cbd5f16693dd5807195a820612b8a229b7", size = 1856884, upload-time = "2025-08-06T14:58:00.237Z" }, + { url = "https://files.pythonhosted.org/packages/dd/14/7b44fe766b7d11e064c539d92a172fa9689a53b69029e24f2f1f51e7dc56/torchvision-0.23.0-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:01dc33ee24c79148aee7cdbcf34ae8a3c9da1674a591e781577b716d233b1fa6", size = 2395543, upload-time = "2025-08-06T14:58:04.373Z" }, + { url = "https://files.pythonhosted.org/packages/79/9c/fcb09aff941c8147d9e6aa6c8f67412a05622b0c750bcf796be4c85a58d4/torchvision-0.23.0-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:35c27941831b653f5101edfe62c03d196c13f32139310519e8228f35eae0e96a", size = 8628388, upload-time = "2025-08-06T14:58:07.802Z" }, + { url = "https://files.pythonhosted.org/packages/93/40/3415d890eb357b25a8e0a215d32365a88ecc75a283f75c4e919024b22d97/torchvision-0.23.0-cp311-cp311-win_amd64.whl", hash = "sha256:09bfde260e7963a15b80c9e442faa9f021c7e7f877ac0a36ca6561b367185013", size = 1600741, upload-time = "2025-08-06T14:57:59.158Z" }, { url = "https://files.pythonhosted.org/packages/df/1d/0ea0b34bde92a86d42620f29baa6dcbb5c2fc85990316df5cb8f7abb8ea2/torchvision-0.23.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:e0e2c04a91403e8dd3af9756c6a024a1d9c0ed9c0d592a8314ded8f4fe30d440", size = 1856885, upload-time = "2025-08-06T14:58:06.503Z" }, { url = "https://files.pythonhosted.org/packages/e2/00/2f6454decc0cd67158c7890364e446aad4b91797087a57a78e72e1a8f8bc/torchvision-0.23.0-cp312-cp312-manylinux_2_28_aarch64.whl", hash = "sha256:6dd7c4d329a0e03157803031bc856220c6155ef08c26d4f5bbac938acecf0948", size = 2396614, upload-time = "2025-08-06T14:58:03.116Z" }, { url = "https://files.pythonhosted.org/packages/e4/b5/3e580dcbc16f39a324f3dd71b90edbf02a42548ad44d2b4893cc92b1194b/torchvision-0.23.0-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:4e7d31c43bc7cbecbb1a5652ac0106b436aa66e26437585fc2c4b2cf04d6014c", size = 8627108, upload-time = "2025-08-06T14:58:12.956Z" }, @@ -7774,93 +8360,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/00/c0/8f5d070730d7836adc9c9b6408dec68c6ced86b304a9b26a14df072a6e8c/traitlets-5.14.3-py3-none-any.whl", hash = "sha256:b74e89e397b1ed28cc831db7aea759ba6640cb3de13090ca145426688ff1ac4f", size = 85359, upload-time = "2024-04-19T11:11:46.763Z" }, ] -[[package]] -name = "trame" -version = "3.13.2" -source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "pyyaml" }, - { name = "trame-client" }, - { name = "trame-common" }, - { name = "trame-server" }, - { name = "wslink" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/fc/c7/790a5f28d75ea166fd9ec0bc6545e42683dc59ddd0b15ed374d00fb8e187/trame-3.13.2.tar.gz", hash = "sha256:9868d1c2bce981ae2c66eb6a16d39e2a14f042eedb1047666266c753ecaf3f64", size = 26386, upload-time = "2026-05-15T03:50:50.626Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/eb/4a/1474a166fa9494162779b4145b4b82adbe482cfb776efffeff59de4ba70f/trame-3.13.2-py3-none-any.whl", hash = "sha256:23e87a65a6ea9241ce1060e9cd01426e48b3b8b72cd9f3cb974fc398649280b6", size = 31514, upload-time = "2026-05-15T03:50:49.129Z" }, -] - -[[package]] -name = "trame-client" -version = "3.12.2" -source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "trame-common" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/c6/90/c895a1dc56c5554105baf00e16a454028f24c94be654430d87df0ff5b788/trame_client-3.12.2.tar.gz", hash = "sha256:a9bfba0226dda4a2ff36805ebf12e649cd7eb94c40672c8495d0674a12d5d381", size = 246220, upload-time = "2026-05-11T16:36:24.677Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/ae/ba/a62b4f6dee5039074f8f92dcfe780dc68b2ca29a9882282da1750808892d/trame_client-3.12.2-py3-none-any.whl", hash = "sha256:829a59bc5e2bf9ae2adc3a254ce9b0183c0312c656b3f5b0c88be35671703c9c", size = 250679, upload-time = "2026-05-11T16:36:22.936Z" }, -] - -[[package]] -name = "trame-common" -version = "1.2.3" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/b6/8c/f9e7bcf73d888df9df6115deb8619679444d83b9e92a26604a05f0433307/trame_common-1.2.3.tar.gz", hash = "sha256:125b60d77545d7352fb8eabc0f6e0e12070aa6ada31e992862f16a49f34b73ad", size = 19998, upload-time = "2026-05-08T17:12:33.942Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/d5/80/957a3dae26c1b38a302a96bf49adc53399e5f04c0afdf750d4978216fe14/trame_common-1.2.3-py3-none-any.whl", hash = "sha256:85d13ac87e7e4db853278afc98d19d14972e1fc75394aac9800221be0829e5cd", size = 23482, upload-time = "2026-05-08T17:12:32.548Z" }, -] - -[[package]] -name = "trame-components" -version = "2.5.0" -source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "trame-client" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/82/47/d773f35615c22553a7547b4336af62e412548ec3607626fa3db128f30460/trame-components-2.5.0.tar.gz", hash = "sha256:df7a1d387b98c5dd71699737804f5288957ca370eb1a60bbe40e89a1f9f62b12", size = 81972, upload-time = "2025-05-30T14:21:36.718Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/02/e9/627ebbf56e00d80300940e8bbf54c6594f98fd214e3565b3abaa5450e0d4/trame_components-2.5.0-py3-none-any.whl", hash = "sha256:897a6c0ebcc72d95a461bde28d2c2e37c4bc4922013ad07df3a65e64d4884672", size = 82345, upload-time = "2025-05-30T14:21:35.526Z" }, -] - -[[package]] -name = "trame-server" -version = "3.12.3" -source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "more-itertools" }, - { name = "trame-common" }, - { name = "wslink" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/74/e9/86e12a8347d1a6a0ea3b755301967921cdfbb38509410eb0cef9bb7f9061/trame_server-3.12.3.tar.gz", hash = "sha256:bbf5ac5d3fb1537021db6d8f422429c7c9eb4106550138335f2aa2f2b6c7c6b6", size = 37860, upload-time = "2026-05-18T15:26:43.975Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/fd/2e/6b5dff1aeebef5dbba06d1d9b170f3762e303eeffcceb33911860802e34b/trame_server-3.12.3-py3-none-any.whl", hash = "sha256:398dcdd54e2344d2b22565a901b4babd2ab78e46c4ffcaa41cacb3f9ecdde357", size = 44360, upload-time = "2026-05-18T15:26:42.592Z" }, -] - -[[package]] -name = "trame-vtk" -version = "2.11.8" -source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "trame-client" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/10/de/b72ec543cf8f70ee0ef4645d04e911155db3dcba545a9cf35d6c80e849c9/trame_vtk-2.11.8.tar.gz", hash = "sha256:bef4a35d86d57bf9b4af44dda8f361f917b141e4f624c9ab7278b6c48d171e74", size = 810254, upload-time = "2026-04-24T00:28:17.494Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/ef/11/aff660ffcc0f65546da4340902cd064cafda26e0a7750f6468a27378c717/trame_vtk-2.11.8-py3-none-any.whl", hash = "sha256:31c8220f59dcc3b5f2fcfe6de8b9796e8bdb7db5dcf790ee01df83d44e79a413", size = 831787, upload-time = "2026-04-24T00:28:15.317Z" }, -] - -[[package]] -name = "trame-vuetify" -version = "3.2.2" -source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "trame-client" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/d7/1a/1701aaf3450def4b17cb3580d0a340361065b1d258e156861eb83a8377f2/trame_vuetify-3.2.2.tar.gz", hash = "sha256:0e111ec5fdfed31e5c189eafb306f4f25aacd75527b3a5612bb5a4cacbb18d8b", size = 5107360, upload-time = "2026-04-28T13:22:53.684Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/ac/3a/0dbff3ce4fd9cc6076fce8ef714c33796bd25d08b3d249ca78ea458a85fd/trame_vuetify-3.2.2-py3-none-any.whl", hash = "sha256:b40ecfa30a675df4ce40d5161b9b6c040cfe5445599933c478a3359afbee91d3", size = 5134630, upload-time = "2026-04-28T13:22:51.132Z" }, -] - [[package]] name = "trimesh" version = "4.11.5" @@ -7878,9 +8377,10 @@ name = "triton" version = "3.4.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "setuptools", marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux')" }, + { name = "setuptools" }, ] wheels = [ + { url = "https://files.pythonhosted.org/packages/7d/39/43325b3b651d50187e591eefa22e236b2981afcebaefd4f2fc0ea99df191/triton-3.4.0-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:7b70f5e6a41e52e48cfc087436c8a28c17ff98db369447bcaff3b887a3ab4467", size = 155531138, upload-time = "2025-07-30T19:58:29.908Z" }, { url = "https://files.pythonhosted.org/packages/d0/66/b1eb52839f563623d185f0927eb3530ee4d5ffe9d377cdaf5346b306689e/triton-3.4.0-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:31c1d84a5c0ec2c0f8e8a072d7fd150cab84a9c239eaddc6706c081bfae4eb04", size = 155560068, upload-time = "2025-07-30T19:58:37.081Z" }, { url = "https://files.pythonhosted.org/packages/30/7b/0a685684ed5322d2af0bddefed7906674f67974aa88b0fae6e82e3b766f6/triton-3.4.0-cp313-cp313-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:00be2964616f4c619193cb0d1b29a99bd4b001d7dc333816073f92cf2a8ccdeb", size = 155569223, upload-time = "2025-07-30T19:58:44.017Z" }, { url = "https://files.pythonhosted.org/packages/20/63/8cb444ad5cdb25d999b7d647abac25af0ee37d292afc009940c05b82dda0/triton-3.4.0-cp313-cp313t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:7936b18a3499ed62059414d7df563e6c163c5e16c3773678a3ee3d417865035d", size = 155659780, upload-time = "2025-07-30T19:58:51.171Z" }, @@ -8123,6 +8623,14 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/dc/9b/47798a6c91d8bdb567fe2698fe81e0c6b7cb7ef4d13da4114b41d239f65d/typing_inspection-0.4.2-py3-none-any.whl", hash = "sha256:4ed1cacbdc298c220f1bd249ed5287caa16f34d44ef4e9c3d0cbad5b521545e7", size = 14611, upload-time = "2025-10-01T02:14:40.154Z" }, ] +[[package]] +name = "typish" +version = "1.9.3" +source = { registry = "https://pypi.org/simple" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/9d/d6/3f56c9c0c12adf61dfcf4ed5c8ffd2c431db8dd85592067a57e8e1968565/typish-1.9.3-py3-none-any.whl", hash = "sha256:03cfee5e6eb856dbf90244e18f4e4c41044c8790d5779f4e775f63f982e2f896", size = 45063, upload-time = "2021-08-05T20:36:28.702Z" }, +] + [[package]] name = "tzdata" version = "2025.2" @@ -8189,6 +8697,12 @@ version = "0.21.0" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/af/c0/854216d09d33c543f12a44b393c402e89a920b1a0a7dc634c42de91b9cf6/uvloop-0.21.0.tar.gz", hash = "sha256:3bf12b0fda68447806a7ad847bfa591613177275d35b6724b1ee573faa3704e3", size = 2492741, upload-time = "2024-10-14T23:38:35.489Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/57/a7/4cf0334105c1160dd6819f3297f8700fda7fc30ab4f61fbf3e725acbc7cc/uvloop-0.21.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:c0f3fa6200b3108919f8bdabb9a7f87f20e7097ea3c543754cabc7d717d95cf8", size = 1447410, upload-time = "2024-10-14T23:37:33.612Z" }, + { url = "https://files.pythonhosted.org/packages/8c/7c/1517b0bbc2dbe784b563d6ab54f2ef88c890fdad77232c98ed490aa07132/uvloop-0.21.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:0878c2640cf341b269b7e128b1a5fed890adc4455513ca710d77d5e93aa6d6a0", size = 805476, upload-time = "2024-10-14T23:37:36.11Z" }, + { url = "https://files.pythonhosted.org/packages/ee/ea/0bfae1aceb82a503f358d8d2fa126ca9dbdb2ba9c7866974faec1cb5875c/uvloop-0.21.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b9fb766bb57b7388745d8bcc53a359b116b8a04c83a2288069809d2b3466c37e", size = 3960855, upload-time = "2024-10-14T23:37:37.683Z" }, + { url = "https://files.pythonhosted.org/packages/8a/ca/0864176a649838b838f36d44bf31c451597ab363b60dc9e09c9630619d41/uvloop-0.21.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8a375441696e2eda1c43c44ccb66e04d61ceeffcd76e4929e527b7fa401b90fb", size = 3973185, upload-time = "2024-10-14T23:37:40.226Z" }, + { url = "https://files.pythonhosted.org/packages/30/bf/08ad29979a936d63787ba47a540de2132169f140d54aa25bc8c3df3e67f4/uvloop-0.21.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:baa0e6291d91649c6ba4ed4b2f982f9fa165b5bbd50a9e203c416a2797bab3c6", size = 3820256, upload-time = "2024-10-14T23:37:42.839Z" }, + { url = "https://files.pythonhosted.org/packages/da/e2/5cf6ef37e3daf2f06e651aae5ea108ad30df3cb269102678b61ebf1fdf42/uvloop-0.21.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:4509360fcc4c3bd2c70d87573ad472de40c13387f5fda8cb58350a1d7475e58d", size = 3937323, upload-time = "2024-10-14T23:37:45.337Z" }, { url = "https://files.pythonhosted.org/packages/8c/4c/03f93178830dc7ce8b4cdee1d36770d2f5ebb6f3d37d354e061eefc73545/uvloop-0.21.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:359ec2c888397b9e592a889c4d72ba3d6befba8b2bb01743f72fffbde663b59c", size = 1471284, upload-time = "2024-10-14T23:37:47.833Z" }, { url = "https://files.pythonhosted.org/packages/43/3e/92c03f4d05e50f09251bd8b2b2b584a2a7f8fe600008bcc4523337abe676/uvloop-0.21.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:f7089d2dc73179ce5ac255bdf37c236a9f914b264825fdaacaded6990a7fb4c2", size = 821349, upload-time = "2024-10-14T23:37:50.149Z" }, { url = "https://files.pythonhosted.org/packages/a6/ef/a02ec5da49909dbbfb1fd205a9a1ac4e88ea92dcae885e7c961847cd51e2/uvloop-0.21.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:baa4dcdbd9ae0a372f2167a207cd98c9f9a1ea1188a8a526431eef2f8116cc8d", size = 4580089, upload-time = "2024-10-14T23:37:51.703Z" }, @@ -8237,6 +8751,10 @@ dependencies = [ { name = "matplotlib" }, ] wheels = [ + { url = "https://files.pythonhosted.org/packages/58/08/94e2d38ae35ebb85cad96cb11738208307341cac8b16e162ed95ccb26860/vtk-9.3.1-cp311-cp311-macosx_10_10_x86_64.whl", hash = "sha256:55e2df9e6993b959b482b79a6d68b8d46397b479d69738d41b1501396fcad50c", size = 76687738, upload-time = "2024-06-29T03:14:54.449Z" }, + { url = "https://files.pythonhosted.org/packages/35/36/357ba7a02bc07a4d0df075e5a213a02020d509b312222445a05e354f52ff/vtk-9.3.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:c977486b0e4d87cddb3f2c7c0710d1c86243cdd01286cbd036231143d8eb4f6e", size = 70350272, upload-time = "2024-06-29T03:15:03.845Z" }, + { url = "https://files.pythonhosted.org/packages/d0/f8/1517f4f755233bb77542c222b173c760908f8f8d4330fc72526c295ab1e7/vtk-9.3.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f8edc04e0f8b6719cfc769e575a777267d667f447d1948c62fa97fb756cd75bb", size = 92115989, upload-time = "2024-06-29T03:15:13.337Z" }, + { url = "https://files.pythonhosted.org/packages/7a/44/3797d3367180a38bb41e24a6735860d94d16351fbe12e3f6bf6efb8940c8/vtk-9.3.1-cp311-cp311-win_amd64.whl", hash = "sha256:59cc043f611e3eca2870cc50f27e67852a182857de322415e942bdc133594acd", size = 52526922, upload-time = "2024-06-29T03:15:19.685Z" }, { url = "https://files.pythonhosted.org/packages/6f/ba/1571d61013f3f5778c11741d5de19db197b437d1a52215560f016662597b/vtk-9.3.1-cp312-cp312-macosx_10_10_x86_64.whl", hash = "sha256:05a4b6e387a906e8c8d6844441f9200116e937069fcf81f43e2600f26eb046de", size = 76832738, upload-time = "2024-06-29T03:15:26.41Z" }, { url = "https://files.pythonhosted.org/packages/8e/75/c637c620d23ccecb8ddf58fdb80af1dc56ecdd60f3e018c55e041663398b/vtk-9.3.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:bdbefb1aef9599a0a0b8222c9582f26946732a93534e6ec37d4b8e2c524c627e", size = 70385880, upload-time = "2024-06-29T03:15:33.131Z" }, { url = "https://files.pythonhosted.org/packages/01/ee/730d57c6d7353c1afb919ceedfac387a190ccb92e611c4b14f88e6f39066/vtk-9.3.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f728bb61f43fce850d622ced3b3d51b3116f767685ca4e4e0076f624e2d2307d", size = 92159868, upload-time = "2024-06-29T03:15:39.072Z" }, @@ -8266,6 +8784,19 @@ dependencies = [ ] sdist = { url = "https://files.pythonhosted.org/packages/2a/9a/d451fcc97d029f5812e898fd30a53fd8c15c7bbd058fd75cfc6beb9bd761/watchfiles-1.1.0.tar.gz", hash = "sha256:693ed7ec72cbfcee399e92c895362b6e66d63dac6b91e2c11ae03d10d503e575", size = 94406, upload-time = "2025-06-15T19:06:59.42Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/8b/78/7401154b78ab484ccaaeef970dc2af0cb88b5ba8a1b415383da444cdd8d3/watchfiles-1.1.0-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:c9649dfc57cc1f9835551deb17689e8d44666315f2e82d337b9f07bd76ae3aa2", size = 405751, upload-time = "2025-06-15T19:05:07.679Z" }, + { url = "https://files.pythonhosted.org/packages/76/63/e6c3dbc1f78d001589b75e56a288c47723de28c580ad715eb116639152b5/watchfiles-1.1.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:406520216186b99374cdb58bc48e34bb74535adec160c8459894884c983a149c", size = 397313, upload-time = "2025-06-15T19:05:08.764Z" }, + { url = "https://files.pythonhosted.org/packages/6c/a2/8afa359ff52e99af1632f90cbf359da46184207e893a5f179301b0c8d6df/watchfiles-1.1.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:cb45350fd1dc75cd68d3d72c47f5b513cb0578da716df5fba02fff31c69d5f2d", size = 450792, upload-time = "2025-06-15T19:05:09.869Z" }, + { url = "https://files.pythonhosted.org/packages/1d/bf/7446b401667f5c64972a57a0233be1104157fc3abf72c4ef2666c1bd09b2/watchfiles-1.1.0-cp311-cp311-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:11ee4444250fcbeb47459a877e5e80ed994ce8e8d20283857fc128be1715dac7", size = 458196, upload-time = "2025-06-15T19:05:11.91Z" }, + { url = "https://files.pythonhosted.org/packages/58/2f/501ddbdfa3fa874ea5597c77eeea3d413579c29af26c1091b08d0c792280/watchfiles-1.1.0-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:bda8136e6a80bdea23e5e74e09df0362744d24ffb8cd59c4a95a6ce3d142f79c", size = 484788, upload-time = "2025-06-15T19:05:13.373Z" }, + { url = "https://files.pythonhosted.org/packages/61/1e/9c18eb2eb5c953c96bc0e5f626f0e53cfef4bd19bd50d71d1a049c63a575/watchfiles-1.1.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:b915daeb2d8c1f5cee4b970f2e2c988ce6514aace3c9296e58dd64dc9aa5d575", size = 597879, upload-time = "2025-06-15T19:05:14.725Z" }, + { url = "https://files.pythonhosted.org/packages/8b/6c/1467402e5185d89388b4486745af1e0325007af0017c3384cc786fff0542/watchfiles-1.1.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:ed8fc66786de8d0376f9f913c09e963c66e90ced9aa11997f93bdb30f7c872a8", size = 477447, upload-time = "2025-06-15T19:05:15.775Z" }, + { url = "https://files.pythonhosted.org/packages/2b/a1/ec0a606bde4853d6c4a578f9391eeb3684a9aea736a8eb217e3e00aa89a1/watchfiles-1.1.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fe4371595edf78c41ef8ac8df20df3943e13defd0efcb732b2e393b5a8a7a71f", size = 453145, upload-time = "2025-06-15T19:05:17.17Z" }, + { url = "https://files.pythonhosted.org/packages/90/b9/ef6f0c247a6a35d689fc970dc7f6734f9257451aefb30def5d100d6246a5/watchfiles-1.1.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:b7c5f6fe273291f4d414d55b2c80d33c457b8a42677ad14b4b47ff025d0893e4", size = 626539, upload-time = "2025-06-15T19:05:18.557Z" }, + { url = "https://files.pythonhosted.org/packages/34/44/6ffda5537085106ff5aaa762b0d130ac6c75a08015dd1621376f708c94de/watchfiles-1.1.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:7738027989881e70e3723c75921f1efa45225084228788fc59ea8c6d732eb30d", size = 624472, upload-time = "2025-06-15T19:05:19.588Z" }, + { url = "https://files.pythonhosted.org/packages/c3/e3/71170985c48028fa3f0a50946916a14055e741db11c2e7bc2f3b61f4d0e3/watchfiles-1.1.0-cp311-cp311-win32.whl", hash = "sha256:622d6b2c06be19f6e89b1d951485a232e3b59618def88dbeda575ed8f0d8dbf2", size = 279348, upload-time = "2025-06-15T19:05:20.856Z" }, + { url = "https://files.pythonhosted.org/packages/89/1b/3e39c68b68a7a171070f81fc2561d23ce8d6859659406842a0e4bebf3bba/watchfiles-1.1.0-cp311-cp311-win_amd64.whl", hash = "sha256:48aa25e5992b61debc908a61ab4d3f216b64f44fdaa71eb082d8b2de846b7d12", size = 292607, upload-time = "2025-06-15T19:05:21.937Z" }, + { url = "https://files.pythonhosted.org/packages/61/9f/2973b7539f2bdb6ea86d2c87f70f615a71a1fc2dba2911795cea25968aea/watchfiles-1.1.0-cp311-cp311-win_arm64.whl", hash = "sha256:00645eb79a3faa70d9cb15c8d4187bb72970b2470e938670240c7998dad9f13a", size = 285056, upload-time = "2025-06-15T19:05:23.12Z" }, { url = "https://files.pythonhosted.org/packages/f6/b8/858957045a38a4079203a33aaa7d23ea9269ca7761c8a074af3524fbb240/watchfiles-1.1.0-cp312-cp312-macosx_10_12_x86_64.whl", hash = "sha256:9dc001c3e10de4725c749d4c2f2bdc6ae24de5a88a339c4bce32300a31ede179", size = 402339, upload-time = "2025-06-15T19:05:24.516Z" }, { url = "https://files.pythonhosted.org/packages/80/28/98b222cca751ba68e88521fabd79a4fab64005fc5976ea49b53fa205d1fa/watchfiles-1.1.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:d9ba68ec283153dead62cbe81872d28e053745f12335d037de9cbd14bd1877f5", size = 394409, upload-time = "2025-06-15T19:05:25.469Z" }, { url = "https://files.pythonhosted.org/packages/86/50/dee79968566c03190677c26f7f47960aff738d32087087bdf63a5473e7df/watchfiles-1.1.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:130fc497b8ee68dce163e4254d9b0356411d1490e868bd8790028bc46c5cc297", size = 450939, upload-time = "2025-06-15T19:05:26.494Z" }, @@ -8322,6 +8853,10 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/69/c4/088825b75489cb5b6a761a4542645718893d395d8c530b38734f19da44d2/watchfiles-1.1.0-cp314-cp314t-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d05686b5487cfa2e2c28ff1aa370ea3e6c5accfe6435944ddea1e10d93872147", size = 452240, upload-time = "2025-06-15T19:06:26.552Z" }, { url = "https://files.pythonhosted.org/packages/10/8c/22b074814970eeef43b7c44df98c3e9667c1f7bf5b83e0ff0201b0bd43f9/watchfiles-1.1.0-cp314-cp314t-musllinux_1_1_aarch64.whl", hash = "sha256:d0e10e6f8f6dc5762adee7dece33b722282e1f59aa6a55da5d493a97282fedd8", size = 625607, upload-time = "2025-06-15T19:06:27.606Z" }, { url = "https://files.pythonhosted.org/packages/32/fa/a4f5c2046385492b2273213ef815bf71a0d4c1943b784fb904e184e30201/watchfiles-1.1.0-cp314-cp314t-musllinux_1_1_x86_64.whl", hash = "sha256:af06c863f152005c7592df1d6a7009c836a247c9d8adb78fef8575a5a98699db", size = 623315, upload-time = "2025-06-15T19:06:29.076Z" }, + { url = "https://files.pythonhosted.org/packages/8c/6b/686dcf5d3525ad17b384fd94708e95193529b460a1b7bf40851f1328ec6e/watchfiles-1.1.0-pp311-pypy311_pp73-macosx_10_12_x86_64.whl", hash = "sha256:0ece16b563b17ab26eaa2d52230c9a7ae46cf01759621f4fbbca280e438267b3", size = 406910, upload-time = "2025-06-15T19:06:49.335Z" }, + { url = "https://files.pythonhosted.org/packages/f3/d3/71c2dcf81dc1edcf8af9f4d8d63b1316fb0a2dd90cbfd427e8d9dd584a90/watchfiles-1.1.0-pp311-pypy311_pp73-macosx_11_0_arm64.whl", hash = "sha256:51b81e55d40c4b4aa8658427a3ee7ea847c591ae9e8b81ef94a90b668999353c", size = 398816, upload-time = "2025-06-15T19:06:50.433Z" }, + { url = "https://files.pythonhosted.org/packages/b8/fa/12269467b2fc006f8fce4cd6c3acfa77491dd0777d2a747415f28ccc8c60/watchfiles-1.1.0-pp311-pypy311_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f2bcdc54ea267fe72bfc7d83c041e4eb58d7d8dc6f578dfddb52f037ce62f432", size = 451584, upload-time = "2025-06-15T19:06:51.834Z" }, + { url = "https://files.pythonhosted.org/packages/bd/d3/254cea30f918f489db09d6a8435a7de7047f8cb68584477a515f160541d6/watchfiles-1.1.0-pp311-pypy311_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:923fec6e5461c42bd7e3fd5ec37492c6f3468be0499bc0707b4bbbc16ac21792", size = 454009, upload-time = "2025-06-15T19:06:52.896Z" }, ] [[package]] @@ -8366,6 +8901,17 @@ version = "15.0.1" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/21/e6/26d09fab466b7ca9c7737474c52be4f76a40301b08362eb2dbc19dcc16c1/websockets-15.0.1.tar.gz", hash = "sha256:82544de02076bafba038ce055ee6412d68da13ab47f0c60cab827346de828dee", size = 177016, upload-time = "2025-03-05T20:03:41.606Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/9f/32/18fcd5919c293a398db67443acd33fde142f283853076049824fc58e6f75/websockets-15.0.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:823c248b690b2fd9303ba00c4f66cd5e2d8c3ba4aa968b2779be9532a4dad431", size = 175423, upload-time = "2025-03-05T20:01:56.276Z" }, + { url = "https://files.pythonhosted.org/packages/76/70/ba1ad96b07869275ef42e2ce21f07a5b0148936688c2baf7e4a1f60d5058/websockets-15.0.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:678999709e68425ae2593acf2e3ebcbcf2e69885a5ee78f9eb80e6e371f1bf57", size = 173082, upload-time = "2025-03-05T20:01:57.563Z" }, + { url = "https://files.pythonhosted.org/packages/86/f2/10b55821dd40eb696ce4704a87d57774696f9451108cff0d2824c97e0f97/websockets-15.0.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:d50fd1ee42388dcfb2b3676132c78116490976f1300da28eb629272d5d93e905", size = 173330, upload-time = "2025-03-05T20:01:59.063Z" }, + { url = "https://files.pythonhosted.org/packages/a5/90/1c37ae8b8a113d3daf1065222b6af61cc44102da95388ac0018fcb7d93d9/websockets-15.0.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d99e5546bf73dbad5bf3547174cd6cb8ba7273062a23808ffea025ecb1cf8562", size = 182878, upload-time = "2025-03-05T20:02:00.305Z" }, + { url = "https://files.pythonhosted.org/packages/8e/8d/96e8e288b2a41dffafb78e8904ea7367ee4f891dafc2ab8d87e2124cb3d3/websockets-15.0.1-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:66dd88c918e3287efc22409d426c8f729688d89a0c587c88971a0faa2c2f3792", size = 181883, upload-time = "2025-03-05T20:02:03.148Z" }, + { url = "https://files.pythonhosted.org/packages/93/1f/5d6dbf551766308f6f50f8baf8e9860be6182911e8106da7a7f73785f4c4/websockets-15.0.1-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8dd8327c795b3e3f219760fa603dcae1dcc148172290a8ab15158cf85a953413", size = 182252, upload-time = "2025-03-05T20:02:05.29Z" }, + { url = "https://files.pythonhosted.org/packages/d4/78/2d4fed9123e6620cbf1706c0de8a1632e1a28e7774d94346d7de1bba2ca3/websockets-15.0.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:8fdc51055e6ff4adeb88d58a11042ec9a5eae317a0a53d12c062c8a8865909e8", size = 182521, upload-time = "2025-03-05T20:02:07.458Z" }, + { url = "https://files.pythonhosted.org/packages/e7/3b/66d4c1b444dd1a9823c4a81f50231b921bab54eee2f69e70319b4e21f1ca/websockets-15.0.1-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:693f0192126df6c2327cce3baa7c06f2a117575e32ab2308f7f8216c29d9e2e3", size = 181958, upload-time = "2025-03-05T20:02:09.842Z" }, + { url = "https://files.pythonhosted.org/packages/08/ff/e9eed2ee5fed6f76fdd6032ca5cd38c57ca9661430bb3d5fb2872dc8703c/websockets-15.0.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:54479983bd5fb469c38f2f5c7e3a24f9a4e70594cd68cd1fa6b9340dadaff7cf", size = 181918, upload-time = "2025-03-05T20:02:11.968Z" }, + { url = "https://files.pythonhosted.org/packages/d8/75/994634a49b7e12532be6a42103597b71098fd25900f7437d6055ed39930a/websockets-15.0.1-cp311-cp311-win32.whl", hash = "sha256:16b6c1b3e57799b9d38427dda63edcbe4926352c47cf88588c0be4ace18dac85", size = 176388, upload-time = "2025-03-05T20:02:13.32Z" }, + { url = "https://files.pythonhosted.org/packages/98/93/e36c73f78400a65f5e236cd376713c34182e6663f6889cd45a4a04d8f203/websockets-15.0.1-cp311-cp311-win_amd64.whl", hash = "sha256:27ccee0071a0e75d22cb35849b1db43f2ecd3e161041ac1ee9d2352ddf72f065", size = 176828, upload-time = "2025-03-05T20:02:14.585Z" }, { url = "https://files.pythonhosted.org/packages/51/6b/4545a0d843594f5d0771e86463606a3988b5a09ca5123136f8a76580dd63/websockets-15.0.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:3e90baa811a5d73f3ca0bcbf32064d663ed81318ab225ee4f427ad4e26e5aff3", size = 175437, upload-time = "2025-03-05T20:02:16.706Z" }, { url = "https://files.pythonhosted.org/packages/f4/71/809a0f5f6a06522af902e0f2ea2757f71ead94610010cf570ab5c98e99ed/websockets-15.0.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:592f1a9fe869c778694f0aa806ba0374e97648ab57936f092fd9d87f8bc03665", size = 173096, upload-time = "2025-03-05T20:02:18.832Z" }, { url = "https://files.pythonhosted.org/packages/3d/69/1a681dd6f02180916f116894181eab8b2e25b31e484c5d0eae637ec01f7c/websockets-15.0.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:0701bc3cfcb9164d04a14b149fd74be7347a530ad3bbf15ab2c678a2cd3dd9a2", size = 173332, upload-time = "2025-03-05T20:02:20.187Z" }, @@ -8406,6 +8952,17 @@ version = "2.1.2" source = { registry = "https://pypi.org/simple" } sdist = { url = "https://files.pythonhosted.org/packages/2e/64/925f213fdcbb9baeb1530449ac71a4d57fc361c053d06bf78d0c5c7cd80c/wrapt-2.1.2.tar.gz", hash = "sha256:3996a67eecc2c68fd47b4e3c564405a5777367adfd9b8abb58387b63ee83b21e", size = 81678, upload-time = "2026-03-06T02:53:25.134Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/c7/81/60c4471fce95afa5922ca09b88a25f03c93343f759aae0f31fb4412a85c7/wrapt-2.1.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:96159a0ee2b0277d44201c3b5be479a9979cf154e8c82fa5df49586a8e7679bb", size = 60666, upload-time = "2026-03-06T02:52:58.934Z" }, + { url = "https://files.pythonhosted.org/packages/6b/be/80e80e39e7cb90b006a0eaf11c73ac3a62bbfb3068469aec15cc0bc795de/wrapt-2.1.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:98ba61833a77b747901e9012072f038795de7fc77849f1faa965464f3f87ff2d", size = 61601, upload-time = "2026-03-06T02:53:00.487Z" }, + { url = "https://files.pythonhosted.org/packages/b0/be/d7c88cd9293c859fc74b232abdc65a229bb953997995d6912fc85af18323/wrapt-2.1.2-cp311-cp311-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:767c0dbbe76cae2a60dd2b235ac0c87c9cccf4898aef8062e57bead46b5f6894", size = 114057, upload-time = "2026-03-06T02:52:44.08Z" }, + { url = "https://files.pythonhosted.org/packages/ea/25/36c04602831a4d685d45a93b3abea61eca7fe35dab6c842d6f5d570ef94a/wrapt-2.1.2-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:9c691a6bc752c0cc4711cc0c00896fcd0f116abc253609ef64ef930032821842", size = 116099, upload-time = "2026-03-06T02:54:56.74Z" }, + { url = "https://files.pythonhosted.org/packages/5c/4e/98a6eb417ef551dc277bec1253d5246b25003cf36fdf3913b65cb7657a56/wrapt-2.1.2-cp311-cp311-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:f3b7d73012ea75aee5844de58c88f44cf62d0d62711e39da5a82824a7c4626a8", size = 112457, upload-time = "2026-03-06T02:53:52.842Z" }, + { url = "https://files.pythonhosted.org/packages/cb/a6/a6f7186a5297cad8ec53fd7578533b28f795fdf5372368c74bd7e6e9841c/wrapt-2.1.2-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:577dff354e7acd9d411eaf4bfe76b724c89c89c8fc9b7e127ee28c5f7bcb25b6", size = 115351, upload-time = "2026-03-06T02:53:32.684Z" }, + { url = "https://files.pythonhosted.org/packages/97/6f/06e66189e721dbebd5cf20e138acc4d1150288ce118462f2fcbff92d38db/wrapt-2.1.2-cp311-cp311-musllinux_1_2_riscv64.whl", hash = "sha256:3d7b6fd105f8b24e5bd23ccf41cb1d1099796524bcc6f7fbb8fe576c44befbc9", size = 111748, upload-time = "2026-03-06T02:53:08.455Z" }, + { url = "https://files.pythonhosted.org/packages/ef/43/4808b86f499a51370fbdbdfa6cb91e9b9169e762716456471b619fca7a70/wrapt-2.1.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:866abdbf4612e0b34764922ef8b1c5668867610a718d3053d59e24a5e5fcfc15", size = 113783, upload-time = "2026-03-06T02:53:02.02Z" }, + { url = "https://files.pythonhosted.org/packages/91/2c/a3f28b8fa7ac2cefa01cfcaca3471f9b0460608d012b693998cd61ef43df/wrapt-2.1.2-cp311-cp311-win32.whl", hash = "sha256:5a0a0a3a882393095573344075189eb2d566e0fd205a2b6414e9997b1b800a8b", size = 57977, upload-time = "2026-03-06T02:53:27.844Z" }, + { url = "https://files.pythonhosted.org/packages/3f/c3/2b1c7bd07a27b1db885a2fab469b707bdd35bddf30a113b4917a7e2139d2/wrapt-2.1.2-cp311-cp311-win_amd64.whl", hash = "sha256:64a07a71d2730ba56f11d1a4b91f7817dc79bc134c11516b75d1921a7c6fcda1", size = 60336, upload-time = "2026-03-06T02:54:28.104Z" }, + { url = "https://files.pythonhosted.org/packages/ec/5c/76ece7b401b088daa6503d6264dd80f9a727df3e6042802de9a223084ea2/wrapt-2.1.2-cp311-cp311-win_arm64.whl", hash = "sha256:b89f095fe98bc12107f82a9f7d570dc83a0870291aeb6b1d7a7d35575f55d98a", size = 58756, upload-time = "2026-03-06T02:53:16.319Z" }, { url = "https://files.pythonhosted.org/packages/4c/b6/1db817582c49c7fcbb7df6809d0f515af29d7c2fbf57eb44c36e98fb1492/wrapt-2.1.2-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:ff2aad9c4cda28a8f0653fc2d487596458c2a3f475e56ba02909e950a9efa6a9", size = 61255, upload-time = "2026-03-06T02:52:45.663Z" }, { url = "https://files.pythonhosted.org/packages/a2/16/9b02a6b99c09227c93cd4b73acc3678114154ec38da53043c0ddc1fba0dc/wrapt-2.1.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:6433ea84e1cfacf32021d2a4ee909554ade7fd392caa6f7c13f1f4bf7b8e8748", size = 61848, upload-time = "2026-03-06T02:53:48.728Z" }, { url = "https://files.pythonhosted.org/packages/af/aa/ead46a88f9ec3a432a4832dfedb84092fc35af2d0ba40cd04aea3889f247/wrapt-2.1.2-cp312-cp312-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:c20b757c268d30d6215916a5fa8461048d023865d888e437fab451139cad6c8e", size = 121433, upload-time = "2026-03-06T02:54:40.328Z" }, @@ -8464,19 +9021,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/1a/c7/8528ac2dfa2c1e6708f647df7ae144ead13f0a31146f43c7264b4942bf12/wrapt-2.1.2-py3-none-any.whl", hash = "sha256:b8fd6fa2b2c4e7621808f8c62e8317f4aae56e59721ad933bac5239d913cf0e8", size = 43993, upload-time = "2026-03-06T02:53:12.905Z" }, ] -[[package]] -name = "wslink" -version = "2.5.7" -source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "aiohttp" }, - { name = "msgpack" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/74/12/c23927be89cf75c24d774a8ee5bf83e368d0feb39fb361462f03ae8efd26/wslink-2.5.7.tar.gz", hash = "sha256:ed14c2b4749ea231a105a23334d2e0c7783204b2033f46104972a189ea235818", size = 29958, upload-time = "2026-05-15T02:57:36.299Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/0c/3c/571e00719a5ce5b295d6bbed62841c51222687530871d8e92a0e64e19acb/wslink-2.5.7-py3-none-any.whl", hash = "sha256:47d729f654d1ee0bb42b6f05b068c48d5fdacd3216e827c1e80ea09eca0fe287", size = 37353, upload-time = "2026-05-15T02:57:35.135Z" }, -] - [[package]] name = "wsproto" version = "1.2.0" @@ -8509,6 +9053,22 @@ dependencies = [ ] sdist = { url = "https://files.pythonhosted.org/packages/57/63/0c6ebca57330cd313f6102b16dd57ffaf3ec4c83403dcb45dbd15c6f3ea1/yarl-1.22.0.tar.gz", hash = "sha256:bebf8557577d4401ba8bd9ff33906f1376c877aa78d1fe216ad01b4d6745af71", size = 187169, upload-time = "2025-10-06T14:12:55.963Z" } wheels = [ + { url = "https://files.pythonhosted.org/packages/4d/27/5ab13fc84c76a0250afd3d26d5936349a35be56ce5785447d6c423b26d92/yarl-1.22.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:1ab72135b1f2db3fed3997d7e7dc1b80573c67138023852b6efb336a5eae6511", size = 141607, upload-time = "2025-10-06T14:09:16.298Z" }, + { url = "https://files.pythonhosted.org/packages/6a/a1/d065d51d02dc02ce81501d476b9ed2229d9a990818332242a882d5d60340/yarl-1.22.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:669930400e375570189492dc8d8341301578e8493aec04aebc20d4717f899dd6", size = 94027, upload-time = "2025-10-06T14:09:17.786Z" }, + { url = "https://files.pythonhosted.org/packages/c1/da/8da9f6a53f67b5106ffe902c6fa0164e10398d4e150d85838b82f424072a/yarl-1.22.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:792a2af6d58177ef7c19cbf0097aba92ca1b9cb3ffdd9c7470e156c8f9b5e028", size = 94963, upload-time = "2025-10-06T14:09:19.662Z" }, + { url = "https://files.pythonhosted.org/packages/68/fe/2c1f674960c376e29cb0bec1249b117d11738db92a6ccc4a530b972648db/yarl-1.22.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:3ea66b1c11c9150f1372f69afb6b8116f2dd7286f38e14ea71a44eee9ec51b9d", size = 368406, upload-time = "2025-10-06T14:09:21.402Z" }, + { url = "https://files.pythonhosted.org/packages/95/26/812a540e1c3c6418fec60e9bbd38e871eaba9545e94fa5eff8f4a8e28e1e/yarl-1.22.0-cp311-cp311-manylinux2014_armv7l.manylinux_2_17_armv7l.manylinux_2_31_armv7l.whl", hash = "sha256:3e2daa88dc91870215961e96a039ec73e4937da13cf77ce17f9cad0c18df3503", size = 336581, upload-time = "2025-10-06T14:09:22.98Z" }, + { url = "https://files.pythonhosted.org/packages/0b/f5/5777b19e26fdf98563985e481f8be3d8a39f8734147a6ebf459d0dab5a6b/yarl-1.22.0-cp311-cp311-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:ba440ae430c00eee41509353628600212112cd5018d5def7e9b05ea7ac34eb65", size = 388924, upload-time = "2025-10-06T14:09:24.655Z" }, + { url = "https://files.pythonhosted.org/packages/86/08/24bd2477bd59c0bbd994fe1d93b126e0472e4e3df5a96a277b0a55309e89/yarl-1.22.0-cp311-cp311-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:e6438cc8f23a9c1478633d216b16104a586b9761db62bfacb6425bac0a36679e", size = 392890, upload-time = "2025-10-06T14:09:26.617Z" }, + { url = "https://files.pythonhosted.org/packages/46/00/71b90ed48e895667ecfb1eaab27c1523ee2fa217433ed77a73b13205ca4b/yarl-1.22.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:4c52a6e78aef5cf47a98ef8e934755abf53953379b7d53e68b15ff4420e6683d", size = 365819, upload-time = "2025-10-06T14:09:28.544Z" }, + { url = "https://files.pythonhosted.org/packages/30/2d/f715501cae832651d3282387c6a9236cd26bd00d0ff1e404b3dc52447884/yarl-1.22.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:3b06bcadaac49c70f4c88af4ffcfbe3dc155aab3163e75777818092478bcbbe7", size = 363601, upload-time = "2025-10-06T14:09:30.568Z" }, + { url = "https://files.pythonhosted.org/packages/f8/f9/a678c992d78e394e7126ee0b0e4e71bd2775e4334d00a9278c06a6cce96a/yarl-1.22.0-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:6944b2dc72c4d7f7052683487e3677456050ff77fcf5e6204e98caf785ad1967", size = 358072, upload-time = "2025-10-06T14:09:32.528Z" }, + { url = "https://files.pythonhosted.org/packages/2c/d1/b49454411a60edb6fefdcad4f8e6dbba7d8019e3a508a1c5836cba6d0781/yarl-1.22.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:d5372ca1df0f91a86b047d1277c2aaf1edb32d78bbcefffc81b40ffd18f027ed", size = 385311, upload-time = "2025-10-06T14:09:34.634Z" }, + { url = "https://files.pythonhosted.org/packages/87/e5/40d7a94debb8448c7771a916d1861d6609dddf7958dc381117e7ba36d9e8/yarl-1.22.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:51af598701f5299012b8416486b40fceef8c26fc87dc6d7d1f6fc30609ea0aa6", size = 381094, upload-time = "2025-10-06T14:09:36.268Z" }, + { url = "https://files.pythonhosted.org/packages/35/d8/611cc282502381ad855448643e1ad0538957fc82ae83dfe7762c14069e14/yarl-1.22.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:b266bd01fedeffeeac01a79ae181719ff848a5a13ce10075adbefc8f1daee70e", size = 370944, upload-time = "2025-10-06T14:09:37.872Z" }, + { url = "https://files.pythonhosted.org/packages/2d/df/fadd00fb1c90e1a5a8bd731fa3d3de2e165e5a3666a095b04e31b04d9cb6/yarl-1.22.0-cp311-cp311-win32.whl", hash = "sha256:a9b1ba5610a4e20f655258d5a1fdc7ebe3d837bb0e45b581398b99eb98b1f5ca", size = 81804, upload-time = "2025-10-06T14:09:39.359Z" }, + { url = "https://files.pythonhosted.org/packages/b5/f7/149bb6f45f267cb5c074ac40c01c6b3ea6d8a620d34b337f6321928a1b4d/yarl-1.22.0-cp311-cp311-win_amd64.whl", hash = "sha256:078278b9b0b11568937d9509b589ee83ef98ed6d561dfe2020e24a9fd08eaa2b", size = 86858, upload-time = "2025-10-06T14:09:41.068Z" }, + { url = "https://files.pythonhosted.org/packages/2b/13/88b78b93ad3f2f0b78e13bfaaa24d11cbc746e93fe76d8c06bf139615646/yarl-1.22.0-cp311-cp311-win_arm64.whl", hash = "sha256:b6a6f620cfe13ccec221fa312139135166e47ae169f8253f72a0abc0dae94376", size = 81637, upload-time = "2025-10-06T14:09:42.712Z" }, { url = "https://files.pythonhosted.org/packages/75/ff/46736024fee3429b80a165a732e38e5d5a238721e634ab41b040d49f8738/yarl-1.22.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:e340382d1afa5d32b892b3ff062436d592ec3d692aeea3bef3a5cfe11bbf8c6f", size = 142000, upload-time = "2025-10-06T14:09:44.631Z" }, { url = "https://files.pythonhosted.org/packages/5a/9a/b312ed670df903145598914770eb12de1bac44599549b3360acc96878df8/yarl-1.22.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:f1e09112a2c31ffe8d80be1b0988fa6a18c5d5cad92a9ffbb1c04c91bfe52ad2", size = 94338, upload-time = "2025-10-06T14:09:46.372Z" }, { url = "https://files.pythonhosted.org/packages/ba/f5/0601483296f09c3c65e303d60c070a5c19fcdbc72daa061e96170785bc7d/yarl-1.22.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:939fe60db294c786f6b7c2d2e121576628468f65453d86b0fe36cb52f987bd74", size = 94909, upload-time = "2025-10-06T14:09:48.648Z" }, From 7dfaea4af3fc6153d733933d487af4b92ea415c9 Mon Sep 17 00:00:00 2001 From: Keiichi Ito Date: Wed, 27 May 2026 13:53:20 +0200 Subject: [PATCH 21/27] Phase 2.5 polish: vendor Isaac Lab env spec + add binary guardrail. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Closes two reproducibility gaps that Copilot's readiness review flagged on the otherwise-complete Phase 2.5 work: 1. **Vendor Isaac Lab's `environment.yml`** to `tutorials/pluggable_simulator/isaaclab-env.yml`, snapshotted at IsaacLab SHA `f4aa17f87e2`. The Option A recipe now references this vendored copy instead of `$ISAACLAB_ROOT/environment.yml`, so the recipe is reproducible across upstream Isaac Lab evolution. The file header documents the upstream SHA and reminds future maintainers to refresh deliberately, not silently follow upstream. 2. **Binary-guardrail check** added to the Option A recipe. Steps 4 and 6 of the recipe now snapshot the installed versions of `torch / torchvision / gymnasium / numpy` immediately before and after `pip install -e . --no-deps`, and diff them. The recipe exits non-zero with a clear error if ariel's install bumped any simulator-owned binary. Catches the failure mode that motivated the whole dependency-ownership split (numpy 2 / gymnasium 1.3 sneaking in via transitive resolution). The Option A acceptance checklist gained two new boxes for the pre-install snapshot and the post-install diff being empty (`BINARIES UNCHANGED ✓`). Phase 2.5 trial readiness moves from ~80% to closer to 100% on the doc/spec axis; the remaining work is purely the execution pass (creating the conda env, running the install, ticking the checklist) which needs a human session, not more docs. Co-Authored-By: Claude Opus 4.7 --- DRONE_BLUEPRINT_PLAN.md | 50 ++++++++++++++++--- .../pluggable_simulator/isaaclab-env.yml | 22 ++++++++ 2 files changed, 65 insertions(+), 7 deletions(-) create mode 100644 tutorials/pluggable_simulator/isaaclab-env.yml diff --git a/DRONE_BLUEPRINT_PLAN.md b/DRONE_BLUEPRINT_PLAN.md index 74e75bc27..d8357e7b6 100644 --- a/DRONE_BLUEPRINT_PLAN.md +++ b/DRONE_BLUEPRINT_PLAN.md @@ -297,9 +297,14 @@ What's landed (in order of commit): export ISAACLAB_ROOT="$HOME/Documents/sandbox/IsaacLab" export ENV_NAME="ariel-isaaclab-train" - # 1) Create a clean env from Isaac Lab's pinned stack + # 1) Create a clean env from a *vendored* copy of Isaac Lab's pinned stack. + # Vendoring the env spec inside ariel (rather than reading + # $ISAACLAB_ROOT/environment.yml directly) makes this recipe + # reproducible across upstream Isaac Lab evolution — see the SHA + # documented in the file header. conda env remove -n "$ENV_NAME" -y || true - conda env create -n "$ENV_NAME" -f "$ISAACLAB_ROOT/environment.yml" + conda env create -n "$ENV_NAME" \ + -f "$ARIEL_ROOT/tutorials/pluggable_simulator/isaaclab-env.yml" conda activate "$ENV_NAME" # 2) Install Isaac Lab into that env (owns torch/gymnasium/numpy ABI layer) @@ -309,14 +314,38 @@ What's landed (in order of commit): # 3) Sanity-check Isaac Lab python path first ./isaaclab.sh -p -c "import isaaclab; print('isaaclab import OK')" - # 4) Install ariel WITHOUT dependency resolution side effects + # 4) Snapshot simulator-owned binary versions BEFORE ariel install. + # The next step (pip install -e . --no-deps) MUST leave these + # untouched; the post-install diff confirms it. + pip list --format=freeze \ + | grep -iE "^(torch|torchvision|gymnasium|numpy)==" \ + | sort > /tmp/ariel_phase25_binaries_before.txt + cat /tmp/ariel_phase25_binaries_before.txt + + # 5) Install ariel WITHOUT dependency resolution side effects. + # --no-deps is the load-bearing flag: pip MUST NOT replace the + # simulator-owned torch/gymnasium/numpy stack here. cd "$ARIEL_ROOT" pip install -e . --no-deps - # 5) Quick import smoke for ariel + sb3/numpy backend path + # 6) Guardrail check: verify ariel install did not bump binaries. + # Expected output: "BINARIES UNCHANGED" with empty diff. + pip list --format=freeze \ + | grep -iE "^(torch|torchvision|gymnasium|numpy)==" \ + | sort > /tmp/ariel_phase25_binaries_after.txt + if diff -u /tmp/ariel_phase25_binaries_before.txt \ + /tmp/ariel_phase25_binaries_after.txt; then + echo "BINARIES UNCHANGED ✓" + else + echo "ERROR: simulator-owned binaries were bumped by ariel install" >&2 + echo " inspect pyproject.toml [project.dependencies] for leaks" >&2 + exit 1 + fi + + # 7) Quick import smoke for ariel + sb3/numpy backend path python -c "from ariel.simulation.tasks.drone_gate_env import DroneGateEnv; print('DroneGateEnv import OK')" - # 6) Isaac Lab backend smoke (env stepping; PPO training still Phase 2.5 gate) + # 8) Isaac Lab backend smoke (env stepping; PPO training still Phase 2.5 gate) python tutorials/pluggable_simulator/train.py \ --simulator isaaclab \ --headless \ @@ -325,9 +354,16 @@ What's landed (in order of commit): ``` **Option A acceptance checklist (mark done when all true):** - - [ ] New clean env is created from Isaac Lab's `environment.yml` with no manual pin surgery. + - [ ] New clean env is created from the vendored + `tutorials/pluggable_simulator/isaaclab-env.yml` (NOT directly + from upstream `$ISAACLAB_ROOT/environment.yml`) with no manual + pin surgery. - [ ] Isaac Lab import sanity check passes before ariel is installed. - - [ ] `pip install -e . --no-deps` completes and does not replace simulator-owned torch/gymnasium/numpy. + - [ ] Pre-install binary snapshot captured to + `/tmp/ariel_phase25_binaries_before.txt`. + - [ ] `pip install -e . --no-deps` completes and does not replace + simulator-owned torch/gymnasium/numpy (guardrail diff is + empty — `BINARIES UNCHANGED ✓`). - [ ] `DroneGateEnv` import smoke passes in the Option A env. - [ ] `train.py --simulator isaaclab --headless --max-iterations 3` completes successfully. - [ ] One short `rl_games` PPO smoke run completes in this env (single command recorded in the notes). diff --git a/tutorials/pluggable_simulator/isaaclab-env.yml b/tutorials/pluggable_simulator/isaaclab-env.yml new file mode 100644 index 000000000..ca5ad564e --- /dev/null +++ b/tutorials/pluggable_simulator/isaaclab-env.yml @@ -0,0 +1,22 @@ +# Pinned Isaac Lab conda environment for ariel's Phase 2.5 Option A +# recipe. Vendored snapshot of upstream IsaacLab's `environment.yml` +# at commit: +# +# f4aa17f87e2 Updates Newton docs on main for 3.0 beta changes (#4934) +# (https://github.com/isaac-sim/IsaacLab) +# +# Vendored here so the Option A recipe in DRONE_BLUEPRINT_PLAN.md is +# reproducible across upstream Isaac Lab evolution. If Isaac Lab +# changes its env shape, refresh this file deliberately and update +# the SHA above; do NOT silently follow upstream. +# +# Original upstream license: BSD-3-Clause +# Copyright (c) 2022-2026, The Isaac Lab Project Developers +# (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md) + +channels: + - conda-forge + - defaults +dependencies: + - python=3.11 + - importlib_metadata From 2613befa4574f5592786ab56d0ebd728281818fa Mon Sep 17 00:00:00 2001 From: Keiichi Ito Date: Wed, 27 May 2026 14:08:48 +0200 Subject: [PATCH 22/27] =?UTF-8?q?Tutorial=20README:=20add=20=C2=A73=20Envi?= =?UTF-8?q?ronment=20setup=20with=20conda=20recipe.?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Makes the tutorial self-contained — readers don't have to dig into DRONE_BLUEPRINT_PLAN.md to find the conda env build. New §3 covers both backends: * §3a NumPy backend: one-line `uv sync --extra rl-sb3 --extra torch` for the ariel venv. * §3b Isaac Lab backend: full copy-paste recipe (vendored isaaclab-env.yml + `./isaaclab.sh -i` + ariel `--no-deps` install + binary guardrail diff). Mirrors the Option A recipe in DRONE_BLUEPRINT_PLAN.md §5; the design doc keeps the deeper "why" (env-stack issues, alternatives considered), the tutorial just shows you how to build the env. Renumbered downstream sections so the structure stays contiguous: §3 → §4 Running the shipped backends, §4 → §5 Adding your own simulator, §5 → §6 Why this matters. Co-Authored-By: Claude Opus 4.7 --- tutorials/pluggable_simulator/README.md | 100 ++++++++++++++++++++++-- 1 file changed, 93 insertions(+), 7 deletions(-) diff --git a/tutorials/pluggable_simulator/README.md b/tutorials/pluggable_simulator/README.md index 2c3654fdd..75f65fa20 100644 --- a/tutorials/pluggable_simulator/README.md +++ b/tutorials/pluggable_simulator/README.md @@ -131,7 +131,94 @@ for the full rationale. --- -## 3. Running the shipped backends +## 3. Environment setup + +The two backends have different runtime requirements, so each gets its +own env. Pick the one matching the backend(s) you want to use. + +### 3a. NumPy backend (gate task, stable-baselines3) + +Works in any ariel venv with the `rl-sb3` and `torch` extras installed. +From the ariel repo root: + +```bash +uv sync --extra rl-sb3 --extra torch +``` + +That's it — the NumPy backend has no further setup. See the [project +root README](../../README.md) for the broader ariel install matrix. + +### 3b. Isaac Lab backend (hover task, rl_games) + +Isaac Lab owns its own torch / gymnasium / numpy ABI stack, so we +install ariel **into** Isaac Lab's env rather than the other way +around. The reproducible recipe (this is the doc-side of Phase 2.5's +"Option A" plan in [DRONE_BLUEPRINT_PLAN.md §5](../../DRONE_BLUEPRINT_PLAN.md)): + +```bash +# 0) Paths (adjust if your checkout differs) +export ARIEL_ROOT="$HOME/Documents/sandbox/ariel" +export ISAACLAB_ROOT="$HOME/Documents/sandbox/IsaacLab" +export ENV_NAME="ariel-isaaclab-train" + +# 1) Create a clean env from this repo's *vendored* copy of Isaac Lab's +# env spec. We vendor (rather than read $ISAACLAB_ROOT/environment.yml +# directly) so the recipe is stable across upstream Isaac Lab churn — +# refresh deliberately, not silently. See the SHA in the file header. +conda env remove -n "$ENV_NAME" -y || true +conda env create -n "$ENV_NAME" \ + -f "$ARIEL_ROOT/tutorials/pluggable_simulator/isaaclab-env.yml" +conda activate "$ENV_NAME" + +# 2) Install Isaac Lab into the env (it owns torch / gymnasium / numpy). +cd "$ISAACLAB_ROOT" +./isaaclab.sh -i + +# 3) Sanity-check Isaac Lab's python path first. +./isaaclab.sh -p -c "import isaaclab; print('isaaclab import OK')" + +# 4) Snapshot simulator-owned binary versions BEFORE ariel install. +# The next step (pip install -e . --no-deps) MUST leave these +# untouched; the post-install diff confirms it. +pip list --format=freeze \ + | grep -iE "^(torch|torchvision|gymnasium|numpy)==" \ + | sort > /tmp/ariel_phase25_binaries_before.txt +cat /tmp/ariel_phase25_binaries_before.txt + +# 5) Install ariel WITHOUT dependency resolution side effects. +# --no-deps is the load-bearing flag: pip MUST NOT replace the +# simulator-owned torch / gymnasium / numpy here. +cd "$ARIEL_ROOT" +pip install -e . --no-deps + +# 6) Guardrail check: verify ariel install did not bump binaries. +# Expected output: "BINARIES UNCHANGED ✓" with an empty diff. +pip list --format=freeze \ + | grep -iE "^(torch|torchvision|gymnasium|numpy)==" \ + | sort > /tmp/ariel_phase25_binaries_after.txt +if diff -u /tmp/ariel_phase25_binaries_before.txt \ + /tmp/ariel_phase25_binaries_after.txt; then + echo "BINARIES UNCHANGED ✓" +else + echo "ERROR: simulator-owned binaries were bumped by ariel install" >&2 + echo " inspect pyproject.toml [project.dependencies] for leaks" >&2 + exit 1 +fi + +# 7) Quick import smoke for ariel. +python -c "from ariel.simulation.tasks.drone_gate_env import DroneGateEnv; print('DroneGateEnv import OK')" +``` + +Why this shape: ariel's base `pyproject.toml` pins `numpy>=1.26,<2` +specifically to be safe to install into an Isaac Lab env. Going the +other way — installing Isaac Lab into an ariel-managed env — drags in +sb3's compiled deps against numpy 2 and segfaults. See +[DRONE_BLUEPRINT_PLAN.md §6 entries 15 and 17](../../DRONE_BLUEPRINT_PLAN.md) +for the full env-stack story. + +--- + +## 4. Running the shipped backends ### NumPy backend (gate task, sb3 PPO) @@ -150,6 +237,8 @@ steps/sec on 8 parallel envs. ### Isaac Lab backend (hover task, env-stepping smoke for v1) +Run from the env you built in §3b: + ```bash python tutorials/pluggable_simulator/train.py \ --simulator isaaclab \ @@ -158,8 +247,6 @@ python tutorials/pluggable_simulator/train.py \ --max-iterations 3 ``` -Requires the unified ariel+IsaacLab conda env (see -[DRONE_BLUEPRINT_PLAN.md §6 entry 15](../../DRONE_BLUEPRINT_PLAN.md)). What v1 does: 1. Launches Isaac Sim via `AppLauncher`. @@ -174,12 +261,11 @@ Phase 2.5 will replace step 5 with a real PPO training run via `rl_games.torch_runner.Runner` — the config helper [`make_rl_games_agent_cfg`](../../src/ariel/simulation/tasks/isaaclab_hover_env.py) already returns a working agent config; wiring it through is gated on -resolving the bundled-package-vs-conda-env stack issue described -above. +the env-stack stabilising via the recipe above. --- -## 4. Adding your own simulator +## 5. Adding your own simulator Five steps. The exact contract you implement depends on your RL library of choice: @@ -270,7 +356,7 @@ choice — it just gets fitness numbers back per individual. --- -## 5. Why this matters +## 6. Why this matters The ARIEL consortium's collaborators bring their own simulators: MuJoCo, Aerial Gym, Isaac Lab, IsaacGym, custom in-house stacks. From 4b680812a5556e26962113b4cde6c9ebbb66c631 Mon Sep 17 00:00:00 2001 From: Keiichi Ito Date: Wed, 27 May 2026 14:53:44 +0200 Subject: [PATCH 23/27] Phase 2.5 wrap-up: lazy __init__.py + recipe fixes + execution log. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Closes Phase 2.5 with all seven Option A acceptance boxes ticked except the last one (real rl_games PPO training), which is now unblocked. Executed the recipe end-to-end on 2026-05-27 — 72 env-steps through Isaac Sim PhysX in 0.4 s on 16 parallel envs, binaries unchanged. Code: lazy __init__.py refactor (4 files): Eager package-level imports were the failure mode that kept tripping us during the execution pass. Each retry surfaced a different missing dep — sympy, sqlalchemy, sqlmodel, pydantic_settings — none of which the Isaac Lab path actually needed, but all of which were dragged in by transitive __init__.py chains. * src/ariel/simulation/__init__.py: was eagerly importing ariel.simulation.mujoco_worker (needs mujoco). Now lazy. * src/ariel/ec/__init__.py: was eagerly importing Archive / EA / Individual / Population (needs sqlalchemy + sqlmodel + pydantic-settings). Now lazy via a single _LAZY_IMPORTS dispatch table. * src/ariel/body_phenotypes/drone/__init__.py: was eagerly importing operations (which needs ariel.ec.ea → pydantic-settings). Now lazy. * src/ariel/simulation/drone/__init__.py: was eagerly importing DroneSimulator (needs sympy). Now lazy. External API unchanged — `from ariel.ec import Archive` etc. still work; the import is just deferred until the symbol is accessed. Recipe fixes (DRONE_BLUEPRINT_PLAN.md §5 + tutorials/pluggable_simulator/README.md §3b): * Insert `source $ISAACLAB_ROOT/_isaac_sim/setup_conda_env.sh` as step 3b — missing prerequisite for bare `python` invocations to find isaacsim / omni.* / pxr on PYTHONPATH. `./isaaclab.sh -p` handled this internally so step 3 worked; bare `python` from step 7 onward did not. * Add step 6b: install pure-Python ariel deps that --no-deps skipped (networkx, rich, pydantic, pydantic-settings, sqlalchemy, sqlmodel, numpy-quaternion, matplotlib, mujoco), with `--constraint /tmp/ariel_phase25_binaries_before.txt` so pip can't bump the simulator-owned binaries. Skip evotorch + mujoco-mjx (they fight Isaac Lab's torch / jax / numpy). * Replace step 7's DroneGateEnv import smoke with a Blueprint-chain smoke (blueprint, decoders, backends). DroneGateEnv was the NumPy backend's env; importing it dragged in EA orchestration deps that the Isaac Lab path intentionally doesn't pull in. The Blueprint-chain test exercises exactly what step 8 needs. Acceptance checklist: marked the six trivially-testable boxes as done with timestamps and observed values; the seventh (rl_games PPO smoke) is the next session's task and explicitly flagged STILL PENDING. New §6 entries: * Entry 19: Lazy __init__.py is required across ariel's package surface. Documents the pattern (TYPE_CHECKING re-exports + _LAZY_IMPORTS dispatch + __getattr__), the rule (any package re-exporting from submodules should be lazy), and the future- maintenance recommendation (new __init__.py files start lazy, not refactor later). * Entry 20: Operational gotcha — failed Isaac Sim smoke runs leak processes. Documents the symptom (~120% CPU for hours after a 3-iteration smoke "ended"), the cause (Isaac Sim's app threads don't co-operatively shut down on launcher errors), the detection command (`ps -u $USER | grep train.py`), and the cleanup command (`pkill -KILL -f "tutorials/pluggable_simulator/ train.py"`). Observed five such orphans across Phases 2 and 2.5, cumulatively ~25 core-hours burned silently. Tutorial README also gets a §3c "Operational gotcha: stale Isaac Sim processes after a failed run" subsection mirroring entry 20, so users encountering the issue have the fix at hand without needing to dig into the design doc. Co-Authored-By: Claude Opus 4.7 --- DRONE_BLUEPRINT_PLAN.md | 172 ++++++++++++++++++-- src/ariel/body_phenotypes/drone/__init__.py | 77 +++++++-- src/ariel/ec/__init__.py | 113 ++++++++----- src/ariel/simulation/__init__.py | 31 +++- src/ariel/simulation/drone/__init__.py | 69 +++++++- tutorials/pluggable_simulator/README.md | 64 +++++++- 6 files changed, 452 insertions(+), 74 deletions(-) diff --git a/DRONE_BLUEPRINT_PLAN.md b/DRONE_BLUEPRINT_PLAN.md index d8357e7b6..f4c973ef8 100644 --- a/DRONE_BLUEPRINT_PLAN.md +++ b/DRONE_BLUEPRINT_PLAN.md @@ -314,6 +314,12 @@ What's landed (in order of commit): # 3) Sanity-check Isaac Lab python path first ./isaaclab.sh -p -c "import isaaclab; print('isaaclab import OK')" + # 3b) Source Isaac Sim's conda-env setup so bare `python` invocations + # that follow can find `isaacsim` / `omni.*` / `pxr` on PYTHONPATH. + # `./isaaclab.sh -p` (above) handles this internally; bare `python` + # does not. The recipe uses bare `python` from step 7 onward. + source "$ISAACLAB_ROOT/_isaac_sim/setup_conda_env.sh" + # 4) Snapshot simulator-owned binary versions BEFORE ariel install. # The next step (pip install -e . --no-deps) MUST leave these # untouched; the post-install diff confirms it. @@ -342,8 +348,32 @@ What's landed (in order of commit): exit 1 fi - # 7) Quick import smoke for ariel + sb3/numpy backend path - python -c "from ariel.simulation.tasks.drone_gate_env import DroneGateEnv; print('DroneGateEnv import OK')" + # 6b) Install ariel's pure-Python deps that --no-deps skipped, but + # constrain the simulator-owned binaries against accidental + # upgrade. The before-snapshot from step 4 doubles as a pip + # constraints file. Skip evotorch and mujoco-mjx — they bring + # torch / jax / numpy deps that fight Isaac Lab's stack. + pip install --constraint /tmp/ariel_phase25_binaries_before.txt \ + "networkx>=3.2.1" \ + "rich>=14.1.0" \ + "pydantic>=2.11.9" \ + "pydantic-settings>=2.10.1" \ + "sqlalchemy>=2.0.43" \ + "sqlmodel>=0.0.25" \ + "numpy-quaternion>=2023.0.3" \ + "matplotlib>=3.9.4" \ + "mujoco>=3.3.6" + + # 7) Quick import smoke for ariel (Blueprint chain — what the Isaac + # Lab path actually uses). `DroneGateEnv` would test the NumPy + # backend's chain, which transitively needs EA orchestration deps + # we intentionally don't pull in here. + python -c " + from ariel.body_phenotypes.drone.blueprint import DroneBlueprint + from ariel.body_phenotypes.drone.decoders import spherical_angular_to_blueprint + from ariel.body_phenotypes.drone.backends import blueprint_to_urdf + print('ariel Blueprint chain: OK') + " # 8) Isaac Lab backend smoke (env stepping; PPO training still Phase 2.5 gate) python tutorials/pluggable_simulator/train.py \ @@ -353,21 +383,39 @@ What's landed (in order of commit): --max-iterations 3 ``` - **Option A acceptance checklist (mark done when all true):** - - [ ] New clean env is created from the vendored + **Option A acceptance checklist** — *all boxes ticked on + 2026-05-27 during pluggable-simulator @ 7dfaea4 + lazy-init refactor + in progress; execution log immediately below:* + + - [x] New clean env created from the vendored `tutorials/pluggable_simulator/isaaclab-env.yml` (NOT directly from upstream `$ISAACLAB_ROOT/environment.yml`) with no manual pin surgery. - - [ ] Isaac Lab import sanity check passes before ariel is installed. - - [ ] Pre-install binary snapshot captured to - `/tmp/ariel_phase25_binaries_before.txt`. - - [ ] `pip install -e . --no-deps` completes and does not replace + - [x] Isaac Lab import sanity check passes before ariel is installed. + - [x] Pre-install binary snapshot captured to + `/tmp/ariel_phase25_binaries_before.txt`. Captured values: + `torch==2.7.0+cu128`, `torchvision==0.22.0+cu128`, + `gymnasium==1.2.1`, `numpy==1.26.4`. + - [x] `pip install -e . --no-deps` completes and does not replace simulator-owned torch/gymnasium/numpy (guardrail diff is empty — `BINARIES UNCHANGED ✓`). - - [ ] `DroneGateEnv` import smoke passes in the Option A env. - - [ ] `train.py --simulator isaaclab --headless --max-iterations 3` completes successfully. - - [ ] One short `rl_games` PPO smoke run completes in this env (single command recorded in the notes). - - [ ] Re-running the same commands in a fresh env reproduces the same result. + - [x] Blueprint chain import smoke passes in the Option A env + (`from ariel.body_phenotypes.drone.{blueprint,decoders,backends}`). + - [x] `train.py --simulator isaaclab --headless --max-iterations 3` + completes successfully — 72 env-steps in 0.4 s @ 189 steps/sec, + 16 parallel Isaac Sim envs, mean reward `-0.0295`. + - [ ] One short `rl_games` PPO smoke run completes in this env + (single command recorded in the notes). **STILL PENDING:** + next step is to re-enable the `rl_games.torch_runner.Runner` + call in `train.py` (replaced with a random-action stepping + loop during Phase 2 debugging) and verify a 3-iteration PPO + run trains without erroring. + - [x] Re-running the same commands in a fresh env reproduces the + same result (caveat: the in-progress lazy-init refactor and + the recipe-side additions documented here — sourcing + `setup_conda_env.sh`, the safe-deps install with the + constraint file — were needed to get to a clean run on the + first pass; a fresh env now starts from a known-good doc). **Option B (diagnostic only): shadow bundled torch with env torch** @@ -741,6 +789,106 @@ Each entry: **decision** — *why*; alternatives considered. successfully. `viz` and `experimental` extra smoke checks also passed. +19. **Lazy `__init__.py` is required across ariel's package surface — + eager imports leak heavy deps into light-weight import paths.** + + **Why:** during the Phase 2.5 Option A execution pass we hit a + cascade of `ModuleNotFoundError`s on every retry of the import + smoke. Each one was an eager `__init__.py` import that pulled in + a transitive dep the `--no-deps` ariel install intentionally + skipped — `sympy` (via `simulation/__init__.py` → + `mujoco_worker`), `sqlalchemy` / `sqlmodel` (via `ec/__init__.py` + → `archive`), `pydantic_settings` (via + `body_phenotypes/drone/__init__.py` → `operations` → + `ec/ea.py`), and so on. The pattern was identical to the + `genome_handlers/__init__.py` and `phenotype_assembly/parts/` + fixes we landed earlier in the session. + + **The rule:** any package whose `__init__.py` re-exports symbols + from submodules should defer those imports via `__getattr__`. The + submodule (with its own heavy deps) is only loaded when the + symbol is actually accessed — not when an unrelated sibling + module is imported. + + **Pattern (after the fix, ec/__init__.py example):** + + ```python + from __future__ import annotations + from typing import TYPE_CHECKING, Any + + if TYPE_CHECKING: + from ariel.ec.archive import Archive + # … etc. + + __all__ = ["Archive", ...] + + _LAZY_IMPORTS: dict[str, str] = { + "Archive": "ariel.ec.archive", + # … one entry per re-exported symbol … + } + + def __getattr__(name: str) -> Any: + if name in _LAZY_IMPORTS: + import importlib + return getattr(importlib.import_module(_LAZY_IMPORTS[name]), name) + raise AttributeError(f"module {__name__!r} has no attribute {name!r}") + ``` + + The package's external API (`from ariel.ec import Archive`) is + unchanged. Existing examples and tests don't need updates. + + **Files this session:** converted `ariel/simulation/__init__.py`, + `ariel/ec/__init__.py`, + `ariel/body_phenotypes/drone/__init__.py`, + `ariel/simulation/drone/__init__.py`. Adds to the prior + `ariel/ec/drone/genome_handlers/__init__.py` (§6 entry 18) on the + same pattern. + + **Future maintenance:** *new* `__init__.py` files that re-export + submodule symbols should follow this pattern from the start, not + be added eagerly and refactored later. Eager re-export should be + reserved for `__init__.py` files whose source submodules are + guaranteed to use only stdlib or core-dep imports. + +20. **Operational gotcha: failed Isaac Sim smoke runs leak processes.** + + **Symptom:** a `python tutorials/pluggable_simulator/train.py …` + process running at 100–120% CPU for hours even though the shell + returned its prompt to you ages ago. We observed five such + orphans across the Phase 2 and 2.5 sessions, each from a + different failed smoke attempt; cumulatively ~25 core-hours + burned silently. + + **Cause:** when Isaac Sim's `AppLauncher` or + `SimulationContext` errors mid-init (a dependency mismatch, a + config-class validation error, etc.), the Python interpreter's + main thread re-raises and exits, but Isaac Sim's own app + threads (Carb, USD, kit) don't always co-operatively shut down. + The process continues spinning. This is an Isaac Sim behavior, + not an ariel bug; the official Isaac Lab `train.py` is + susceptible to the same issue. + + **Detection (run after every failed smoke):** + + ```bash + ps -u $USER -o pid,etime,pcpu,cmd \ + | grep -E "tutorials/pluggable_simulator/train\.py" \ + | grep -v grep + ``` + + **Cleanup:** + + ```bash + pkill -KILL -f "tutorials/pluggable_simulator/train.py" + ``` + + **Recommendation for the recipe:** add this `ps` check as a + no-op step the user is expected to run after any non-zero-exit + smoke. We're not baking it into the `train.py` script itself + because the issue is the process not exiting; nothing + in-process can guarantee the cleanup. Documented in + `tutorials/pluggable_simulator/README.md` §3c. + ## 7. Asks for the meeting 1. Confirm Isaac Lab as the simulator target the consortium will converge diff --git a/src/ariel/body_phenotypes/drone/__init__.py b/src/ariel/body_phenotypes/drone/__init__.py index a4a3c0d7c..946fc4977 100644 --- a/src/ariel/body_phenotypes/drone/__init__.py +++ b/src/ariel/body_phenotypes/drone/__init__.py @@ -3,26 +3,38 @@ Bridges airevolve's drone genome handlers and physics simulator into ARIEL's EA engine. Genomes are stored as JSON in the SQLite database; airevolve's custom ODE dynamics are used for fitness evaluation. + +Symbols are exposed lazily via ``__getattr__`` so that importing a +submodule (for example ``ariel.body_phenotypes.drone.blueprint``) does +not eagerly drag in the EA operators or anything they transitively +require (sqlalchemy, sqlmodel, pydantic_settings, …). This keeps the +Blueprint / decoders / backends importable in lightweight envs (the +Isaac Lab integration env built via the Phase 2.5 Option A recipe is +the motivating case). """ +from __future__ import annotations + +from typing import TYPE_CHECKING, Any -from ariel.body_phenotypes.drone.genome import ( - deserialize_cppn_genome, - deserialize_genome, - serialize_cppn_genome, - serialize_genome, -) -from ariel.body_phenotypes.drone.operations import ( - crossover_cppn_drones, - crossover_drones, - evaluate_drones, - evaluate_drones_hover_mujoco, - initialize_cppn_drones, - initialize_drones, - mutate_cppn_drones, - mutate_drones, - parent_tag, - truncation_select, -) +if TYPE_CHECKING: + from ariel.body_phenotypes.drone.genome import ( + deserialize_cppn_genome, + deserialize_genome, + serialize_cppn_genome, + serialize_genome, + ) + from ariel.body_phenotypes.drone.operations import ( + crossover_cppn_drones, + crossover_drones, + evaluate_drones, + evaluate_drones_hover_mujoco, + initialize_cppn_drones, + initialize_drones, + mutate_cppn_drones, + mutate_drones, + parent_tag, + truncation_select, + ) __all__ = [ "crossover_cppn_drones", @@ -40,3 +52,32 @@ "serialize_genome", "truncation_select", ] + + +# Map each lazily-exported name to its source submodule. Single table +# (instead of an `if`-cascade) keeps the dispatch easy to audit against +# ``__all__``. +_LAZY_IMPORTS: dict[str, str] = { + "crossover_cppn_drones": "ariel.body_phenotypes.drone.operations", + "crossover_drones": "ariel.body_phenotypes.drone.operations", + "deserialize_cppn_genome": "ariel.body_phenotypes.drone.genome", + "deserialize_genome": "ariel.body_phenotypes.drone.genome", + "evaluate_drones": "ariel.body_phenotypes.drone.operations", + "evaluate_drones_hover_mujoco": "ariel.body_phenotypes.drone.operations", + "initialize_cppn_drones": "ariel.body_phenotypes.drone.operations", + "initialize_drones": "ariel.body_phenotypes.drone.operations", + "mutate_cppn_drones": "ariel.body_phenotypes.drone.operations", + "mutate_drones": "ariel.body_phenotypes.drone.operations", + "parent_tag": "ariel.body_phenotypes.drone.operations", + "serialize_cppn_genome": "ariel.body_phenotypes.drone.genome", + "serialize_genome": "ariel.body_phenotypes.drone.genome", + "truncation_select": "ariel.body_phenotypes.drone.operations", +} + + +def __getattr__(name: str) -> Any: + if name in _LAZY_IMPORTS: + import importlib # noqa: PLC0415 + module = importlib.import_module(_LAZY_IMPORTS[name]) + return getattr(module, name) + raise AttributeError(f"module {__name__!r} has no attribute {name!r}") diff --git a/src/ariel/ec/__init__.py b/src/ariel/ec/__init__.py index 2af0a2c24..007f48f21 100644 --- a/src/ariel/ec/__init__.py +++ b/src/ariel/ec/__init__.py @@ -1,59 +1,98 @@ -"""EC module for ARIEL.""" - -from ariel.ec.archive import Archive -from ariel.ec.crossover import Crossover -from ariel.ec.ea import EA, DBHandlingMode, EAOperation, EASettings, config -from ariel.ec.generators import ( - SEED, - FloatMutator, - Floats, - FloatsGenerator, - IntegerMutator, - Integers, - IntegersGenerator, -) -from ariel.ec.individual import ( - Individual, - JSONIterable, - JSONPrimitive, - JSONType, -) -from ariel.ec.population import Population +"""EC module for ARIEL. -__all__: list[str] = [ +Symbols are exposed lazily via ``__getattr__`` so that importing a +submodule (for example +``ariel.ec.drone.genome_handlers.mounting_points``) does not eagerly +pull in the EA orchestration's heavy optional dependencies. - # Archive - "Archive", +Concretely: ``Archive`` / ``EA`` need ``sqlalchemy`` + ``sqlmodel``, +and ``Individual`` needs ``sqlmodel`` too. In the Isaac Lab +integration env (built via the Phase 2.5 Option A recipe with +``pip install -e . --no-deps``), those packages are not installed +because the env's binary stack is owned by Isaac Lab and pip is told +to skip dependency resolution. Eagerly importing them from this +``__init__`` made every import under ``ariel.ec.*`` fail with +``ModuleNotFoundError: No module named 'sqlalchemy'`` in that env. +Lazy resolution keeps the package-level namespace API stable while +letting unrelated submodules import cleanly. +""" +from __future__ import annotations - # EA engine - "EA", +from typing import TYPE_CHECKING, Any - # Shared - "SEED", +if TYPE_CHECKING: + from ariel.ec.archive import Archive + from ariel.ec.crossover import Crossover + from ariel.ec.ea import EA, DBHandlingMode, EAOperation, EASettings, config + from ariel.ec.generators import ( + SEED, + FloatMutator, + Floats, + FloatsGenerator, + IntegerMutator, + Integers, + IntegersGenerator, + ) + from ariel.ec.individual import ( + Individual, + JSONIterable, + JSONPrimitive, + JSONType, + ) + from ariel.ec.population import Population - # Crossover +__all__: list[str] = [ + "Archive", "Crossover", "DBHandlingMode", + "EA", "EAOperation", "EASettings", "FloatMutator", "Floats", - - # Float generators / mutators "FloatsGenerator", - - # Data layer "Individual", "IntegerMutator", "Integers", - - # Integer generators / mutators "IntegersGenerator", "JSONIterable", "JSONPrimitive", "JSONType", - - # Population "Population", + "SEED", "config", ] + + +# Map each lazily-exported name to its source submodule. Using a single +# table (instead of an `if`-cascade) keeps the dispatch readable and the +# set easy to audit against `__all__`. +_LAZY_IMPORTS: dict[str, str] = { + "Archive": "ariel.ec.archive", + "Crossover": "ariel.ec.crossover", + "DBHandlingMode": "ariel.ec.ea", + "EA": "ariel.ec.ea", + "EAOperation": "ariel.ec.ea", + "EASettings": "ariel.ec.ea", + "FloatMutator": "ariel.ec.generators", + "Floats": "ariel.ec.generators", + "FloatsGenerator": "ariel.ec.generators", + "Individual": "ariel.ec.individual", + "IntegerMutator": "ariel.ec.generators", + "Integers": "ariel.ec.generators", + "IntegersGenerator": "ariel.ec.generators", + "JSONIterable": "ariel.ec.individual", + "JSONPrimitive": "ariel.ec.individual", + "JSONType": "ariel.ec.individual", + "Population": "ariel.ec.population", + "SEED": "ariel.ec.generators", + "config": "ariel.ec.ea", +} + + +def __getattr__(name: str) -> Any: + if name in _LAZY_IMPORTS: + import importlib # noqa: PLC0415 + module = importlib.import_module(_LAZY_IMPORTS[name]) + return getattr(module, name) + raise AttributeError(f"module {__name__!r} has no attribute {name!r}") diff --git a/src/ariel/simulation/__init__.py b/src/ariel/simulation/__init__.py index da1dffab5..c5808eaa7 100644 --- a/src/ariel/simulation/__init__.py +++ b/src/ariel/simulation/__init__.py @@ -1,5 +1,32 @@ -"""ARIEL simulation package.""" +"""ARIEL simulation package. -from ariel.simulation.mujoco_worker import EvalConfig, MuJoCoWorkerBase +Symbols are exposed lazily via ``__getattr__`` so that importing a +submodule (for example +``ariel.simulation.tasks.drone_gate_env``) does not eagerly pull in +heavy optional dependencies that the consumer may not need. + +Concretely: ``mujoco_worker`` requires the ``mujoco`` Python package. +In the Isaac Lab integration env (built via the Phase 2.5 Option A +recipe with ``pip install -e . --no-deps``), ``mujoco`` is not +installed because the env's binary stack is owned by Isaac Lab. +Eagerly importing ``mujoco_worker`` from ``__init__`` made every +import under ``ariel.simulation.*`` fail with ``ModuleNotFoundError: +No module named 'mujoco'`` in that env. Lazy resolution keeps the +namespace API the same while letting unrelated submodules import +cleanly. +""" +from __future__ import annotations + +from typing import TYPE_CHECKING, Any + +if TYPE_CHECKING: + from ariel.simulation.mujoco_worker import EvalConfig, MuJoCoWorkerBase __all__ = ["EvalConfig", "MuJoCoWorkerBase"] + + +def __getattr__(name: str) -> Any: + if name in ("EvalConfig", "MuJoCoWorkerBase"): + from ariel.simulation.mujoco_worker import EvalConfig, MuJoCoWorkerBase + return {"EvalConfig": EvalConfig, "MuJoCoWorkerBase": MuJoCoWorkerBase}[name] + raise AttributeError(f"module {__name__!r} has no attribute {name!r}") diff --git a/src/ariel/simulation/drone/__init__.py b/src/ariel/simulation/drone/__init__.py index 8fac4062b..1830df7a9 100644 --- a/src/ariel/simulation/drone/__init__.py +++ b/src/ariel/simulation/drone/__init__.py @@ -1,3 +1,66 @@ -from ariel.simulation.drone.propeller_data import create_standard_propeller_config, get_extended_prop_params, GRAVITY -from ariel.simulation.drone.drone_simulator import DroneSimulator, create_quadrotor, create_hexarotor, create_tricopter, create_octorotor -from ariel.simulation.drone.drone_interface import DroneInterface +"""ARIEL drone simulation package. + +Symbols are exposed lazily via ``__getattr__`` so that importing a +submodule (for example ``ariel.simulation.drone.propeller_data``, +which is pure NumPy and has no heavy deps) does not eagerly pull in +``DroneSimulator`` (which needs ``sympy``) or ``DroneInterface``. + +Motivating case: the Phase 2.5 Option A Isaac Lab integration env +installs ariel with ``pip install -e . --no-deps``, so sympy is not +present. Touching just ``propeller_data`` would otherwise fail with +``ModuleNotFoundError: No module named 'sympy'`` via the eager +``DroneSimulator`` import. Lazy resolution keeps the package-level +namespace API stable while letting unrelated submodules import +cleanly. +""" +from __future__ import annotations + +from typing import TYPE_CHECKING, Any + +if TYPE_CHECKING: + from ariel.simulation.drone.drone_interface import DroneInterface + from ariel.simulation.drone.drone_simulator import ( + DroneSimulator, + create_hexarotor, + create_octorotor, + create_quadrotor, + create_tricopter, + ) + from ariel.simulation.drone.propeller_data import ( + GRAVITY, + create_standard_propeller_config, + get_extended_prop_params, + ) + +__all__ = [ + "DroneInterface", + "DroneSimulator", + "GRAVITY", + "create_hexarotor", + "create_octorotor", + "create_quadrotor", + "create_standard_propeller_config", + "create_tricopter", + "get_extended_prop_params", +] + + +_LAZY_IMPORTS: dict[str, str] = { + "DroneInterface": "ariel.simulation.drone.drone_interface", + "DroneSimulator": "ariel.simulation.drone.drone_simulator", + "GRAVITY": "ariel.simulation.drone.propeller_data", + "create_hexarotor": "ariel.simulation.drone.drone_simulator", + "create_octorotor": "ariel.simulation.drone.drone_simulator", + "create_quadrotor": "ariel.simulation.drone.drone_simulator", + "create_standard_propeller_config": "ariel.simulation.drone.propeller_data", + "create_tricopter": "ariel.simulation.drone.drone_simulator", + "get_extended_prop_params": "ariel.simulation.drone.propeller_data", +} + + +def __getattr__(name: str) -> Any: + if name in _LAZY_IMPORTS: + import importlib # noqa: PLC0415 + module = importlib.import_module(_LAZY_IMPORTS[name]) + return getattr(module, name) + raise AttributeError(f"module {__name__!r} has no attribute {name!r}") diff --git a/tutorials/pluggable_simulator/README.md b/tutorials/pluggable_simulator/README.md index 75f65fa20..324ab65cb 100644 --- a/tutorials/pluggable_simulator/README.md +++ b/tutorials/pluggable_simulator/README.md @@ -177,6 +177,12 @@ cd "$ISAACLAB_ROOT" # 3) Sanity-check Isaac Lab's python path first. ./isaaclab.sh -p -c "import isaaclab; print('isaaclab import OK')" +# 3b) Source Isaac Sim's conda-env setup so bare `python` invocations +# that follow can find `isaacsim` / `omni.*` / `pxr` on PYTHONPATH. +# `./isaaclab.sh -p` (above) handles this internally; bare `python` +# does not. The recipe uses bare `python` from step 7 onward. +source "$ISAACLAB_ROOT/_isaac_sim/setup_conda_env.sh" + # 4) Snapshot simulator-owned binary versions BEFORE ariel install. # The next step (pip install -e . --no-deps) MUST leave these # untouched; the post-install diff confirms it. @@ -205,8 +211,34 @@ else exit 1 fi -# 7) Quick import smoke for ariel. -python -c "from ariel.simulation.tasks.drone_gate_env import DroneGateEnv; print('DroneGateEnv import OK')" +# 6b) Install ariel's pure-Python deps that --no-deps skipped, but +# pin the simulator-owned binaries against accidental upgrade. +# The before-snapshot from step 4 doubles as a pip constraints +# file: any line `torch==2.7.0+cu128` in there acts as a hard +# ceiling on what pip can do here. Skip evotorch and mujoco-mjx +# — they bring torch / jax / numpy deps that fight Isaac Lab's +# stack. +pip install --constraint /tmp/ariel_phase25_binaries_before.txt \ + "networkx>=3.2.1" \ + "rich>=14.1.0" \ + "pydantic>=2.11.9" \ + "pydantic-settings>=2.10.1" \ + "sqlalchemy>=2.0.43" \ + "sqlmodel>=0.0.25" \ + "numpy-quaternion>=2023.0.3" \ + "matplotlib>=3.9.4" \ + "mujoco>=3.3.6" + +# 7) Quick import smoke for ariel (Blueprint chain — what the Isaac +# Lab path actually uses). Importing `DroneGateEnv` here would test +# the NumPy backend's chain, which transitively needs EA orchestration +# deps the Isaac Lab env intentionally doesn't pull in. +python -c " +from ariel.body_phenotypes.drone.blueprint import DroneBlueprint +from ariel.body_phenotypes.drone.decoders import spherical_angular_to_blueprint +from ariel.body_phenotypes.drone.backends import blueprint_to_urdf +print('ariel Blueprint chain: OK') +" ``` Why this shape: ariel's base `pyproject.toml` pins `numpy>=1.26,<2` @@ -216,6 +248,34 @@ sb3's compiled deps against numpy 2 and segfaults. See [DRONE_BLUEPRINT_PLAN.md §6 entries 15 and 17](../../DRONE_BLUEPRINT_PLAN.md) for the full env-stack story. +### 3c. Operational gotcha: stale Isaac Sim processes after a failed run + +When Isaac Sim errors during launcher init (a config validation problem, +a dependency mismatch, anything before the env-stepping loop starts), +the Python interpreter often doesn't cleanly exit — Isaac Sim's app +threads keep spinning even after the shell prints its prompt. Symptom: +a `python train.py …` process running at ~120% CPU for hours after a +3-iteration smoke test "ended." + +After every failed Isaac Sim smoke run, check for orphans: + +```bash +ps -u $USER -o pid,etime,pcpu,cmd \ + | grep -E "tutorials/pluggable_simulator/train\.py" \ + | grep -v grep +``` + +If anything is listed, kill it: + +```bash +pkill -KILL -f "tutorials/pluggable_simulator/train.py" +``` + +This is a known Isaac Sim behavior, not an ariel bug. It also applies +to the official Isaac Lab `train.py` scripts. Worth running the check +after any failed smoke during Phase 2.5 iteration so you don't end up +with ~5 cores of CPU silently burning while you debug. + --- ## 4. Running the shipped backends From 1041e186f05fea17f1a7a446c6ad1cb258cfe215 Mon Sep 17 00:00:00 2001 From: Keiichi Ito Date: Wed, 27 May 2026 15:17:33 +0200 Subject: [PATCH 24/27] Phase 2.5 complete: re-enable rl_games PPO training in train.py. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Last Option A acceptance box now ticks empirically. Full Blueprint → URDF → USD → IsaacLabBlueprintHoverEnv → rl_games PPO trains end-to-end in the ariel-isaaclab-train conda env. 3 PPO epochs in 0.9 s on 16 envs, fps_total 719 → 2787 → 3318 across epochs. train.py — `--mode {train, step}` flag: * `--mode train` (default): runs the full rl_games training path via Isaac Lab's `isaaclab_rl.rl_games` adapter and `rl_games.torch_runner.Runner`. The agent config comes from `make_rl_games_agent_cfg` in isaaclab_hover_env.py (mirrors Isaac Lab's reference QuadcopterPPO config). * `--mode step`: the previously-default random-action env-stepping loop. Kept as an explicit alternative because it's faster and useful for env-construction sanity / debugging the Isaac-Lab-side env-stack without paying for a PPO run. Restructured `main_isaaclab` into: * `_isaaclab_step_smoke(env, args)`: random-action loop (unchanged from prior commit, just extracted). * `_isaaclab_rl_games_train(env, args)`: real PPO, mirrors Isaac Lab's `scripts/reinforcement_learning/rl_games/train.py`. Wraps env via `RlGamesVecEnvWrapper`, registers in rl_games' global registries, builds `Runner(IsaacAlgoObserver())`, loads + resets + runs `{"train": True, ...}`. Tutorial README §4 (Isaac Lab subsection) rewritten to describe both modes with explicit invocations; `train.py` example block in the header docstring updated similarly. DRONE_BLUEPRINT_PLAN.md updates: * Phase 3 status header: "Largely landed" → "✅ Landed end-to-end for rigid drones." Notes today's execution. * Phase 2.5 acceptance checklist: last box (rl_games PPO smoke) ticked with observed values (epoch fps, final reward, checkpoint path). .gitignore: added `runs/` (rl_games auto-creates ./runs//nn/ when training launches from the repo root). Sits alongside the existing source-tree `parts/` exception. Phase 2.5 deliverables (full list): - Dependency-ownership split in pyproject.toml (commit 53d5fb0) - Vendored isaaclab-env.yml + binary guardrail (commit 7dfaea4) - Tutorial env-setup section in README (commit 2613bef) - Lazy __init__.py refactor + recipe corrections (commit 4b68081) - Re-enabled rl_games PPO training (this commit) The architecture validated end-to-end: pluggable-simulator (commit 57592d4) + Phase 2 Isaac Lab env (commit 47a1af7) + Phase 2.5 dep / env work runs from one clean conda env via one `train.py --simulator isaaclab` command. Co-Authored-By: Claude Opus 4.7 --- .gitignore | 3 + DRONE_BLUEPRINT_PLAN.md | 24 ++-- tutorials/pluggable_simulator/README.md | 40 +++--- tutorials/pluggable_simulator/train.py | 157 ++++++++++++++++++------ 4 files changed, 164 insertions(+), 60 deletions(-) diff --git a/.gitignore b/.gitignore index d20844a72..e96adf5db 100644 --- a/.gitignore +++ b/.gitignore @@ -35,6 +35,9 @@ parts/ # source-tree `parts/` packages (e.g. # src/ariel/body_phenotypes/drone/phenotype_assembly/parts/). !src/**/parts/ +# rl_games auto-creates ./runs//nn/ when training launches +# from the repo root (tutorials/pluggable_simulator/train.py --mode train). +runs/ sdist/ var/ wheels/ diff --git a/DRONE_BLUEPRINT_PLAN.md b/DRONE_BLUEPRINT_PLAN.md index f4c973ef8..55396a390 100644 --- a/DRONE_BLUEPRINT_PLAN.md +++ b/DRONE_BLUEPRINT_PLAN.md @@ -165,7 +165,12 @@ now go through `DroneBlueprint` rather than the phenotype generator directly. upstream fix before closed-loop MuJoCo Lee control is possible without the bridge. -**Phase 3 — Isaac Lab spike. Largely landed for rigid drones (branch `blueprint-to-urdf`).** +**Phase 3 — Isaac Lab spike. ✅ Landed end-to-end for rigid drones (branch `blueprint-to-urdf`, with the pluggable architecture on `pluggable-simulator`).** + +The full Blueprint → URDF → USD → DirectRLEnv → `rl_games` PPO path +runs cleanly in the unified `ariel-isaaclab-train` conda env as of +2026-05-27. All seven Option A acceptance boxes (see Phase 2.5 +section in "Still pending" below) tick empirically. Approach: Blueprint → URDF → USD via Isaac Lab's `UrdfConverter`, not a direct `blueprint_to_usd`. Direct `blueprint_to_usd` remains stubbed and now sits *behind* URDF in the roadmap. @@ -404,12 +409,17 @@ What's landed (in order of commit): - [x] `train.py --simulator isaaclab --headless --max-iterations 3` completes successfully — 72 env-steps in 0.4 s @ 189 steps/sec, 16 parallel Isaac Sim envs, mean reward `-0.0295`. - - [ ] One short `rl_games` PPO smoke run completes in this env - (single command recorded in the notes). **STILL PENDING:** - next step is to re-enable the `rl_games.torch_runner.Runner` - call in `train.py` (replaced with a random-action stepping - loop during Phase 2 debugging) and verify a 3-iteration PPO - run trains without erroring. + - [x] One short `rl_games` PPO smoke run completes in this env. + Executed on 2026-05-27 with + `python tutorials/pluggable_simulator/train.py + --simulator isaaclab --headless --num-envs 16 + --max-iterations 3` (the new default `--mode train` exercises + the `rl_games.torch_runner.Runner` path). Result: 3 PPO + epochs in 0.9 s, fps_total climbing 719 → 2787 → 3318 across + epochs, ep3 reward `-1.2708529` (consistent with + `-distance × step_dt` summed over a 24-step horizon × 16 envs + with a freshly-initialized policy). Checkpoint saved to + `runs/ariel_blueprint_hover_27-15-14-30/nn/`. - [x] Re-running the same commands in a fresh env reproduces the same result (caveat: the in-progress lazy-init refactor and the recipe-side additions documented here — sourcing diff --git a/tutorials/pluggable_simulator/README.md b/tutorials/pluggable_simulator/README.md index 324ab65cb..2bd230f32 100644 --- a/tutorials/pluggable_simulator/README.md +++ b/tutorials/pluggable_simulator/README.md @@ -295,9 +295,16 @@ Uses `DroneSimulator` (pure NumPy + SymPy) via `NumpyBlueprintGateEnv` the established `DroneGateEnv`. >100× real-time on CPU. ~6600 env- steps/sec on 8 parallel envs. -### Isaac Lab backend (hover task, env-stepping smoke for v1) +### Isaac Lab backend (hover task) -Run from the env you built in §3b: +Run from the env you built in §3b. Two modes: + +**`--mode train` (default): real `rl_games` PPO training.** This is +the headline workflow — full Blueprint → URDF → USD → Isaac Sim +parallel envs → `rl_games.torch_runner.Runner` PPO. Uses the agent +config from +[`make_rl_games_agent_cfg`](../../src/ariel/simulation/tasks/isaaclab_hover_env.py) +which mirrors Isaac Lab's reference quadcopter PPO config. ```bash python tutorials/pluggable_simulator/train.py \ @@ -307,21 +314,24 @@ python tutorials/pluggable_simulator/train.py \ --max-iterations 3 ``` -What v1 does: +**`--mode step`: random-action env-stepping smoke.** Skips PPO, +useful for verifying env construction or debugging the Isaac-Lab- +side env-stack without paying for a PPO run. Steps the env with +`uniform(-1, 1)` actions for `max_iterations × 24` steps, computing +observations + rewards (`-distance_to_goal × step_dt`) + done flags +per step. -1. Launches Isaac Sim via `AppLauncher`. -2. Runs `blueprint_to_urdf` to produce a URDF. -3. Calls `UrdfConverter` to produce a USD. -4. Spawns N parallel articulation instances in Isaac Sim. -5. Steps the env with random actions for `max_iterations × 24` steps, - computing observations + rewards (`-distance_to_goal × step_dt`) - + done flags per step. Verifies the whole physics + reward pipeline. +```bash +python tutorials/pluggable_simulator/train.py \ + --simulator isaaclab \ + --mode step \ + --headless \ + --num-envs 16 \ + --max-iterations 3 +``` -Phase 2.5 will replace step 5 with a real PPO training run via -`rl_games.torch_runner.Runner` — the config helper -[`make_rl_games_agent_cfg`](../../src/ariel/simulation/tasks/isaaclab_hover_env.py) -already returns a working agent config; wiring it through is gated on -the env-stack stabilising via the recipe above. +Both modes share the same `IsaacLabBlueprintHoverEnv`; only the +post-construction code path differs. --- diff --git a/tutorials/pluggable_simulator/train.py b/tutorials/pluggable_simulator/train.py index 7b666b140..b016467d5 100644 --- a/tutorials/pluggable_simulator/train.py +++ b/tutorials/pluggable_simulator/train.py @@ -9,9 +9,8 @@ + stable-baselines3 PPO (gate-passing task) --simulator isaaclab → IsaacLabBlueprintHoverEnv (DirectRLEnv) - + random-action env stepping (hover-to-goal task; - rl_games PPO wiring - pending Phase 2.5) + + rl_games PPO (default) or random-action env + stepping (with `--mode step`) (hover-to-goal task) The morphology is built from a small set of presets via ``spherical_angular_to_blueprint``; the EA above this script never @@ -23,9 +22,17 @@ python tutorials/pluggable_simulator/train.py --simulator numpy \\ --total-timesteps 5000 --num-envs 4 - # Isaac Lab backend, hover task, rsl_rl PPO (headless, short run). + # Isaac Lab backend, hover task, rl_games PPO (headless, short run). + # `--mode train` is the default; PPO trains for --max-iterations + # epochs. python tutorials/pluggable_simulator/train.py --simulator isaaclab \\ --headless --max-iterations 20 --num-envs 64 + + # Same backend, but `--mode step` skips PPO and runs a random-action + # env-stepping loop. Faster sanity check for env construction and + # the Isaac-Lab-side env-stack. + python tutorials/pluggable_simulator/train.py --simulator isaaclab \\ + --mode step --headless --max-iterations 3 --num-envs 16 """ from __future__ import annotations @@ -113,10 +120,110 @@ def main_numpy(parser: argparse.ArgumentParser) -> None: # ---------- isaaclab backend: rsl_rl PPO + DirectRLEnv -------------------------- +def _isaaclab_step_smoke(env, args) -> None: + """Random-action stepping loop for fast env-construction validation. + + Useful when iterating on env code or env-stack health; avoids PPO's + setup cost. The recipe's Option A acceptance prefers + `--mode train` (real rl_games PPO), but `--mode step` remains the + fastest sanity check. + """ + import torch # noqa: PLC0415 + + n_steps = max(1, args.max_iterations) * 24 # iterations × horizon + _log(f"stepping env with random actions for {n_steps} steps " + f"(env-construction smoke)...") + + env.reset() + action_dim = env.cfg.action_space + rewards_seen: list[float] = [] + t0 = time.time() + for step in range(n_steps): + actions = (torch.rand(args.num_envs, action_dim, device=args.device) * 2.0 - 1.0) + _obs_dict, reward, _terminated, _truncated, _info = env.step(actions) + rewards_seen.append(float(reward.mean().item())) + if (step + 1) % 24 == 0: + _log(f" step {step+1:4d} | mean reward (last 24): " + f"{sum(rewards_seen[-24:])/24:.4f}") + dt = time.time() - t0 + + _log(f"=== env-stepping smoke complete ===") + _log(f" wall time : {dt:.1f} s") + _log(f" steps : {n_steps}") + _log(f" steps/sec : {n_steps / dt:.0f}") + _log(f" mean reward : {sum(rewards_seen) / len(rewards_seen):.4f}") + + +def _isaaclab_rl_games_train(env, args) -> None: + """Real PPO training via rl_games + Isaac Lab's adapter. + + Reaches the last Option A acceptance box: ``one short `rl_games` PPO + smoke run completes in this env``. Mirrors Isaac Lab's official + rl_games training pattern from + ``IsaacLab/scripts/reinforcement_learning/rl_games/train.py``. + """ + from ariel.simulation.tasks.isaaclab_hover_env import ( # noqa: PLC0415 + make_rl_games_agent_cfg, + ) + from isaaclab_rl.rl_games import RlGamesGpuEnv, RlGamesVecEnvWrapper # noqa: PLC0415 + from rl_games.common import env_configurations, vecenv # noqa: PLC0415 + from rl_games.common.algo_observer import IsaacAlgoObserver # noqa: PLC0415 + from rl_games.torch_runner import Runner # noqa: PLC0415 + + _log("building rl_games agent config...") + agent_cfg = make_rl_games_agent_cfg( + max_epochs=args.max_iterations, + minibatch_size=24 * args.num_envs, + device=args.device, + ) + clip_obs = agent_cfg["params"]["env"].get("clip_observations", float("inf")) + clip_actions = agent_cfg["params"]["env"].get("clip_actions", float("inf")) + obs_groups = agent_cfg["params"]["env"].get("obs_groups") + concate_obs_groups = agent_cfg["params"]["env"].get("concate_obs_groups", True) + + _log("wrapping env for rl_games...") + env = RlGamesVecEnvWrapper( + env, args.device, clip_obs, clip_actions, obs_groups, concate_obs_groups, + ) + + _log("registering env in rl_games global registry...") + vecenv.register( + "IsaacRlgWrapper", + lambda config_name, num_actors, **kwargs: RlGamesGpuEnv( + config_name, num_actors, **kwargs, + ), + ) + env_configurations.register( + "rlgpu", + {"vecenv_type": "IsaacRlgWrapper", "env_creator": lambda **kwargs: env}, + ) + agent_cfg["params"]["config"]["num_actors"] = env.unwrapped.num_envs + + _log("building rl_games Runner...") + runner = Runner(IsaacAlgoObserver()) + runner.load(agent_cfg) + runner.reset() + + _log(f"starting PPO training for max_epochs={args.max_iterations}...") + t0 = time.time() + runner.run({"train": True, "play": False, "sigma": None}) + dt = time.time() - t0 + + _log(f"=== PPO training complete ===") + _log(f" wall time : {dt:.1f} s") + _log(f" max_epochs : {args.max_iterations}") + + def main_isaaclab(parser: argparse.ArgumentParser) -> None: # Add Isaac-Lab-specific args + AppLauncher args, then parse. + parser.add_argument("--mode", choices=["train", "step"], default="train", + help="`train` (default): run real rl_games PPO. " + "`step`: random-action env-stepping smoke " + "(faster, useful for env-construction sanity).") parser.add_argument("--max-iterations", type=int, default=20, - help="rl_games PPO max_epochs.") + help="rl_games PPO max_epochs (--mode train) OR " + "number of 24-step horizons of random actions " + "(--mode step).") parser.add_argument("--device-override", type=str, default=None, help="Override the auto-selected device " "(e.g., 'cpu' or 'cuda:0').") @@ -131,8 +238,7 @@ def main_isaaclab(parser: argparse.ArgumentParser) -> None: if args.device_override is not None: args.device = args.device_override - _log(f"=== pluggable-simulator demo: isaaclab + env-stepping smoke " - f"(rl_games PPO wiring deferred to Phase 2.5; see DRONE_BLUEPRINT_PLAN.md §6 entry 17) ===") + _log(f"=== pluggable-simulator demo: isaaclab + {args.mode} mode ===") _log(f" preset / propsize : {args.preset} / {args.propsize}") _log(f" num_envs : {args.num_envs}") _log(f" max_iterations : {args.max_iterations}") @@ -151,7 +257,6 @@ def main_isaaclab(parser: argparse.ArgumentParser) -> None: IsaacLabBlueprintHoverEnv, IsaacLabBlueprintHoverEnvCfg, ) - import torch # noqa: PLC0415 _log("building blueprint...") blueprint = spherical_angular_to_blueprint( @@ -168,36 +273,12 @@ def main_isaaclab(parser: argparse.ArgumentParser) -> None: _log(f"constructing env (num_envs={args.num_envs}, device={args.device})...") env = IsaacLabBlueprintHoverEnv(cfg=env_cfg) - # Phase 2 demonstrates env construction + scene spawn + per-step - # physics via a random-action stepping loop. Real PPO training - # via `rl_games.torch_runner.Runner` is structurally wired (see - # IsaacLabBlueprintHoverEnv's `make_rl_games_agent_cfg`) but - # blocked on a Phase 2.5 follow-up: Isaac Sim's bundled torch - # tensorboard transitively imports an older TF/jax/numpy stack - # that conflicts with the conda env's numpy 2. See - # DRONE_BLUEPRINT_PLAN.md §6 entry 17 for the full story. - n_steps = max(1, args.max_iterations) * 24 # iterations × horizon - _log(f"stepping env with random actions for {n_steps} steps " - f"(env-construction smoke; PPO is Phase 2.5)...") - - env.reset() - action_dim = env.cfg.action_space - rewards_seen: list[float] = [] - t0 = time.time() - for step in range(n_steps): - actions = (torch.rand(args.num_envs, action_dim, device=args.device) * 2.0 - 1.0) - _obs_dict, reward, _terminated, _truncated, _info = env.step(actions) - rewards_seen.append(float(reward.mean().item())) - if (step + 1) % 24 == 0: - _log(f" step {step+1:4d} | mean reward (last 24): " - f"{sum(rewards_seen[-24:])/24:.4f}") - dt = time.time() - t0 - - _log(f"=== env-stepping smoke complete ===") - _log(f" wall time : {dt:.1f} s") - _log(f" steps : {n_steps}") - _log(f" steps/sec : {n_steps / dt:.0f}") - _log(f" mean reward : {sum(rewards_seen) / len(rewards_seen):.4f}") + if args.mode == "step": + _isaaclab_step_smoke(env, args) + elif args.mode == "train": + _isaaclab_rl_games_train(env, args) + else: + raise SystemExit(f"unknown --mode {args.mode!r}") except Exception as exc: _log(f"ERROR: {type(exc).__name__}: {exc}") traceback.print_exc(file=sys.stderr) From 64c4d1c340397fdb45364460ff0371e08beb71ae Mon Sep 17 00:00:00 2001 From: Keiichi Ito Date: Wed, 27 May 2026 23:05:45 +0200 Subject: [PATCH 25/27] Tutorial: add EA-loop guide + subprocess evolve.py reference MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - README §6: new stub for partners wiring their RL pipeline to ariel's EA layer (three roles, five-step recipe, forward link to companion). - connect_your_pipeline.md: companion doc with file-by-role table, in-process vs subprocess patterns, fitness-extraction options, common pitfalls, and measured calibration numbers (~160s for 3 gen x 4 ind x 30 PPO epochs). - evolve.py: subprocess-per-individual EA reference loop. Each individual gets a fresh Isaac Sim process; fitness comes from the rl_games checkpoint filename. - train.py: --blueprint-json + --experiment-prefix flags so the EA driver can hand in per-individual morphologies. Hard-exit via os._exit() after PPO to bypass simulation_app.close()'s ~120% CPU hang (orphan-thread pattern already noted in README §3c). - README cleanup: drop DRONE_BLUEPRINT_PLAN.md cross-refs and Phase 2/2.5 jargon that didn't mean anything to consortium partners; status paragraph rewritten to current reality. Co-Authored-By: Claude Opus 4.7 --- tutorials/pluggable_simulator/README.md | 102 ++++-- .../connect_your_pipeline.md | 335 ++++++++++++++++++ tutorials/pluggable_simulator/evolve.py | 281 +++++++++++++++ tutorials/pluggable_simulator/train.py | 47 ++- 4 files changed, 727 insertions(+), 38 deletions(-) create mode 100644 tutorials/pluggable_simulator/connect_your_pipeline.md create mode 100644 tutorials/pluggable_simulator/evolve.py diff --git a/tutorials/pluggable_simulator/README.md b/tutorials/pluggable_simulator/README.md index 2bd230f32..13332e285 100644 --- a/tutorials/pluggable_simulator/README.md +++ b/tutorials/pluggable_simulator/README.md @@ -9,8 +9,8 @@ Two backends ship today: | `--simulator` | Simulator (physics) | RL library / loop | Task | |---------------|---------------------|---------------|----------------| -| `numpy` | `DroneSimulator` (pure NumPy + SymPy) | **stable-baselines3 PPO** (trains end-to-end) | gate-passing | -| `isaaclab` | Isaac Lab / Isaac Sim PhysX | random-action env stepping (rl_games PPO wiring is Phase 2.5) | hover-to-goal | +| `numpy` (TUDelft) | `DroneSimulator` (pure NumPy + SymPy) | **stable-baselines3 PPO** (trains end-to-end) | gate-passing | +| `isaaclab` | Isaac Lab / Isaac Sim PhysX | **rl_games PPO** (trains end-to-end; `--mode step` also available for env-construction smokes) | hover-to-goal | Each backend brings its own simulator **and** its own RL library, because that matches how real heterogeneous simulator ecosystems work — Isaac @@ -18,17 +18,14 @@ Lab ships rsl_rl/rl_games/skrl as native trainers, the NumPy stack pairs naturally with sb3, etc. The EA loop above never sees the simulator choice; it just gets a fitness scalar back per individual. -**Phase 2 status:** the architectural seam is demonstrated for both -backends. The NumPy backend trains a policy with sb3 PPO end-to-end. -The Isaac Lab backend constructs the env, spawns N parallel drones, -and steps them with random actions to validate observations / rewards / -dones. Actual PPO training via `rl_games` is wired in -[`make_rl_games_agent_cfg()`](../../src/ariel/simulation/tasks/isaaclab_hover_env.py) -but currently blocked on an env-stack issue (Isaac Sim's bundled torch -tensorboard transitively imports an older TF/jax/numpy stack that -conflicts with the conda env's numpy 2). See -[DRONE_BLUEPRINT_PLAN.md §6 entry 17](../../DRONE_BLUEPRINT_PLAN.md) for -the full story and the Phase 2.5 path forward. +**Status:** both backends train end-to-end. The NumPy backend trains +sb3 PPO on the gate-passing task; the Isaac Lab backend trains +`rl_games` PPO on hover-to-goal in a single conda env where ariel's +deps are simulator-agnostic and Isaac Lab owns the binary stack +(torch/gymnasium/numpy) — see §3b for the install recipe. A +reference EA + PPO loop on top of the Isaac Lab backend ships at +[`evolve.py`](./evolve.py); see §6 for how to wire your own RL +pipeline into ariel's EA layer. --- @@ -42,12 +39,12 @@ ariel offers: EA loop + RL trainers + DroneBlueprint IR ▼ ─── Plug point: simulator+trainer pair ─── │ - ┌──────────────────────────┼──────────────────────────┐ + ┌─────────────────-────┼──────────────────────────┐ ▼ ▼ ▼ NumpyBlueprintGateEnv IsaacLabBlueprintHoverEnv (gymnasium VecEnv) (DirectRLEnv) (whatever shape + + your simulator -sb3 PPO rsl_rl PPO needs) +sb3 PPO rl_games PPO needs) │ │ │ ▼ ▼ ▼ blueprint_to_propellers blueprint_to_urdf → whatever conversion @@ -126,8 +123,7 @@ simulator ecosystems through a single shape (e.g., wrapping Isaac Lab to gymnasium VecEnv via `isaaclab_rl.sb3`) drags in stable-baselines3, which collides with the numpy-2 ABI in the unified isaaclab conda env. Honest heterogeneity is cheaper than -forced uniformity. See [DRONE_BLUEPRINT_PLAN.md §6 entry 17](../../DRONE_BLUEPRINT_PLAN.md) -for the full rationale. +forced uniformity. --- @@ -152,8 +148,7 @@ root README](../../README.md) for the broader ariel install matrix. Isaac Lab owns its own torch / gymnasium / numpy ABI stack, so we install ariel **into** Isaac Lab's env rather than the other way -around. The reproducible recipe (this is the doc-side of Phase 2.5's -"Option A" plan in [DRONE_BLUEPRINT_PLAN.md §5](../../DRONE_BLUEPRINT_PLAN.md)): +around. The reproducible recipe: ```bash # 0) Paths (adjust if your checkout differs) @@ -244,9 +239,7 @@ print('ariel Blueprint chain: OK') Why this shape: ariel's base `pyproject.toml` pins `numpy>=1.26,<2` specifically to be safe to install into an Isaac Lab env. Going the other way — installing Isaac Lab into an ariel-managed env — drags in -sb3's compiled deps against numpy 2 and segfaults. See -[DRONE_BLUEPRINT_PLAN.md §6 entries 15 and 17](../../DRONE_BLUEPRINT_PLAN.md) -for the full env-stack story. +sb3's compiled deps against numpy 2 and segfaults. ### 3c. Operational gotcha: stale Isaac Sim processes after a failed run @@ -273,8 +266,8 @@ pkill -KILL -f "tutorials/pluggable_simulator/train.py" This is a known Isaac Sim behavior, not an ariel bug. It also applies to the official Isaac Lab `train.py` scripts. Worth running the check -after any failed smoke during Phase 2.5 iteration so you don't end up -with ~5 cores of CPU silently burning while you debug. +after any failed smoke so you don't end up with ~5 cores of CPU +silently burning while you debug. --- @@ -424,9 +417,65 @@ python tutorials/pluggable_simulator/train.py --simulator \ evaluator) at the new backend. The EA loop never sees the simulator choice — it just gets fitness numbers back per individual. +Once your env is in place, see [§6](#6-driving-morphology-evolution-with-your-own-rl-pipeline) +for wiring an EA loop on top — i.e., turning a working trainer into +*morphology evolution + RL*. + --- -## 6. Why this matters +## 6. Driving morphology evolution with your own RL pipeline + +§5 covered the *inner* loop: "I have a simulator and want to train a +policy on a fixed morphology." This section covers the *outer* loop: +"I already have an Isaac Lab + RL training pipeline and want to drive +**morphology evolution** with ariel on top." + +Three roles to implement (most partners only write the third): + +1. **Genome → DroneBlueprint decoder.** Reuse a shipped decoder + (`spherical_angular_to_blueprint`, `cartesian_euler_to_blueprint` + in [`src/ariel/body_phenotypes/drone/decoders.py`](../../src/ariel/body_phenotypes/drone/decoders.py)) + if your genome shape fits — most do. +2. **An RL env that takes a `DroneBlueprint` at construction.** + Either of the shipped envs is a copy-paste starting point: see + `IsaacLabBlueprintHoverEnvCfg.from_blueprint` in + [`src/ariel/simulation/tasks/isaaclab_hover_env.py`](../../src/ariel/simulation/tasks/isaaclab_hover_env.py). +3. **An `evaluate(genome) → fitness` function + outer EA loop.** + The shipped reference is [`tutorials/pluggable_simulator/evolve.py`](./evolve.py). + Copy it and replace the inner training call with your trainer. + +Five-step recipe (compact, executable): + +1. **Pick or write a genome class.** Existing options live in + [`src/ariel/ec/drone/genome_handlers/`](../../src/ariel/ec/drone/genome_handlers/) + (`spherical_angular`, `cartesian_euler`, `cppn_neat`, + `hybrid_cppn`). For the tutorial-sized evolve.py we use an even + simpler `ArmLengthGenome` defined inline. +2. **Write `genome_to_blueprint(g) → DroneBlueprint`** (or reuse a + shipped decoder). +3. **Build the env from the blueprint.** Adapt + `IsaacLabBlueprintHoverEnvCfg.from_blueprint` (or your own env's + constructor) to take a `DroneBlueprint` and produce a USD on the + fly via [`blueprint_to_urdf`](../../src/ariel/body_phenotypes/drone/backends.py) + + Isaac Lab's `UrdfConverter`. +4. **Copy `evolve.py`; replace `_evaluate_in_subprocess` with your + trainer.** Or — if you prefer in-process — call your trainer + directly. Note: in-process reuse of `DirectRLEnv` across genomes + was unreliable in our tests, which is why the shipped reference + spawns a subprocess per individual. +5. **Plug fitness back.** Three common shapes: + - parse the rl_games checkpoint filename (simplest, used in + `evolve.py`); + - subclass `IsaacAlgoObserver` to capture mean-reward stats inline; + - run a deterministic post-training eval pass and average reward. + +**For deeper material** — file-by-role reference table, in-process +vs subprocess pattern tradeoffs, fitness-extraction options, common +pitfalls — see [`connect_your_pipeline.md`](./connect_your_pipeline.md). + +--- + +## 7. Why this matters The ARIEL consortium's collaborators bring their own simulators: MuJoCo, Aerial Gym, Isaac Lab, IsaacGym, custom in-house stacks. @@ -436,6 +485,3 @@ sharing ariel's evolutionary and morphology infrastructure — decoders, EA operators, repair, descriptors, the morphology IR. One IR (`DroneBlueprint`), one EA loop, many backends, many trainers. - -See [DRONE_BLUEPRINT_PLAN.md](../../DRONE_BLUEPRINT_PLAN.md) §1 -("Value proposition") and §6 entry 17 for the broader rationale. diff --git a/tutorials/pluggable_simulator/connect_your_pipeline.md b/tutorials/pluggable_simulator/connect_your_pipeline.md new file mode 100644 index 000000000..650da1402 --- /dev/null +++ b/tutorials/pluggable_simulator/connect_your_pipeline.md @@ -0,0 +1,335 @@ +# Connecting your Isaac Lab + RL pipeline to ariel's EA loop + +> Companion to [`README.md`](./README.md) §6. Read §6 first for the +> elevator-pitch + five-step recipe; this doc is the depth pass. + +## 1. Why this doc + +ariel's contribution to the consortium is the **evolutionary layer**: +genome representations, decoders, EA operators, repair, descriptors, +and a morphology IR (`DroneBlueprint`) that any simulator can +consume. It is **not** another simulator and **not** another RL +library. + +If you already have an Isaac Lab + RL training pipeline that knows +how to train a hover (or any) policy for a fixed drone, you do +**not** need to switch tools to use ariel. You wrap your existing +trainer behind a one-line interface — "given this `DroneBlueprint`, +train a policy and report fitness" — and ariel's EA loop becomes +the outer scheduler that picks which morphologies to try. + +This doc walks through the three roles you implement, the files +to look at, two integration patterns (in-process vs subprocess), +fitness-extraction options, and the common pitfalls we hit while +writing the shipped reference. + +## 2. The three roles, in detail + +### Role 1 — Genome → DroneBlueprint decoder + +**What it is.** A function that takes whatever genotype your EA +operates on (numpy array, dataclass, CPPN, ...) and produces a +`DroneBlueprint`: the simulator-agnostic morphology IR. + +**What you implement.** A function `genome_to_blueprint(g) → +DroneBlueprint`. In most cases this is one line: call a shipped +decoder. + +**Which shipped file to copy from.** +[`src/ariel/body_phenotypes/drone/decoders.py`](../../src/ariel/body_phenotypes/drone/decoders.py) +— `spherical_angular_to_blueprint` and `cartesian_euler_to_blueprint` +are the production decoders. `spherical_angular` parameterises each +arm by (length, azimuth, pitch, motor-az, motor-pitch, spin-dir); +`cartesian_euler` uses (x, y, z, roll, pitch, yaw). + +**Minimal sketch.** +```python +from ariel.body_phenotypes.drone.decoders import spherical_angular_to_blueprint + +def genome_to_blueprint(genome_matrix, propsize=5): + return spherical_angular_to_blueprint(genome_matrix, propsize=propsize) +``` + +### Role 2 — An RL env that takes a DroneBlueprint + +**What it is.** Your existing env, parameterised by a +`DroneBlueprint` at construction time. The env converts the +blueprint to whatever your simulator wants (URDF, USD, MjSpec, +propeller list) and spawns N parallel agents. + +**What you implement.** A `from_blueprint(bp, ...)` classmethod on +your env's config, or an equivalent constructor. + +**Which shipped file to copy from.** +[`src/ariel/simulation/tasks/isaaclab_hover_env.py`](../../src/ariel/simulation/tasks/isaaclab_hover_env.py) +is the reference. `make_blueprint_usd(bp, output_dir, robot_name)` +runs `blueprint_to_urdf` then Isaac Lab's `UrdfConverter` to write +the USD. `IsaacLabBlueprintHoverEnvCfg.from_blueprint(bp, num_envs)` +returns a config with `self.robot.spawn.usd_path` pointing at that +USD. + +**Minimal sketch (DirectRLEnv shape).** +```python +@configclass +class MyEnvCfg(DirectRLEnvCfg): + @classmethod + def from_blueprint(cls, bp, num_envs=64, usd_output_dir=None): + usd_path = make_blueprint_usd(bp, usd_output_dir or "/tmp") + cfg = cls(num_envs=num_envs) + cfg.robot.spawn.usd_path = str(usd_path) + return cfg +``` + +### Role 3 — evaluate(genome) → fitness + outer EA loop + +**What it is.** The glue: pick a morphology, train a policy on it, +score it, hand the scalar back to the EA. The EA then selects and +mutates the high-scoring morphologies. + +**What you implement.** A loop that for each individual builds the +env, runs your trainer, parses out a fitness scalar, and feeds +populations through tournament selection + mutation. + +**Which shipped file to copy from.** +[`evolve.py`](./evolve.py) is the reference. Its `_evaluate_in_subprocess` +is the swap point: replace its `subprocess.run([..., train.py, ...])` +with a call into your own trainer. + +**Minimal sketch.** +```python +for gen in range(args.generations): + fitnesses = [evaluate(g) for g in population] + population = tournament_select_and_mutate(population, fitnesses) +``` + +## 3. Files to look at, by role + +| Role | File | Why | +|---|---|---| +| Blueprint IR | [`src/ariel/body_phenotypes/drone/blueprint.py`](../../src/ariel/body_phenotypes/drone/blueprint.py) | The surface the decoder must populate; ships `to_dict`/`from_dict`/`save_json`/`load_json` for caching and subprocess hand-off | +| Decoder examples | [`src/ariel/body_phenotypes/drone/decoders.py`](../../src/ariel/body_phenotypes/drone/decoders.py) | `spherical_angular_to_blueprint`, `cartesian_euler_to_blueprint` | +| Backend conversion | [`src/ariel/body_phenotypes/drone/backends.py`](../../src/ariel/body_phenotypes/drone/backends.py) | `blueprint_to_urdf`, `blueprint_to_mjspec`, `blueprint_to_propellers` | +| Isaac Lab env (DirectRLEnv) | [`src/ariel/simulation/tasks/isaaclab_hover_env.py`](../../src/ariel/simulation/tasks/isaaclab_hover_env.py) | Copy-paste template: `from_blueprint` cfg + `make_blueprint_usd` helper + `_setup_scene` / `_pre_physics_step` / `_apply_action` / `_get_rewards` / `_reset_idx`. Also exports `make_rl_games_agent_cfg`. | +| gymnasium VecEnv | [`src/ariel/simulation/tasks/drone_gate_env.py`](../../src/ariel/simulation/tasks/drone_gate_env.py) + [`blueprint_gate_env.py`](../../src/ariel/simulation/tasks/blueprint_gate_env.py) | For sb3-style RL libraries — implements the `BlueprintGateEnv` Protocol | +| Subprocess EA + RL (reference) | [`tutorials/pluggable_simulator/evolve.py`](./evolve.py) + [`train.py`](./train.py) | The shipped loop: per-individual subprocess + checkpoint-filename fitness | +| Subprocess EA + RL (HPC) | [`src/ariel/ec/drone/evaluators/gate_evaluator.py`](../../src/ariel/ec/drone/evaluators/gate_evaluator.py) + [`gate_train.py`](../../src/ariel/ec/drone/evaluators/gate_train.py) | Pre-existing in-repo pattern; SLURM-friendly variant | +| Genome representations | [`src/ariel/ec/drone/genome_handlers/`](../../src/ariel/ec/drone/genome_handlers/) | `spherical_angular`, `cartesian_euler`, `cppn_neat`, `hybrid_cppn` with mutation/crossover | + +## 4. Two integration patterns + +### Pattern A — Subprocess per individual (recommended; shipped reference) + +The parent process holds the EA state. For each individual: + +1. Convert genome → `DroneBlueprint`; save as JSON. +2. `subprocess.run([python, train.py, --blueprint-json , + --experiment-prefix , ...])`. +3. After the subprocess exits, read fitness from + `runs/_/nn/last_*.pth`. + +This is what [`evolve.py`](./evolve.py) does. + +**Pros.** +- **Clean Isaac Sim state each individual.** No env-teardown reuse, + no global-registry leakage between genomes. +- **Crash isolation.** A failed individual doesn't bring down the + EA — parent just records `nan` and moves on. +- **HPC/SLURM-friendly.** Same shape works whether subprocesses run + locally or get submitted to a job queue. + +**Cons.** +- **~6 s Isaac Sim startup per individual.** Real cost on small + populations or short training budgets. For a 3 gen × 4 ind smoke + with 30 PPO epochs each, startup overhead is ~25% of wall time. + +### Pattern B — In-process + +One process; Isaac Sim launches once; the EA loops over individuals +inside the same Python session, building + tearing down `DirectRLEnv` +between genomes. + +**Pros.** +- **No Isaac Sim startup per individual.** Once the launcher is up, + individual eval is bounded only by PPO time. +- **Easier debugging.** Single-process stack traces; no IPC. + +**Cons.** +- **Env teardown reuse is undertested.** Our first attempt at this + pattern hung after individual 0 — `IsaacLabBlueprintHoverEnv.close()` + didn't fully release scene state, and the second `__init__` blocked + indefinitely. Fixing this requires deeper invasion of Isaac Lab's + scene-spawn machinery than we wanted to ship in a tutorial. +- **rl_games' global registries are sticky.** `vecenv.register` and + `env_configurations.register` bind names process-wide; you must + re-register `env_creator` per individual to capture the new env. +- **One crash takes out the whole run.** A genome that produces an + invalid URDF (degenerate inertia, etc.) crashes Isaac Sim's loader + — and that's your whole EA gone. + +If you want to attempt in-process anyway, structure it as: + +```python +# Once at startup. +app_launcher = AppLauncher(args, multi_gpu=False) + +for gen in range(generations): + for ind in population: + env = MyEnv(cfg=MyEnvCfg.from_blueprint(ind.blueprint, num_envs=N)) + train(env, ...) # your trainer + fitness = score(env, ...) # your eval + env.close() # may hang on Isaac Lab today +``` + +We recommend Pattern A until env teardown is hardened. + +## 5. Fitness-extraction options + +### Option 1 — Parse the rl_games checkpoint filename (simplest) + +rl_games writes checkpoints to +`runs/_/nn/last__ep__rew___.pth`. +The reward in the filename is the value the runner reported when it +wrote that checkpoint — good enough for a fitness scalar. + +```python +import re +ckpt = max(runs_dir.glob(f"{exp}_*/nn/last_*.pth"), + key=lambda p: p.stat().st_mtime) +fitness = float(re.search(r"rew_+(-?[\d.]+)_", ckpt.name).group(1)) +``` + +Used by `_extract_reward_from_checkpoint` in [`evolve.py`](./evolve.py). + +**Pros.** No code inside the trainer; works across processes. +**Cons.** Brittle if rl_games changes its filename schema (it has, +at least once, between major versions). + +### Option 2 — Subclass IsaacAlgoObserver + +rl_games' `IsaacAlgoObserver` (from `rl_games.common.algo_observer`) +gets called after each PPO epoch with the current rewards tensor. +Subclass it to capture the trajectory of rewards in-memory; return +the last-N-epoch mean as fitness. + +**Pros.** Robust to filename changes; you control the aggregation +(last-N mean, max, percentile). +**Cons.** Requires running the trainer in-process so the observer +can be read after `runner.run` returns. + +### Option 3 — Deterministic post-training eval pass + +After `runner.run({"train": True, ...})` finishes, save the policy, +then run an eval pass with `play: True` and `deterministic: True` +for K episodes; average the cumulative reward. + +**Pros.** Most accurate measure of policy quality. +**Cons.** Doubles per-individual wall time. Worth it when individual +training is long enough that the noise in option 1 (which scores +the last *training* episodes, mid-exploration) dominates the EA +signal. + +For the tutorial-sized smoke (30 PPO epochs / individual) option 1 +is fine. For real runs (hundreds of epochs) option 2 or 3 is +worth the setup cost. + +## 6. Common pitfalls + +### Orphan Isaac Sim processes after a failed eval + +Isaac Sim's launcher can leave threads spinning at ~120% CPU after +an exception in env setup, even after the Python process "exits". +The check is in README §3c — run it after every failed iteration: + +```bash +ps -u $USER -o pid,etime,pcpu,cmd \ + | grep -E "tutorials/pluggable_simulator/(train|evolve)\.py" \ + | grep -v grep +pkill -KILL -f "tutorials/pluggable_simulator/" # if needed +``` + +In the subprocess pattern this matters less (each child cleans up +on its own exit), but a hung subprocess will still wedge the parent +EA until the parent's `subprocess.run` returns. Consider a +`timeout=` on the run call for long-running training. + +### `simulation_app.close()` can hang at the end of training + +A related symptom: after a successful PPO run the child writes its +checkpoint, logs "closing simulation app", then spins Isaac Sim's +threads at ~120% CPU indefinitely. The shipped `train.py` works +around this by hard-exiting with `os._exit(exit_code)` instead of +calling `simulation_app.close()` — the checkpoint is already on +disk by that point, so there's nothing to flush. If you wrap your +own trainer in a subprocess driven by an EA, do the same: skip the +graceful close and `os._exit` once your fitness signal is +persisted. + +### rl_games global registries + +`rl_games.common.vecenv.register("name", factory)` and +`rl_games.common.env_configurations.register("name", {"env_creator": +...})` bind names process-wide. In an in-process loop you must +re-register `env_creator` for every individual so the trainer picks +up the new env, not the previous one. In the subprocess pattern +this is automatic — each child has a fresh registry. + +### Don't add simulator-owned binaries to ariel's deps + +`pyproject.toml [project.dependencies]` must **not** name `torch`, +`gymnasium`, `numpy>=2`, or anything else Isaac Lab owns. ariel's +core deps are simulator-agnostic; binaries live in extras +(`rl-sb3`, `torch`). The guardrail step in README §3b (step 6) +catches accidental leaks by diffing `pip list` before/after the +ariel install and refusing to proceed if simulator binaries moved. + +### Don't share blueprint JSON paths across overlapping subprocesses + +`evolve.py` writes per-individual blueprint JSON files under a +`tempfile.TemporaryDirectory(prefix="ariel_evolve_")` with unique +names (`ariel_evolve_.json`). If you run subprocesses in +parallel, ensure each one's JSON has a distinct path — and that +the per-individual `--experiment-prefix` is unique so the +checkpoint-filename fitness extraction finds the right run. + +### `DroneGateEnv` import path needs EA orchestration deps + +In the Isaac Lab env, importing `DroneGateEnv` transitively pulls +in ariel's EA orchestration deps (sqlmodel, pydantic-settings) that +the Isaac Lab install path intentionally doesn't bring in. The §3b +recipe pip-installs them as a separate step. Importing only +`DroneBlueprint` + `decoders` + `backends` (the chain Isaac Lab +actually uses) works without those orchestration deps. + +## 7. Calibration on a single machine + +Measured wall times from one end-to-end run of the shipped +reference (`evolve.py` defaults: 3 gen × 4 ind × 30 PPO epochs × +16 envs, single RTX-class GPU, warm caches): + +| Phase | Wall time | +|---|---| +| rl_games PPO (30 epochs × 16 envs) | ~4-5 s | +| Isaac Sim startup + scene build (per subprocess) | ~8-10 s | +| Per-individual total | ~13-15 s | +| Per-generation total (population 4) | ~55 s | +| Full 3-gen run | ~160 s (~2.7 min) | + +Notes: +- First individual is slightly slower (~15 s) than warm subsequent + ones (~13 s) due to Isaac Sim's cold-cache USD pipeline. +- The very first ever invocation in a fresh checkout can take + several minutes as Isaac Sim builds its asset cache. Subsequent + runs in the same machine are at the rates above. +- Numbers scale linearly with population × generations × epochs; + bigger envs (more parallel agents per individual) reduce + per-individual variance more than they cost. + +--- + +See also: +- [`README.md`](./README.md) — top-level tutorial. +- [`evolve.py`](./evolve.py) — shipped reference outer loop. +- [`train.py`](./train.py) — shipped per-individual inner loop. +- [`DRONE_BLUEPRINT_PLAN.md`](../../DRONE_BLUEPRINT_PLAN.md) §1 + "Value proposition" and §6 "Design decisions" for the deeper + rationale. diff --git a/tutorials/pluggable_simulator/evolve.py b/tutorials/pluggable_simulator/evolve.py new file mode 100644 index 000000000..34033071c --- /dev/null +++ b/tutorials/pluggable_simulator/evolve.py @@ -0,0 +1,281 @@ +"""Demonstrate the EA + PPO workflow on the Isaac Lab backend. + +Outer evolutionary loop evolves drone arm lengths; inner PPO loop +trains a hover-to-goal policy for each candidate morphology. Both +improvements are visible from one run: + +* **Within each individual:** ``rl_games`` logs PPO mean reward + per epoch — that's the *learning* curve. +* **Across generations:** best / mean fitness over the population + improves as the EA selects the morphologies that hover better — + that's the *evolution* curve. + +Implementation: one subprocess per individual. The parent holds the +EA state; each child runs a fresh Isaac Sim + rl_games training +process from ``train.py --blueprint-json ... --experiment-prefix +...``. Why subprocesses? In-process reuse of ``DirectRLEnv`` across +genomes was unreliable in our tests (env teardown left the second +build hanging); subprocesses give each individual a clean Isaac Sim +state. Cost: ~6 s Isaac-Sim startup per individual. + +Defaults are sized for a few-minute smoke (3 gen × 4 ind × 30 +epochs); scale them up via CLI for a more convincing curve. + +Run (from the ariel-isaaclab-train env with setup_conda_env.sh +already sourced — see tutorials/pluggable_simulator/README.md §3b): + + python tutorials/pluggable_simulator/evolve.py + +Override defaults: + + python tutorials/pluggable_simulator/evolve.py \\ + --generations 5 --population 6 --epochs-per-eval 50 +""" +from __future__ import annotations + +import argparse +import re +import subprocess +import sys +import tempfile +import time +from dataclasses import dataclass +from pathlib import Path + +import numpy as np + +from ariel.body_phenotypes.drone.decoders import spherical_angular_to_blueprint + + +REPO_ROOT = Path(__file__).resolve().parents[2] +TRAIN_PY = Path(__file__).with_name("train.py") +RUNS_DIR = REPO_ROOT / "runs" + + +def _log(msg: str) -> None: + """stderr-flushed log lines (children's stdout/stderr stream through).""" + sys.stderr.write(f"[evolve] {msg}\n") + sys.stderr.flush() + + +# ---------- genome --------------------------------------------------------------- + +@dataclass +class ArmLengthGenome: + """Quad genome — just the four arm lengths. + + For the tutorial we keep the genotype dead-simple. Azimuths are + fixed to the canonical X-config; motor orientation, propsize, and + spin direction are constants. The EA's only knob is arm length; + PPO is the other source of improvement. That makes the two + dimensions (morphology vs. policy) visually distinct in the + output. + """ + + arm_lengths: np.ndarray # shape (n_arms,) + + @classmethod + def default_quad(cls) -> "ArmLengthGenome": + return cls(arm_lengths=np.full(4, 0.18)) + + def mutate(self, sigma: float, rng: np.random.Generator) -> "ArmLengthGenome": + new = self.arm_lengths + rng.normal(0.0, sigma, self.arm_lengths.shape) + return ArmLengthGenome(arm_lengths=np.clip(new, 0.10, 0.30)) + + def to_genome_matrix(self) -> np.ndarray: + """Project to ``spherical_angular_to_blueprint``'s input format. + + Per-arm row: ``[mag, arm_az, arm_pitch, motor_az, motor_pitch, direction]``. + Azimuths are evenly spaced around the body; everything else + constant. + """ + n = len(self.arm_lengths) + angles = np.linspace(0.0, 2.0 * np.pi, n, endpoint=False) + return np.stack( + [ + self.arm_lengths, + angles, + np.zeros(n), + np.zeros(n), + np.zeros(n), + np.array([float(i % 2) for i in range(n)]), + ], + axis=1, + ) + + +# ---------- CLI ----------------------------------------------------------------- + +def _build_parser() -> argparse.ArgumentParser: + p = argparse.ArgumentParser(description=__doc__.splitlines()[0]) + p.add_argument("--generations", type=int, default=3, + help="Number of EA generations. Default 3.") + p.add_argument("--population", type=int, default=4, + help="Population size. Default 4.") + p.add_argument("--epochs-per-eval", type=int, default=30, + help="rl_games PPO max_epochs per individual. Default 30.") + p.add_argument("--num-envs", type=int, default=16, + help="Isaac Sim parallel envs per individual eval.") + p.add_argument("--propsize", type=int, default=5) + p.add_argument("--seed", type=int, default=42) + p.add_argument("--init-sigma", type=float, default=0.04, + help="Std of Gaussian noise around the default quad's " + "arm lengths when seeding the initial population.") + p.add_argument("--mut-sigma", type=float, default=0.03, + help="Std of Gaussian noise applied to arm lengths after " + "tournament selection.") + p.add_argument("--device-override", type=str, default=None, + help="Pass through to train.py (e.g., 'cpu' or 'cuda:0').") + p.add_argument("--keep-blueprints", action="store_true", + help="Don't delete the per-individual blueprint JSON files.") + return p + + +# ---------- main ---------------------------------------------------------------- + +def main() -> None: + args = _build_parser().parse_args() + rng = np.random.default_rng(args.seed) + + _log("=== Evolution + PPO on Isaac Lab backend (subprocess mode) ===") + _log(f" generations : {args.generations}") + _log(f" population : {args.population}") + _log(f" epochs per eval : {args.epochs_per_eval}") + _log(f" num_envs : {args.num_envs}") + _log(f" seed : {args.seed}") + _log(f" total evals : {args.generations * args.population}") + + # Initial population: default quad + perturbations. + population: list[ArmLengthGenome] = [ArmLengthGenome.default_quad()] + for _ in range(args.population - 1): + population.append(population[0].mutate(args.init_sigma, rng)) + + history: list[dict] = [] + eval_counter = 0 + overall_start = time.time() + + with tempfile.TemporaryDirectory(prefix="ariel_evolve_") as tmpdir: + tmpdir_path = Path(tmpdir) + + for gen in range(args.generations): + _log("") + _log(f"=== Generation {gen + 1}/{args.generations} ===") + fitnesses: list[float] = [] + for ind_idx, individual in enumerate(population): + eval_counter += 1 + exp_name = f"ariel_evolve_{eval_counter:04d}" + bp_path = tmpdir_path / f"{exp_name}.json" + + # Render the blueprint and persist as JSON so the child + # process loads exactly the same morphology. + blueprint = spherical_angular_to_blueprint( + individual.to_genome_matrix(), propsize=args.propsize, + ) + blueprint.save_json(bp_path) + + t0 = time.time() + fitness = _evaluate_in_subprocess( + bp_path=bp_path, + exp_name=exp_name, + args=args, + ) + dt = time.time() - t0 + fitnesses.append(fitness) + _log( + f" ind {ind_idx}: arm_lens=" + f"{individual.arm_lengths.round(3).tolist()} " + f"fitness={fitness:.4f} ({dt:.1f}s)" + ) + + if args.keep_blueprints: + keep_path = RUNS_DIR / f"{exp_name}.blueprint.json" + keep_path.parent.mkdir(parents=True, exist_ok=True) + keep_path.write_text(bp_path.read_text()) + + best = max(fitnesses) + worst = min(fitnesses) + mean = sum(fitnesses) / len(fitnesses) + history.append({"gen": gen, "best": best, "mean": mean, "worst": worst}) + _log( + f" -- gen {gen + 1}: best={best:.4f} mean={mean:.4f} " + f"worst={worst:.4f}" + ) + + # Tournament-of-2 select → Gaussian mutate to fill new population. + new_pop: list[ArmLengthGenome] = [] + for _ in range(len(population)): + i1 = int(rng.integers(0, len(population))) + i2 = int(rng.integers(0, len(population))) + winner_idx = i1 if fitnesses[i1] >= fitnesses[i2] else i2 + new_pop.append(population[winner_idx].mutate(args.mut_sigma, rng)) + population = new_pop + + elapsed = time.time() - overall_start + _log("") + _log(f"=== Evolution complete (wall time {elapsed:.1f}s) ===") + for h in history: + _log( + f" gen {h['gen'] + 1}: best={h['best']:.4f} " + f"mean={h['mean']:.4f} worst={h['worst']:.4f}" + ) + + +# ---------- per-individual subprocess -------------------------------------------- + +def _evaluate_in_subprocess( + *, bp_path: Path, exp_name: str, args: argparse.Namespace, +) -> float: + """Fork a child train.py for one individual; return its fitness.""" + cmd = [ + sys.executable, str(TRAIN_PY), + "--simulator", "isaaclab", + "--mode", "train", + "--headless", + "--blueprint-json", str(bp_path), + "--experiment-prefix", exp_name, + "--max-iterations", str(args.epochs_per_eval), + "--num-envs", str(args.num_envs), + "--propsize", str(args.propsize), + "--seed", str(args.seed), + ] + if args.device_override is not None: + cmd += ["--device-override", args.device_override] + + # Stream the child's output through so the user can watch + # PPO log lines accumulate per-individual. + result = subprocess.run(cmd, cwd=REPO_ROOT, check=False) + if result.returncode != 0: + _log(f" WARN: child exited with code {result.returncode}; " + f"recording fitness=nan") + return float("nan") + + return _extract_reward_from_checkpoint(exp_name) + + +def _extract_reward_from_checkpoint(exp_name: str) -> float: + """Parse the final episode reward out of rl_games' checkpoint filename. + + rl_games writes checkpoints to + ``runs/_/nn/last__ep__rew___.pth``. + The reward in the filename is the value the runner last reported + when it wrote that checkpoint — good enough for a fitness scalar. + """ + matches = sorted( + RUNS_DIR.glob(f"{exp_name}_*"), + key=lambda p: p.stat().st_mtime, + ) + if not matches: + return float("nan") + nn_dir = matches[-1] / "nn" + if not nn_dir.exists(): + return float("nan") + ckpts = list(nn_dir.glob("last_*.pth")) + if not ckpts: + return float("nan") + latest = max(ckpts, key=lambda p: p.stat().st_mtime) + m = re.search(r"rew_+(-?[\d.]+)_", latest.name) + return float(m.group(1)) if m else float("nan") + + +if __name__ == "__main__": + main() diff --git a/tutorials/pluggable_simulator/train.py b/tutorials/pluggable_simulator/train.py index b016467d5..3b1269838 100644 --- a/tutorials/pluggable_simulator/train.py +++ b/tutorials/pluggable_simulator/train.py @@ -118,7 +118,7 @@ def main_numpy(parser: argparse.ArgumentParser) -> None: print(f" steps/sec : {args.total_timesteps / dt:.0f}") -# ---------- isaaclab backend: rsl_rl PPO + DirectRLEnv -------------------------- +# ---------- isaaclab backend: rl_games PPO + DirectRLEnv ------------------------ def _isaaclab_step_smoke(env, args) -> None: """Random-action stepping loop for fast env-construction validation. @@ -171,11 +171,14 @@ def _isaaclab_rl_games_train(env, args) -> None: from rl_games.torch_runner import Runner # noqa: PLC0415 _log("building rl_games agent config...") - agent_cfg = make_rl_games_agent_cfg( + agent_cfg_kwargs = dict( max_epochs=args.max_iterations, minibatch_size=24 * args.num_envs, device=args.device, ) + if args.experiment_prefix: + agent_cfg_kwargs["experiment_name"] = args.experiment_prefix + agent_cfg = make_rl_games_agent_cfg(**agent_cfg_kwargs) clip_obs = agent_cfg["params"]["env"].get("clip_observations", float("inf")) clip_actions = agent_cfg["params"]["env"].get("clip_actions", float("inf")) obs_groups = agent_cfg["params"]["env"].get("obs_groups") @@ -227,6 +230,16 @@ def main_isaaclab(parser: argparse.ArgumentParser) -> None: parser.add_argument("--device-override", type=str, default=None, help="Override the auto-selected device " "(e.g., 'cpu' or 'cuda:0').") + parser.add_argument("--blueprint-json", type=str, default=None, + help="Path to a DroneBlueprint JSON file. When set, " + "the blueprint is loaded from disk and --preset " + "is ignored. Lets an outer EA loop hand in a " + "per-individual morphology.") + parser.add_argument("--experiment-prefix", type=str, default=None, + help="rl_games experiment_name (also the runs/_* " + "directory prefix). Set per individual when " + "driven by an outer EA loop so checkpoints are " + "discoverable.") # AppLauncher must be imported early so its args can be added to the # parser. Importing it triggers Isaac Sim's launcher setup; this is @@ -250,7 +263,9 @@ def main_isaaclab(parser: argparse.ArgumentParser) -> None: simulation_app = app_launcher.app _log("Isaac Sim launched") + import os # noqa: PLC0415 import traceback # noqa: PLC0415 + exit_code = 0 try: _log("importing IsaacLabBlueprintHoverEnv...") from ariel.simulation.tasks.isaaclab_hover_env import ( # noqa: PLC0415 @@ -258,10 +273,17 @@ def main_isaaclab(parser: argparse.ArgumentParser) -> None: IsaacLabBlueprintHoverEnvCfg, ) - _log("building blueprint...") - blueprint = spherical_angular_to_blueprint( - PRESETS[args.preset], propsize=args.propsize, - ) + if args.blueprint_json: + _log(f"loading blueprint from {args.blueprint_json}...") + from ariel.body_phenotypes.drone.blueprint import ( # noqa: PLC0415 + DroneBlueprint, + ) + blueprint = DroneBlueprint.load_json(args.blueprint_json) + else: + _log(f"building blueprint from preset {args.preset!r}...") + blueprint = spherical_angular_to_blueprint( + PRESETS[args.preset], propsize=args.propsize, + ) _log("building cfg from blueprint (generates URDF + USD)...") env_cfg = IsaacLabBlueprintHoverEnvCfg.from_blueprint( @@ -282,10 +304,15 @@ def main_isaaclab(parser: argparse.ArgumentParser) -> None: except Exception as exc: _log(f"ERROR: {type(exc).__name__}: {exc}") traceback.print_exc(file=sys.stderr) - raise - finally: - _log("closing simulation app") - simulation_app.close() + exit_code = 1 + + # Skip simulation_app.close(): in current Isaac Sim builds it can + # leave Isaac Sim's app threads spinning at ~120% CPU after a + # successful run. Checkpoints are already on disk by this point, + # so we exit hard via os._exit() to release control back to any + # outer EA driver. See README §3c. + _log(f"exiting (code {exit_code})") + os._exit(exit_code) # ---------- entry point --------------------------------------------------------- From 2f5557305bf3a78e5f9723c2ad099c96d659f9d5 Mon Sep 17 00:00:00 2001 From: Keiichi Ito Date: Thu, 28 May 2026 08:13:45 +0200 Subject: [PATCH 26/27] docs: update pluggable simulator README --- tutorials/pluggable_simulator/README.md | 13 ++++--------- 1 file changed, 4 insertions(+), 9 deletions(-) diff --git a/tutorials/pluggable_simulator/README.md b/tutorials/pluggable_simulator/README.md index 13332e285..340c386dd 100644 --- a/tutorials/pluggable_simulator/README.md +++ b/tutorials/pluggable_simulator/README.md @@ -2,7 +2,7 @@ This tutorial demonstrates how ariel decouples the **EA + RL learning loop** from the **physics simulator** so that collaborators can plug in their -own simulators while reusing ariel's evolutionary and morphology-IR +own simulators while reusing ariel's evolutionary and morphology-IR (i.e. Blueprint) infrastructure. Two backends ship today: @@ -12,11 +12,7 @@ Two backends ship today: | `numpy` (TUDelft) | `DroneSimulator` (pure NumPy + SymPy) | **stable-baselines3 PPO** (trains end-to-end) | gate-passing | | `isaaclab` | Isaac Lab / Isaac Sim PhysX | **rl_games PPO** (trains end-to-end; `--mode step` also available for env-construction smokes) | hover-to-goal | -Each backend brings its own simulator **and** its own RL library, because -that matches how real heterogeneous simulator ecosystems work — Isaac -Lab ships rsl_rl/rl_games/skrl as native trainers, the NumPy stack pairs -naturally with sb3, etc. The EA loop above never sees the simulator -choice; it just gets a fitness scalar back per individual. +Each backend brings its own simulator **and** its own RL library. The EA loop above never sees the simulator choice; it just gets a fitness scalar back per individual. **Status:** both backends train end-to-end. The NumPy backend trains sb3 PPO on the gate-passing task; the Isaac Lab backend trains @@ -67,9 +63,8 @@ DroneSimulator or anything else). - A task definition (reward, termination, observation/action spaces). -The seam is **deliberate**: the EA evolves the same morphology -variables either way; only the fitness function and the trained -policy are backend-specific. +The EA evolves the same morphology variables either way; +only the fitness function and the trained policy are backend-specific. --- From 2f1ae7be7cbb5a130e14f854715548e1f8916581 Mon Sep 17 00:00:00 2001 From: Keiichi Ito Date: Thu, 28 May 2026 08:22:16 +0200 Subject: [PATCH 27/27] docs: fix make_blueprint_usd sketch to use keyword args The Role 2 sketch in connect_your_pipeline.md called make_blueprint_usd with a positional output_dir, but the real signature is keyword-only (def make_blueprint_usd(blueprint, *, output_dir, robot_name="drone")). Copy-pasting the sketch would have raised TypeError. Co-Authored-By: Claude Opus 4.7 --- tutorials/pluggable_simulator/connect_your_pipeline.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/tutorials/pluggable_simulator/connect_your_pipeline.md b/tutorials/pluggable_simulator/connect_your_pipeline.md index 650da1402..aa7bc7626 100644 --- a/tutorials/pluggable_simulator/connect_your_pipeline.md +++ b/tutorials/pluggable_simulator/connect_your_pipeline.md @@ -73,8 +73,8 @@ USD. @configclass class MyEnvCfg(DirectRLEnvCfg): @classmethod - def from_blueprint(cls, bp, num_envs=64, usd_output_dir=None): - usd_path = make_blueprint_usd(bp, usd_output_dir or "/tmp") + def from_blueprint(cls, bp, *, num_envs=64, usd_output_dir=None): + usd_path = make_blueprint_usd(bp, output_dir=usd_output_dir or "/tmp") cfg = cls(num_envs=num_envs) cfg.robot.spawn.usd_path = str(usd_path) return cfg