![]() |
Echoflow
1.0.0
A ROS2 Toolset for tracking marine radar targets
|
Node that uses a particle filter to track targets in a 2D grid map of marine radar data. More...
#include <particle_filter_node.hpp>
Classes | |
struct | Parameters |
All configurable parameters for the particle filter node. More... | |
Public Member Functions | |
ParticleFilterNode () | |
Construct a new Particle Filter Node object. | |
Public Attributes | |
std::shared_ptr< grid_map::GridMap > | map_ptr_ |
Shared pointer to the underlying grid map of radar intensity & EDT layers. | |
Protected Attributes | |
Parameters | parameters_ |
Runtime parameters. | |
Node that uses a particle filter to track targets in a 2D grid map of marine radar data.
This node shares a pointer to a grid map with the radar_grid_map_node and spawns particles on areas of the map with valid radar returns in order to track the position and course of moving radar targets.
The node publishes a pointcloud of particles and a grid map with aggregated statistics on the particles (number of particles per cell, mean and standard deviation of particle age, x-position, y-position, course and velocity).
ParticleFilterNode::ParticleFilterNode | ( | ) |
Construct a new Particle Filter Node object.
Also creates grid map to compute and publish the following particle filter statistics for each cell:
std::shared_ptr<grid_map::GridMap> echoflow::ParticleFilterNode::map_ptr_ |
Shared pointer to the underlying grid map of radar intensity & EDT layers.
|
protected |
Runtime parameters.