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 Namespace Reference

Classes

class  LocalizationManager
 Primary logic class for the localization manager node. More...
 
struct  LocalizationManagerConfig
 Struct to store the configuration settings for the LocalizationManager class. More...
 
class  LocalizationTransitionTable
 Class defining the state transition table behavior for the LocalizationManager. More...
 
class  Node
 Core execution node for this package. More...
 

Enumerations

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

Functions

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

Enumeration Type Documentation

◆ LocalizationSignal

Enum describing the possible signals to change the current LocalizationState.

Enumerator
INITIAL_POSE 
GOOD_NDT_FREQ_AND_FITNESS_SCORE 
POOR_NDT_FREQ_OR_FITNESS_SCORE 
UNUSABLE_NDT_FREQ_OR_FITNESS_SCORE 
TIMEOUT 
LIDAR_SENSOR_FAILURE 
LIDAR_INITIALIZED_SWITCH_TO_GPS 
GNSS_DATA_TIMEOUT 

Definition at line 67 of file LocalizationTypes.hpp.

◆ LocalizationState

Enum describing the possible states of the localization system.

Enumerator
UNINITIALIZED 
INITIALIZING 
OPERATIONAL 
DEGRADED 
DEGRADED_NO_LIDAR_FIX 
AWAIT_MANUAL_INITIALIZATION 

Definition at line 41 of file LocalizationTypes.hpp.

◆ LocalizerMode

Enum describing the possible operational modes of the LocalizationManager.

Enumerator
NDT 
GNSS 
AUTO_WITH_TIMEOUT 
AUTO_WITHOUT_TIMEOUT 
GNSS_WITH_NDT_INIT 
GNSS_WITH_FIXED_OFFSET 

Definition at line 25 of file LocalizationTypes.hpp.

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 };

Function Documentation

◆ generate_launch_description()

def localization_manager.generate_launch_description ( )

Definition at line 31 of file localization_manager.py.

32
33 # Declare the log_level launch argument
34 log_level = LaunchConfiguration('log_level')
35 declare_log_level_arg = DeclareLaunchArgument(
36 name ='log_level', default_value='WARN')
37
38 # Get parameter file path
39 param_file_path = os.path.join(
40 get_package_share_directory('localization_manager'), 'config/parameters.yaml')
41
42
43 # Launch node(s) in a carma container to allow logging to be configured
44 container = ComposableNodeContainer(
45 package='carma_ros2_utils',
46 name='localization_manager_container',
47 namespace=GetCurrentNamespace(),
48 executable='carma_component_container_mt',
49 composable_node_descriptions=[
50
51 # Launch the core node(s)
52 ComposableNode(
53 package='localization_manager',
54 plugin='localization_manager::Node',
55 name='localization_manager_node',
56 extra_arguments=[
57 {'use_intra_process_comms': True},
58 {'--log-level' : log_level }
59 ],
60 parameters=[ param_file_path ]
61 ),
62 ]
63 )
64
65 return LaunchDescription([
66 declare_log_level_arg,
67 container
68 ])

◆ operator<<() [1/3]

std::ostream & localization_manager::operator<< ( std::ostream &  os,
LocalizationSignal  s 
)

Stream operator for LocalizationSignal enum.

Definition at line 51 of file LocalizationTypes.cpp.

52 {
53 switch (s)
54 { // clang-format off
55 case LocalizationSignal::INITIAL_POSE : os << "INITIAL_POSE"; break;
56 case LocalizationSignal::GOOD_NDT_FREQ_AND_FITNESS_SCORE: os << "GOOD_NDT_FREQ_AND_FITNESS_SCORE"; break;
57 case LocalizationSignal::POOR_NDT_FREQ_OR_FITNESS_SCORE : os << "POOR_NDT_FREQ_OR_FITNESS_SCORE"; break;
58 case LocalizationSignal::UNUSABLE_NDT_FREQ_OR_FITNESS_SCORE : os << "UNUSABLE_NDT_FREQ_OR_FITNESS_SCORE"; break;
59 case LocalizationSignal::TIMEOUT : os << "TIMEOUT"; break;
60 case LocalizationSignal::LIDAR_SENSOR_FAILURE : os << "LIDAR_SENSOR_FAILURE"; break;
61 case LocalizationSignal::LIDAR_INITIALIZED_SWITCH_TO_GPS : os << "LIDAR_INITIALIZED_SWITCH_TO_GPS"; break;
62 case LocalizationSignal::GNSS_DATA_TIMEOUT : os << "GNSS_DATA_TIMEOUT"; break;
63 default: os.setstate(std::ios_base::failbit);
64 } // clang-format on
65 return os;
66 }

References GNSS_DATA_TIMEOUT, GOOD_NDT_FREQ_AND_FITNESS_SCORE, INITIAL_POSE, LIDAR_INITIALIZED_SWITCH_TO_GPS, LIDAR_SENSOR_FAILURE, POOR_NDT_FREQ_OR_FITNESS_SCORE, TIMEOUT, and UNUSABLE_NDT_FREQ_OR_FITNESS_SCORE.

◆ operator<<() [2/3]

std::ostream & localization_manager::operator<< ( std::ostream &  os,
LocalizationState  s 
)

Stream operator for LocalizationState enum.

Definition at line 36 of file LocalizationTypes.cpp.

37 {
38 switch (s)
39 { // clang-format off
40 case LocalizationState::UNINITIALIZED : os << "UNINITIALIZED"; break;
41 case LocalizationState::INITIALIZING: os << "INITIALIZING"; break;
42 case LocalizationState::OPERATIONAL : os << "OPERATIONAL"; break;
43 case LocalizationState::DEGRADED : os << "DEGRADED"; break;
44 case LocalizationState::DEGRADED_NO_LIDAR_FIX : os << "DEGRADED_NO_LIDAR_FIX"; break;
45 case LocalizationState::AWAIT_MANUAL_INITIALIZATION : os << "AWAIT_MANUAL_INITIALIZATION"; break;
46 default: os.setstate(std::ios_base::failbit);
47 } // clang-format on
48 return os;
49 }

References AWAIT_MANUAL_INITIALIZATION, DEGRADED, DEGRADED_NO_LIDAR_FIX, INITIALIZING, OPERATIONAL, and UNINITIALIZED.

◆ operator<<() [3/3]

std::ostream & localization_manager::operator<< ( std::ostream &  os,
LocalizerMode  m 
)

Stream operator for LocalizerMode enum.

Definition at line 21 of file LocalizationTypes.cpp.

22 {
23 switch (m)
24 { // clang-format off
25 case LocalizerMode::NDT : os << "NDT"; break;
26 case LocalizerMode::GNSS: os << "GNSS"; break;
27 case LocalizerMode::GNSS_WITH_NDT_INIT: os << "GNSS_WITH_NDT_INIT"; break;
28 case LocalizerMode::GNSS_WITH_FIXED_OFFSET: os << "GNSS_WITH_FIXED_OFFSET"; break;
29 case LocalizerMode::AUTO_WITH_TIMEOUT : os << "AUTO_WITH_TIMEOUT"; break;
30 case LocalizerMode::AUTO_WITHOUT_TIMEOUT : os << "AUTO_WITHOUT_TIMEOUT"; break;
31 default: os.setstate(std::ios_base::failbit);
32 } // clang-format on
33 return os;
34 }

References AUTO_WITH_TIMEOUT, AUTO_WITHOUT_TIMEOUT, GNSS_WITH_FIXED_OFFSET, GNSS_WITH_NDT_INIT, and NDT.

◆ stateToMsg()

carma_localization_msgs::msg::LocalizationStatusReport localization_manager::stateToMsg ( LocalizationState  state,
const rclcpp::Time &  stamp 
)

Helper function to convert LocalizationState objects into LocalizationStatusReport ROS messages.

Parameters
stateThe state to convert
stampThe timestamp to set for the message header
Returns
The initialized report message

Definition at line 68 of file LocalizationTypes.cpp.

69 {
70 carma_localization_msgs::msg::LocalizationStatusReport msg;
71 switch (state)
72 {
73 case LocalizationState::UNINITIALIZED:
74 msg.status = carma_localization_msgs::msg::LocalizationStatusReport::UNINITIALIZED;
75 break;
76 case LocalizationState::INITIALIZING:
77 msg.status = carma_localization_msgs::msg::LocalizationStatusReport::INITIALIZING;
78 break;
79 case LocalizationState::OPERATIONAL:
80 msg.status = carma_localization_msgs::msg::LocalizationStatusReport::OPERATIONAL;
81 break;
82 case LocalizationState::DEGRADED:
83 msg.status = carma_localization_msgs::msg::LocalizationStatusReport::DEGRADED;
84 break;
85 case LocalizationState::DEGRADED_NO_LIDAR_FIX:
86 msg.status = carma_localization_msgs::msg::LocalizationStatusReport::DEGRADED_NO_LIDAR_FIX;
87 break;
88 case LocalizationState::AWAIT_MANUAL_INITIALIZATION:
89 msg.status = carma_localization_msgs::msg::LocalizationStatusReport::AWAIT_MANUAL_INITIALIZATION;
90 break;
91 default:
92 throw std::invalid_argument("LocalizationStates do not match carma_localization_msgs::msg::LocalizationStatusReport "
93 "states");
94 break;
95 }
96 msg.header.stamp = stamp;
97
98 return msg;
99 }

References AWAIT_MANUAL_INITIALIZATION, DEGRADED, DEGRADED_NO_LIDAR_FIX, INITIALIZING, OPERATIONAL, and UNINITIALIZED.

Referenced by localization_manager::LocalizationManager::posePubTick().

Here is the caller graph for this function: