Echoflow  1.0.0
A ROS2 Toolset for tracking marine radar targets
Loading...
Searching...
No Matches
echoflow::ParticleFilterNode::Parameters Struct Reference

All configurable parameters for the particle filter node. More...

#include <particle_filter_node.hpp>

Public Member Functions

void declare (rclcpp::Node *node)
 Declares all node parameters.
 
void update (rclcpp::Node *node)
 Updates all node parameters.
 

Public Attributes

struct { 
 
   int   num_particles = 100000 
 Total number of particles used in the filter. More...
 
   double   update_interval = 0.2 
 Time (in seconds) between particle weight updates. More...
 
   double   initial_max_speed = 20.0 
 Maximum speed (m/s) assigned to particles during initialization. More...
 
   double   observation_sigma = 50.0 
 Standard deviation (m) of the observation likelihood model. More...
 
   double   weight_decay_half_life = 3.0 
 Half-life (in seconds) for exponential decay of particle weights. More...
 
   double   seed_fraction = 0.001 
 Fraction of particles (per second) that are reseeded with random poses on each resample step. More...
 
   double   noise_std_position = 0.1 
 Standard deviation (m) of positional noise added during resampling. More...
 
   double   noise_std_yaw = 0.05 
 Standard deviation (radians) of yaw angle noise added during resampling. More...
 
   double   noise_std_yaw_rate = 0.0 
 Standard deviation (radians/sec) of yaw rate noise added during resampling. More...
 
   double   noise_std_speed = 0.2 
 Standard deviation (m/s) of speed noise added during resampling. More...
 
   double   maximum_target_size = 200.0 
 Maximum physical size (in meters) for a trackable target blob. More...
 
   double   density_feedback_factor = 0.8 
 Density (particles/m²) at which the weight of a particle will be reduced by half. More...
 
particle_filter 
 Parameters controlling the behavior of the particle filter.
 
struct { 
 
   std::string   frame_id = "map" 
 Coordinate frame in which the particle statistics map is published. More...
 
   double   length = 2500.0 
 Length (in meters) of the grid map. More...
 
   double   width = 2500.0 
 Width (in meters) of the grid map. More...
 
   double   resolution = 25.0 
 Resolution of each grid cell (in meters). More...
 
   double   pub_interval = 0.5 
 Time interval (in seconds) between publishing the statistics map. More...
 
particle_filter_statistics 
 Parameters defining the statistical grid map used for monitoring particle behavior.
 

Detailed Description

All configurable parameters for the particle filter node.

Member Function Documentation

◆ declare()

NS_HEAD void ParticleFilterNode::Parameters::declare ( rclcpp::Node * node)

Declares all node parameters.

Parameters
nodePointer to the ROS2 node for parameter declaration.

Copyright © 2025 Seaward Science.

◆ update()

void ParticleFilterNode::Parameters::update ( rclcpp::Node * node)

Updates all node parameters.

Parameters
nodePointer to the ROS2 node for parameter update.

Member Data Documentation

◆ density_feedback_factor

double echoflow::ParticleFilterNode::Parameters::density_feedback_factor = 0.8

Density (particles/m²) at which the weight of a particle will be reduced by half.

Lower this value if particles cluster too aggressively on single targets.

◆ frame_id

std::string echoflow::ParticleFilterNode::Parameters::frame_id = "map"

Coordinate frame in which the particle statistics map is published.

◆ initial_max_speed

double echoflow::ParticleFilterNode::Parameters::initial_max_speed = 20.0

Maximum speed (m/s) assigned to particles during initialization.

◆ length

double echoflow::ParticleFilterNode::Parameters::length = 2500.0

Length (in meters) of the grid map.

◆ maximum_target_size

double echoflow::ParticleFilterNode::Parameters::maximum_target_size = 200.0

Maximum physical size (in meters) for a trackable target blob.

Used to reduce computational load on large targets like shorelines.

◆ noise_std_position

double echoflow::ParticleFilterNode::Parameters::noise_std_position = 0.1

Standard deviation (m) of positional noise added during resampling.

◆ noise_std_speed

double echoflow::ParticleFilterNode::Parameters::noise_std_speed = 0.2

Standard deviation (m/s) of speed noise added during resampling.

◆ noise_std_yaw

double echoflow::ParticleFilterNode::Parameters::noise_std_yaw = 0.05

Standard deviation (radians) of yaw angle noise added during resampling.

◆ noise_std_yaw_rate

double echoflow::ParticleFilterNode::Parameters::noise_std_yaw_rate = 0.0

Standard deviation (radians/sec) of yaw rate noise added during resampling.

◆ num_particles

int echoflow::ParticleFilterNode::Parameters::num_particles = 100000

Total number of particles used in the filter.

◆ observation_sigma

double echoflow::ParticleFilterNode::Parameters::observation_sigma = 50.0

Standard deviation (m) of the observation likelihood model.

◆ [struct]

struct { ... } echoflow::ParticleFilterNode::Parameters::particle_filter

Parameters controlling the behavior of the particle filter.

◆ [struct]

struct { ... } echoflow::ParticleFilterNode::Parameters::particle_filter_statistics

Parameters defining the statistical grid map used for monitoring particle behavior.

◆ pub_interval

double echoflow::ParticleFilterNode::Parameters::pub_interval = 0.5

Time interval (in seconds) between publishing the statistics map.

◆ resolution

double echoflow::ParticleFilterNode::Parameters::resolution = 25.0

Resolution of each grid cell (in meters).

◆ seed_fraction

double echoflow::ParticleFilterNode::Parameters::seed_fraction = 0.001

Fraction of particles (per second) that are reseeded with random poses on each resample step.

Increase this value to more quickly lock on to newly detected targets.

◆ update_interval

double echoflow::ParticleFilterNode::Parameters::update_interval = 0.2

Time (in seconds) between particle weight updates.

◆ weight_decay_half_life

double echoflow::ParticleFilterNode::Parameters::weight_decay_half_life = 3.0

Half-life (in seconds) for exponential decay of particle weights.

Lower values cause weights to fade more quickly over time. This should generally be on the order of the radar sweep time.

◆ width

double echoflow::ParticleFilterNode::Parameters::width = 2500.0

Width (in meters) of the grid map.


The documentation for this struct was generated from the following files: