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.
|
Struct to store the configuration settings for the LocalizationManager class. More...
#include <LocalizationManagerConfig.hpp>
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) |
Struct to store the configuration settings for the LocalizationManager class.
Definition at line 24 of file LocalizationManagerConfig.hpp.
|
friend |
Definition at line 57 of file LocalizationManagerConfig.hpp.
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().
double localization_manager::LocalizationManagerConfig::fitness_score_degraded_threshold = 20.0 |
NDT Fitness score above which the localization is considered in a degraded state.
Definition at line 27 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().
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().
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().
int localization_manager::LocalizationManagerConfig::gnss_only_operation_timeout = 20000 |
Timeout in ms for GNSS only operation. Ignored when in GNSS mode.
Definition at line 40 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().
int localization_manager::LocalizationManagerConfig::localization_mode = static_cast<int>(LocalizerMode::AUTO_WITHOUT_TIMEOUT) |
Localization mode to use.
Definition at line 47 of file LocalizationManagerConfig.hpp.
Referenced by localization_manager::Node::Node(), localization_manager::Node::handle_on_configure(), localization_manager::LocalizationManager::poseAndStatsCallback(), and localization_manager::LocalizationManager::posePubTick().
double localization_manager::LocalizationManagerConfig::ndt_frequency_degraded_threshold = 8.0 |
NDT solution frequency below which the localization is considered in a degraded state.
Definition at line 32 of file LocalizationManagerConfig.hpp.
Referenced by localization_manager::Node::Node(), localization_manager::LocalizationManager::computeNDTFreq(), localization_manager::Node::handle_on_configure(), localization_manager::Node::parameter_update_callback(), localization_manager::LocalizationManager::poseAndStatsCallback(), and localization_manager::LocalizationManager::posePubTick().
double localization_manager::LocalizationManagerConfig::ndt_frequency_fault_threshold = 0.66 |
NDT solution frequency below which the localization is considered in a fault state and NDT matching can no longer be used.
Definition at line 35 of file LocalizationManagerConfig.hpp.
Referenced by localization_manager::Node::Node(), localization_manager::LocalizationManager::computeNDTFreq(), localization_manager::Node::handle_on_configure(), localization_manager::Node::parameter_update_callback(), localization_manager::LocalizationManager::poseAndStatsCallback(), and localization_manager::LocalizationManager::posePubTick().
double localization_manager::LocalizationManagerConfig::pose_pub_rate = 10.0 |
Selected pose publication rate.
Definition at line 49 of file LocalizationManagerConfig.hpp.
Referenced by localization_manager::Node::Node(), localization_manager::Node::handle_on_configure(), and localization_manager::Node::parameter_update_callback().
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().
double localization_manager::LocalizationManagerConfig::x_offset = 2.8 |
GPS Offset to apply if that mode is enabled.
Definition at line 51 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().
double localization_manager::LocalizationManagerConfig::y_offset = -2.1 |
double localization_manager::LocalizationManagerConfig::z_offset = 0.0 |