Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
localization_manager::LocalizationManagerConfig Struct Reference

Struct to store the configuration settings for the LocalizationManager class. More...

#include <LocalizationManagerConfig.hpp>

Collaboration diagram for localization_manager::LocalizationManagerConfig:
Collaboration graph

Public Attributes

double fitness_score_degraded_threshold = 20.0
 NDT Fitness score above which the localization is considered in a degraded state. More...
 
double fitness_score_fault_threshold = 10000.0
 
double ndt_frequency_degraded_threshold = 8.0
 NDT solution frequency below which the localization is considered in a degraded state. More...
 
double ndt_frequency_fault_threshold = 0.66
 
int auto_initialization_timeout = 30000
 
int gnss_only_operation_timeout = 20000
 Timeout in ms for GNSS only operation. Ignored when in GNSS mode. More...
 
int sequential_timesteps_until_gps_operation = 5
 
int gnss_data_timeout = 500
 GNSS Data timeout. If exceeded the system will assume the GNSS is no longer functional. Units are ms. More...
 
int localization_mode = static_cast<int>(LocalizerMode::AUTO_WITHOUT_TIMEOUT)
 Localization mode to use. More...
 
double pose_pub_rate = 10.0
 Selected pose publication rate. More...
 
double x_offset = 2.8
 GPS Offset to apply if that mode is enabled. More...
 
double y_offset = -2.1
 
double z_offset = 0.0
 

Friends

std::ostream & operator<< (std::ostream &output, const LocalizationManagerConfig &c)
 

Detailed Description

Struct to store the configuration settings for the LocalizationManager class.

Definition at line 24 of file LocalizationManagerConfig.hpp.

Friends And Related Function Documentation

◆ operator<<

std::ostream & operator<< ( std::ostream &  output,
const LocalizationManagerConfig c 
)
friend

Definition at line 57 of file LocalizationManagerConfig.hpp.

58 {
59 output << "localization_manager::Config { " << std::endl
60 << "fitness_score_degraded_threshold: " << c.fitness_score_degraded_threshold << std::endl
61 << "fitness_score_fault_threshold: " << c.fitness_score_fault_threshold << std::endl
62 << "ndt_frequency_degraded_threshold: " << c.ndt_frequency_degraded_threshold << std::endl
63 << "ndt_frequency_fault_threshold: " << c.ndt_frequency_fault_threshold << std::endl
64 << "auto_initialization_timeout: " << c.auto_initialization_timeout << std::endl
65 << "gnss_only_operation_timeout: " << c.gnss_only_operation_timeout << std::endl
66 << "sequential_timesteps_until_gps_operation: " << c.sequential_timesteps_until_gps_operation << std::endl
67 << "gnss_data_timeout: " << c.gnss_data_timeout << std::endl
68 << "localization_mode: " << static_cast<LocalizerMode>(c.localization_mode) << std::endl
69 << "pose_pub_rate: " << c.pose_pub_rate << std::endl
70 << "x_offset: " << c.x_offset << std::endl
71 << "y_offset: " << c.y_offset << std::endl
72 << "z_offset: " << c.z_offset << std::endl
73 << "}" << std::endl;
74 return output;
75 }
LocalizerMode
Enum describing the possible operational modes of the LocalizationManager.

Member Data Documentation

◆ auto_initialization_timeout

int localization_manager::LocalizationManagerConfig::auto_initialization_timeout = 30000

Timeout in ms for auto initialization. If initialization cannot be completed in this time user action will be requested.

Definition at line 38 of file LocalizationManagerConfig.hpp.

Referenced by localization_manager::Node::Node(), localization_manager::Node::handle_on_configure(), localization_manager::Node::parameter_update_callback(), and localization_manager::LocalizationManager::stateTransitionCallback().

◆ fitness_score_degraded_threshold

double localization_manager::LocalizationManagerConfig::fitness_score_degraded_threshold = 20.0

◆ fitness_score_fault_threshold

double localization_manager::LocalizationManagerConfig::fitness_score_fault_threshold = 10000.0

NDT Fitness score above which the localization is considered in a fault state and NDT matching can no longer be used.

Definition at line 30 of file LocalizationManagerConfig.hpp.

Referenced by localization_manager::Node::Node(), localization_manager::Node::handle_on_configure(), localization_manager::Node::parameter_update_callback(), and localization_manager::LocalizationManager::poseAndStatsCallback().

◆ gnss_data_timeout

int localization_manager::LocalizationManagerConfig::gnss_data_timeout = 500

GNSS Data timeout. If exceeded the system will assume the GNSS is no longer functional. Units are ms.

Definition at line 45 of file LocalizationManagerConfig.hpp.

Referenced by localization_manager::Node::Node(), localization_manager::Node::handle_on_configure(), localization_manager::Node::parameter_update_callback(), and localization_manager::LocalizationManager::posePubTick().

◆ gnss_only_operation_timeout

int localization_manager::LocalizationManagerConfig::gnss_only_operation_timeout = 20000

◆ localization_mode

int localization_manager::LocalizationManagerConfig::localization_mode = static_cast<int>(LocalizerMode::AUTO_WITHOUT_TIMEOUT)

◆ ndt_frequency_degraded_threshold

double localization_manager::LocalizationManagerConfig::ndt_frequency_degraded_threshold = 8.0

◆ ndt_frequency_fault_threshold

double localization_manager::LocalizationManagerConfig::ndt_frequency_fault_threshold = 0.66

◆ pose_pub_rate

double localization_manager::LocalizationManagerConfig::pose_pub_rate = 10.0

◆ sequential_timesteps_until_gps_operation

int localization_manager::LocalizationManagerConfig::sequential_timesteps_until_gps_operation = 5

Integer: Maximum allowed number of sequential timesteps to let lidar initialize before switching to GPS only mode NOTE: Only used in GNSS only with NDT initialization mode

Definition at line 43 of file LocalizationManagerConfig.hpp.

Referenced by localization_manager::Node::Node(), localization_manager::Node::handle_on_configure(), localization_manager::Node::parameter_update_callback(), and localization_manager::LocalizationManager::poseAndStatsCallback().

◆ x_offset

double localization_manager::LocalizationManagerConfig::x_offset = 2.8

◆ y_offset

◆ z_offset


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