debug

package
v0.5.0 Latest Latest
Warning

This package is not in the latest version of its module.

Go to latest
Published: Mar 25, 2026 License: Apache-2.0 Imports: 0 Imported by: 0

Documentation

Overview

Package debug provides instrumentation for LiDAR tracking algorithms. The DebugCollector captures algorithm internals (association decisions, gating thresholds, Kalman residuals) for visualisation and tuning.

Index

Constants

This section is empty.

Variables

This section is empty.

Functions

This section is empty.

Types

type AssociationRecord

type AssociationRecord struct {
	ClusterID              int64   // Which cluster
	TrackID                string  // Which track
	MahalanobisDistSquared float32 // Distance metric
	Accepted               bool    // Whether association was accepted
}

AssociationRecord captures a single cluster-track pairing considered during association.

type DebugCollector

type DebugCollector struct {
	// contains filtered or unexported fields
}

DebugCollector accumulates debug artifacts during a single frame's processing. When enabled, it records tracking algorithm internals: which clusters were considered for association, gating decisions, Kalman filter innovations, etc.

The collector is stateful: call Record*() methods during processing, then Emit() at frame completion to extract the artifacts. Reset() before the next frame.

func NewDebugCollector

func NewDebugCollector() *DebugCollector

NewDebugCollector creates a collector that's initially disabled. Call SetEnabled(true) to begin collecting artifacts.

func (*DebugCollector) BeginFrame

func (c *DebugCollector) BeginFrame(frameID uint64)

BeginFrame initialises collection for a new frame. Must be called before any Record*() calls.

func (*DebugCollector) Emit

func (c *DebugCollector) Emit() *DebugFrame

Emit returns the accumulated debug frame and prepares for the next frame. Returns nil if collection is disabled or no frame was begun.

func (*DebugCollector) IsEnabled

func (c *DebugCollector) IsEnabled() bool

IsEnabled returns true if the collector is actively recording.

func (*DebugCollector) RecordAssociation

func (c *DebugCollector) RecordAssociation(clusterID int64, trackID string, distSquared float32, accepted bool)

RecordAssociation captures a cluster-track pairing evaluation. Called during the association stage for each candidate pair.

func (*DebugCollector) RecordGatingRegion

func (c *DebugCollector) RecordGatingRegion(trackID string, centerX, centerY, semiMajor, semiMinor, rotation float32)

RecordGatingRegion captures the Mahalanobis gating ellipse for a track. Called after computing the innovation covariance matrix.

func (*DebugCollector) RecordInnovation

func (c *DebugCollector) RecordInnovation(trackID string, predX, predY, measX, measY, residualMag float32)

RecordInnovation captures a Kalman filter innovation (measurement residual). Called during the update step after computing predicted vs. measured state.

func (*DebugCollector) RecordPrediction

func (c *DebugCollector) RecordPrediction(trackID string, x, y, vx, vy float32)

RecordPrediction captures a track's predicted state before measurement update. Called during the predict step for each active track.

func (*DebugCollector) Reset

func (c *DebugCollector) Reset()

Reset clears any pending artifacts without emitting them. Useful when aborting frame processing.

func (*DebugCollector) SetEnabled

func (c *DebugCollector) SetEnabled(enabled bool)

SetEnabled controls whether the collector records artifacts. When disabled, all Record*() calls are no-ops for zero overhead.

type DebugFrame

type DebugFrame struct {
	FrameID uint64

	// Association stage: which cluster-track pairs were evaluated
	AssociationCandidates []AssociationRecord

	// Gating stage: Mahalanobis distance thresholds for each track
	GatingRegions []GatingRegion

	// Kalman update: innovation vectors (measurement - prediction)
	Innovations []KalmanInnovation

	// Kalman predict: state predictions before measurement update
	StatePredictions []StatePrediction
}

DebugFrame contains all debug artifacts for a single frame. This structure is exported to the visualiser for overlay rendering.

type GatingRegion

type GatingRegion struct {
	TrackID     string
	CenterX     float32
	CenterY     float32
	SemiMajorM  float32 // Semi-major axis length (metres)
	SemiMinorM  float32 // Semi-minor axis length (metres)
	RotationRad float32 // Ellipse rotation (radians)
}

GatingRegion represents a Mahalanobis distance threshold ellipse around a track. Used to visualise the association search region.

type KalmanInnovation

type KalmanInnovation struct {
	TrackID     string
	PredictedX  float32 // Predicted position before measurement
	PredictedY  float32
	MeasuredX   float32 // Actual measurement
	MeasuredY   float32
	ResidualMag float32 // ||measured - predicted||
}

KalmanInnovation represents a measurement residual in the Kalman update step.

type StatePrediction

type StatePrediction struct {
	TrackID string
	X       float32 // Predicted X
	Y       float32 // Predicted Y
	VX      float32 // Predicted VX
	VY      float32 // Predicted VY
}

StatePrediction represents a track's predicted state after the predict step but before the update step. Useful for debugging motion models.

Jump to

Keyboard shortcuts

? : This menu
/ : Search site
f or F : Jump to
y or Y : Canonical URL