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 File Reference
#include <iostream>
#include <carma_localization_msgs/msg/localization_status_report.hpp>
#include <rclcpp/rclcpp.hpp>
Include dependency graph for LocalizationTypes.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  localization_manager
 

Enumerations

enum  localization_manager::LocalizerMode {
  localization_manager::NDT = 0 , localization_manager::GNSS = 1 , localization_manager::AUTO_WITH_TIMEOUT = 2 , localization_manager::AUTO_WITHOUT_TIMEOUT = 3 ,
  localization_manager::GNSS_WITH_NDT_INIT = 4 , localization_manager::GNSS_WITH_FIXED_OFFSET = 5
}
 Enum describing the possible operational modes of the LocalizationManager. More...
 
enum class  localization_manager::LocalizationState {
  localization_manager::UNINITIALIZED , localization_manager::INITIALIZING , localization_manager::OPERATIONAL , localization_manager::DEGRADED ,
  localization_manager::DEGRADED_NO_LIDAR_FIX , localization_manager::AWAIT_MANUAL_INITIALIZATION
}
 Enum describing the possible states of the localization system. More...
 
enum class  localization_manager::LocalizationSignal {
  localization_manager::INITIAL_POSE , localization_manager::GOOD_NDT_FREQ_AND_FITNESS_SCORE , localization_manager::POOR_NDT_FREQ_OR_FITNESS_SCORE , localization_manager::UNUSABLE_NDT_FREQ_OR_FITNESS_SCORE ,
  localization_manager::TIMEOUT , localization_manager::LIDAR_SENSOR_FAILURE , localization_manager::LIDAR_INITIALIZED_SWITCH_TO_GPS , localization_manager::GNSS_DATA_TIMEOUT
}
 Enum describing the possible signals to change the current LocalizationState. More...
 

Functions

std::ostream & localization_manager::operator<< (std::ostream &os, LocalizerMode m)
 Stream operator for LocalizerMode enum. More...
 
std::ostream & localization_manager::operator<< (std::ostream &os, LocalizationState s)
 Stream operator for LocalizationState enum. More...
 
carma_localization_msgs::msg::LocalizationStatusReport localization_manager::stateToMsg (LocalizationState state, const rclcpp::Time &stamp)
 Helper function to convert LocalizationState objects into LocalizationStatusReport ROS messages. More...
 
std::ostream & localization_manager::operator<< (std::ostream &os, LocalizationSignal s)
 Stream operator for LocalizationSignal enum. More...