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.
LocalizationTypes.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
18#include <iostream>
19#include <carma_localization_msgs/msg/localization_status_report.hpp>
20#include <rclcpp/rclcpp.hpp>
21
23{
26 {
27 NDT = 0, // NDT only operation
28 GNSS = 1, // GNSS only operation
29 AUTO_WITH_TIMEOUT = 2, // NDT operation with support for GPS fallback that will timeout
30 AUTO_WITHOUT_TIMEOUT = 3, // NDT operation with support for GPS fallback that will not timeout
31 GNSS_WITH_NDT_INIT = 4, // GNSS only operation with NDT initialization, switching to GNSS after 5 sequential timesteps of OPERATIONAL NDT
32 GNSS_WITH_FIXED_OFFSET = 5 // GNSS only operation with fixed offset
33 };
34
38 std::ostream &operator<<(std::ostream &os, LocalizerMode m);
39
42 {
49 };
50
54 std::ostream &operator<<(std::ostream &os, LocalizationState s);
55
64 carma_localization_msgs::msg::LocalizationStatusReport stateToMsg(LocalizationState state, const rclcpp::Time &stamp);
65
68 {
73 TIMEOUT,
77 };
78
82 std::ostream &operator<<(std::ostream &os, LocalizationSignal s);
83
84} // namespace localization_manager
carma_localization_msgs::msg::LocalizationStatusReport stateToMsg(LocalizationState state, const rclcpp::Time &stamp)
Helper function to convert LocalizationState objects into LocalizationStatusReport ROS messages.
LocalizationState
Enum describing the possible states of the localization system.
std::ostream & operator<<(std::ostream &os, LocalizerMode m)
Stream operator for LocalizerMode enum.
LocalizerMode
Enum describing the possible operational modes of the LocalizationManager.
LocalizationSignal
Enum describing the possible signals to change the current LocalizationState.