From 3a73806a5268ff68d4741074595be7f63d997626 Mon Sep 17 00:00:00 2001 From: Ruben van de Ven Date: Fri, 7 Nov 2025 12:07:05 +0100 Subject: [PATCH] Tweaks for running live with lidar --- EXPERIMENTS/config.json | 6 +- README.md | 7 +- supervisord.conf | 36 ++- tests/stage_lines.ipynb | 248 ++++++++++++++++ .../trajectron_maps.ipynb | 16 +- trap/cv_renderer.py | 7 +- trap/lidar_tracker.py | 267 +++++++++++++----- trap/lines.py | 118 +++++++- trap/prediction_server.py | 1 + trap/process_data.py | 73 +++-- trap/settings.py | 18 +- trap/stage.py | 113 +++++--- trap/tools.py | 2 + trap/tracker.py | 125 +++++--- trap/utils.py | 2 +- 15 files changed, 840 insertions(+), 199 deletions(-) create mode 100644 tests/stage_lines.ipynb rename test_trajectron_maps.ipynb => tests/trajectron_maps.ipynb (99%) diff --git a/EXPERIMENTS/config.json b/EXPERIMENTS/config.json index 399e7a7..da052d2 100644 --- a/EXPERIMENTS/config.json +++ b/EXPERIMENTS/config.json @@ -2,12 +2,12 @@ "batch_size": 512, "grad_clip": 1.0, "learning_rate_style": "exp", - "learning_rate": 0.01, + "learning_rate": 0.0001, "min_learning_rate": 1e-05, "learning_decay_rate": 0.9999, - "prediction_horizon": 30, + "prediction_horizon": 60, "minimum_history_length": 5, - "maximum_history_length": 50, + "maximum_history_length": 150, "map_encoder": { "PEDESTRIAN": { "heading_state_index": [2, 3], diff --git a/README.md b/README.md index d5e4522..56d84fd 100644 --- a/README.md +++ b/README.md @@ -21,9 +21,14 @@ These are roughly the steps to go from datagathering to training 2. Lidar: `uv run trap_lidar --min-box-area 0 --pi LOCAL_IP --smooth-tracks` 4. Save the tracks emitted by the video or lidar tracker: `uv run trap_track_writer --output-dir EXPERIMENTS/raw/hof-lidar` * Each recording adds a new txt file to the `raw` folder. -4. Parse tracker data to Trajectron format: `uv run process_data --src-dir EXPERIMENTS/raw/NAME --dst-dir EXPERIMENTS/trajectron-data/ --name NAME` Optionally, smooth tracks: `--smooth-tracks` +4. Parse tracker data to Trajectron format: `uv run process_data --src-dir EXPERIMENTS/raw/NAME --dst-dir EXPERIMENTS/trajectron-data/ --name NAME` + * Optionally, smooth tracks: `--smooth-tracks` + * Optionally, and variations with noise: `--noise-tracks 2` (creates 2 variations) + * Optionally, and variations with at a random offset: `--offset-tracks 2` (creates 2 variations) * Optionally, add a map: ideally a RGB png: 3 layers of 0-255 * `uv run process_data --src-dir EXPERIMENTS/raw/NAME --dst-dir EXPERIMENTS/trajectron-data/ --name NAME --smooth-tracks --camera-fps 12 --homography ../DATASETS/NAME/homography.json --calibration ../DATASETS/NAME/calibration.json --filter-displacement 2 --map-img-path ../DATASETS/NAME/map.png` + * See [[tests/trajectron_maps.ipynb]] for more info how to do so (e.g. the homography map/scale settings, which are also set in process_data) + 5. Train Trajectron model `uv run trajectron_train --eval_every 10 --vis_every 1 --train_data_dict NAME_train.pkl --eval_data_dict NAME_val.pkl --offline_scene_graph no --preprocess_workers 8 --log_dir EXPERIMENTS/models --log_tag _NAME --train_epochs 100 --conf EXPERIMENTS/config.json --batch_size 256 --data_dir EXPERIMENTS/trajectron-data ` 6. The run! * `uv run supervisord` diff --git a/supervisord.conf b/supervisord.conf index 100dcd6..c99e7c1 100644 --- a/supervisord.conf +++ b/supervisord.conf @@ -28,10 +28,24 @@ command=uv run trap_video_source --homography ../DATASETS/hof3-cam-baumer-cropp directory=%(here)s [program:tracker] -# command=uv run trap_tracker --smooth-tracks -command=uv run trap_lidar --min-box-area 0 --viz --smooth-tracks +command=uv run trap_tracker --smooth-tracks +# command=uv run trap_lidar --min-box-area 0 --viz --smooth-tracks +# environment=DISPLAY=":0" +directory=%(here)s +autostart=false + +[program:lidar] +command=uv run trap_lidar --min-box-area 0.1 --viz --smooth-tracks environment=DISPLAY=":0" directory=%(here)s +autostart=false + +[program:track_writer] +command=uv run trap_track_writer --output-dir EXPERIMENTS/raw/hof-lidar +# environment=DISPLAY=":0" +directory=%(here)s +autostart=false +stopwaitsecs=60 [program:stage] # command=uv run trap_stage @@ -46,7 +60,7 @@ directory=%(here)s [program:predictor] command=uv run trap_prediction --eval_device cuda:0 --model_dir EXPERIMENTS/models/models_20241229_21_35_13_hof3-m2-ud-split-conv12-f2.0-map-2024-12-29/ --num-samples 1 --map_encoding --eval_data_dict EXPERIMENTS/trajectron-data/hof3-m2-ud-split-nostep-conv12-f2.0-map-2024-12-29_val.pkl --prediction-horizon 120 --gmm-mode True --z-mode - +# command=uv run trap_prediction --eval_device cuda:0 --model_dir EXPERIMENTS/models/models_20251106_11_51_00_hof-lidar-m2-ud-nostep-kalsmooth-noise2-offsets2-f2.0-map-2025-11-06/ --num-samples 1 --map_encoding --eval_data_dict EXPERIMENTS/trajectron-data/hof-lidar-m2-ud-nostep-kalsmooth-noise2-offsets2-f2.0-map-2025-11-06_val.pkl --prediction-horizon 120 --gmm-mode True --z-mode # uv run trajectron_train --continue_training_from EXPERIMENTS/models/models_20241229_21_35_13_hof3-m2-ud-split-conv12-f2.0-map-2024-12-29/ --eval_every 5 --train_data_dict hof3-nostep-conv12-f2.0-map-2024-12-27_train.pkl --eval_data_dict hof3-nostep-conv12-f2.0-map-2024-12-27_val.pkl --offline_scene_graph no --preprocess_workers 8 --log_dir EXPERIMENTS/models --log_tag _hof3-conv12-f2.0-map-2024-12-27 --train_epochs 10 --conf EXPERIMENTS/config.json --data_dir EXPERIMENTS/trajectron-data --map_encoding directory=%(here)s @@ -58,6 +72,22 @@ autostart=false ; can be long to quit if rendering to video file stopwaitsecs=60 +[program:render_cv] +command=uv run trap_render_cv +directory=%(here)s +environment=DISPLAY=":0" +autostart=false +; can be long to quit if rendering to video file +stopwaitsecs=60 + +[program:laserspace] +command=cargo run --release tcp://127.0.0.1:99174 +directory=%(here)s/../laserspace +environment=DISPLAY=":0" +autostart=false +; can be long to quit if rendering to video file +stopwaitsecs=60 + # during development auto restart some services when the code changes [program:superfsmon] diff --git a/tests/stage_lines.ipynb b/tests/stage_lines.ipynb new file mode 100644 index 0000000..d5788f1 --- /dev/null +++ b/tests/stage_lines.ipynb @@ -0,0 +1,248 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 2, + "id": "485919cd", + "metadata": {}, + "outputs": [], + "source": [ + "import logging\n", + "from pathlib import Path\n", + "import time\n", + "from typing import List\n", + "\n", + "import numpy as np\n", + "from trap.base import Camera, Track\n", + "from trap.lines import Coordinate\n", + "from trap.tracker import FinalDisplacementFilter, Smoother, TrackReader\n", + "\n", + "from scipy.spatial import KDTree" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "id": "53b68ede", + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "[[ 1 0 0]\n", + " [ 0 1 0]\n", + " [ 0 0 1]]\n" + ] + } + ], + "source": [ + "from trap.base import UndistortedCamera\n", + "\n", + "\n", + "path = Path(\"../EXPERIMENTS/raw/hof3/\")\n", + "dataset_path = Path(\"../DATASETS/hof3/\")\n", + "\n", + "path = Path(\"../EXPERIMENTS/raw/hof-lidar/\")\n", + "dataset_path = Path(\"../../DATASETS/hof-lidar/\")\n", + "logging.basicConfig(level=logging.DEBUG)\n", + "\n", + "calibration_path = dataset_path / \"calibration.json\"\n", + "homography_path = dataset_path / \"homography.json\"\n", + "camera = Camera.from_paths(calibration_path, homography_path, 12)\n", + "camera = UndistortedCamera()\n", + "\n", + "print(camera.H)\n", + "# device = device = torch.device('cuda' if torch.cuda.is_available() else 'cpu')\n" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "id": "998e73c6", + "metadata": {}, + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "DEBUG:history:loaded 32 tracks\n", + "DEBUG:history:after filtering left with 23 tracks\n", + "ERROR:trap.base:WARNING, gap between frames 632 -> 322 is negative?\n", + "ERROR:trap.base:WARNING, gap between frames 1003 -> 895 is negative?\n", + "DEBUG:history:interpolated 23 tracks\n" + ] + }, + { + "name": "stderr", + "output_type": "stream", + "text": [ + "DEBUG:history:smoothed\n", + "DEBUG:history:projected to world space\n", + "DEBUG:history:built tree\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "loaded 23 tracks in 0.16869831085205078s\n" + ] + } + ], + "source": [ + "from trap.track_history import TrackHistory\n", + "\n", + "s = time.time()\n", + "history = TrackHistory(path, camera, None)\n", + "dt = time.time() - s\n", + "print(f'loaded {len(history.state.tracks)} tracks in {dt}s')\n" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "id": "cba8c9b0", + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "" + ] + }, + "execution_count": 5, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "history" + ] + }, + { + "cell_type": "code", + "execution_count": 26, + "id": "122e3311", + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "" + ] + }, + "execution_count": 26, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "track = list(history.state.tracks.values())[3]\n", + "trajectory_crop = history.state.track_histories[track.track_id]\n", + "trajectory_org = track.get_projected_history(camera=camera)\n", + "target_point = trajectory_org[len(trajectory_org)//2+90]\n", + "\n", + "import matplotlib.pyplot as plt # Visualization \n", + "\n", + "plt.gca().set_aspect('equal')\n", + "plt.scatter(trajectory_crop[:,0], trajectory_crop[:,1], c='orange')\n", + "until = 772\n", + "plt.plot(trajectory_org[:-until,0], trajectory_org[:-until,1], c='blue', alpha=.2)\n", + "plt.scatter(target_point[0], target_point[1], c='red', alpha=1)\n", + "\n" + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "id": "bbbf97c9", + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "'2446 track points in the set'" + ] + }, + "execution_count": 6, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "f\"{len(history.state.indexed_track_ids)} track points in the set\"" + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "id": "d22c1f35", + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "track_set = history.get_nearest_tracks(target_point, 10, max_r=np.inf)\n", + "\n", + "\n", + "\n", + "plt.gca().set_aspect('equal')\n", + "plt.scatter(trajectory_crop[:,0], trajectory_crop[:,1], c='orange')\n", + "plt.plot(trajectory_org[:,0], trajectory_org[:,1], c='blue', alpha=1)\n", + "plt.scatter(target_point[0], target_point[1], c='red', alpha=1)\n", + "for track_id in track_set:\n", + " closeby = history.state.tracks[track_id].get_projected_history(camera=camera)\n", + " plt.plot(closeby[:,0], closeby[:,1], c='green', alpha=.1)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "6478440c", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "trap-py3.10", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.10.4" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/test_trajectron_maps.ipynb b/tests/trajectron_maps.ipynb similarity index 99% rename from test_trajectron_maps.ipynb rename to tests/trajectron_maps.ipynb index 25a685c..5c67d52 100644 --- a/test_trajectron_maps.ipynb +++ b/tests/trajectron_maps.ipynb @@ -36,9 +36,9 @@ "import matplotlib.pyplot as plt\n", "import numpy as np\n", "\n", - "path = Path(\"EXPERIMENTS/raw/hof3/\")\n", - "calibration_path = Path(\"../DATASETS/hof3/calibration.json\")\n", - "homography_path = Path(\"../DATASETS/hof3/homography.json\")\n", + "path = Path(\"../EXPERIMENTS/raw/hof3/\")\n", + "calibration_path = Path(\"../../DATASETS/hof3/calibration.json\")\n", + "homography_path = Path(\"../../DATASETS/hof3/homography.json\")\n", "\n", "camera = Camera.from_paths(calibration_path, homography_path, 12)\n" ] @@ -52,13 +52,13 @@ "name": "stdout", "output_type": "stream", "text": [ - "../DATASETS/hof-lidar/map-undistorted-H-3.png True\n" + "../../DATASETS/hof-lidar/map-undistorted-H-3.png True\n" ] } ], "source": [ - "image_path = Path(\"../DATASETS/hof3/map-undistorted-H-2.png\")\n", - "image_path = Path(\"../DATASETS/hof-lidar/map-undistorted-H-3.png\")\n", + "image_path = Path(\"../../DATASETS/hof3/map-undistorted-H-2.png\")\n", + "image_path = Path(\"../../DATASETS/hof-lidar/map-undistorted-H-3.png\")\n", "print(image_path, image_path.exists())\n" ] }, @@ -79,7 +79,7 @@ { "data": { "text/plain": [ - "" + "" ] }, "execution_count": 3, @@ -142,7 +142,7 @@ { "data": { "text/plain": [ - "" + "" ] }, "execution_count": 5, diff --git a/trap/cv_renderer.py b/trap/cv_renderer.py index ea80e7f..a83e133 100644 --- a/trap/cv_renderer.py +++ b/trap/cv_renderer.py @@ -274,7 +274,7 @@ class CvRenderer(Node): render_parser.add_argument('--debug-map', help='specify a map (svg-file) from which to load lines which will be overlayed', type=str, - default="../DATASETS/hof3/map_hof.svg") + default="../DATASETS/hof-lidar/map_hof.svg") return render_parser def click_print_position(self, event,x,y,flags,param): @@ -410,8 +410,9 @@ def decorate_frame(frame: Frame, tracker_frame: Frame, prediction_frame: Frame, inv_H = np.linalg.pinv(prediction_frame.H) # For debugging: # draw_trackjectron_history(img, track, int(track.track_id), conversion) - anim_position = get_animation_position(track, frame) - draw_track_predictions(img, track, int(track.track_id)+1, frame.camera, conversion, anim_position=anim_position, as_clusters=as_clusters) + # anim_position = get_animation_position(track, frame) + anim_position = 1 + draw_track_predictions(img, track, int(track.track_id)+1, prediction_frame.camera, conversion, anim_position=anim_position, as_clusters=as_clusters) cv2.putText(img, f"{len(track.predictor_history) if track.predictor_history else 'none'}", to_point(track.history[0].get_foot_coords()), cv2.FONT_HERSHEY_COMPLEX, 1, (255,255,255), 1) if prediction_frame.maps: for i, m in enumerate(prediction_frame.maps): diff --git a/trap/lidar_tracker.py b/trap/lidar_tracker.py index 477e19b..c7e512e 100644 --- a/trap/lidar_tracker.py +++ b/trap/lidar_tracker.py @@ -4,18 +4,21 @@ from copy import copy from pathlib import Path import select import socket -from typing import DefaultDict, Dict, List +from turtle import update +from typing import DefaultDict, Dict, List, Tuple import dpkt import numpy as np import open3d as o3d import shapely -from sklearn.cluster import DBSCAN +from sklearn.cluster import DBSCAN, OPTICS, Birch from scipy.spatial.distance import cdist import logging import time + +from sklearn.decomposition import PCA from trap.base import Camera, Detection, Frame, Track, UndistortedCamera from trap.counter import CounterSender -from trap.lines import load_lines_from_svg +from trap.lines import Coordinate, load_lines_from_svg from trap.node import Node from bytetracker import BYTETracker import velodyne_decoder as vd @@ -196,7 +199,7 @@ def filter_pcd_points_below_z(pcd: o3d.geometry.PointCloud, z_threshold: float) return pcd_sel - +ASSUMED_FPS = 12 class Lidar(Node): def setup(self): @@ -220,18 +223,27 @@ class Lidar(Node): self.tracks: DefaultDict[str, Track] = defaultdict(lambda: Track()) - self.room_filter = VoxelOccupancyFilter( + + self.room_filter = AdaptiveVoxelFilter( voxel_size=.5, - history_size=80, - history_interval=8, #not every frame needs to impact history - ready_for_action_at=25, - static_threshold=0.3 + nr_of_frames_to_static=120 * ASSUMED_FPS , # (confidence_threshold * update_interval) = nr of frames needed to count as static + nr_of_frames_to_unstatic=10 * ASSUMED_FPS, + update_interval=20, #not every frame needs to impact history + decay_rate=1 ) + # self.room_filter = VoxelOccupancyFilter( + # voxel_size=.5, + # history_size=80, + # history_interval=20, #not every frame needs to impact history + # ready_for_action_at=25, + # static_threshold=0.3 + # ) self.debug_lines = load_lines_from_svg(self.config.debug_map, 100, '') if self.config.debug_map else [] self.map_outline = None self.map_outline_volume = None + self.map_outline_geom = None if self.config.map_outlines: lines = load_lines_from_svg(self.config.map_outlines, 100, '') @@ -240,22 +252,34 @@ class Lidar(Node): else: if len(lines) > 1: logger.warning("Multiple lines in outline file, using first only") - self.map_outline = shapely.Polygon([p.position for p in lines[0].points]) + + polygon_points =np.array([[*p.position, 0] for p in lines[0].points]) + # self.map_outline = shapely.Polygon([p.position for p in lines[0].points]) + boundary_lines = [[i, (i+1) % len(lines[0].points)] for i in range(len(lines[0].points))] + line_set = o3d.geometry.LineSet( + points=o3d.utility.Vector3dVector(polygon_points), + lines=o3d.utility.Vector2iVector(boundary_lines) + ) + + # Optional: set color + line_set.colors = o3d.utility.Vector3dVector([[1, 0, 0] for _ in lines[0].points]) + self.map_outline_geom = line_set + self.map_outline_volume = o3d.visualization.SelectionPolygonVolume() self.map_outline_volume.orthogonal_axis = "Z" # extrusion direction of polygon self.map_outline_volume.axis_min = .3 # filter from slightly above ground self.map_outline_volume.axis_max = 2.2 - polygon_points =np.array([[*p.position, 0] for p in lines[0].points]) + self.map_outline_volume.bounding_polygon = o3d.utility.Vector3dVector(polygon_points) if self.config.smooth_tracks: - fps = 12 # TODO)) make configurable, or get from cam - logger.info(f"Smoother enabled, assuming {fps} fps") - self.smoother = Smoother(window_len=fps*5, convolution=False) + # TODO)) make configurable + logger.info(f"Smoother enabled, assuming {ASSUMED_FPS} fps") + self.smoother = Smoother(window_len=ASSUMED_FPS*5, convolution=False) else: logger.info("Smoother Disabled (enable with --smooth-tracks)") @@ -334,6 +358,8 @@ class Lidar(Node): ) ground_lines.paint_uniform_color([0,1,0]) vis.add_geometry(ground_lines, False) + if self.map_outline_geom: + vis.add_geometry(self.map_outline_geom, False) for line in self.debug_lines: coords = [[*p.position, 0] for p in line.points] @@ -455,14 +481,12 @@ class Lidar(Node): points_2d = project_to_xy(filtered_pcd) - labels = cluster_2d( - points_2d, - self.get_setting('lidar.eps', .3), - self.get_setting('lidar.min_samples', 8) + clusters = self.cluster_2d( + points_2d, ) # boxes, centroids = get_cluster_boxes(points_2d, labels, min_area= 0.3*0.3) - boxes, centroids = get_cluster_boxes(points_2d, labels, min_area= self.get_setting('lidar.min_box_area', .1)) + boxes, centroids = get_cluster_boxes(clusters, min_area= self.get_setting('lidar.min_box_area', .1)) # append confidence and class (placeholders) @@ -633,13 +657,62 @@ class Lidar(Node): argparser.add_argument('--debug-map', help='specify a map (svg-file) from which to load lines which will be overlayed', type=str, - default="../DATASETS/hof3/map_hof.svg") + default="../DATASETS/hof-lidar/map_hof.svg") argparser.add_argument('--map-outlines', help='specify a map (svg-file) from which to load boundary of the map. Any points outside will be filtered (removing floor and walls)', type=Path, - default="../DATASETS/hof3/map_hof_lidar_boundaries.svg") + default="../DATASETS/hof-lidar/map_hof_lidar_boundaries.svg") return argparser + + + + + # ==== Clustering and Centroids ==== + def cluster_2d(self, points_xy) -> List[np.ndarray]: + """ + Returns a list of clusters + """ + + # skip when only having a few points + # this is anyhow good, regardless of clustering method + if len(points_xy) < self.get_setting('lidar.min_samples', 8): + return [] + + method = self.get_setting('lidar.cluster.method', default='dbscan') + if method == 'dbscan': + labels = DBSCAN( + eps=self.get_setting('lidar.eps', .132), + min_samples=self.get_setting('lidar.min_samples', 6) + ).fit_predict(points_xy) + elif method == 'optics': + labels = OPTICS( + max_eps=self.get_setting('lidar.eps', .132), + min_samples=self.get_setting('lidar.min_samples', 6), algorithm="ball_tree" + ).fit_predict(points_xy) + elif method == 'birch': + process_subclusters = self.get_setting('lidar.birch_process_subclusters', True) + labels = Birch( + max_eps=self.get_setting('lidar.birch_threshold', 1), # "The radius of the subcluster obtained by merging a new sample" + branching_factor=self.get_setting('lidar.birch_branching_factor', 50), + n_clusters=None if not process_subclusters else DBSCAN( + eps=self.get_setting('lidar.eps', .132), + min_samples=self.get_setting('lidar.min_samples', 6) + ) + ).fit_predict(points_xy) + else: + self.logger.critical("Unknown clustering method") + return [] + + + # db.labels_ + clusters = [] + for label in labels: + if label == -1: + continue # Skip noise + + clusters.append(points_xy[labels == label]) + return clusters # ==== Ground Removal ==== def find_ground(pcd: o3d.geometry.PointCloud, distance_threshold=0.1): @@ -651,6 +724,39 @@ def find_ground(pcd: o3d.geometry.PointCloud, distance_threshold=0.1): non_ground = pcd.select_by_index(inliers, invert=True) return np.asarray(non_ground.points), np.asarray(ground) +# def fit_ellipse_pca(points): +# """ +# Fit an ellipse approximation to 2D points using PCA. +# Returns: (center_x, center_y), (major_axis_length, minor_axis_length), angle (in radians) +# """ +# # Center the data +# center = np.mean(points, axis=0) +# centered_points = points - center + +# # Perform PCA +# pca = PCA(n_components=2) +# pca.fit(centered_points) + +# # Get the principal axes (eigenvectors) and their lengths (eigenvalues) +# axes = pca.components_ +# lengths = np.sqrt(pca.explained_variance_) + +# # The angle of the major axis +# angle = np.arctan2(axes[0, 1], axes[0, 0]) +# dx = typical_person_depth * np.cos(angle) +# dy = typical_person_depth * np.sin(angle) +# adjusted_center = center + np.array([dx, dy]) + +# return center, lengths, angle + +# def weighted_mean(points, weights): +# return np.average(points, axis=0, weights=weights) + +# # Example: Assign higher weights to points farther from the LiDAR +# weights = 1 / np.linalg.norm(points - lidar_position, axis=1) # Inverse distance weighting +# weighted_center = weighted_mean(points, weights) +# print("Weighted center:", weighted_center) + def segment_planes(pcd, num_planes = 5, num_iterations=100, distance_threshold=0.1) -> List[o3d.geometry.PointCloud]: @@ -689,15 +795,6 @@ def segment_planes(pcd, num_planes = 5, num_iterations=100, distance_threshold=0 return planes - -# ==== Clustering and Centroids ==== -def cluster_2d(points_xy, eps=0.5, min_samples=5): - if len(points_xy) < min_samples: - return [] - - db = DBSCAN(eps=eps, min_samples=min_samples).fit(points_xy) - return db.labels_ - def split_cluster_by_convex_hull(points, max_hull_area): """ Splits a cluster of points based on its convex hull area. @@ -743,18 +840,13 @@ def split_cluster_by_convex_hull(points, max_hull_area): -def get_cluster_boxes(points_xy, labels, min_area = 0): - if not len(labels): +def get_cluster_boxes(clusters, min_area = 0): + if not len(clusters): return np.empty([0,4]), np.empty([0,2]) boxes = [] # Each box: [x1, y1, x2, y2] centroids = [] - unique_labels = set(labels) - - for label in unique_labels: - if label == -1: - continue # Skip noise - cluster = points_xy[labels == label] + for cluster in clusters: x_min, y_min = cluster.min(axis=0) x_max, y_max = cluster.max(axis=0) @@ -928,57 +1020,94 @@ class VoxelOccupancyFilter: return filtered_pcd, dropped_indexes -class DecayingVoxelOccupancyFilter: - def __init__(self, voxel_size=0.1, decay_rate=0.01, appear_increment=0.01, static_threshold=0.2): +class AdaptiveVoxelFilter: + def __init__( + self, + voxel_size=0.1, + nr_of_frames_to_static=720, + nr_of_frames_to_unstatic=720, + decay_rate=1, + update_interval=10, + ): """ - WIP!! Initializes the voxel occupancy filter with decay. + Initialize the adaptive voxel filter. Parameters: voxel_size (float): Size of each voxel in meters. - decay_rate (float): Amount to decay occupancy per frame. - appear_increment (float): Value added when a voxel appears in current frame. - static_threshold (float): Threshold to consider voxel as static. + confidence_threshold (int): (update_interval * confidence_threshold = nr of frames filled to count as static) + max_occupancy_score (int): max value of occupied voxels (((max_occupancy_score-confidence_treshhold) / decay_rate) * update_interval = conseccutive empty measurements needed to become unstatic) + decay_rate (int): How much to decrement confidence for unoccupied voxels per scan. + update_interval (int): Update static map every N scans. """ + self.confidence_threshold = (nr_of_frames_to_static / update_interval) * decay_rate + self.max_occupancy_score = (nr_of_frames_to_unstatic / update_interval) * decay_rate + self.confidence_threshold self.voxel_size = voxel_size + # self.confidence_threshold = confidence_threshold + # self.max_occupancy_score = max_occupancy_score self.decay_rate = decay_rate - self.appear_increment = appear_increment - self.static_threshold = static_threshold - self.voxel_occupancy = {} # dict: voxel tuple -> occupancy score + + self.update_interval = update_interval + + # Static map: {voxel: confidence} + self.static_map: Dict[Tuple[int, int], int] = defaultdict(int) + + # Counter for update interval + self.scan_counter = 0 + + self.initialised = False - def _point_cloud_to_voxel_set(self, pcd): - points = np.asarray(pcd.points) - voxel_coords = np.floor(points / self.voxel_size).astype(np.int32) - return set(map(tuple, voxel_coords)) def remove_static(self, current_pcd): - current_voxels = self._point_cloud_to_voxel_set(current_pcd) + """ + Remove static points from the current point cloud. - # Decay all existing voxel scores - for voxel in list(self.voxel_occupancy.keys()): - self.voxel_occupancy[voxel] *= (1.0 - self.decay_rate) - if self.voxel_occupancy[voxel] < self.appear_increment: - del self.voxel_occupancy[voxel] # clean up low-score entries + Parameters: + current_pcd (open3d.geometry.PointCloud): Current point cloud. - # Update occupancy with current frame - for voxel in current_voxels: - self.voxel_occupancy[voxel] = self.voxel_occupancy.get(voxel, 0.0) + self.appear_increment - self.voxel_occupancy[voxel] = min(self.voxel_occupancy[voxel], 1.0) # clamp to max=1.0 - - # Identify static voxels - static_voxels = {v for v, score in self.voxel_occupancy.items() if score >= self.static_threshold} - - # Filter points + Returns: + filtered_pcd (open3d.geometry.PointCloud): Point cloud with static points removed. + dropped_indices (list): Indices of dropped (static) points. + """ + + points = np.asarray(current_pcd.points) filtered_points = [] - for pt in np.asarray(current_pcd.points): + dropped_indices = [] + + current_voxel_set = set() + # Check each point in the current scan + for i, pt in enumerate(points): voxel = tuple(np.floor(pt / self.voxel_size).astype(np.int32)) - if voxel not in static_voxels: + current_voxel_set.add(voxel) + + if voxel in self.static_map and self.static_map[voxel] > self.confidence_threshold: + dropped_indices.append(i) + else: filtered_points.append(pt) + # Update static map and confidence + self.scan_counter += 1 + if self.scan_counter % self.update_interval == 0: + if not self.initialised and self.scan_counter > self.confidence_threshold: + self.initialised = True + + # Add new voxels to static map + for voxel in current_voxel_set: + if self.static_map[voxel] < self.max_occupancy_score: + self.static_map[voxel] += 1 + + # Decay confidence for voxels not in current scan + for voxel in list(self.static_map.keys()): + if voxel not in current_voxel_set: + self.static_map[voxel] -= self.decay_rate + if self.static_map[voxel] <= 0: + del self.static_map[voxel] + + # Create filtered point cloud filtered_pcd = o3d.geometry.PointCloud() if filtered_points: filtered_pcd.points = o3d.utility.Vector3dVector(np.array(filtered_points)) - return filtered_pcd + return filtered_pcd, dropped_indices # def point_cloud_to_voxel_set(pcd, voxel_size): # points = np.asarray(pcd.points) diff --git a/trap/lines.py b/trap/lines.py index 49c2f20..40c4bcf 100644 --- a/trap/lines.py +++ b/trap/lines.py @@ -589,6 +589,20 @@ class FadeOutLine(LineAnimator): return target_line +class SimplifyLine(LineAnimator): + """ + Simplify the line + """ + def __init__(self, target_line = None, factor: float =.003): + super().__init__(target_line) + self.factor = factor + self.ready = True # filter holds no state, so always ready + + + + def apply(self, target_line: RenderableLine, dt: DeltaT) -> RenderableLine: + return target_line.as_simplified(SimplifyMethod.RDP, self.factor) + class FadeOutJitterLine(LineAnimator): """ Fade the line providing an alpha, 1 by default @@ -978,7 +992,46 @@ class DashedLine(LineAnimator): return RenderableLine.from_multilinestring(multilinestring, color) +class StartFromClosestPoint(LineAnimator): + """ + Dashed line + """ + def __init__(self, target_line = None, from_point: Optional[Tuple[float,float]] = None): + super().__init__(target_line) + self.from_point = from_point + self.ready = True # static filter, always ready + + def disable(self): + self.from_point = None + + def set_point(self, point: Tuple[float,float]): + self.from_point = point + + def apply(self, target_line: RenderableLine, dt: DeltaT) -> RenderableLine: + """ + warning, dashing (for now) removes all color + """ + + if len(target_line) < 1 or self.from_point is None: + return target_line + + distance = math.inf + idx = 0 + from_point = np.array(self.from_point) + + for i, point in enumerate(target_line.points): + to_point = np.array(point.position) + new_distance = np.linalg.norm(from_point-to_point) + if new_distance < distance: + distance = new_distance + idx = i + else: + break + # print(idx, target_line.points[idx]) + return RenderableLine(target_line.points[idx:]) + + class RotatingLine(LineAnimator): """ @@ -1013,6 +1066,8 @@ class RotatingLine(LineAnimator): # associated_diff = self.prediction_diffs[a] # progress = associated_diff.nr_of_passed_points() + is_ready: List[bool] = [] + for i, (target_point, drawn_point) in enumerate(zip(target_line.points, list(self.drawn_points))): # TODO: this should be done in polar space starting from origin (i.e. self.drawn_posision[-1]) decay = max(3, (18/i) if i else 10) # points further away move with more delay @@ -1026,18 +1081,77 @@ class RotatingLine(LineAnimator): if abs(drawn_angle - pred_angle) > math.pi: pred_angle -= math.pi * 2 angle = exponentialDecay(drawn_angle, pred_angle, decay, dt) - x, y = relativePolarToPoint(origin, r, angle) + x, y = relativePolarToPoint(origin.position, r, angle) r = exponentialDecay(drawn_point.color.red, target_point.color.red, decay, dt) g = exponentialDecay(drawn_point.color.green, target_point.color.green, decay, dt) b = exponentialDecay(drawn_point.color.blue, target_point.color.blue, decay, dt) a = exponentialDecay(drawn_point.color.alpha, target_point.color.alpha, decay, dt) + + + self.drawn_points[i].position = (x, y) self.drawn_points[i].color = SrgbaColor(r, g, b, a) + is_ready.append(np.isclose(drawn_point.position, target_point.position, atol=.05).all()) + + self.ready = all(is_ready) return RenderableLine(self.drawn_points) - + +class NoodleWiggler(LineAnimator): + """When a line is 'noodling' don't draw it as a whole, but sway it animated + """ + + def __init__(self, target_line = None): + super().__init__(target_line) + + def apply(self, target_line, dt): + return target_line + + @classmethod + def detect_noodling_sections(cls, line, segment_length=0.1, ratio_threshold=2.0): + """ + Detects noodling sections in a LineString using the ratio of actual length to straight-line distance. + + Args: + line (LineString): Input LineString. + segment_length (float): Length of each segment as a fraction of the total line length. + ratio_threshold (float): Threshold for the ratio (actual_length / straight_line_distance). + + Returns: + list: List of noodling segments (as LineStrings). + """ + noodling_sections = [] + total_length = line.length + segment_start = 0.0 + + while segment_start < 1.0: + segment_end = min(segment_start + segment_length, 1.0) + segment = substring(line, segment_start, segment_end, normalized=True) + + # Calculate straight-line distance between start and end points + start_point = Point(segment.coords[0]) + end_point = Point(segment.coords[-1]) + straight_line_distance = start_point.distance(end_point) + + # Calculate actual length of the segment + actual_length = segment.length + + # Check if the ratio exceeds the threshold + if straight_line_distance > 0 and (actual_length / straight_line_distance) > ratio_threshold: + noodling_sections.append(segment) + + segment_start = segment_end + + return noodling_sections + + # # Example usage: + # line = LineString([(0, 0), (0.1, 0.1), (0.2, 0.2), (0.3, 0.1), (0.4, 0.2), (1, 1)]) + # noodling_segments = detect_noodling_sections(line, segment_length=0.2, area_threshold=0.02) + + # for i, segment in enumerate(noodling_segments): + # print(f"Noodling segment {i+1}: {segment}") IndexAndOffset = Tuple[int, float] diff --git a/trap/prediction_server.py b/trap/prediction_server.py index 6c20ed8..e53580a 100644 --- a/trap/prediction_server.py +++ b/trap/prediction_server.py @@ -87,6 +87,7 @@ def get_maps_for_input(input_dict, scene: Scene, hyperparams, device): heading_angle = None scene_map: ImageMap = scene.map[node.type] + scene_map.set_bounds() # update old pickled maps # map_point = x[-1, :2] map_point = x[:2] # map_point = x[:2].clip(0) # prevent crash for out of map point. diff --git a/trap/process_data.py b/trap/process_data.py index 09dfb8b..eb07b36 100644 --- a/trap/process_data.py +++ b/trap/process_data.py @@ -8,6 +8,7 @@ import time from xml.dom.pulldom import default_bufsize from attr import dataclass import cv2 +import noise import numpy as np import pandas as pd import dill @@ -18,7 +19,7 @@ from typing import Dict, List, Optional from trap.base import Track from trap.config import CameraAction, HomographyAction from trap.frame_emitter import Camera -from trap.tracker import FinalDisplacementFilter, Smoother, TrackReader +from trap.tracker import FinalDisplacementFilter, Noiser, RandomOffset, Smoother, TrackReader #sys.path.append("../../") from trajectron.environment import Environment, Scene, Node @@ -73,22 +74,29 @@ class TrackIteration: smooth: bool step_size: int step_offset: int + noisy: bool = False + offset: bool = False @classmethod - def iteration_variations(cls, smooth = True, toggle_smooth=True, sample_step_size=1): + def iteration_variations(cls, smooth = True, toggle_smooth=True, sample_step_size=1, noisy_variations=0, offset_variations=0): iterations: List[TrackIteration] = [] for i in range(sample_step_size): - iterations.append(TrackIteration(smooth, sample_step_size, i)) - if toggle_smooth: - iterations.append(TrackIteration(not smooth, sample_step_size, i)) + for n in range(noisy_variations+1): + for f in range(offset_variations+1): + iterations.append(TrackIteration(smooth, sample_step_size, i, noisy=bool(n), offset=bool(f))) + if toggle_smooth: + iterations.append(TrackIteration(not smooth, sample_step_size, i, noisy=bool(n), offset=bool(f))) return iterations # maybe_makedirs('trajectron-data') # for desired_source in [ 'hof2', ]:# ,'hof-maskrcnn', 'hof-yolov8', 'VIRAT-0102-parsed', 'virat-resnet-keypoints-full']: -def process_data(src_dir: Path, dst_dir: Path, name: str, smooth_tracks: bool, cm_to_m: bool, center_data: bool, bin_positions: bool, camera: Camera, step_size: int, filter_displacement:float, map_img_path: Optional[Path]): +def process_data(src_dir: Path, dst_dir: Path, name: str, smooth_tracks: bool, noise_tracks: int, offset_tracks: int, center_data: bool, bin_positions: bool, camera: Camera, step_size: int, filter_displacement:float, map_img_path: Optional[Path]): name += f"-nostep" if step_size == 1 else f"-step{step_size}" - name += f"-conv{smooth_window}" if smooth_tracks else f"-nosmooth" + # name += f"-conv{smooth_window}" if smooth_tracks else f"-nosmooth" + name += f"-kalsmooth" if smooth_tracks else f"-nosmooth" + name += f"-noise{noise_tracks}" if noise_tracks else f"" + name += f"-offsets{offset_tracks}" if offset_tracks else f"" name += f"-f{filter_displacement}" if filter_displacement > 0 else "" name += "-map" if map_img_path else "-nomap" name += f"-{datetime.date.today()}" @@ -128,8 +136,10 @@ def process_data(src_dir: Path, dst_dir: Path, name: str, smooth_tracks: bool, c skipped_for_error = 0 created = 0 - smoother = Smoother(window_len=smooth_window, convolution=True) if smooth_tracks else None - + # smoother = Smoother(window_len=smooth_window, convolution=True) if smooth_tracks else None + smoother = Smoother(convolution=False) if smooth_tracks else None + noiser = Noiser(amplitude=.1) if noise_tracks else None + reader = TrackReader(src_dir, camera.fps) tracks = [t for t in reader] print(f"Unfiltered total: {len(tracks)} tracks") @@ -142,9 +152,9 @@ def process_data(src_dir: Path, dst_dir: Path, name: str, smooth_tracks: bool, c bar = tqdm.tqdm(total=total) destinations = { - 'train': int(total * .8), - 'val': int(total * .12), - 'test': int(total * .08), + 'train': int(total * .91), + 'val': int(total * .08), + 'test': int(total * .01), # I don't realyl care about this } max_track = reader.get(str(max([int(k) for k in reader._tracks.keys()]))) @@ -170,7 +180,7 @@ def process_data(src_dir: Path, dst_dir: Path, name: str, smooth_tracks: bool, c print(f"Camera FPS: {camera.fps}, actual fps: {camera.fps/step_size} (or {(1/camera.fps)*step_size})") - names = {} + names: Dict[str, Path] = {} max_pos = 0 for data_class, nr_of_items in destinations.items(): @@ -190,7 +200,9 @@ def process_data(src_dir: Path, dst_dir: Path, name: str, smooth_tracks: bool, c # scene = None scene_nodes = defaultdict(lambda: []) - variations = TrackIteration.iteration_variations(smooth_tracks, False, step_size) + variations = TrackIteration.iteration_variations(smooth_tracks, True, step_size, noise_tracks, offset_tracks) + + print(f"Create {len(variations)} variations") for i, track in enumerate(sets[data_class]): bar.update() @@ -221,12 +233,17 @@ def process_data(src_dir: Path, dst_dir: Path, name: str, smooth_tracks: bool, c for variation_nr, iteration_settings in enumerate(variations): + track = interpolated_track + if iteration_settings.noisy: + track = noiser.apply_track(track) + if iteration_settings.offset: + offset = RandomOffset(amplitude=.1) + track = offset.apply_track(track) if iteration_settings.smooth: - track = smoother.smooth_track(interpolated_track) + track = smoother.smooth_track(track) # track = Smoother(smooth_window, False).smooth_track(track) - else: - track = interpolated_track # TODO)) Copy & move smooth outside iter loop + c = time.time() if iteration_settings.step_size > 1: @@ -310,9 +327,26 @@ def process_data(src_dir: Path, dst_dir: Path, name: str, smooth_tracks: bool, c with open(data_dict_path, 'wb') as f: dill.dump(env, f, protocol=dill.HIGHEST_PROTOCOL) + bar.close() + # print(f"Linear: {l}") # print(f"Non-Linear: {nl}") print(f"error: {skipped_for_error}, used: {created}") + print("Run with") + # set eval_every very high, because we're not interested in theoretical evaluations, and we don't mind overfitting + print(f""" + uv run trajectron_train --eval_every 200 \\ + --train_data_dict {names['train'].name} \\ + --eval_data_dict {names['val'].name} \\ + --offline_scene_graph no --preprocess_workers 8 \\ + --log_dir EXPERIMENTS/models \\ + --log_tag _{name} \\ + --train_epochs 100 \\ + --conf EXPERIMENTS/config.json \\ + --data_dir {dst_dir} \\ + {"--map_encoding" if map_img_path else ""} + """) + return names def main(): @@ -321,6 +355,8 @@ def main(): parser.add_argument("--dst-dir", "-d", type=Path, required=True, help="Destination directory to store parsed .pkl files (typically 'trajectron-data')") parser.add_argument("--name", "-n", type=str, required=True, help="Identifier to prefix the output .pkl files with (result is NAME-train.pkl, NAME-test.pkl)") parser.add_argument("--smooth-tracks", action='store_true', help=f"Enable smoother. Set to {smooth_window} frames") + parser.add_argument("--noise-tracks", type=int, default=0, help=f"Enable Noiser. provide number for how many noisy variations") + parser.add_argument("--offset-tracks", type=int, default=0, help=f"Enable Offset. provide number for how many random offset variations") parser.add_argument("--cm-to-m", action='store_true', help=f"If homography is in cm, convert tracked points to meter for beter results") parser.add_argument("--center-data", action='store_true', help=f"Normalise around center") parser.add_argument("--bin-positions", action='store_true', help=f"Experiment to put round positions to a grid") @@ -358,7 +394,8 @@ def main(): args.dst_dir, args.name, args.smooth_tracks, - args.cm_to_m, + args.noise_tracks, + args.offset_tracks, args.center_data, args.bin_positions, args.camera, diff --git a/trap/settings.py b/trap/settings.py index 65a5fc7..be0a2db 100644 --- a/trap/settings.py +++ b/trap/settings.py @@ -38,13 +38,27 @@ class Settings(Node): dpg.add_text(f"Settings from {self.config.settings_file}") dpg.add_button(label="Save", callback=self.save) - with dpg.window(label="Lidar", pos=(0, 150)): + with dpg.window(label="Stage", pos=(0, 150)): + self.register_setting(f'stage.fps', dpg.add_checkbox(label="FPS cap", default_value=self.get_setting(f'stage.fps', 30), callback=self.on_change)) + + with dpg.window(label="Lidar", pos=(0, 250)): self.register_setting(f'lidar.crop_map_boundaries', dpg.add_checkbox(label="crop_map_boundaries", default_value=self.get_setting(f'lidar.crop_map_boundaries', True), callback=self.on_change)) self.register_setting(f'lidar.viz_cropping', dpg.add_checkbox(label="viz_cropping", default_value=self.get_setting(f'lidar.viz_cropping', True), callback=self.on_change)) self.register_setting(f'lidar.tracking_enabled', dpg.add_checkbox(label="tracking_enabled", default_value=self.get_setting(f'lidar.tracking_enabled', True), callback=self.on_change)) + + + dpg.add_separator(label="Clustering") + cluster_methods = ("birch", "optics", "dbscan") + self.register_setting('lidar.cluster.method', dpg.add_combo(label="Method", items=cluster_methods, default_value=self.get_setting('lidar.cluster.method', default='dbscan'), callback=self.on_change)) self.register_setting(f'lidar.eps', dpg.add_slider_float(label="DBSCAN epsilon", default_value=self.get_setting(f'lidar.eps', 0.3), max_value=1, callback=self.on_change)) self.register_setting(f'lidar.min_samples', dpg.add_slider_int(label="DBSCAN min_samples", default_value=self.get_setting(f'lidar.min_samples', 8), max_value=30, callback=self.on_change)) - self.register_setting(f'lidar.min_box_area', dpg.add_slider_float(label="DBSCAN min_samples", default_value=self.get_setting(f'lidar.min_box_area', .1), min_value=0, max_value=1, callback=self.on_change)) + dpg.add_text("When using BIRCH, the resulting subclusters can be postprocessed by DBSCAN:") + self.register_setting('lidar.birch_process_subclusters', dpg.add_checkbox(label="Process subclusters", default_value=self.get_setting('lidar.birch_process_subclusters', True), callback=self.on_change)) + self.register_setting('lidar.birch_threshold', dpg.add_slider_float(label="Threshold", default_value=self.get_setting('lidar.birch_threshold', 1), max_value=2.5, callback=self.on_change)) + self.register_setting('lidar.birch_branching_factor', dpg.add_slider_int(label="Branching factor", default_value=self.get_setting('lidar.birch_branching_factor', 50), max_value=100, callback=self.on_change)) + + dpg.add_separator(label="Cluster filter") + self.register_setting(f'lidar.min_box_area', dpg.add_slider_float(label="min_box_area", default_value=self.get_setting(f'lidar.min_box_area', .1), min_value=0, max_value=1, callback=self.on_change)) for lidar in ["192.168.0.16", "192.168.0.10"]: name = lidar.replace(".", "_") diff --git a/trap/stage.py b/trap/stage.py index a38c4b3..ce8b3af 100644 --- a/trap/stage.py +++ b/trap/stage.py @@ -22,7 +22,7 @@ import zmq from trap.anomaly import DiffSegment, calc_anomaly, calculate_loitering_scores from trap.base import CameraAction, DataclassJSONEncoder, Frame, HomographyAction, ProjectedTrack, Track from trap.counter import CounterSender -from trap.lines import AppendableLine, AppendableLineAnimator, Coordinate, CoordinateSpace, CropAnimationLine, CropLine, DashedLine, DeltaT, FadeOutJitterLine, FadeOutLine, FadedEndsLine, FadedTailLine, LineAnimationStack, LineAnimator, NoiseLine, RenderableLayers, RenderableLine, RenderableLines, RotatingLine, SegmentLine, SimplifyMethod, SrgbaColor, StaticLine, layers_to_message, load_lines_from_svg +from trap.lines import AppendableLine, AppendableLineAnimator, Coordinate, CoordinateSpace, CropAnimationLine, CropLine, DashedLine, DeltaT, FadeOutJitterLine, FadeOutLine, FadedEndsLine, FadedTailLine, LineAnimationStack, LineAnimator, NoiseLine, RenderableLayers, RenderableLine, RenderableLines, RotatingLine, SegmentLine, SimplifyLine, SimplifyMethod, SrgbaColor, StartFromClosestPoint, StaticLine, layers_to_message, load_lines_from_svg from trap.node import Node from trap.track_history import TrackHistory @@ -316,6 +316,7 @@ def build_line_others(): others_color = SrgbaColor(1,1,0,1) line_others = LineAnimationStack(StaticLine([], others_color)) # line_others.add(SegmentLine(line_others.tail, duration=3, anim_f=partial(SegmentLine.anim_grow, in_and_out=True, max_len=5))) + line_others.add(SimplifyLine(line_others.tail, 0.001)) # Simplify before effects, so they don't distort line_others.add(CropAnimationLine(line_others.tail, lambda dt: 10 + math.sin(dt/4) * 70, assume_fps=TRACK_ASSUMED_FPS*2)) # speed up line_others.add(NoiseLine(line_others.tail, amplitude=0, t_factor=.3)) # line_others.add(DashedLine(line_others.tail, t_factor=4, loop_offset=True)) @@ -332,7 +333,7 @@ class DrawnScenario(Scenario): This distinction is only for ordering the code """ - MAX_HISTORY = 200 # points of history of trajectory to display (preventing too long lines) + MAX_HISTORY = 130 # points of history of trajectory to display (preventing too long lines) CUT_GAP = 5 # when adding a new prediction, keep the existing prediction until that point + this CUT_GAP margin def __init__(self, track_id): @@ -343,9 +344,9 @@ class DrawnScenario(Scenario): history_color = SrgbaColor(1.,0.,1.,1.) history = StaticLine([], history_color) self.line_history = LineAnimationStack(history) - self.line_history.add(AppendableLineAnimator(self.line_history.tail, draw_decay_speed=25)) - + self.line_history.add(AppendableLineAnimator(self.line_history.tail, draw_decay_speed=120)) self.line_history.add(CropLine(self.line_history.tail, self.MAX_HISTORY)) + self.line_history.add(SimplifyLine(self.line_history.tail, 0.003)) # Simplify before effects, so they don't distort self.line_history.add(FadedTailLine(self.line_history.tail, TRACK_FADE_AFTER_DURATION * TRACK_ASSUMED_FPS, TRACK_END_FADE)) self.line_history.add(NoiseLine(self.line_history.tail, amplitude=0, t_factor=.3)) self.line_history.add(FadeOutJitterLine(self.line_history.tail, frequency=5, t_factor=.5)) @@ -353,10 +354,13 @@ class DrawnScenario(Scenario): self.prediction_color = SrgbaColor(0,1,0,1) self.line_prediction = LineAnimationStack(StaticLine([], self.prediction_color)) self.line_prediction.add(RotatingLine(self.line_prediction.tail, decay_speed=16)) - self.line_prediction.get(RotatingLine).skip = True + self.line_prediction.get(RotatingLine).skip = False self.line_prediction.add(SegmentLine(self.line_prediction.tail, duration=.5)) - self.line_prediction.add(DashedLine(self.line_prediction.tail, t_factor=4, loop_offset=True)) - self.line_prediction.get(DashedLine).skip = True + self.line_prediction.get(SegmentLine).skip = True + self.line_prediction.add(SimplifyLine(self.line_prediction.tail, 0.003)) # Simplify before effects, so they don't distort + self.line_prediction.add(DashedLine(self.line_prediction.tail, dash_len=.6, gap_len=0.9, t_factor=2, loop_offset=True)) + self.line_prediction.get(DashedLine).skip = False + self.line_prediction.add(StartFromClosestPoint(self.line_prediction.tail)) self.line_prediction.add(FadeOutLine(self.line_prediction.tail)) # when rendering tracks from others similar/close to the current one @@ -374,41 +378,55 @@ class DrawnScenario(Scenario): self.line_history.root.points = self.track.projected_history if len(self.prediction_tracks): + now_p = np.array(self.line_history.root.points[-1]) + prev_p = np.array(self.line_history.root.points[-1 * min(4, len(self.line_history.root.points))]) + diff = now_p - prev_p + self.line_prediction.get(StartFromClosestPoint).set_point(now_p + diff) + # print("set origin", self.line_history.root.points[-1]) + # TODO: only when animation is ready for it? or collect lines if not self.active_ptrack: + # draw the first prediction self.active_ptrack = self.prediction_tracks[-1] + self.line_prediction.root.points = self.active_ptrack._track.predictions[0] + self.line_prediction.start() # reset positions elif self.active_ptrack._track.updated_at < self.prediction_tracks[-1]._track.updated_at: + # stale prediction # switch only if drawing animation is ready - if self.line_prediction.is_ready(): + # if self.line_prediction.is_ready(): self.active_ptrack = self.prediction_tracks[-1] - self.line_prediction.get(SegmentLine).anim_f = partial(SegmentLine.anim_arrive, length=.3) - self.line_prediction.get(SegmentLine).duration = .5 - self.line_prediction.get(DashedLine).skip = True - # print('restart') + self.line_prediction.root.points = self.active_ptrack._track.predictions[0] + self.line_prediction.start() # reset positions - # print(self.line_prediction.get(SegmentLine).running_for()) - else: - if self.line_prediction.is_ready(): - # little hack: check is dashedline skips, to only run this once per animation: - if self.line_prediction.get(DashedLine).skip: - # no new yet, but ready with anim, start stage 2 - self.line_prediction.get(SegmentLine).anim_f = partial(SegmentLine.anim_grow) - self.line_prediction.get(SegmentLine).duration = 1 - # self.line_prediction.get(SegmentLine).skip = True - self.line_prediction.get(DashedLine).skip = False - self.line_prediction.start() - elif self.line_prediction.get(SegmentLine).duration != 2: # hack to only play once - self.line_prediction.get(SegmentLine).anim_f = partial(SegmentLine.anim_grow, reverse=True) - self.line_prediction.get(SegmentLine).duration = 2 - self.line_prediction.get(SegmentLine).start() + + # self.line_prediction.get(SegmentLine).anim_f = partial(SegmentLine.anim_arrive, length=.3) + # self.line_prediction.get(SegmentLine).duration = .5 + # self.line_prediction.get(DashedLine).skip = True + # # print('restart') + # self.line_prediction.start() # reset positions + # # print(self.line_prediction.get(SegmentLine).running_for()) + # else: + # if self.line_prediction.is_ready(): + # # little hack: check is dashedline skips, to only run this once per animation: + # if self.line_prediction.get(DashedLine).skip: + # # no new yet, but ready with anim, start stage 2 + # self.line_prediction.get(SegmentLine).anim_f = partial(SegmentLine.anim_grow) + # self.line_prediction.get(SegmentLine).duration = 1 + # # self.line_prediction.get(SegmentLine).skip = True + # self.line_prediction.get(DashedLine).skip = False + # self.line_prediction.start() + # elif self.line_prediction.get(SegmentLine).duration != 2: # hack to only play once + # self.line_prediction.get(SegmentLine).anim_f = partial(SegmentLine.anim_grow, reverse=True) + # self.line_prediction.get(SegmentLine).duration = 2 + # self.line_prediction.get(SegmentLine).start() # self.line_prediction_dashed.set_offset_t(self.active_ptrack._track.track_update_dt() * 4) - self.line_prediction.root.points = self.active_ptrack._track.predictions[0] + # special case: LOITERING @@ -428,8 +446,6 @@ class DrawnScenario(Scenario): # print(transition > .999, self.is_running, current_position_rounded, time_diff) if transition > .999 and self.is_running and not all(self.tracks_to_self_pos == current_position_rounded) and time_diff > 5: # only do these expensive calls when running - logger.info(f"Fetch similar tracks for {self.track_id}") - t = time.perf_counter() self.tracks_to_self_pos = current_position_rounded self.tracks_to_self_fetched_at = time.perf_counter() @@ -438,7 +454,7 @@ class DrawnScenario(Scenario): self.track_ids_to_self = iter(track_ids) self.tracks_to_self = stage.history.ids_as_trajectory(track_ids) - print(time.perf_counter() - t, "fetch delay") + stage.logger.info(f"Fetched similar tracks for {self.track_id}. (Took {time.perf_counter() - self.tracks_to_self_fetched_at}s)") # if self.tracks_to_self and not len(self.line_others.root.points): if self.tracks_to_self and not self.line_others.is_running(): @@ -479,9 +495,10 @@ class DrawnScenario(Scenario): # 1) history, fade out when lost # self.line_history.get(StaticLine).color = SrgbaColor(1, 0, 1-self.anomaly_factor(), 1) + self.line_history.get(FadeOutJitterLine).set_alpha(1-self.lost_factor()) self.line_prediction.get(FadeOutLine).set_alpha(1-self.lost_factor()) - self.line_history.get(NoiseLine).amplitude = self.lost_factor() + self.line_history.get(NoiseLine).amplitude = self.lost_factor() * 1.5 # fade out history after max duration, given in frames track_age_in_frames = self.track_age() * TRACK_ASSUMED_FPS @@ -559,12 +576,16 @@ class DatasetDrawer(): line_color = SrgbaColor(0,1,1,1) self.track_line = LineAnimationStack(StaticLine([], line_color)) - self.track_line.add(CropAnimationLine(self.track_line.tail, 100, assume_fps=TRACK_ASSUMED_FPS*30)) # speed up + self.track_line.add(SimplifyLine(self.track_line.tail, 0.003)) # Simplify before cropping, to get less noodling + self.track_line.add(CropAnimationLine(self.track_line.tail, 50, assume_fps=TRACK_ASSUMED_FPS*20)) # speed up + # self.track_line.add(DashedLine(self.track_line.tail, t_factor=4, loop_offset=True)) # self.track_line.get(DashedLine).skip = True - self.track_line.add(FadedEndsLine(self.track_line.tail, 10, 10)) + # self.track_line.add(FadedEndsLine(self.track_line.tail, 10, 10)) + self.track_line.add(FadeOutJitterLine(self.track_line.tail, t_factor=3)) # self.track_line.add(FadeOutLine(self.track_line.tail)) - # self.track_line.get(FadeOutLine).set_alpha(1) + self.track_line.get(FadeOutJitterLine).set_alpha(np.random.random()*.3+.7) + def to_renderable_lines(self, dt: DeltaT): lines = RenderableLines([], CoordinateSpace.WORLD) @@ -587,12 +608,12 @@ class DatasetDrawer(): class Stage(Node): - FPS = 60 + FALLBACK_FPS = 30 # we render to lasers, no need to go faster! def setup(self): self.active_scenarios: List[DrawnScenario] = [] # List of currently running Scenario instances - + self.scenarios: Dict[str, DrawnScenario] = DefaultDictKeyed(lambda key: DrawnScenario(key)) self.frame_noimg_sock = self.sub(self.config.zmq_frame_noimg_addr) self.trajectory_sock = self.sub(self.config.zmq_trajectory_addr) @@ -616,8 +637,8 @@ class Stage(Node): def run(self): - while self.run_loop_capped_fps(self.FPS, warn_below_fps=10): - dt = max(1/ self.FPS, self.dt_since_last_tick) # never dt of 0 + while self.run_loop_capped_fps(self.get_setting('stage.fps', self.FALLBACK_FPS), warn_below_fps=10): + dt = max(1/ self.get_setting('stage.fps', self.FALLBACK_FPS), self.dt_since_last_tick) # never dt of 0 # t1 = time.perf_counter() self.loop_receive() @@ -720,18 +741,18 @@ class Stage(Node): lines = training_lines t2b = time.perf_counter() - rl_scenario = lines.as_simplified(SimplifyMethod.RDP, .003) # or segmentise (see shapely) - rl_training = training_lines.as_simplified(SimplifyMethod.RDP, .003) # or segmentise (see shapely) + # rl_scenario = lines.as_simplified(SimplifyMethod.RDP, .003) # or segmentise (see shapely) + # rl_training = training_lines.as_simplified(SimplifyMethod.RDP, .003) # or segmentise (see shapely) self.counter.set("stage.lines", len(lines.lines)) - self.counter.set("stage.points_orig", lines.point_count()) - self.counter.set("stage.points", rl_scenario.point_count()) + # self.counter.set("stage.points_orig", lines.point_count()) + self.counter.set("stage.points", lines.point_count()) t3 = time.perf_counter() layers: RenderableLayers = { - 1: rl_scenario, + 1: lines, 2: self.debug_lines, - 3: rl_training, + 3: training_lines, } t4 = time.perf_counter() @@ -784,7 +805,7 @@ class Stage(Node): argparser.add_argument('--debug-map', help='specify a map (svg-file) from which to load lines which will be overlayed', type=str, - default="../DATASETS/hof3/map_hof.svg") + default="../DATASETS/hof-lidar/map_hof.svg") argparser.add_argument('--max-active-scenarios', help='Maximum number of active scenarios that can be drawn at once (to not overlod the laser)', type=int, diff --git a/trap/tools.py b/trap/tools.py index 71c6471..9bdd65d 100644 --- a/trap/tools.py +++ b/trap/tools.py @@ -330,6 +330,7 @@ def track_predictions_to_lines(track: Track, camera:Camera, anim_position=.8): return current_point = track.get_projected_history(camera=camera)[-1] + slide_t = min(1, max(0, inv_lerp(0, 0.8, anim_position))) # slide_position lines = [] @@ -371,6 +372,7 @@ def draw_track_predictions(img: cv2.Mat, track: Track, color_index: int, camera: """ lines = track_predictions_to_lines(track, camera, anim_position) + if not lines: return diff --git a/trap/tracker.py b/trap/tracker.py index 915648c..977e6f5 100644 --- a/trap/tracker.py +++ b/trap/tracker.py @@ -1,3 +1,4 @@ +from abc import ABC, abstractmethod import argparse import csv import json @@ -776,7 +777,54 @@ def run(): is_running.clear() -class Smoother: +class TrackPointFilter(ABC): + @abstractmethod + def apply(self, points: List[float]): + pass + + + def apply_track(self, track: Track) -> Track: + ls = [d.l for d in track.history] + ts = [d.t for d in track.history] + ws = [d.w for d in track.history] + hs = [d.h for d in track.history] + ls = self.apply(ls) + ts = self.apply(ts) + ws = self.apply(ws) + hs = self.apply(hs) + new_history = [Detection(d.track_id, l, t, w, h, d.conf, d.state, d.frame_nr, d.det_class) for l, t, w, h, d in zip(ls,ts,ws,hs, track.history)] + return track.get_with_new_history(new_history) + + def apply_to_frame_tracks(self, frame: Frame) -> Frame: + new_tracks = [] + for track in frame.tracks.values(): + new_track = self.apply_track(track) + new_tracks.append(new_track) + frame.tracks = {t.track_id: t for t in new_tracks} + return frame + + def apply_to_frame_predictions(self, frame: Frame) -> Frame: + + for track in frame.tracks.values(): + new_predictions = [] + if not track.predictions: + continue + + for prediction in track.predictions: + xs = [d[0] for d in prediction] + ys = [d[1] for d in prediction] + + xs = self.apply(xs) + ys = self.apply(ys) + + filtered_prediction = [[x,y] for x, y in zip(xs, ys)] + + new_predictions.append(filtered_prediction) + track.predictions = new_predictions + + return frame + +class Smoother(TrackPointFilter): def __init__(self, window_len=6, convolution=False): # for some reason this smoother messes the predictions. Probably skews the points too much?? @@ -789,54 +837,45 @@ class Smoother: - def smooth(self, points: List[float]): + + def apply(self, points: List[float]): self.smoother.smooth(points) return self.smoother.smooth_data[0] + + # aliases, for historic reasons + def smooth(self, points: List[float]): + return self.apply(points) + def smooth_track(self, track: Track) -> Track: - ls = [d.l for d in track.history] - ts = [d.t for d in track.history] - ws = [d.w for d in track.history] - hs = [d.h for d in track.history] - self.smoother.smooth(ls) - ls = self.smoother.smooth_data[0] - self.smoother.smooth(ts) - ts = self.smoother.smooth_data[0] - self.smoother.smooth(ws) - ws = self.smoother.smooth_data[0] - self.smoother.smooth(hs) - hs = self.smoother.smooth_data[0] - new_history = [Detection(d.track_id, l, t, w, h, d.conf, d.state, d.frame_nr, d.det_class) for l, t, w, h, d in zip(ls,ts,ws,hs, track.history)] - return track.get_with_new_history(new_history) - # return Track(track.track_id, new_history, track.predictor_history, track.predictions, track.fps) + return self.apply_track(track) def smooth_frame_tracks(self, frame: Frame) -> Frame: - new_tracks = [] - for track in frame.tracks.values(): - new_track = self.smooth_track(track) - new_tracks.append(new_track) - frame.tracks = {t.track_id: t for t in new_tracks} - return frame + return self.apply_to_frame_tracks(frame) def smooth_frame_predictions(self, frame: Frame) -> Frame: + return self.apply_to_frame_predictions(frame) + +class Noiser(TrackPointFilter): + + def __init__(self, amplitude=.1): + self.amplitude = amplitude + + + def apply(self, points: List[float]): + return np.random.normal(points, scale=self.amplitude).tolist() + + +class RandomOffset(TrackPointFilter): + """ + A bit hacky way to offset the whole track. Does x & y & w & h with the same value + """ + def __init__(self, amplitude=.1): + self.amplitude = np.random.normal(scale=amplitude) - for track in frame.tracks.values(): - new_predictions = [] - if not track.predictions: - continue - - for prediction in track.predictions: - xs = [d[0] for d in prediction] - ys = [d[1] for d in prediction] - - self.smoother.smooth(xs) - xs = self.smoother.smooth_data[0] - self.smoother.smooth(ys) - ys = self.smoother.smooth_data[0] - - smooth_prediction = [[x,y] for x, y in zip(xs, ys)] - - new_predictions.append(smooth_prediction) - track.predictions = new_predictions - - return frame \ No newline at end of file + + + def apply(self, points: List[float]): + return [p + self.amplitude for p in points] + + \ No newline at end of file diff --git a/trap/utils.py b/trap/utils.py index 655cea6..b0d45f0 100644 --- a/trap/utils.py +++ b/trap/utils.py @@ -158,7 +158,7 @@ class ImageMap(GeometricMap): # TODO Implement for image maps -> watch flipped """ Use homography and image to calculate the limits of positions in world coordinates """ - print(self.data.shape) + # print(self.data.shape) max_x = self.data.shape[1] max_y = self.data.shape[2]