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.
gnss_to_map_convertor::Config Struct Reference

Stuct containing the algorithm configuration values for gnss_to_map_convertor. More...

#include <gnss_to_map_convertor_config.hpp>

Collaboration diagram for gnss_to_map_convertor::Config:
Collaboration graph

Public Attributes

std::string base_link_frame = "base_link"
 
std::string map_frame = "map"
 
std::string heading_frame = "ned_heading"
 

Friends

std::ostream & operator<< (std::ostream &output, const Config &c)
 

Detailed Description

Stuct containing the algorithm configuration values for gnss_to_map_convertor.

Definition at line 28 of file gnss_to_map_convertor_config.hpp.

Friends And Related Function Documentation

◆ operator<<

std::ostream & operator<< ( std::ostream &  output,
const Config c 
)
friend

Definition at line 35 of file gnss_to_map_convertor_config.hpp.

36 {
37 output << "gnss_to_map_convertor::Config { " << std::endl
38 << "base_link_frame: " << c.base_link_frame << std::endl
39 << "map_frame: " << c.map_frame << std::endl
40 << "heading_frame: " << c.heading_frame << std::endl
41 << "}" << std::endl;
42 return output;
43 }

Member Data Documentation

◆ base_link_frame

std::string gnss_to_map_convertor::Config::base_link_frame = "base_link"

◆ heading_frame

std::string gnss_to_map_convertor::Config::heading_frame = "ned_heading"

◆ map_frame


The documentation for this struct was generated from the following file: