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::BaseSubsystemController Class Reference

A base class for all subsystem_controllers which provides default lifecycle behavior for subsystems. More...

#include <base_subsystem_controller.hpp>

Inheritance diagram for subsystem_controllers::BaseSubsystemController:
Inheritance graph
Collaboration diagram for subsystem_controllers::BaseSubsystemController:
Collaboration graph

Public Member Functions

 BaseSubsystemController ()=delete
 
 BaseSubsystemController (const rclcpp::NodeOptions &options)
 Constructor. Set explicitly to support node composition. More...
 
 ~BaseSubsystemController ()=default
 
void set_config (BaseSubSystemControllerConfig config)
 
virtual void on_system_alert (const carma_msgs::msg::SystemAlert::UniquePtr msg)
 
virtual carma_ros2_utils::CallbackReturn handle_on_configure (const rclcpp_lifecycle::State &prev_state)
 
virtual carma_ros2_utils::CallbackReturn handle_on_activate (const rclcpp_lifecycle::State &prev_state)
 
virtual carma_ros2_utils::CallbackReturn handle_on_deactivate (const rclcpp_lifecycle::State &prev_state)
 
virtual carma_ros2_utils::CallbackReturn handle_on_cleanup (const rclcpp_lifecycle::State &prev_state)
 
virtual carma_ros2_utils::CallbackReturn handle_on_error (const rclcpp_lifecycle::State &prev_state, const std::string &exception_string)
 
virtual carma_ros2_utils::CallbackReturn handle_on_shutdown (const rclcpp_lifecycle::State &prev_state)
 

Protected Member Functions

std::vector< std::string > get_nodes_in_namespace (const std::string &node_namespace) const
 Returns the list of fully qualified node names for all ROS2 nodes in the provided namespace. More...
 
std::vector< std::string > get_non_intersecting_set (const std::vector< std::string > &set_a, const std::vector< std::string > &set_b) const
 Returns all elements of the provided set_a which are NOT contained in the provided set_b. More...
 

Protected Attributes

ros2_lifecycle_manager::Ros2LifecycleManager lifecycle_mgr_
 Lifecycle Manager which will track the managed nodes and call their lifecycle services on request. More...
 
rclcpp::Subscription< carma_msgs::msg::SystemAlert >::SharedPtr system_alert_sub_
 The subscriber for the system alert topic. More...
 
BaseSubSystemControllerConfig base_config_
 The configuration struct. More...
 
bool trigger_managed_nodes_configure_from_base_class_ = true
 Collection of flags which, if true, will cause the base class to make lifecycle service calls to managed nodes. More...
 
bool trigger_managed_nodes_activate_from_base_class_ = true
 
bool trigger_managed_nodes_deactivate_from_base_class_ = true
 
bool trigger_managed_nodes_cleanup_from_base_class_ = true
 

Detailed Description

A base class for all subsystem_controllers which provides default lifecycle behavior for subsystems.

The default behavior which is provided is as follows

  • Takes in a list of required nodes and a namespace
  • Manages the lifecycle of all nodes which are the union of the required nodes and the namespace
  • Monitors the system_alert topic and if a node within its required node set crashes it notifies the larger system that the subsystem has failed

Definition at line 39 of file base_subsystem_controller.hpp.

Constructor & Destructor Documentation

◆ BaseSubsystemController() [1/2]

subsystem_controllers::BaseSubsystemController::BaseSubsystemController ( )
delete

◆ BaseSubsystemController() [2/2]

subsystem_controllers::BaseSubsystemController::BaseSubsystemController ( const rclcpp::NodeOptions &  options)
explicit

Constructor. Set explicitly to support node composition.

Parameters
optionsThe node options to use for configuring this node

Definition at line 27 of file base_subsystem_controller.cpp.

28 : CarmaLifecycleNode(options),
29 lifecycle_mgr_(get_node_base_interface(), get_node_graph_interface(), get_node_logging_interface(), get_node_services_interface())
30 {
31 // Declare parameters
32 base_config_.service_timeout_ms = this->declare_parameter<int>("service_timeout_ms", base_config_.service_timeout_ms);
33 base_config_.call_timeout_ms = this->declare_parameter<int>("call_timeout_ms", base_config_.call_timeout_ms);
34 base_config_.required_subsystem_nodes = this->declare_parameter<std::vector<std::string>>("required_subsystem_nodes", base_config_.required_subsystem_nodes);
35 base_config_.subsystem_namespace = this->declare_parameter<std::string>("subsystem_namespace", base_config_.subsystem_namespace);
36 base_config_.full_subsystem_required = this->declare_parameter<bool>("full_subsystem_required", base_config_.full_subsystem_required);
37 base_config_.unmanaged_required_nodes = this->declare_parameter<std::vector<std::string>>("unmanaged_required_nodes", base_config_.unmanaged_required_nodes);
38
39 // Handle fact that parameter vectors cannot be empty
42 }
43
46 }
47
48 }
BaseSubSystemControllerConfig base_config_
The configuration struct.
ros2_lifecycle_manager::Ros2LifecycleManager lifecycle_mgr_
Lifecycle Manager which will track the managed nodes and call their lifecycle services on request.
std::vector< std::string > required_subsystem_nodes
List of nodes to consider required and who's failure shall result in system shutdown.
bool full_subsystem_required
If this flag is true then all nodes under subsystem_namespace are treated as required in addition to ...
std::string subsystem_namespace
Node Namespace. Any node under this namespace shall have its lifecycle managed by this controller.
std::vector< std::string > unmanaged_required_nodes
List of nodes which will not be directly managed by this subsystem controller.

References base_config_, subsystem_controllers::BaseSubSystemControllerConfig::call_timeout_ms, subsystem_controllers::BaseSubSystemControllerConfig::full_subsystem_required, subsystem_controllers::BaseSubSystemControllerConfig::required_subsystem_nodes, subsystem_controllers::BaseSubSystemControllerConfig::service_timeout_ms, subsystem_controllers::BaseSubSystemControllerConfig::subsystem_namespace, and subsystem_controllers::BaseSubSystemControllerConfig::unmanaged_required_nodes.

◆ ~BaseSubsystemController()

subsystem_controllers::BaseSubsystemController::~BaseSubsystemController ( )
default

Member Function Documentation

◆ get_nodes_in_namespace()

std::vector< std::string > subsystem_controllers::BaseSubsystemController::get_nodes_in_namespace ( const std::string &  node_namespace) const
protected

Returns the list of fully qualified node names for all ROS2 nodes in the provided namespace.

Parameters
node_namespaceThe ros namespace to get all nodes within. For example /guidance
Returns
The list of node names

Definition at line 279 of file base_subsystem_controller.cpp.

280 {
281
282 // These two services are exposed by lifecycle nodes.
283 static const std::string CHANGE_STATE_SRV = "/change_state";
284 static const std::string GET_STATE_SRV = "/get_state";
285
286 static const std::string CHANGE_STATE_TYPE = "lifecycle_msgs/srv/ChangeState";
287 static const std::string GET_STATE_TYPE = "lifecycle_msgs/srv/GetState";
288
289 static const std::string this_full_name = std::string(get_namespace()) + "/" + std::string(get_name());
290
291
292 auto all_nodes = this->get_node_names();
293
294 std::vector<std::string> nodes_in_namspace;
295 nodes_in_namspace.reserve(all_nodes.size());
296
297
298 for (const auto &node : all_nodes)
299 {
300
301 if (node == this_full_name)
302 continue; // no need for this node to try managing itself
303
304 if (node.find(node_namespace) == 0)
305 { // The node is in the provided namespace
306
307
309 // In the following section of code we check if the current node in the target namespace is actually a lifecycle node
310 // This check is done by evaluating if that nodes exposes the change_state and get_state lifecycle services.
311 // If the node does not expose these services then it cannot be managed by this component.
312 // However, this does not result in an error as the node could be wrapped by a lifecycle component wrapper
314
315 // First extract the service names and types for the current node. This requires seperating the node base name and namespace
316 std::vector<std::string> result;
317 boost::split(result, node, boost::is_any_of("/"));
318
319 if (result.empty()) {
320 throw std::runtime_error("Fully specified node name does not contain '/' seems to suggest internal ROS error.");
321 }
322
323 std::string base_name = result.back();
324 result.pop_back();
325 std::string namespace_joined = boost::algorithm::join(result, "/");
326
327 auto services_and_types = get_service_names_and_types_by_node(base_name, namespace_joined);
328
329
330 // Next we check if both services are available with the correct type
331 // Short variable names used here to make conditional more readable
332 const std::string cs_srv = node + CHANGE_STATE_SRV;
333 const std::string gs_srv = node + GET_STATE_SRV;
334
335 if (services_and_types.find(cs_srv) != services_and_types.end()
336 && services_and_types.find(gs_srv) != services_and_types.end()
337 && std::find(services_and_types.at(cs_srv).begin(), services_and_types.at(cs_srv).end(), CHANGE_STATE_TYPE) != services_and_types.at(cs_srv).end()
338 && std::find(services_and_types.at(gs_srv).begin(), services_and_types.at(gs_srv).end(), GET_STATE_TYPE) != services_and_types.at(gs_srv).end())
339 {
340
341 nodes_in_namspace.emplace_back(node);
342
343 } else {
344 // Current node is not a lifecycle node so log a warning
345 RCLCPP_WARN_STREAM(get_logger(), "Failed to find lifecycle services for node: " << node << " this node will not be managed. NOTE: If this node is wrapped by a lifecycle component that is managed then this is not an issue.");
346
347 continue;
348
349 }
350 }
351 }
352
353 return nodes_in_namspace;
354 }

References process_traj_logs::split.

Referenced by handle_on_configure().

Here is the caller graph for this function:

◆ get_non_intersecting_set()

std::vector< std::string > subsystem_controllers::BaseSubsystemController::get_non_intersecting_set ( const std::vector< std::string > &  set_a,
const std::vector< std::string > &  set_b 
) const
protected

Returns all elements of the provided set_a which are NOT contained in the provided set_b.

set_a The set of strings which will have its intersection checked against

set_b The set of strings which will NOT be in the returned set

Returns
A set of not intersecting strings which are in set_a but not set_b

Definition at line 356 of file base_subsystem_controller.cpp.

357 {
358
359 std::vector<std::string> non_intersecting_set; // Returned set
360 non_intersecting_set.reserve(set_a.size());
361
362 std::unordered_set<std::string> set_b_lookup; // Quick lookup map of set_b
363 set_b_lookup.reserve(set_b.size());
364
365 set_b_lookup.insert(set_b.begin(), set_b.end());
366
367 for (const auto &string : set_a)
368 {
369 if (set_b_lookup.find(string) == set_b_lookup.end())
370 { // No intersection so store
371 non_intersecting_set.emplace_back(string);
372 }
373 }
374
375 return non_intersecting_set;
376 }

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

Here is the caller graph for this function:

◆ handle_on_activate()

carma_ros2_utils::CallbackReturn subsystem_controllers::BaseSubsystemController::handle_on_activate ( const rclcpp_lifecycle::State &  prev_state)
virtual

Reimplemented in subsystem_controllers::GuidanceControllerNode, and subsystem_controllers::DriversControllerNode.

Definition at line 167 of file base_subsystem_controller.cpp.

168 {
169 RCLCPP_INFO_STREAM(get_logger(), "Subsystem trying to activate");
170
172 return CallbackReturn::SUCCESS;
173 }
174
176
177 if (success)
178 {
179
180 RCLCPP_INFO_STREAM(get_logger(), "Subsystem able to activate");
181 return CallbackReturn::SUCCESS;
182 }
183 else
184 {
185
186 RCLCPP_INFO_STREAM(get_logger(), "Subsystem unable to activate");
187 return CallbackReturn::FAILURE;
188 }
189 }
std::chrono::milliseconds std_msec

References base_config_, subsystem_controllers::BaseSubSystemControllerConfig::call_timeout_ms, lifecycle_mgr_, subsystem_controllers::BaseSubSystemControllerConfig::service_timeout_ms, and trigger_managed_nodes_activate_from_base_class_.

Referenced by subsystem_controllers::GuidanceControllerNode::handle_on_activate(), and subsystem_controllers::DriversControllerNode::handle_on_activate().

Here is the caller graph for this function:

◆ handle_on_cleanup()

carma_ros2_utils::CallbackReturn subsystem_controllers::BaseSubsystemController::handle_on_cleanup ( const rclcpp_lifecycle::State &  prev_state)
virtual

Reimplemented in subsystem_controllers::GuidanceControllerNode.

Definition at line 215 of file base_subsystem_controller.cpp.

216 {
217 RCLCPP_INFO_STREAM(get_logger(), "Subsystem trying to cleanup");
218
220 return CallbackReturn::SUCCESS;
221 }
222
224
225 if (success)
226 {
227
228 RCLCPP_INFO_STREAM(get_logger(), "Subsystem able to cleanup");
229 return CallbackReturn::SUCCESS;
230 }
231 else
232 {
233
234 RCLCPP_INFO_STREAM(get_logger(), "Subsystem unable to cleanup");
235 return CallbackReturn::FAILURE;
236 }
237 }

References base_config_, subsystem_controllers::BaseSubSystemControllerConfig::call_timeout_ms, lifecycle_mgr_, subsystem_controllers::BaseSubSystemControllerConfig::service_timeout_ms, and trigger_managed_nodes_cleanup_from_base_class_.

Referenced by subsystem_controllers::GuidanceControllerNode::handle_on_cleanup().

Here is the caller graph for this function:

◆ handle_on_configure()

carma_ros2_utils::CallbackReturn subsystem_controllers::BaseSubsystemController::handle_on_configure ( const rclcpp_lifecycle::State &  prev_state)
virtual

Reimplemented in subsystem_controllers::GuidanceControllerNode, subsystem_controllers::DriversControllerNode, and subsystem_controllers::LocalizationControllerNode.

Definition at line 92 of file base_subsystem_controller.cpp.

93 {
94 RCLCPP_INFO_STREAM(get_logger(), "Subsystem trying to configure");
95
96 // Reset config
97 base_config_ = BaseSubSystemControllerConfig();
98
99 // Load Parameters
100 get_parameter<int>("service_timeout_ms", base_config_.service_timeout_ms);
101 get_parameter<int>("call_timeout_ms", base_config_.call_timeout_ms);
102 get_parameter<std::vector<std::string>>("required_subsystem_nodes", base_config_.required_subsystem_nodes);
103 get_parameter<std::string>("subsystem_namespace", base_config_.subsystem_namespace);
104 get_parameter<bool>("full_subsystem_required", base_config_.full_subsystem_required);
105 get_parameter<std::vector<std::string>>("unmanaged_required_nodes", base_config_.unmanaged_required_nodes);
106
107 // Handle fact that parameter vectors cannot be empty
110 }
111
114 }
115
116 RCLCPP_INFO_STREAM(get_logger(), "Loaded config: " << base_config_);
117
118 // Create subscriptions
119 system_alert_sub_ = create_subscription<carma_msgs::msg::SystemAlert>(
120 system_alert_topic_, 100,
121 std::bind(&BaseSubsystemController::on_system_alert, this, std::placeholders::_1));
122
123 // Initialize lifecycle manager
125
126 std::vector<std::string> managed_nodes = nodes_in_namespace;
127 managed_nodes.reserve(nodes_in_namespace.size() + base_config_.required_subsystem_nodes.size());
128
129 // Collect non-namespace nodes if any and add them to our set of managed nodes
130 auto additional_nodes = get_non_intersecting_set(base_config_.required_subsystem_nodes, nodes_in_namespace);
131
132 managed_nodes.insert(managed_nodes.end(), additional_nodes.begin(), additional_nodes.end());
133
134 lifecycle_mgr_.set_managed_nodes(managed_nodes);
135
136 // Check if all nodes are required
138 RCLCPP_INFO_STREAM(get_logger(), "full_subsystem_required is True. Setting all namespace nodes as required");
139
141
142 RCLCPP_INFO_STREAM(get_logger(), "New config: " << base_config_);
143 }
144
145
147 return CallbackReturn::SUCCESS;
148 }
149
150 // With all of our managed nodes now being tracked we can execute their configure operations
152
153 if (success)
154 {
155
156 RCLCPP_INFO_STREAM(get_logger(), "Subsystem able to configure");
157 return CallbackReturn::SUCCESS;
158 }
159 else
160 {
161
162 RCLCPP_INFO_STREAM(get_logger(), "Subsystem unable to configure");
163 return CallbackReturn::FAILURE;
164 }
165 }
std::vector< std::string > get_nodes_in_namespace(const std::string &node_namespace) const
Returns the list of fully qualified node names for all ROS2 nodes in the provided namespace.
rclcpp::Subscription< carma_msgs::msg::SystemAlert >::SharedPtr system_alert_sub_
The subscriber for the system alert topic.
virtual void on_system_alert(const carma_msgs::msg::SystemAlert::UniquePtr msg)
std::vector< std::string > get_non_intersecting_set(const std::vector< std::string > &set_a, const std::vector< std::string > &set_b) const
Returns all elements of the provided set_a which are NOT contained in the provided set_b.
bool trigger_managed_nodes_configure_from_base_class_
Collection of flags which, if true, will cause the base class to make lifecycle service calls to mana...

References base_config_, subsystem_controllers::BaseSubSystemControllerConfig::call_timeout_ms, subsystem_controllers::BaseSubSystemControllerConfig::full_subsystem_required, get_nodes_in_namespace(), get_non_intersecting_set(), lifecycle_mgr_, on_system_alert(), subsystem_controllers::BaseSubSystemControllerConfig::required_subsystem_nodes, subsystem_controllers::BaseSubSystemControllerConfig::service_timeout_ms, subsystem_controllers::BaseSubSystemControllerConfig::subsystem_namespace, system_alert_sub_, trigger_managed_nodes_configure_from_base_class_, and subsystem_controllers::BaseSubSystemControllerConfig::unmanaged_required_nodes.

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

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_on_deactivate()

carma_ros2_utils::CallbackReturn subsystem_controllers::BaseSubsystemController::handle_on_deactivate ( const rclcpp_lifecycle::State &  prev_state)
virtual

Reimplemented in subsystem_controllers::GuidanceControllerNode.

Definition at line 191 of file base_subsystem_controller.cpp.

192 {
193 RCLCPP_INFO_STREAM(get_logger(), "Subsystem trying to deactivate");
194
196 return CallbackReturn::SUCCESS;
197 }
198
200
201 if (success)
202 {
203
204 RCLCPP_INFO_STREAM(get_logger(), "Subsystem able to deactivate");
205 return CallbackReturn::SUCCESS;
206 }
207 else
208 {
209
210 RCLCPP_INFO_STREAM(get_logger(), "Subsystem unable to deactivate");
211 return CallbackReturn::FAILURE;
212 }
213 }

References base_config_, subsystem_controllers::BaseSubSystemControllerConfig::call_timeout_ms, lifecycle_mgr_, subsystem_controllers::BaseSubSystemControllerConfig::service_timeout_ms, and trigger_managed_nodes_deactivate_from_base_class_.

Referenced by subsystem_controllers::GuidanceControllerNode::handle_on_deactivate().

Here is the caller graph for this function:

◆ handle_on_error()

carma_ros2_utils::CallbackReturn subsystem_controllers::BaseSubsystemController::handle_on_error ( const rclcpp_lifecycle::State &  prev_state,
const std::string &  exception_string 
)
virtual

Definition at line 239 of file base_subsystem_controller.cpp.

240 {
241 RCLCPP_INFO_STREAM(get_logger(), "Subsystem trying to shutdown due to error");
242
244
245 if (success)
246 {
247
248 RCLCPP_INFO_STREAM(get_logger(), "Subsystem able to shutdown");
249 return CallbackReturn::SUCCESS;
250 }
251 else
252 {
253
254 RCLCPP_INFO_STREAM(get_logger(), "Subsystem unable to shutdown");
255 return CallbackReturn::FAILURE;
256 }
257 }

References base_config_, subsystem_controllers::BaseSubSystemControllerConfig::call_timeout_ms, lifecycle_mgr_, and subsystem_controllers::BaseSubSystemControllerConfig::service_timeout_ms.

◆ handle_on_shutdown()

carma_ros2_utils::CallbackReturn subsystem_controllers::BaseSubsystemController::handle_on_shutdown ( const rclcpp_lifecycle::State &  prev_state)
virtual

Reimplemented in subsystem_controllers::GuidanceControllerNode.

Definition at line 259 of file base_subsystem_controller.cpp.

260 {
261 RCLCPP_INFO_STREAM(get_logger(), "Subsystem trying to shutdown");
262
264
265 if (success)
266 {
267
268 RCLCPP_INFO_STREAM(get_logger(), "Subsystem able to shutdown");
269 return CallbackReturn::SUCCESS;
270 }
271 else
272 {
273
274 RCLCPP_INFO_STREAM(get_logger(), "Subsystem unable to shutdown");
275 return CallbackReturn::FAILURE;
276 }
277 }

References base_config_, subsystem_controllers::BaseSubSystemControllerConfig::call_timeout_ms, lifecycle_mgr_, and subsystem_controllers::BaseSubSystemControllerConfig::service_timeout_ms.

Referenced by subsystem_controllers::GuidanceControllerNode::handle_on_shutdown().

Here is the caller graph for this function:

◆ on_system_alert()

void subsystem_controllers::BaseSubsystemController::on_system_alert ( const carma_msgs::msg::SystemAlert::UniquePtr  msg)
virtual

Reimplemented in subsystem_controllers::LocalizationControllerNode.

Definition at line 55 of file base_subsystem_controller.cpp.

56 {
57
58
59 RCLCPP_INFO_STREAM(
60 get_logger(), "Received SystemAlert message of type: " << static_cast<int>(msg->type) << " with message: " << msg->description);
61
62 // NOTE: Here we check the required nodes not the full managed node set
63 if (msg->type == carma_msgs::msg::SystemAlert::FATAL)
64 {
65
66 // Required node has failed
69 {
70 // Our subsystem has failed so notify the overall system controller
71
72 RCLCPP_ERROR_STREAM(
73 get_logger(), "Failure in required node: " << msg->source_node);
74
75 carma_msgs::msg::SystemAlert alert;
76 alert.type = carma_msgs::msg::SystemAlert::FATAL;
77 alert.description = base_config_.subsystem_namespace + " subsytem has failed with error: " + msg->description;
78 alert.source_node = get_node_base_interface()->get_fully_qualified_name();
79 publish_system_alert(alert);
80
81 // TODO: It might be worth trying to deactivate or shutdown after alerting the larger system,
82 // but not clear on if that will increase instability of shutdown process
83 }
84 else
85 { // Optional node has failed
86 RCLCPP_WARN_STREAM(
87 get_logger(), "Failure in optional node: " << msg->source_node);
88 }
89 }
90 }

References base_config_, subsystem_controllers::BaseSubSystemControllerConfig::required_subsystem_nodes, subsystem_controllers::BaseSubSystemControllerConfig::subsystem_namespace, and subsystem_controllers::BaseSubSystemControllerConfig::unmanaged_required_nodes.

Referenced by handle_on_configure(), and subsystem_controllers::LocalizationControllerNode::on_system_alert().

Here is the caller graph for this function:

◆ set_config()

void subsystem_controllers::BaseSubsystemController::set_config ( BaseSubSystemControllerConfig  config)

Definition at line 50 of file base_subsystem_controller.cpp.

51 {
52 base_config_ = config;
53 }

References base_config_.

Member Data Documentation

◆ base_config_

◆ lifecycle_mgr_

ros2_lifecycle_manager::Ros2LifecycleManager subsystem_controllers::BaseSubsystemController::lifecycle_mgr_
protected

◆ system_alert_sub_

rclcpp::Subscription<carma_msgs::msg::SystemAlert>::SharedPtr subsystem_controllers::BaseSubsystemController::system_alert_sub_
protected

The subscriber for the system alert topic.

Definition at line 93 of file base_subsystem_controller.hpp.

Referenced by handle_on_configure().

◆ trigger_managed_nodes_activate_from_base_class_

bool subsystem_controllers::BaseSubsystemController::trigger_managed_nodes_activate_from_base_class_ = true
protected

Definition at line 105 of file base_subsystem_controller.hpp.

Referenced by handle_on_activate().

◆ trigger_managed_nodes_cleanup_from_base_class_

bool subsystem_controllers::BaseSubsystemController::trigger_managed_nodes_cleanup_from_base_class_ = true
protected

Definition at line 107 of file base_subsystem_controller.hpp.

Referenced by handle_on_cleanup().

◆ trigger_managed_nodes_configure_from_base_class_

bool subsystem_controllers::BaseSubsystemController::trigger_managed_nodes_configure_from_base_class_ = true
protected

◆ trigger_managed_nodes_deactivate_from_base_class_

bool subsystem_controllers::BaseSubsystemController::trigger_managed_nodes_deactivate_from_base_class_ = true
protected

Definition at line 106 of file base_subsystem_controller.hpp.

Referenced by handle_on_deactivate().


The documentation for this class was generated from the following files: