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.
LocalizationManagerConfig.hpp
Go to the documentation of this file.
1#pragma once
2/*
3 * Copyright (C) 2022 LEIDOS.
4 *
5 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
6 * use this file except in compliance with the License. You may obtain a copy of
7 * the License at
8 *
9 * http://www.apache.org/licenses/LICENSE-2.0
10 *
11 * Unless required by applicable law or agreed to in writing, software
12 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
13 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
14 * License for the specific language governing permissions and limitations under
15 * the License.
16 */
17
20
22{
25 {
49 double pose_pub_rate = 10.0;
51 double x_offset = 2.8;
52 double y_offset = -2.1;
53 double z_offset = 0.0;
54
55
56 // Stream operator for this config
57 friend std::ostream &operator<<(std::ostream &output, const LocalizationManagerConfig &c)
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 }
76 };
77} // namespace localization_manager
LocalizerMode
Enum describing the possible operational modes of the LocalizationManager.
Struct to store the configuration settings for the LocalizationManager class.
int gnss_only_operation_timeout
Timeout in ms for GNSS only operation. Ignored when in GNSS mode.
double fitness_score_degraded_threshold
NDT Fitness score above which the localization is considered in a degraded state.
double pose_pub_rate
Selected pose publication rate.
friend std::ostream & operator<<(std::ostream &output, const LocalizationManagerConfig &c)
double x_offset
GPS Offset to apply if that mode is enabled.
int gnss_data_timeout
GNSS Data timeout. If exceeded the system will assume the GNSS is no longer functional....
double ndt_frequency_degraded_threshold
NDT solution frequency below which the localization is considered in a degraded state.