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.
SystemControllerConfig Struct Reference

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

#include <system_controller_config.hpp>

Collaboration diagram for SystemControllerConfig:
Collaboration graph

Public Attributes

std::vector< std::string > required_subsystem_nodes
 List of nodes to consider required and who's failure shall result in system shutdown. More...
 
double signal_configure_delay = 20.0
 Time in seconds to wait before telling all nodes to configure. More...
 
uint64_t service_timeout_ms = 1000
 Timeout in ms for service availability. More...
 
uint64_t call_timeout_ms = 1000
 Timeout in ms for service calls. More...
 

Friends

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

Detailed Description

Stuct containing the algorithm configuration values for the SystemController.

Definition at line 24 of file system_controller_config.hpp.

Friends And Related Function Documentation

◆ operator<<

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

Definition at line 40 of file system_controller_config.hpp.

41 {
42 output << "SystemControllerConfig { " << std::endl
43 << "signal_configure_delay: " << c.signal_configure_delay << std::endl
44 << "service_timeout_ms: " << c.service_timeout_ms << std::endl
45 << "call_timeout_ms: " << c.call_timeout_ms << std::endl
46 << "required_subsystem_nodes: [ ";
47
48 for (auto node : c.required_subsystem_nodes)
49 output << node << " ";
50
51
52 output << "] " << std::endl << "}" << std::endl;
53 return output;
54 }

Member Data Documentation

◆ call_timeout_ms

◆ required_subsystem_nodes

std::vector<std::string> SystemControllerConfig::required_subsystem_nodes

List of nodes to consider required and who's failure shall result in system shutdown.

Definition at line 28 of file system_controller_config.hpp.

Referenced by system_controller::SystemControllerNode::initialize(), and system_controller::SystemControllerNode::on_system_alert().

◆ service_timeout_ms

◆ signal_configure_delay

double SystemControllerConfig::signal_configure_delay = 20.0

Time in seconds to wait before telling all nodes to configure.

Definition at line 31 of file system_controller_config.hpp.

Referenced by system_controller::SystemControllerNode::initialize().


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