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.
subsystem_controllers::DriversControllerConfig Struct Reference

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

#include <drivers_controller_config.hpp>

Collaboration diagram for subsystem_controllers::DriversControllerConfig:
Collaboration graph

Public Attributes

std::vector< std::string > ros1_required_drivers_
 List of ros1 controller drivers (node name) to consider required and who's failure shall result in automation abort. More...
 
std::vector< std::string > ros1_camera_drivers_
 List of ros1 camera drivers (node name) to consider required and who's failure shall result in automation abort. More...
 
std::vector< std::string > excluded_namespace_nodes_
 List of nodes in the namespace which will not be managed by this subsystem controller. More...
 
int startup_duration_
 The time allocated for system startup in seconds. More...
 
double driver_timeout_ = 1000
 The timeout threshold for essential drivers in ms. More...
 

Friends

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

Detailed Description

Stuct containing the algorithm configuration values for the GuidanceController.

Definition at line 27 of file drivers_controller_config.hpp.

Friends And Related Function Documentation

◆ operator<<

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

Definition at line 43 of file drivers_controller_config.hpp.

44 {
45
46 output << "DriversControllerConfig { " << std::endl
47 << "ros1_required_drivers: [ " << std::endl;
48
49 for (auto node : c.ros1_required_drivers_)
50 output << node << " ";
51
52 output << "] " << std::endl << "ros1_camera_drivers: [ ";
53
54 for (auto node : c.ros1_camera_drivers_)
55 output << node << " ";
56
57 output << "] " << std::endl << "excluded_namespace_nodes: [ ";
58
59 for (auto node : c.excluded_namespace_nodes_)
60 output << node << " ";
61
62 output<< "] " << std::endl << "startup_duration: "<< c.startup_duration_ << std::endl;
63
64 output <<"driver_timeout: "<< c.driver_timeout_ << std::endl
65
66 << "}" << std::endl;
67 return output;
68 }

Member Data Documentation

◆ driver_timeout_

double subsystem_controllers::DriversControllerConfig::driver_timeout_ = 1000

◆ excluded_namespace_nodes_

std::vector<std::string> subsystem_controllers::DriversControllerConfig::excluded_namespace_nodes_

List of nodes in the namespace which will not be managed by this subsystem controller.

Definition at line 35 of file drivers_controller_config.hpp.

Referenced by subsystem_controllers::DriversControllerNode::DriversControllerNode(), and subsystem_controllers::DriversControllerNode::handle_on_configure().

◆ ros1_camera_drivers_

std::vector<std::string> subsystem_controllers::DriversControllerConfig::ros1_camera_drivers_

List of ros1 camera drivers (node name) to consider required and who's failure shall result in automation abort.

Definition at line 33 of file drivers_controller_config.hpp.

Referenced by subsystem_controllers::DriversControllerNode::DriversControllerNode(), and subsystem_controllers::DriversControllerNode::handle_on_configure().

◆ ros1_required_drivers_

std::vector<std::string> subsystem_controllers::DriversControllerConfig::ros1_required_drivers_

List of ros1 controller drivers (node name) to consider required and who's failure shall result in automation abort.

Definition at line 31 of file drivers_controller_config.hpp.

Referenced by subsystem_controllers::DriversControllerNode::DriversControllerNode(), and subsystem_controllers::DriversControllerNode::handle_on_configure().

◆ startup_duration_

int subsystem_controllers::DriversControllerConfig::startup_duration_

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