trackerGridRFS
Description
The trackerGridRFS
System object™ is a tracker capable of processing detections of multiple targets from multiple
sensors in a 2-D environment. The tracker tracks dynamic objects around an autonomous system
using high resolution sensor data such as point clouds and radar detections. The tracker uses
the random finite set (RFS) based approach combined with Dempster-Shafer approximations
defined in [1] to estimate the dynamic
characteristics of the grid cells. To extract objects from the grid, the tracker uses a
cell-to-track association scheme [2]. For more details, see
Algorithms.
To track targets using this object:
Create the
trackerGridRFS
object and set its properties.Call the object with arguments, as if it were a function.
To learn more about how System objects work, see What Are System Objects?
Creation
Description
creates a
tracker
= trackerGridRFStrackerGridRFS
System object with default property values.
sets properties for the tracker using one or more name-value pairs. For example,
tracker
= trackerGridRFS(Name,Value
)trackerGridRFS('MaxNumTracks',100)
creates a grid-based multi-object
tracker that allows a maximum of 100 tracks. Enclose each property name in quotes.
Properties
Unless otherwise indicated, properties are nontunable, which means you cannot change their
values after calling the object. Objects lock when you call them, and the
release
function unlocks them.
If a property is tunable, you can change its value at any time.
For more information on changing property values, see System Design in MATLAB Using System Objects.
Tracker ConfigurationTrackerIndex
— Unique tracker identifier
0
(default) | nonnegative integer
Unique tracker identifier, specified as a nonnegative integer. This property is used as the SourceIndex
in the tracker outputs, and distinguishes tracks that come from different trackers in a multiple-tracker system. You must specify this property as a positive integer to use the track outputs as inputs to a track fuser.
Example: 1
SensorConfigurations
— Configurations of tracking sensors
trackingSensorConfiguration
object | array of trackingSensorConfiguration
objects | cell array of trackingSensorConfiguration
objects | equivalent structure formats
Configuration of tracking sensors, specified as a trackingSensorConfiguration
objects, an array of
trackingSensorConfiguration
, or a cell array of array of
trackingSensorConfiguration
objects. This property provides the
tracking sensor configuration information, such as sensor detection limits, sensor
resolution, and sensor mounting, to the tracker. There are no default values for the
SensorConfigurations
property, and you must specify the
SensorConfigurations
property before using the tracker. You can
update the configuration, if the HasSensorConfigurationsInput
property is set to true
, by specifying the configuration input
argument configs
.
When specifying the trackingSensorConfiguration
object, the
following properties must be specified with these formats:
Property Name | Format |
---|---|
SensorIndex | Unique identifier of the sensor, specified as a positive integer. |
IsValidTime | Indicate if the sensor data should be used to update tracks,
specified as |
SensorTransformParameters | Parameters of sensor transform function, specified as a
p-element array of measurement parameter structures.
p is the number of sensors. The structure should
contain fields with the same names as the measurement parameters used in a
measurement function, such as the The first structure must describe the transformation from the autonomous system to the sensor coordinates. The subsequent structure describes the transformation from the autonomous system to the tracking coordinate frame. If only one structure is provided, the tracker assumes tracking is performed in the coordinate frame of the autonomous system. |
SensorLimits | Sensor detection limits, specified as a 2-by-2 matrix of scalars. The first row specifies the lower and upper limits of the azimuth angle in degrees. The second row specifies the lower and upper limits of the detection range in meters. |
The tracker ignores the FilterInitializationFcn
,
SensorTransformFcn
, and MaxNumDetsPerObject
properties of the trackingSensorConfiguration
object.
Alternately, you can specify this property using structures with fields names same as
the property names of the trackingSensorConfiguration
object.
HasSensorConfigurationsInput
— Enable updating sensor configurations with time
false
(default) | true
Enable updating sensor configurations with time, specified as
false
or true
. Set this property to
true
if you want the configurations of the sensors updated with
time. When this property is set to true
, you must specify the
configuration input configs
when using this object.
Data Types: logical
StateParameters
— Parameters of track state reference frame
struct([])
(default) | struct array
Parameters of the track state reference frame, specified as a structure or a structure
array. The tracker passes its StateParameters
property values to
the StateParameters
property of the generated tracks. You can use
these parameters to define the reference frame in which the track is reported or other
desirable attributes of the generated tracks.
For example, you can use the following structure to define a rectangular reference
frame whose origin position is at [10 10 0]
meters and whose origin
velocity is [2 -2 0] meters per second with respect to the scenario frame.
Field Name | Value |
---|---|
Frame | "Rectangular" |
Position | [10 10 0] |
Velocity | [2 -2 0] |
Tunable: Yes
Data Types: struct
MaxNumSensors
— Maximum number of sensors
20
(default) | positive integer
Maximum number of sensors that can be connected to the tracker, specified as a
positive integer. MaxNumSensors
must be greater than or equal to
the largest value of SensorIndex
found in all the sensor data and
configurations used to update the tracker.
Data Types: single
| double
MaxNumTracks
— Maximum number of tracks
100
(default) | positive integer
Maximum number of tracks that the tracker can maintain, specified as a positive integer.
Data Types: single
| double
GridLength
— x-direction dimension of grid
100
(default) | positive scalar
x-direction dimension of the grid in the local coordinates, specified as a positive scalar in meters.
GridWidth
— y-direction dimension of grid
100
(default) | positive scalar
y-direction dimension of the grid in the local coordinates, specified as a positive scalar in meters.
GridResolution
— Resolution of grid
1
(default) | positive scalar
Resolution of the grid, specified as a positive scalar.
GridResolution
represents the number of cells per meter of the
grid for both the x- and y-direction of the grid.
GridOriginInLocal
— Location of grid origin in local coordinate frame
[-50 -50]
(default) | two-element vector of scalar
Location of the grid origin in the local coordinate frame, specified as a two-element vector of scalars in meters. The grid origin represents the bottom-left corner of the grid.
MotionModel
— Motion model for tracking
'constant-velocity'
(default) | 'constant-acceleration'
| 'constant-turn-rate'
Motion model for tracking, specified as 'constant-velocity'
,
'constant-acceleration'
, or
'constant-turn-rate'
. The particle state and object state for each
motion model are:
MotionModel | Particle State | Object State |
---|---|---|
'constant-velocity' | [x; vx; y; vy] | [x; vx; y; vy; yaw; L; W] |
'constant-acceleration' | [x; vx; ax; y; vy; ay] | [x; vx; ax; y; vy; ay; yaw; L; W] |
'constant-turn-rate' | [x; vx; y; vy; w] | [x; vx; y; vy; w; yaw; L; W] |
where:
x
— Position of the object in the x direction of the local tracking frame (m)y
— Position of the object in the y direction of the local tracking frame (m)vx
— Velocity of the object in the x direction of the local tracking frame (m/s)vy
— Velocity of the object in the y direction of the local tracking frame (m/s)ax
— Acceleration of the object in the x direction of the local tracking frame (m/s2)ay
— Acceleration of the object in the y direction of the local tracking frame (m/s2)w
— Yaw-rate of the object in the local tracking frame (degree/s)yaw
— Yaw angle of the object in the local tracking frame (deg)L
— Length of the object (m)W
— Width of the object (m)
VelocityLimits
— Minimum and maximum velocity of objects
[-10 10; -10 10]
(default) | 2-by-2 matrix of scalar
Minimum and maximum velocity of objects, specified as a 2-by-2 matrix of scalars in m/s. The first row specifies the lower and upper velocity limits in the x-direction and the second row specifies the lower and upper velocity limits in the y-direction. The tracker uses these limits to sample new particles in the grid using a uniform distribution.
AccelerationLimits
— Minimum and maximum acceleration of objects
[-5 5; -5 5]
(default) | 2-by-2 matrix of scalar
Minimum and maximum acceleration of objects, specified as a 2-by-2 matrix of scalars in m/s2. The first row specifies the lower and upper acceleration limits in the x-direction and the second row specifies the lower and upper acceleration limits in the y-direction. The tracker uses these limits to sample new particles in the grid using a uniform distribution.
This property is only active when the MotionModel
property is
set to 'constant-acceleration'
.
TurnrateLimits
— Minimum and maximum turn rate of objects
[-5; 5]
(default) | two-element vector of scalar
Minimum and maximum turn rate of objects, specified a two-element vector of scalars in degree/s. The first element defines the minimum turn rate and the second element defines the maximum turn-rate.
This property is only active when the MotionModel
property is
set to 'constant-turnrate'
.
ProcessNoise
— Process noise covariance
N-by-N identity matrix (default) | N-by-N matrix of scalar
Process noise covariance, specified as an N-by-N matrix of scalars. This property specifies the process noise for positions of particles and the geometric centers of targets.
When the
HasAdditiveProcessNoise
property is set totrue
, the process directly adds to the prediction model. In this case, N is equal to the dimension of the particle state.When the
HasAdditiveProcessNoise
property is set tofalse
, define the process noise according to the selected motion model. The process noise is added to the higher order terms, such as the acceleration for the'constant-velocity'
model.MotionModel
Number of Terms for Acceleration Meaning of Terms 'constant-velocity'
2
Acceleration in the x and y directions 'constant-acceleration'
2
Jerk in the x and y directions 'constant-turn-rate'
3
Acceleration in the x and y directions as well as the angular acceleration
Example: [1.0 0.05; 0.05 2]
Tunable: Yes
HasAdditiveProcessNoise
— Enable to model process noise as additive
false
(default) | true
Enable to model process noise as additive, specified as true
or
false
. When this property is true
, process noise
is added directly to the state vector. Otherwise, noise is incorporated in the motion
model.
Example: true
NumParticles
— Number of particles per grid
10000
(default) | positive integer
Number of particles per grid, specified as a positive integer. A higher number of particles can improve estimation quality, but can increase computational cost.
NumBirthParticles
— Number of newborn particles per time step
1000
(default) | positive scalar
Number of newborn (initialized) particles per time step, specified as a positive
integer. The tracker determines the locations of these new-born particles by using the
mismatch between the predicted and the updated occupancy belief masses and the
BirthProbability
property. A reasonable value of the
NumBirthParticles
property is approximately ten percent of the
number of particles specified by the NumParticles
property.
BirthProbability
— Probability of target birth in a cell per step
0.01
(default) | scalar in [0 1)
Probability of target birth in a cell per step, specified as a scalar in the range
[0 1)
. The birth probability controls the
probability that new particles are generated in a cell.
Example: 1e-4
DeathRate
— Death rate of particles per unit time
1e-3
(default) | positive scalar
Death rate of particles per unit time, specified as a positive scalar. Death rate indicates the possibility that a particle or target vanishes after one time step. Death rate influences the survival probability (Ps) of a component between successive time steps as:
where ΔT is the time step.
Example: 1e-4
Tunable: Yes
FreeSpaceDiscountFactor
— Confidence in free space prediction
0.8
(default) | scalar
Confidence in free space prediction, specified as a scalar. In the prediction stage
of the tracker, the belief mass of a cell to be in the "free" (unoccupied) state is
reduced by the FreeSpaceDiscountFactor
:
where k is the time step index, m is the belief mass, α is the free space discount factor, and ΔT is the time step.
Tunable: Yes
Clustering
— Clustering method used for new object extraction
'DBSCAN'
(default) | 'Custom'
Clustering method used for new object extraction, specified as
'DBSCAN'
or 'Custom'
.
'DBSCAN'
— Cluster unassigned dynamic grid cells using the density-based spatial clustering of applications with noise (DBSCAN) algorithm. You can configure the DBSCAN algorithm by specifying theClusteringThreshold
andMinNumCellsPerCluster
properties of the tracker.'Custom'
— Cluster unassigned dynamic grid cells using a custom clustering function specified in theCustomClusteringFcn
property of the tracker.
ClusteringThreshold
— Threshold for DBSCAN clustering
5
(default) | positive scalar
Threshold for DBSCAN clustering, specified as a positive scalar.
To enable this property, set the Clustering
property to
'DBSCAN'
.
CustomClusteringFcn
— Custom function for clustering unassigned grid cells
function handle
Custom function for clustering unassigned grid cells, specified as a function handle. The function must support this signature:
function indices = myFunction(dynamicGridCells)
dynamicGridCells
is a structure defining a set of grid cells
initializing the track. It must have these fields:
Field | Description |
---|---|
Width | Width of the cell, specified as a positive scalar. |
GridIndices | Indices of the grid cells, specified as an N-by-2 array, where N is the number of unassigned cells. The first element specifies the grid index in the x-direction and the second element specifies the grid index in the y-direction. |
State | States of the grid cells, specified as a P-by-N array of scalars, where P is the dimension of the state and N is the number of unassigned cells. |
StateCovariance | State covariances of the grid cells, specified as a P-by-P-by-N array of scalars, where P is the dimension of the state and N is the number of unassigned cells. |
OccupancyMass | Occupancy belief mass of the cells, specified as an N-element vector, where N is the number of unassigned cells. |
FreeMass | Free belief mass of the cells, specified as an N-element vector, where N is the number of unassigned cells. |
indices
must be returned as an
N-element vector of indices defining the cluster index for each
dynamic grid cell.
To enable this property, set the Clustering
property to
'Custom'
.
MinNumCellsPerCluster
— Minimum number of cells per cluster for DBSCAN
2
(default) | positive integer
Minimum number of cells per cluster for DBSCAN, specified as a positive scalar. This property affects whether a point is a core point in the DBSCAN algorithm.
To enable this property, set the Clustering
property to
'DBSCAN'
.
TrackInitializationFcn
— Function to initialize new track
'trackerGridRFS.defaultTrackInitialization'
(default) | function handle
Function to initialize new tracks, specified as a function handle. The initialization function initiates a track from a set of dynamic grid cells.
The default initialization function merges the Gaussian estimate from each cell to describe the state of the object. The orientation of the object is aligned with the direction of its mean velocity. With a defined orientation, the length and width of the object are extracted using the geometric properties of the cells. The object calculates uncertainties in length, width, and orientation estimates using linear approximations.
If you choose to customize your own initialization function, the function must support the following signature:
function track = myFunction(dynamicGridCells)
dynamicGridCells
is a structure defining a set of grid cells
initializing the track. It has the following fields:
Field | Description |
---|---|
Width | Width of the cell, specified as a positive scalar. |
GridIndices | Indices of the grid cells, specified as an N-by-2 array, where N is the number of unassigned cells. The first element specifies the grid index in the x-direction and the second element specifies the grid index in the y-direction. |
State | States of the grid cells, specified as a P-by-N array of scalars, where P is the dimension of the state and N is the number of unassigned cells. |
StateCovariance | State covariances of the grid cells, specified as a P-by-P-by-N array of scalars, where P is the dimension of the state and N is the number of unassigned cells. |
OccupancyMass | Occupancy belief mass of the cells, specified as an N-element vector, where N is the number of unassigned cells. |
FreeMass | Free belief mass of the cells, specified as an N-element vector, where N is the number of unassigned cells. |
track
must be returned as an objectTrack
object or a structure
whose field names are the same as the property names of an objectTrack
object. The dimension
of the state must be the same as the state dimension specified in the
MotionModel
property.
TrackUpdateFcn
— Function to update existing track
'trackerGridRFS.defaultTrackUpdate'
(default) | function handle
Function to update an existing track using its associated set of dynamic grid cells, specified as a function handle.
The default update function updates the State
and
StateCovariance
properties of the track using the new estimate
from the dynamic grid cells associated with the track. The update process is similar to
the initialization process for the TrackInitializationFcn
property.
The tracker does not apply filtering to the state and state covariance.
If you choose to customize your own update function, the function must support this signature:
function updatedTrack = TrackUpdateFcn(predictedTrack,dynamicGridCells)
predictedTrack
is the predicted track of an object, specified as anobjectTrack
object.dynamicGridCells
is a structure defining a set of dynamic grid cells associated to the track. The structure has these fields:Field Description Width
Width of the cell, specified as a positive scalar. GridIndices
Indices of the grid cells, specified as an N-by-2 array, where N is the number of unassigned cells. The first element specifies the grid index in the x-direction and the second element specifies the grid index in the y-direction. State
States of the grid cells, specified as a P-by-N array of scalars, where P is the dimension of the state and N is the number of unassigned cells. StateCovariance
State covariances of the grid cells, specified as a P-by-P-by-N array of scalars, where P is the dimension of the state and N is the number of unassigned cells. OccupancyMass
Occupancy belief mass of the cells, specified as an N-element array of scalars, where N is the number of unassigned cells. FreeMass
Free belief mass of the cells, specified as an N-element array of scalars, where N is the number of unassigned cells. updatedTrack
is the updated track, returned as anobjectTrack
object or a structure whose field names are the same as the property names of anobjectTrack
object.
AssignmentThreshold
— Threshold for assigning dynamic grid cells to tracks
30
(default) | positive scalar
Threshold for assigning dynamic grid cells to tracks, specified as a positive
scalar. A dynamic grid cell can only be associated to a track if its distance
(represented by the negative log-likelihood) to the track is less than the
AssignmentThreshold
value.
Increase the threshold if a dynamic cell is not being assigned to a track that it should be assigned to.
Decrease the threshold if there are dynamic cells being assigned to a track that they should be not assigned to.
Example: 18.1
ConfirmationThreshold
— Threshold for track confirmation
[2 3]
(default) | real-valued 1-by-2 vector of positive integers
Threshold for track confirmation, specified as a real-valued 1-by-2 vector of
positive integers [M N]
. A track is confirmed if it has been assigned
to any dynamic grid cell in at least M
updates of the last
N
updates.
DeletionThreshold
— Threshold for track deletion
[5 5]
(default) | real-valued 1-by-2 vector of positive integers
Threshold for track deletion, specified as a real-valued 1-by-2 vector of positive
integers [P R]
. A track is deleted if has not been assigned to any
dynamic grid cell in at least P
updates of the last
R
updates.
Example: 0.01
Data Types: single
| double
NumTracks
— Number of tracks maintained by tracker
nonnegative integer
This property is read-only.
Number of tracks maintained by the tracker, returned as a nonnegative integer.
Data Types: double
NumConfirmedTracks
— Number of confirmed tracks
nonnegative integer
This property is read-only.
Number of confirmed tracks, returned as a nonnegative integer. If the
IsConfirmed
property of an output track object is
true
, the track is confirmed.
Data Types: double
UseGPU
— Enable using GPU for estimation of dynamic grid map
false
(default) | true
Enable using GPU for estimation of the dynamic grid map, specified as
true
or false
. Enabling GPU computation requires
the Parallel Computing Toolbox™.
Usage
Syntax
Description
returns a list of confirmed tracks that are updated from a list of sensor data
confirmedTracks
= tracker(sensorData
,time
)sensorData
at the update time time
. Confirmed
tracks are corrected and predicted to the update time.
also specifies the configurations of sensors confirmedTracks
= tracker(sensorData
,configs
,time
)configs
. To enable this
syntax, set the HasSensorConfigurationsInput
property to
true
.
[
also returns a list of tentative tracks confirmedTracks
,tentativeTracks
,allTracks
] = tracker(___)tentativeTracks
and a list of
all tracks allTracks
. You can use any combination of input arguments
from previous syntaxes.
[
additionally returns the evidential grid map maintained in the tracker. You can use the
returned map to obtain details on the estimates.confirmedTracks
,tentativeTracks
,allTracks
,map
] = tracker(___)
Input Arguments
sensorData
— Sensor data
N-element array of structure
Sensor data, specified as an N-element array of structures. Each structure must define the measurement from a high resolution sensor using the these fields:
Fields | Description |
---|---|
Time | Time at which the sensor reports the data, specified as a nonnegative scalar. |
SensorIndex | Unique identifier of the sensor, specified as a positive integer. |
Measurement | Measurements of the sensor, specified a K-by-M matrix of scalars. K is the dimension of measurements, and M is the number of measurements. Each measurement defines the positional aspects of the detection in a rectangular or spherical frame. |
MeasurementParameters | Measurement parameters, specified as a structure describing the transformation from the particle state to measurement. See Object Detections for more details. |
The Time
value must be less than or equal to the current update
time, time
, and greater than the previous time value used to
update the tracker.
time
— Time of update
scalar
Time of update, specified as a scalar. The tracker updates all tracks to this time. Units are in seconds.
time
must be greater than or equal to the largest
Time
field value of the sensorData
structures. time
must increase in value with each update to the
tracker.
Data Types: single
| double
configs
— Sensor configurations
array of structures | cell array of structures | cell array of trackingSensorConfiguration
objects
Sensor configurations, specified as an array of structures, a cell array of
structures, or a cell array of trackingSensorConfiguration
objects. If you specify the value using an
array of structures or a cell array of structures, you must include
SensorIndex
as a field in each structure. Other fields are
optional, but each field in a structure must have the same names as the
trackingSensorConfiguration
object properties. You only need to
specify sensor configurations that need to be updated. For example, if you want to
update the IsValidTime
property for only the fifth sensor,
specify configs
as
struct('SensorIndex',5,'IsValidTime',false)
.
Tip
If you have a fusionRadarSensor
sensor object in the tracking system, you can directly
use the configuration structure output of the sensor object as this input.
Dependencies
To enable this argument, set the
HasSensorConfigurationsInput
property to
true
.
Output Arguments
confirmedTracks
— Confirmed tracks
array of objectTrack
objects
Confirmed tracks updated to the current time, returned as an array of objectTrack
objects, where each
element represents the track of an object. The state form of each track follows the
form specified in the MotionModel
property.
tentativeTracks
— Tentative tracks
array of objectTrack
objects
Tentative tracks, returned as an array of objectTrack
objects, where each
element represents the track of an object. The state form of each track follows the
form specified in the MotionModel
property.
allTracks
— All tracks
structure | array of objects
All tracks, returned as an array of objectTrack
objects, where each
element represents the track of an object. The state form of each track follows the
form specified in the MotionModel
property.
map
— Dynamic evidential grid map
dynamicEvidentialGridMap
object
Dynamic evidential grid map, returned as a dynamicEvidentialGridMap
object.
Object Functions
To use an object function, specify the
System object as the first input argument. For
example, to release system resources of a System object named obj
, use
this syntax:
release(obj)
Specific to trackerGridRFS
predictTracksToTime | Predict track state |
predictMapToTime | Predict dynamic map to a time stamp |
showDynamicMap | Plot dynamic occupancy grid map |
Examples
Track Targets Using Grid-Based Tracker
Create a tracking scenario.
scene = trackingScenario('UpdateRate',5,'StopTime',5); rng(2021); % For reproducible results
Add a platform with a mounted lidar sensor to the tracking scenario.
plat = platform(scene); lidar = monostaticLidarSensor(1,'DetectionCoordinates','Body','HasOrganizedOutput',false);
Add two targets with random positions and velocities to the scenario. Also, define the trajectory, mesh, and dimension of each platform.
for i = 1:2 target = platform(scene); x = 50*(2*rand - 1); y = 50*(2*rand - 1); vx = 5*(2*rand - 1); vy = 5*(2*rand - 1); target.Trajectory.Position = [x y 0]; target.Trajectory.Velocity = [vx vy 0]; % Align the orientation of the target with the direction of motion. target.Trajectory.Orientation = quaternion([atan2d(vy,vx),0,0],'eulerd','ZYX','frame'); target.Mesh = extendedObjectMesh('sphere'); target.Dimensions = struct('Length',4,'Width',4,'Height',2,'OriginOffset',[0 0 0]); end
Define the configuration of the lidar sensor.
config = trackingSensorConfiguration(1,... 'SensorLimits',[-180 180;0 100],... 'SensorTransformParameters',struct,... 'IsValidTime',true);
Create a grid-based tracker.
tracker = trackerGridRFS('SensorConfigurations',config,... 'AssignmentThreshold',5,... 'MinNumCellsPerCluster',4,... 'ClusteringThreshold',3);
Define a theaterPlot
object and two associated plotters for visualizing the tracking scene.
tp = theaterPlot('XLimits',[-50 50],'YLimits',[-50 50]); trkPlotter = trackPlotter(tp,'DisplayName','Tracks','MarkerFaceColor','g'); tthPlotter = platformPlotter(tp,'DisplayName','Truths','MarkerFaceColor','r','ExtentAlpha',0.2);
Advance the scenario and run the tracker with the lidar data.
while advance(scene) time = scene.SimulationTime; % Generate point cloud. tgtMeshes = targetMeshes(plat); [ptCloud, config] = lidar(tgtMeshes, time); % Format the data for the tracker. sensorData = struct('Time',time,... 'SensorIndex',1,... 'Measurement',ptCloud',... 'MeasurementParameters',struct... ); % Update the tracker using the sensor data. tracks = tracker(sensorData, time); % Visualize tracks. pos = zeros(numel(tracks),3); vel = zeros(numel(tracks),3); orient = quaternion.ones(numel(tracks),1); dim = repmat(plat.Dimensions,numel(tracks),1); ids = string([tracks.TrackID]); for i = 1:numel(tracks) vel(i,:) = [tracks(i).State(2);tracks(i).State(4);0]; pos(i,:) = [tracks(i).State(1);tracks(i).State(3);0]; dim(i).Length = tracks(i).State(6); dim(i).Width = tracks(i).State(7); orient(i) = quaternion([tracks(i).State(5) 0 0],'eulerd','ZYX','frame'); end trkPlotter.plotTrack(pos,dim,orient,ids); % Visualize platforms. pos = vertcat(tgtMeshes.Position); meshes = vertcat(tgtMeshes.Mesh); orient = vertcat(tgtMeshes.Orientation); tthPlotter.plotPlatform(pos,meshes,orient); end
Algorithms
Tracker Logic Flow
The trackerGridRFS
system object initializes, confirms, and deletes tracks
automatically by using this algorithm:
The tracker projects sensor data from all sensors on a two-dimensional grid map to represent the occupancy and free evidence in a Dempster-Shafer framework.
The tracker uses a particle-based approach to estimate the dynamic state of the 2-D grid. This helps the tracker to classify each cell as dynamic or static.
The tracker manage tracks based on this logic:
The tracker associates each dynamic grid cell with the existing tracks using a gated nearest-neighbor approach.
The tracker initializes new tracks using unassigned dynamic grid cells. A track is created with a
Tentative
status, and the status will change toConfirmed
after enough updates. For more information, see theConfirmationThreshold
property.Alternatively, the tracker confirms a track immediately if the
ObjectClassID
of the track is set to a positive value after track initialization. For more information, see theTrackInitializationFcn
property.The tracker performs coasting, predicting unassigned tracks to the current time, and deletes tracks with more misses than allowed. For more information, see the
DeletionThreshold
property.
References
[1] Nuss, D., Reuter, S., Thom, M., Yuan, T., Krehl, G., Maile, M., Gern, A. and Dietmayer, K., 2018. A random finite set approach for dynamic occupancy grid maps with real-time application. The International Journal of Robotics Research, 37(8), pp.841-866.
[2] Steyer, Sascha, Georg Tanzmeister, and Dirk Wollherr. "Object tracking based on evidential dynamic occupancy grids in urban environments." In 2017 IEEE Intelligent Vehicles Symposium (IV), pp. 1064-1070. IEEE, 2017.
Extended Capabilities
C/C++ Code Generation
Generate C and C++ code using MATLAB® Coder™.
Version History
Introduced in R2020b
See Also
MATLAB Command
You clicked a link that corresponds to this MATLAB command:
Run the command by entering it in the MATLAB Command Window. Web browsers do not support MATLAB commands.
Select a Web Site
Choose a web site to get translated content where available and see local events and offers. Based on your location, we recommend that you select: .
You can also select a web site from the following list
How to Get Best Site Performance
Select the China site (in Chinese or English) for best site performance. Other MathWorks country sites are not optimized for visits from your location.
Americas
- América Latina (Español)
- Canada (English)
- United States (English)
Europe
- Belgium (English)
- Denmark (English)
- Deutschland (Deutsch)
- España (Español)
- Finland (English)
- France (Français)
- Ireland (English)
- Italia (Italiano)
- Luxembourg (English)
- Netherlands (English)
- Norway (English)
- Österreich (Deutsch)
- Portugal (English)
- Sweden (English)
- Switzerland
- United Kingdom (English)
Asia Pacific
- Australia (English)
- India (English)
- New Zealand (English)
- 中国
- 日本Japanese (日本語)
- 한국Korean (한국어)