diff --git a/PathPlanning/README.md b/PathPlanning/README.md new file mode 100644 index 0000000..8d924c7 --- /dev/null +++ b/PathPlanning/README.md @@ -0,0 +1,306 @@ +# Path Planning Module + +This module implements real-time path planning for the UCSC FSAE driverless vehicle, generating optimal racing paths at 25 Hz. + +**Based on**: AMZ Driverless (ETH Zurich) boundary estimation algorithm +- **Paper**: "AMZ Driverless: The Full Autonomous Racing System" (Kabzan et al., 2019) +- **Competition Results**: 1st place FSG 2017, 2018, FSI 2018 +- **Performance**: 28.48s fastest lap, 1.5g lateral acceleration +- **Reference**: arXiv:1905.05150v1, Section 4.3 +- **GitHub**: https://github.com/AMZ-Driverless + +## Module Overview + +### Core Files + +1. **config.py** - Configuration and constants + - Track constraints (min width 3m, turning radius 4.5m) + - Performance parameters (25 Hz, beam width) + - Cost function weights (qc, qw, qs, qcolor, ql) + - Vehicle dynamics parameters + - Sensor range (~10m) + +2. **delaunay.py** - Delaunay Triangulation **[IN PROGRESS]** + - Uses `scipy.spatial.Delaunay` for triangulation (NOT CGAL) + - Creates triangulation from cone [x, y] positions + - Extracts midpoint graph for waypoints + - **Important**: Handles duplicate midpoints (interior edges shared by 2 triangles) + - Visualization utilities (matplotlib) + - **AMZ Implementation**: Used CGAL library, we use scipy for simplicity + - **Status**: In Progress (Nov 8-15) + +3. **path_tree.py** - Path Tree Population (Breadth-First) + - Builds breadth-first tree of possible paths through midpoint graph + - Starting node: current vehicle position + - Manages PathNode objects with parent/child relationships + - Each path connects to center points of surrounding edges + - Limited tree depth to meet 40ms cycle time constraint + - **AMZ approach**: Breadth-first manor, fixed iteration limit + - **Status**: Not Started (Deadline: Nov 22) + +4. **cost_functions.py** - Path Cost Evaluation (5 AMZ Terms) + + Implements the exact AMZ cost function with 5 weighted terms: + + - **Term 1**: Maximum angle change between path segments + - Rationale: Sharp corners use multiple cones, sudden angles unlikely + + - **Term 2**: Track width standard deviation (~3m expected) + - Rationale: Rules specify 3m min width, unlikely to change drastically + + - **Term 3**: Cone spacing standard deviation (~5m max expected) + - Rationale: Cones typically spaced evenly along boundaries + + - **Term 4**: Wrong color probability (blue=left, yellow=right) + - Rationale: Uses probabilistic color estimates from perception + - Becomes zero if no color information available + + - **Term 5**: Path length deviation from sensor range (~10m) + - Rationale: Penalize too short/long paths, prefer sensor range length + + **Cost Function Formula**: + ```python + cost = qc * normalize(max_angle_change)² + + qw * normalize(track_width_stddev)² + + qs * normalize(cone_spacing_stddev)² + + qcolor * normalize(wrong_color_prob)² + + ql * normalize(path_length_diff)² + ``` + + - Each term normalized, squared, and weighted + - Weights (qc, qw, qs, qcolor, ql) tuned experimentally + - **Status**: Not Started (Deadline: Dec 3) + +5. **beam_search.py** - Beam Search Pruning + - Prunes path tree to keep only top-k best paths at each level + - Prevents exponential growth of search tree + - Limits computational complexity for real-time performance + - Integrates cost function evaluation + - **AMZ result**: Only 4.2% of paths left track, mostly at >7m distance + - **Status**: Not Started (Deadline: Nov 29) + +6. **path_smoother.py** - Spline Interpolation + - Smooths discrete waypoints using scipy.interpolate + - Options: splprep/splev (parametric splines) or CubicSpline + - Calculates curvature profiles for velocity planning + - Generates velocity profiles respecting dynamics + - Resampling utilities for control planning + - **AMZ approach**: Feeds smoothed path to pure pursuit controller + - **Status**: Not Started (Deadline: Dec 3) + +7. **path_planner.py** - Main Integration Module + - 25 Hz planning loop (40ms cycle time) + - Integrates all 5 phases of algorithm + - SLAM interface (input): receives cone positions at 25 Hz + - Control planning interface (output): sends path data at 25 Hz + - Real-time performance monitoring + - **AMZ timing**: 50ms in SLAM mode, 40ms in racing mode + - **Status**: Not Started (Deadline: Dec 6) + +## Algorithm Pipeline + +Based on AMZ Section 4.3: Boundary Estimation + +``` +SLAM -> Cones -> Delaunay -> Waypoints -> Path Tree -> Beam Search -> Best Path -> Spline Smooth -> Control + | | + +------------------------------------ 25 Hz Loop (40ms cycle time) ----------------------------------+ +``` + +### Phase 1: Graph Generation (Delaunay Triangulation) +- **Input**: Cone positions [x, y] from SLAM +- **Library**: scipy.spatial.Delaunay (AMZ uses CGAL) +- **Process**: + 1. Create Delaunay triangulation of all visible cones + 2. Triangles maximize minimum internal angles + 3. Extract midpoints of all triangle edges + 4. Handle duplicate midpoints from shared interior edges +- **Output**: Midpoint waypoint graph +- **AMZ approach**: Discretizes X-Y space into connected triangles + +### Phase 2: Tree Population (Breadth-First Search) +- **Input**: Waypoints + current vehicle position +- **Process**: + 1. Start from vehicle position + 2. Build tree by connecting to surrounding edge midpoints + 3. Each level represents one waypoint ahead + 4. Branches represent alternative route choices + 5. Limit depth by iteration count (computational budget) +- **Output**: Tree of all possible paths +- **AMZ approach**: Breadth-first manor, explores all possible center lines + +### Phase 3: Beam Search (Cost-Based Pruning) +- **Input**: Path tree from Phase 2 +- **Process**: + 1. Evaluate each path using 5-term cost function + 2. Normalize, square, and weight each cost term + 3. Keep only top-k paths with lowest cost at each level + 4. Discard worst paths (beam search pruning) +- **Output**: Top-k best paths +- **AMZ result**: 4.2% invalid paths at FSG 2018, mostly >7m away + +### Phase 4: Path Selection & Smoothing +- **Input**: Best path waypoints from Phase 3 +- **Process**: + 1. Select path with absolute lowest cost + 2. Fit spline through discrete waypoints + 3. Calculate curvature along path +- **Output**: Smooth continuous path with curvature +- **AMZ approach**: Passes to pure pursuit controller + +### Phase 5: Control Interface +- **Input**: Smooth path + curvatures +- **Process**: + 1. Calculate velocity profile (optional, may be control team's job) + 2. Package waypoints, velocities, curvatures + 3. Send to control planning at 25 Hz +- **Output**: Path data for control planning +- **Coordinate with**: Ray Zou, Nathan Margolis (Control Planning team) + +## Running Tests + +Each module has standalone tests in its `if __name__ == "__main__"` block: + +```bash +# Test Delaunay triangulation (CURRENTLY WORKING) +python PathPlanning/delaunay.py + +# Test path tree (after implementation) +python PathPlanning/path_tree.py + +# Test cost functions (after implementation) +python PathPlanning/cost_functions.py + +# Test beam search (after implementation) +python PathPlanning/beam_search.py + +# Test path smoother (after implementation) +python PathPlanning/path_smoother.py + +# Test full integrated system (after implementation) +python PathPlanning/path_planner.py +``` + +### Delaunay Test Patterns + +The delaunay.py script includes multiple test patterns (modify `test_cone_data` variable): + +```python +# Available test patterns: +test_cone_data = oval_track # Realistic oval racing circuit +test_cone_data = simple_track # Basic straight-to-turn layout +test_cone_data = slalom # Chicane/slalom pattern +test_cone_data = grid # Stress test with regular grid +test_cone_data = random_scatter # Random cones for robustness test +``` + +## Performance Requirements + +- **Frequency**: 25 Hz (40ms cycle time) +- **Hardware**: Raspberry Pi (limited CPU/memory) +- **Real-time**: Must complete before next SLAM update +- **Robustness**: Handle noisy monocular vision data +- **AMZ benchmark**: 50ms cycle time in SLAM mode, achieved 1.5g lateral acceleration + +### Computational Budget + +- Delaunay triangulation: ~5-10ms (scipy is fast) +- Tree building: Variable (limit iterations) +- Cost evaluation: ~5-10ms (vectorize with NumPy) +- Beam search: ~5ms (fixed beam width) +- Spline smoothing: ~5ms +- **Total target**: <40ms on Raspberry Pi + +## Key Implementation Differences from AMZ + +| Aspect | AMZ (ETH Zurich) | Our Implementation | +|--------|------------------|-------------------| +| Triangulation Library | CGAL (C++) | scipy.spatial.Delaunay (Python) | +| Update Frequency | 50ms (20 Hz) SLAM mode | 40ms (25 Hz) target | +| Hardware | Industrial PC + GPU | Raspberry Pi (CPU only) | +| Sensors | LiDAR + Stereo Camera | Monocular Camera only | +| Programming Language | C++ / ROS | Python / ROS | +| Sensor Range | ~10m (LiDAR) | ~10m (monocular depth estimation) | + +**Key Challenge**: Monocular vision provides noisier/sparser cone detections than LiDAR, so our cost function needs to be more robust. + +## Integration Points + +### Input from Localization/SLAM +- **Team**: Parker Costa, Hansika Nerusa, Chanchal Mukeshsingh +- **Format**: TBD - coordinate on cone position data structure + - Need: [x, y] positions in global frame + - Need: Color probabilities [p_blue, p_yellow, p_orange, p_unknown] + - Need: Position uncertainties (covariance matrices) +- **Update rate**: 25 Hz + +### Output to Control Planning +- **Team**: Ray Zou, Nathan Margolis +- **Format**: TBD - coordinate on path/velocity data structure + - Provide: Waypoint coordinates [x, y] array + - Provide: Desired velocities at each waypoint (optional) + - Provide: Curvature at each waypoint + - Provide: Path confidence/quality metric +- **Update rate**: 25 Hz + +## Development Timeline + +| Task | Deadline | Status | +|------|----------|--------| +| Delaunay Triangulation (scipy) | Nov 8 | **IN PROGRESS** | +| Test & Visualize | Nov 15 | **IN PROGRESS** | +| Path Tree Population | Nov 22 | Not Started | +| Beam Search Pruning | Nov 29 | Not Started | +| Cost Functions (5 AMZ terms) | Dec 3 | Not Started | +| Path Smoothing (scipy splines) | Dec 3 | Not Started | +| Control Interface | Dec 6 | Not Started | + +## Dependencies + +```python +import numpy as np +from scipy.spatial import Delaunay # Delaunay triangulation +from scipy.interpolate import splprep, splev, CubicSpline # Path smoothing +import matplotlib.pyplot as plt # Visualization +``` + +No CGAL required! Everything uses standard scipy/numpy. + +## AMZ Cost Function Tuning Guide + +The 5 cost weights need experimental tuning on your specific tracks: + +```python +# In config.py - starting values (tune these!) +qc = 1.0 # Angle change weight +qw = 1.0 # Track width variance weight +qs = 1.0 # Cone spacing variance weight +qcolor = 2.0 # Color mismatch weight (higher = trust colors more) +ql = 0.5 # Path length deviation weight +``` + +**Tuning strategy**: +1. Start with all weights = 1.0 +2. Test on simple_track and oval_track patterns +3. Visualize which paths are selected +4. Increase weights for terms that should be more important +5. qcolor should be high if perception gives good colors, low if noisy +6. AMZ used squared and normalized costs, so relative weights matter more than absolute + +## Team + +- Nathan Yee +- Suhani Agarwal +- Aedan Benavides + +## References + +**Primary**: +- Kabzan et al. "AMZ Driverless: The Full Autonomous Racing System", 2019 +- Section 4.3: Boundary Estimation (our algorithm) +- Section 5: MPC Control (Control Planning team's reference) + +**Additional**: +- Delaunay, B. "Sur la sphère vide", 1934 (original Delaunay paper) +- scipy.spatial.Delaunay documentation +- Formula Student Germany Rules (track specifications) diff --git a/PathPlanning/beam_search.py b/PathPlanning/beam_search.py new file mode 100644 index 0000000..2741bab --- /dev/null +++ b/PathPlanning/beam_search.py @@ -0,0 +1,9 @@ +""" +Beam Search Path Pruning +Deadline: Nov 29, 2025 +""" + +import numpy as np +from typing import List +from path_tree import PathNode +import config diff --git a/PathPlanning/config.py b/PathPlanning/config.py new file mode 100644 index 0000000..7142bcd --- /dev/null +++ b/PathPlanning/config.py @@ -0,0 +1,45 @@ +""" +Path Planning Configuration +Contains all constants and parameters for the path planning system +""" + +# Performance Requirements +PLANNING_FREQUENCY_HZ = 25 # Hz - must compute new path 25 times/sec +CYCLE_TIME_MS = 40 # ms - max computation time (1000/25) + +# Track Constraints (from Formula Student Driverless rules) +MIN_TRACK_WIDTH = 3.0 # meters (DD.2.2.2.c) +MIN_TURNING_DIAMETER = 9.0 # meters (DD.2.2.2.d) +MIN_TURNING_RADIUS = MIN_TURNING_DIAMETER / 2 # 4.5 meters +MAX_STRAIGHT_LENGTH = 80.0 # meters (DD.2.2.2.a) +LAP_LENGTH_MIN = 200.0 # meters (DD.2.2.2.e) +LAP_LENGTH_MAX = 500.0 # meters (DD.2.2.2.e) + +# Cone Colors (from DD.1.1) +CONE_COLOR_BLUE = 0 # Left track border +CONE_COLOR_YELLOW = 1 # Right track border +CONE_COLOR_ORANGE_SMALL = 2 # Entry/exit lanes +CONE_COLOR_ORANGE_LARGE = 3 # Start/finish lines + +# Beam Search Parameters +BEAM_WIDTH = 10 # Number of best paths to keep at each tree level +MAX_TREE_DEPTH = 15 # Maximum number of waypoints to look ahead + +# Cost Function Weights +WEIGHT_BOUNDARY_VIOLATION = 1000.0 # Heavily penalize leaving track +WEIGHT_TURNING_RADIUS = 100.0 # Penalize sharp turns +WEIGHT_CURVATURE_CHANGE = 50.0 # Prefer smooth paths +WEIGHT_DISTANCE = 1.0 # Prefer shorter paths +WEIGHT_CENTER_LINE = 10.0 # Prefer staying near center of track + +# Path Smoothing Parameters +SPLINE_DEGREE = 3 # Cubic spline +SPLINE_SMOOTHING_FACTOR = 0.1 # Lower = smoother, higher = closer to waypoints + +# Vehicle Dynamics (estimated - coordinate with Control Planning team) +VEHICLE_MAX_SPEED = 20.0 # m/s (72 km/h - from competitor data) +VEHICLE_MAX_ACCELERATION = 15.0 # m/s^2 (0-100 km/h in ~2s) + +# Noise/Robustness Parameters +MAX_CONE_POSITION_ERROR = 0.5 # meters - expected SLAM noise from monocular vision +MIN_CONES_FOR_VALID_PATH = 4 # Minimum cones needed to plan a path diff --git a/PathPlanning/cost_functions.py b/PathPlanning/cost_functions.py new file mode 100644 index 0000000..66ef316 --- /dev/null +++ b/PathPlanning/cost_functions.py @@ -0,0 +1,8 @@ +""" +Cost Function Heuristics for Path Planning +Deadline: Dec 3, 2025 +""" + +import numpy as np +from typing import List, Tuple +import config diff --git a/PathPlanning/delaunay.py b/PathPlanning/delaunay.py new file mode 100644 index 0000000..7ba78f5 --- /dev/null +++ b/PathPlanning/delaunay.py @@ -0,0 +1,89 @@ +from scipy.spatial import Delaunay +import numpy as np +import matplotlib.pyplot as plt + +def create_delaunay_triangulation(cones): + # Create a Delaunay Triangulation from the cone positions + points = np.array(cones) + + return Delaunay(points) + +def get_midpoint_graph(tri, points): + # Get a midpoint graph from the Delaunay Triangulation + waypoints = [] + + for simplex in tri.simplices: + i, j ,k = simplex + # Get coordinates of each point + p1 = points[i] + p2 = points[j] + p3 = points[k] + + # Compute midpoints of each edge and add to waypoints + waypoints.append((p1 + p2) / 2) + waypoints.append((p1 + p3) / 2) + waypoints.append((p2 + p3) / 2) + + return np.array(waypoints) + +def visualize_triangulation(points, tri, waypoints): + # Visualize and verify triangulation of points + + plt.figure(figsize=(10,8)) + + plt.triplot(points[ : , 0], points[ : , 1], tri.simplices, 'b-', linewidth=0.5) + plt.plot(points[ : , 0], points[ : , 1], 'ro', markersize=10, label="Cones") + plt.plot(waypoints[ : , 0], waypoints[ : , 1], 'go', markersize=10, label="Waypoints") + + plt.xlabel('X position') + plt.ylabel('Y position') + plt.title('Delaunay Triangulation of Cones') + plt.legend() + plt.show() + +if __name__ == "__main__": + # Test data option 1: Simple track-like pattern + simple_track = [ + [0, 0], [1, 0], [2, 0.5], [3, 1], [4, 1.5], + [4, -0.5], [3, -1], [2, -1.5], [1, -1], [0, -0.5] + ] + + # Test data option 2: Oval/loop track (more realistic) + oval_track = [ + # Outer boundary + [0, 0], [2, -1], [4, -1.5], [6, -1.5], [8, -1], [10, 0], + [10, 2], [8, 3], [6, 3.5], [4, 3.5], [2, 3], [0, 2], + # Inner boundary + [2, 0.5], [4, 0], [6, 0], [8, 0.5], [8, 1.5], [6, 2], + [4, 2], [2, 1.5] + ] + + # Test data option 3: Slalom/chicane pattern + slalom = [ + [0, 0], [1, 1], [2, -1], [3, 1.5], [4, -1.5], + [5, 2], [6, -2], [7, 2.5], [8, -2.5], [9, 0], + [0, -0.5], [1, -2], [2, 1], [3, -2.5], [4, 2], + [5, -3], [6, 2.5], [7, -3.5], [8, 3], [9, 0.5] + ] + + # Test data option 4: Grid pattern (stress test) + grid = [] + for x in range(0, 10, 2): + for y in range(-4, 5, 2): + grid.append([x, y]) + + # Test data option 5: Random scattered (realistic chaos) + import random + random.seed(42) + random_scatter = [[random.uniform(0, 10), random.uniform(-3, 3)] for _ in range(30)] + + # Choose which test data to use + test_cone_data = oval_track# Change this to try different patterns + + # Parse and create triangulation + points = np.array(test_cone_data) + tri = create_delaunay_triangulation(test_cone_data) + waypoints = get_midpoint_graph(tri, points) + + # Visualize + visualize_triangulation(points, tri, waypoints) diff --git a/PathPlanning/path_planner.py b/PathPlanning/path_planner.py new file mode 100644 index 0000000..a4828b8 --- /dev/null +++ b/PathPlanning/path_planner.py @@ -0,0 +1,13 @@ +""" +Main Path Planning Module +Deadline: Dec 6, 2025 +""" + +import numpy as np +from typing import Tuple +from delaunay import create_delaunay_triangulation, get_midpoint_graph +from path_tree import PathTree +from cost_functions import PathCostEvaluator +from beam_search import BeamSearchPathPlanner +from path_smoother import PathSmoother +import config diff --git a/PathPlanning/path_smoother.py b/PathPlanning/path_smoother.py new file mode 100644 index 0000000..f98ed55 --- /dev/null +++ b/PathPlanning/path_smoother.py @@ -0,0 +1,9 @@ +""" +Path Smoothing using Spline Interpolation +Deadline: Dec 3, 2025 +""" + +import numpy as np +from typing import List, Tuple +from scipy.interpolate import splprep, splev, CubicSpline +import config diff --git a/PathPlanning/path_tree.py b/PathPlanning/path_tree.py new file mode 100644 index 0000000..524ff6d --- /dev/null +++ b/PathPlanning/path_tree.py @@ -0,0 +1,9 @@ +""" +Path Tree Population Module +Deadline: Nov 22, 2025 +""" + +import numpy as np +from typing import List, Optional +from dataclasses import dataclass +import config diff --git a/Projects/Archive/IMUDataProcessings.md b/Projects/Archive/IMUDataProcessings.md new file mode 100644 index 0000000..b3d0acc --- /dev/null +++ b/Projects/Archive/IMUDataProcessings.md @@ -0,0 +1,30 @@ +# IMU Data Processing + +## Active Members +1. Saahith Veeramaneni + +## Design Review Dates/Timeline +1. Literature review by November 3rd +1. PDR by November 10th +1. Theoretical codebase, Thanksgiving + +## Introduction +Due to the low compute on the car, it is not possible to use multiple +cameras so this project will explore using structure from motion (sfm) +to create binocular views. + +## Overview of the Problem +Having multiple perspectives on a car allows the creation of a +disparity map from an image which can be used to estimate depth if the +exact distance between the cameras is well understood. Thus, we must +explore if we can achieve high enough accuracy from the IMU to use sfm +in the data processing pipeline. + +## Steps in the project +1. Literature review +1. Understanding compute requirements +1. Draft of the code if it is feasible + +## Suggested direction +1. Begin with a long literature review and exploring its use on other + Formula Student teams and in industry diff --git a/Projects/ControlPlanning.md b/Projects/ControlPlanning.md index 5586123..c4a5157 100644 --- a/Projects/ControlPlanning.md +++ b/Projects/ControlPlanning.md @@ -2,6 +2,7 @@ ## Active Members 1. Ray Zou +2. Nathan Margolis ## Design Review Dates/Timeline 1. PDR November 3rd diff --git a/README.md b/README.md index 76babfb..ee3acff 100644 --- a/README.md +++ b/README.md @@ -1,2 +1,5 @@ # Driverless The driverless effort of the UCSC FSAE team + +# Setup +A conda envrionment is used running python 3.10.9 diff --git a/environment.yml b/environment.yml new file mode 100644 index 0000000..f9178ff --- /dev/null +++ b/environment.yml @@ -0,0 +1,239 @@ +name: fsae +channels: + - pytorch + - conda-forge + - defaults +dependencies: + - absl-py=2.3.1 + - aom=3.9.1 + - blas=1.0 + - bottleneck=1.3.7 + - brotli=1.0.9 + - brotli-bin=1.0.9 + - bzip2=1.0.8 + - c-ares=1.34.5 + - ca-certificates=2025.10.5 + - cairo=1.18.0 + - certifi=2025.10.5 + - charset-normalizer=3.4.3 + - contourpy=1.2.0 + - cycler=0.11.0 + - cython=3.1.4 + - dav1d=1.2.1 + - expat=2.6.3 + - filelock=3.13.1 + - fluidsynth=2.3.7 + - font-ttf-dejavu-sans-mono=2.37 + - font-ttf-inconsolata=2.001 + - font-ttf-source-code-pro=2.030 + - font-ttf-ubuntu=0.83 + - fontconfig=2.15.0 + - fonts-anaconda=1 + - fonts-conda-ecosystem=1 + - fonttools=4.51.0 + - freetype=2.13.3 + - fsspec=2024.6.1 + - gettext=0.22.5 + - gettext-tools=0.22.5 + - giflib=5.2.2 + - graphite2=1.3.14 + - grpcio=1.62.2 + - harfbuzz=10.2.0 + - icu=73.2 + - importlib-metadata=8.7.0 + - jinja2=3.1.4 + - joblib=1.4.2 + - kiwisolver=1.4.4 + - lame=3.100 + - lcms2=2.17 + - lerc=4.0.0 + - libabseil=20240116.2 + - libasprintf=0.22.5 + - libasprintf-devel=0.22.5 + - libavif16=1.1.1 + - libbrotlicommon=1.0.9 + - libbrotlidec=1.0.9 + - libbrotlienc=1.0.9 + - libcxx=21.1.2 + - libdeflate=1.22 + - libexpat=2.6.3 + - libffi=3.4.4 + - libflac=1.4.3 + - libfreetype=2.13.3 + - libfreetype6=2.13.3 + - libgettextpo=0.22.5 + - libgettextpo-devel=0.22.5 + - libgfortran=5.0.0 + - libgfortran5=11.3.0 + - libglib=2.82.2 + - libgrpc=1.62.2 + - libiconv=1.18 + - libintl=0.22.5 + - libintl-devel=0.22.5 + - libjpeg-turbo=3.0.3 + - libmad=0.15.1b + - libmagic=5.46 + - libogg=1.3.5 + - libopenblas=0.3.21 + - libopus=1.3.1 + - libpng=1.6.50 + - libprotobuf=4.25.3 + - libre2-11=2023.09.01 + - libsndfile=1.2.2 + - libsqlite=3.45.2 + - libtiff=4.7.0 + - libvorbis=1.3.7 + - libwebp=1.5.0 + - libwebp-base=1.5.0 + - libxcb=1.17.0 + - libzlib=1.3.1 + - llvm-openmp=15.0.7 + - lz4-c=1.9.4 + - markdown=3.9 + - markupsafe=2.1.3 + - matplotlib=3.9.2 + - matplotlib-base=3.9.2 + - mpg123=1.32.8 + - mpmath=1.3.0 + - ncurses=6.4 + - networkx=3.3 + - numexpr=2.8.7 + - numpy=1.26.4 + - numpy-base=1.26.4 + - openjpeg=2.5.2 + - openssl=3.5.4 + - opusfile=0.12 + - packaging=24.1 + - pcre2=10.44 + - pip=24.2 + - pixman=0.43.4 + - polars=1.10.0 + - portaudio=19.6.0 + - portmidi=2.0.4 + - pthread-stubs=0.3 + - pybind11-abi=5 + - pycocotools=2.0.10 + - pygame=2.6.1 + - pyparsing=3.1.2 + - pysocks=1.7.1 + - python=3.12.2 + - python-dateutil=2.9.0post0 + - python-tzdata=2023.3 + - python_abi=3.12 + - pytorch=2.4.0 + - pytz=2024.1 + - pyyaml=6.0.3 + - rav1e=0.6.6 + - re2=2023.09.01 + - readline=8.2 + - requests=2.32.5 + - scikit-learn=1.5.1 + - scipy=1.13.1 + - sdl2=2.30.7 + - sdl2_image=2.8.2 + - sdl2_mixer=2.6.3 + - sdl2_ttf=2.22.0 + - setuptools=75.1.0 + - six=1.16.0 + - sleef=3.5.1 + - sqlite=3.45.2 + - svt-av1=2.3.0 + - sympy=1.13.2 + - tensorboard=2.20.0 + - tensorboard-data-server=0.7.0 + - tensorboardx=2.6.2.2 + - termcolor=3.1.0 + - terminaltables=3.1.10 + - threadpoolctl=3.5.0 + - tk=8.6.13 + - torchaudio=2.4.0 + - torchvision=0.19.0 + - tornado=6.4.1 + - tzdata=2024b + - unicodedata2=15.1.0 + - werkzeug=3.1.3 + - wheel=0.44.0 + - xorg-libxau=1.0.12 + - xorg-libxdmcp=1.1.5 + - xz=5.4.6 + - yaml=0.2.5 + - zipp=3.23.0 + - zlib=1.3.1 + - pip: + - aiofiles==24.1.0 + - annotated-types==0.7.0 + - anyio==4.2.0 + - arel==0.4.0 + - async-asgi-testclient==1.4.11 + - attrs==25.4.0 + - beautifulsoup4==4.14.2 + - bidict==0.23.1 + - cacheout==0.14.1 + - cachetools==5.5.0 + - click==8.3.0 + - debugpy==1.8.17 + - distinctipy==1.3.4 + - executing==2.2.1 + - fastapi==0.109.0 + - ffmpeg-python==0.2.0 + - future==1.0.0 + - gitdb==4.0.12 + - gitpython==3.1.45 + - giturlparse==0.12.0 + - h11==0.16.0 + - h2==4.3.0 + - hpack==4.1.0 + - httpcore==1.0.9 + - httptools==0.6.4 + - httpx==0.27.2 + - hyperframe==6.1.0 + - idna==3.10 + - imutils==0.5.4 + - jsonpatch==1.33 + - jsonpointer==3.0.0 + - jsonschema==4.23.0 + - jsonschema-specifications==2025.9.1 + - markdown-it-py==4.0.0 + - mdurl==0.1.2 + - multidict==6.7.0 + - numerize==0.12 + - opencv-python==4.11.0.86 + - pandas==2.1.4 + - pillow==10.4.0 + - protobuf==3.20.3 + - psutil==5.9.8 + - ptable==0.9.2 + - pydantic==2.11.3 + - pydantic-core==2.33.1 + - pydicom==2.4.4 + - pygments==2.19.2 + - pyjwt==2.10.1 + - pynrrd==0.4.3 + - python-dotenv==1.0.1 + - python-json-logger==2.0.7 + - python-magic==0.4.27 + - python-multipart==0.0.12 + - referencing==0.36.2 + - requests-toolbelt==1.0.0 + - rich==14.1.0 + - rpds-py==0.27.1 + - shapely==2.0.2 + - simpleitk==2.4.1 + - smmap==5.0.2 + - sniffio==1.3.1 + - soupsieve==2.8 + - starlette==0.35.1 + - stringcase==1.2.0 + - supervisely==6.73.451 + - tqdm==4.67.1 + - trimesh==4.5.0 + - typing-extensions==4.15.0 + - typing-inspection==0.4.2 + - urllib3==2.2.3 + - uvicorn==0.37.0 + - uvloop==0.21.0 + - varname==0.15.0 + - watchfiles==1.1.0 + - websockets==13.1 + - zstd==1.5.7.2 +prefix: /Users/daniel/anaconda3/envs/fsae