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.
lightbar_manager_node.hpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2023 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
16
17#pragma once
18
19#include <string>
20#include <rclcpp/rclcpp.hpp>
21#include <carma_ros2_utils/carma_lifecycle_node.hpp>
22
23#include <vector>
24#include <map>
25
26#include <carma_msgs/msg/light_bar_cda_type.hpp>
27#include <carma_msgs/msg/light_bar_indicator.hpp>
28#include <carma_msgs/msg/light_bar_indicator_controllers.hpp>
29#include <carma_driver_msgs/msg/light_bar_status.hpp>
30#include <carma_planning_msgs/msg/guidance_state.hpp>
31#include <automotive_platform_msgs/msg/turn_signal_command.hpp>
32
33#include <carma_msgs/srv/request_indicator_control.hpp>
34#include <carma_msgs/srv/release_indicator_control.hpp>
35#include <carma_driver_msgs/srv/set_light_bar_indicator.hpp>
36#include <carma_driver_msgs/srv/set_lights.hpp>
37
39
41{
42
46struct Config
47{
48 double spin_rate_hz = 10.0;
49 bool normal_operation = true; // if false, other plugins are able to take control over the lightbar status
50 std::vector<std::string> lightbar_priorities = {}; // Tsesters are for unit testing. Keep it there.
51 std::vector<std::string> lightbar_cda_table = {}; // Keys for lightbar_cda_to_ind_table, 1-to-1 with lightbar_ind_table
52 std::vector<std::string> lightbar_ind_table = {}; // Values for lightbar_cda_to_ind_table, 1-to-1 with lightbar_cda_table
53
54 // Stream operator for this config
55 friend std::ostream &operator<<(std::ostream &output, const Config &c)
56 {
57 output << "LightBarManager::Config { " << std::endl
58 << "spin_rate_hz: " << c.spin_rate_hz << std::endl
59 << "lightbar_priorities.size(): " << c.lightbar_priorities.size() << std::endl
60 << "lightbar_cda_table.size(): " << c.lightbar_cda_table.size() << std::endl
61 << "lightbar_ind_table.size(): " << c.lightbar_ind_table.size() << std::endl
62 << "}" << std::endl;
63 return output;
64 }
65
66};
67
68class LightBarManager : public carma_ros2_utils::CarmaLifecycleNode
69{
70 public:
71
77 explicit LightBarManager(const rclcpp::NodeOptions &);
78
83 std::shared_ptr<LightBarManagerWorker> getWorker();
84
89 void turnOffAll();
90
95 int setIndicator(LightBarIndicator ind, IndicatorStatus ind_status, const std::string& requester_name);
96
101 void turnSignalCallback(automotive_platform_msgs::msg::TurnSignalCommand::UniquePtr msg_ptr);
102
104 // Overrides
106 carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &);
107 carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &);
108
109 private:
110
112
117 void processTurnSignal(const automotive_platform_msgs::msg::TurnSignalCommand& msg);
118
119 // Node Data
120 std::string node_name_ = "lightbar_manager";
121 double spin_rate_ = 10.0;
122 std::map<lightbar_manager::LightBarIndicator, std::string> prev_owners_before_turn_;
123
124 // spin callback function
125 bool spinCallBack();
126
127 // Message/service callbacks
128 bool requestControlCallBack(const std::shared_ptr<rmw_request_id_t>,
129 const std::shared_ptr<carma_msgs::srv::RequestIndicatorControl::Request> req,
130 std::shared_ptr<carma_msgs::srv::RequestIndicatorControl::Response> resp);
131 bool releaseControlCallBack(const std::shared_ptr<rmw_request_id_t>,
132 const std::shared_ptr<carma_msgs::srv::ReleaseIndicatorControl::Request> req,
133 std::shared_ptr<carma_msgs::srv::ReleaseIndicatorControl::Response> resp);
134 bool setIndicatorCallBack(const std::shared_ptr<rmw_request_id_t>,
135 const std::shared_ptr<carma_driver_msgs::srv::SetLightBarIndicator::Request> req,
136 std::shared_ptr<carma_driver_msgs::srv::SetLightBarIndicator::Response> resp);
137 void stateChangeCallBack(carma_planning_msgs::msg::GuidanceState::UniquePtr msg_ptr);
138
139 // Service servers/clients
140 carma_ros2_utils::ServicePtr<carma_msgs::srv::RequestIndicatorControl> request_control_server_;
141 carma_ros2_utils::ServicePtr<carma_msgs::srv::ReleaseIndicatorControl> release_control_server_;
142 carma_ros2_utils::ServicePtr<carma_driver_msgs::srv::SetLightBarIndicator> set_indicator_server_;
143 carma_ros2_utils::ClientPtr<carma_driver_msgs::srv::SetLights> lightbar_driver_client_;
144
145 // Publishers
146 carma_ros2_utils::PubPtr<carma_msgs::msg::LightBarIndicatorControllers> indicator_control_publisher_;
147
148 // Subscribers
149 carma_ros2_utils::SubPtr<carma_planning_msgs::msg::GuidanceState> guidance_state_subscriber_;
150 carma_ros2_utils::SubPtr<automotive_platform_msgs::msg::TurnSignalCommand> turn_signal_subscriber_;
151
152 // LightBarManager Worker
153 std::shared_ptr<LightBarManagerWorker> lbm_;
154
155 rclcpp::TimerBase::SharedPtr pub_timer_;
156
157 FRIEND_TEST(LightBarManagerNodeTest, testSetIndicator);
158 FRIEND_TEST(LightBarManagerNodeTest, testTurnOffAll);
159 FRIEND_TEST(LightBarManagerNodeTest, testTurnSignalCallback);
160
161}; //class LightBarManagerNode
162} // namespace lightbar_manager
163
164#include "rclcpp_components/register_node_macro.hpp"
165
166// Register the component with class_loader
167RCLCPP_COMPONENTS_REGISTER_NODE(lightbar_manager::LightBarManager)
void turnOffAll()
Miscellaneous function that forces the state to disengaged and turn off all indicators....
carma_ros2_utils::PubPtr< carma_msgs::msg::LightBarIndicatorControllers > indicator_control_publisher_
void turnSignalCallback(automotive_platform_msgs::msg::TurnSignalCommand::UniquePtr msg_ptr)
Callback function for turning signal.
carma_ros2_utils::SubPtr< automotive_platform_msgs::msg::TurnSignalCommand > turn_signal_subscriber_
carma_ros2_utils::ClientPtr< carma_driver_msgs::srv::SetLights > lightbar_driver_client_
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &)
bool requestControlCallBack(const std::shared_ptr< rmw_request_id_t >, const std::shared_ptr< carma_msgs::srv::RequestIndicatorControl::Request > req, std::shared_ptr< carma_msgs::srv::RequestIndicatorControl::Response > resp)
std::shared_ptr< LightBarManagerWorker > getWorker()
Get ptr to lightbar_manager_worker (for ease of unit testing)
carma_ros2_utils::ServicePtr< carma_msgs::srv::ReleaseIndicatorControl > release_control_server_
void processTurnSignal(const automotive_platform_msgs::msg::TurnSignalCommand &msg)
Turn signal callback function helper.
bool releaseControlCallBack(const std::shared_ptr< rmw_request_id_t >, const std::shared_ptr< carma_msgs::srv::ReleaseIndicatorControl::Request > req, std::shared_ptr< carma_msgs::srv::ReleaseIndicatorControl::Response > resp)
carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &)
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::GuidanceState > guidance_state_subscriber_
int setIndicator(LightBarIndicator ind, IndicatorStatus ind_status, const std::string &requester_name)
Try to turn the given indicator ON or OFF (comm with hardware) upon the given component's request.
std::map< lightbar_manager::LightBarIndicator, std::string > prev_owners_before_turn_
FRIEND_TEST(LightBarManagerNodeTest, testTurnOffAll)
FRIEND_TEST(LightBarManagerNodeTest, testTurnSignalCallback)
std::shared_ptr< LightBarManagerWorker > lbm_
FRIEND_TEST(LightBarManagerNodeTest, testSetIndicator)
void stateChangeCallBack(carma_planning_msgs::msg::GuidanceState::UniquePtr msg_ptr)
LightBarManager(const rclcpp::NodeOptions &)
carma_ros2_utils::ServicePtr< carma_driver_msgs::srv::SetLightBarIndicator > set_indicator_server_
carma_ros2_utils::ServicePtr< carma_msgs::srv::RequestIndicatorControl > request_control_server_
rclcpp::TimerBase::SharedPtr pub_timer_
bool setIndicatorCallBack(const std::shared_ptr< rmw_request_id_t >, const std::shared_ptr< carma_driver_msgs::srv::SetLightBarIndicator::Request > req, std::shared_ptr< carma_driver_msgs::srv::SetLightBarIndicator::Response > resp)
std::vector< std::string > lightbar_priorities
std::vector< std::string > lightbar_cda_table
std::vector< std::string > lightbar_ind_table
friend std::ostream & operator<<(std::ostream &output, const Config &c)