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.
drivers_controller_node.hpp
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2021 LEIDOS.
5 *
6 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
7 * use this file except in compliance with the License. You may obtain a copy of
8 * the License at
9 *
10 * http://www.apache.org/licenses/LICENSE-2.0
11 *
12 * Unless required by applicable law or agreed to in writing, software
13 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15 * License for the specific language governing permissions and limitations under
16 * the License.
17 */
18
19#include <memory>
20
22#include "rclcpp/rclcpp.hpp"
23#include "ros2_lifecycle_manager/ros2_lifecycle_manager.hpp"
26#include <boost/algorithm/string.hpp>
27
28#include "carma_msgs/msg/system_alert.hpp"
29#include <carma_driver_msgs/msg/driver_status.hpp>
30
32{
34{
35public:
37
39
45 explicit DriversControllerNode(const rclcpp::NodeOptions & options);
46
47private:
48 // SSCDriverManager to handle all the driver specific discovery and reporting
49 std::shared_ptr<SSCDriverManager> ssc_driver_manager_;
50
53
55 carma_ros2_utils::SubPtr<carma_driver_msgs::msg::DriverStatus> driver_status_sub_;
56
57 // message/service callbacks
58 void driver_discovery_cb(const carma_driver_msgs::msg::DriverStatus::SharedPtr msg);
59
62
63 carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State & prev_state);
64 carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State & prev_state);
65
67 std::vector<std::string> ros1_ssc_driver_name_;
68
69 // record of startup timestamp
71
72 rclcpp::TimerBase::SharedPtr ssc_status_check_timer_;
73
74 // Previously published alert message
75 boost::optional<carma_msgs::msg::SystemAlert> prev_alert;
76};
77
78} // namespace subsystem_controllers
A base class for all subsystem_controllers which provides default lifecycle behavior for subsystems.
void critical_drivers_check_callback()
Timer callback function to check status of required ros1 drivers.
DriversControllerConfig config_
Config for user provided parameters.
std::shared_ptr< SSCDriverManager > ssc_driver_manager_
carma_ros2_utils::SubPtr< carma_driver_msgs::msg::DriverStatus > driver_status_sub_
ROS handles.
boost::optional< carma_msgs::msg::SystemAlert > prev_alert
void driver_discovery_cb(const carma_driver_msgs::msg::DriverStatus::SharedPtr msg)
carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &prev_state)
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &prev_state)
std::vector< std::string > ros1_ssc_driver_name_
ROS parameters.
Stuct containing the algorithm configuration values for the GuidanceController.