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.cpp
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
19#include <algorithm>
20
21namespace lightbar_manager
22{
23
24namespace std_ph = std::placeholders;
25
26LightBarManager::LightBarManager(const rclcpp::NodeOptions &options) : carma_ros2_utils::CarmaLifecycleNode(options)
27{
28 // Create initial config
29 config_ = Config();
30 config_.spin_rate_hz = declare_parameter<double>("spin_rate_hz", config_.spin_rate_hz);
31 config_.normal_operation = declare_parameter<bool>("normal_operation", config_.normal_operation);
32 declare_parameter("lightbar_cda_table", config_.lightbar_cda_table);
33 declare_parameter("lightbar_ind_table", config_.lightbar_ind_table);
34 declare_parameter("lightbar_priorities", config_.lightbar_priorities);
35 lbm_ = std::make_shared<LightBarManagerWorker>();
36}
37
38carma_ros2_utils::CallbackReturn LightBarManager::handle_on_configure(const rclcpp_lifecycle::State &)
39{
40 // Reset config
41 config_ = Config();
42
43 RCLCPP_INFO_STREAM(rclcpp::get_logger("lightbar_manager"),"Initalizing lightbar manager node...");
44
45 // Load the spin rate param to determine how fast to process messages
46 // Default rate 10.0 Hz
47 get_parameter<double>("spin_rate_hz", config_.spin_rate_hz);
48
49 request_control_server_= create_service<carma_msgs::srv::RequestIndicatorControl>("request_control", std::bind(&LightBarManager::requestControlCallBack, this, std_ph::_1, std_ph::_2, std_ph::_3));
50 release_control_server_= create_service<carma_msgs::srv::ReleaseIndicatorControl>("release_control", std::bind(&LightBarManager::releaseControlCallBack, this, std_ph::_1, std_ph::_2, std_ph::_3));
51 set_indicator_server_= create_service<carma_driver_msgs::srv::SetLightBarIndicator>("set_indicator", std::bind(&LightBarManager::setIndicatorCallBack, this, std_ph::_1, std_ph::_2, std_ph::_3));
52 indicator_control_publisher_ = create_publisher<carma_msgs::msg::LightBarIndicatorControllers>("indicator_control", 5);
53 guidance_state_subscriber_ = create_subscription<carma_planning_msgs::msg::GuidanceState>("state", 5, std::bind(&LightBarManager::stateChangeCallBack, this, std_ph::_1));
54 turn_signal_subscriber_ = create_subscription<automotive_platform_msgs::msg::TurnSignalCommand>("turn_signal_command", 5, std::bind(&LightBarManager::turnSignalCallback, this, std_ph::_1));
55 lightbar_driver_client_ = create_client<carma_driver_msgs::srv::SetLights>("set_lights");
56
57 // Load Conversion table, CDAType to Indicator mapping
58
59 rclcpp::Parameter lightbar_cda_table_param = get_parameter("lightbar_cda_table");
60 if (lightbar_cda_table_param.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET)
61 config_.lightbar_cda_table = lightbar_cda_table_param.as_string_array();
62
63 rclcpp::Parameter lightbar_ind_table_param = get_parameter("lightbar_ind_table");
64 if (lightbar_ind_table_param.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET)
65 config_.lightbar_ind_table = lightbar_ind_table_param.as_string_array();
66
68 {
69 throw std::invalid_argument("Size of lightbar_cda_table is not same as that of lightbar_ind_table");
70 }
71
73
74 // Initialize indicator control map. Fills with supporting indicators with empty string name as owners.
75 lbm_->setIndicatorControllers();
76
77 // Initialize indicator representation of lightbar status to all OFF
78 for (int i =0; i < INDICATOR_COUNT; i++)
79 lbm_->light_status.push_back(OFF);
80
81 rclcpp::Parameter lightbar_priorities_param = get_parameter("lightbar_priorities");
82 if (lightbar_priorities_param.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET)
83 {
84 config_.lightbar_priorities = lightbar_priorities_param.as_string_array();
85 lbm_->control_priorities = config_.lightbar_priorities;
86 }
87
88 // Take control of green light
89 get_parameter<bool>("normal_operation", config_.normal_operation);
90
91 RCLCPP_INFO_STREAM(rclcpp::get_logger("lightbar_manager"), "Loaded params: " << config_);
92
93 std::vector<LightBarIndicator> denied_list, greens = {GREEN_SOLID, GREEN_FLASH};
94
95 denied_list = lbm_->requestControl(greens, node_name_);
96 if (denied_list.size() != 0)
97 {
99 {
100 RCLCPP_WARN_STREAM(rclcpp::get_logger("lightbar_manager"),"In fuction " << __FUNCTION__ << ", LightBarManager was not able to take control of all green indicators."
101 << ".\n Please check priority list rosparameter, and ensure " << node_name_ << " has the highest priority."
102 << ".\n If this is intended, pass false to normal_operation argument. Exiting...");
104 }
105 else
106 {
107 RCLCPP_WARN_STREAM(rclcpp::get_logger("lightbar_manager"),"In fuction " << __FUNCTION__ << ", LightBarManager was not able to take control of all green indicators."
108 << ".\n Resuming...");
109 }
110 }
111 return CallbackReturn::SUCCESS;
112}
113
114carma_ros2_utils::CallbackReturn LightBarManager::handle_on_activate(const rclcpp_lifecycle::State &)
115{
116 pub_timer_ = create_timer(get_clock(),
117 std::chrono::milliseconds((int)(1 / config_.spin_rate_hz * 1000)),
118 std::bind(&LightBarManager::spinCallBack, this));
119 return CallbackReturn::SUCCESS;
120}
121
122carma_ros2_utils::CallbackReturn LightBarManager::handle_on_deactivate(const rclcpp_lifecycle::State &)
123{
124 // Deactivate the lightbar if deactivated
125 turnOffAll();
126 return CallbackReturn::SUCCESS;
127}
128
129carma_ros2_utils::CallbackReturn LightBarManager::handle_on_cleanup(const rclcpp_lifecycle::State &)
130{
131 // Cleanup the lightbar if cleaned up
132 turnOffAll();
133 return CallbackReturn::SUCCESS;
134}
135
136carma_ros2_utils::CallbackReturn LightBarManager::handle_on_error(const rclcpp_lifecycle::State &)
137{
138 // Cleanup the lightbar if error
139 turnOffAll();
140 return CallbackReturn::FAILURE; // By default an error will take us into the finalized sate.
141}
142
143carma_ros2_utils::CallbackReturn LightBarManager::handle_on_shutdown(const rclcpp_lifecycle::State &)
144{
145 // Cleanup the lightbar if shutdown
146 turnOffAll();
147 return CallbackReturn::SUCCESS; // By default shutdown will take us into the finalized state.
148}
149
151{
152 // All components lose controls and turn the indicators off by giving lightbarmanar the control
153 std::vector<LightBarIndicator> all_indicators;
154
155 RCLCPP_INFO_STREAM(rclcpp::get_logger("lightbar_manager"),"LightBarManager was commanded to turn off all indicators!");
156
157 for (std::pair <LightBarIndicator, std::string> element : lbm_->getIndicatorControllers())
158 all_indicators.push_back(element.first);
159
160 // Reset all controls
161 lbm_->setIndicatorControllers();
162
163 // Give lightbar manager the control which is guaranteed to succeed
164 lbm_->requestControl(all_indicators, node_name_);
165 int response_code = 0;
166 for (auto indicator : all_indicators)
167 {
168 response_code = setIndicator(indicator, OFF, node_name_);
169 if (response_code != 0)
170 RCLCPP_WARN_STREAM(rclcpp::get_logger("lightbar_manager"),"In Function " << __FUNCTION__ << ": LightBarManager was not able to turn off indicator ID:"
171 << indicator << ". Response code: " << response_code);
172 }
173
174 // Once forced them off, release controls in case carma is still running so that lightbar_manager does not hog the control
175 all_indicators.erase(std::remove(all_indicators.begin(), all_indicators.end(), GREEN_FLASH), all_indicators.end());
176 all_indicators.erase(std::remove(all_indicators.begin(), all_indicators.end(), GREEN_SOLID), all_indicators.end());
177 lbm_->releaseControl(all_indicators, node_name_);
178}
179
180bool LightBarManager::requestControlCallBack(const std::shared_ptr<rmw_request_id_t>,
181 const std::shared_ptr<carma_msgs::srv::RequestIndicatorControl::Request> req,
182 std::shared_ptr<carma_msgs::srv::RequestIndicatorControl::Response> resp)
183{
184 std::vector<LightBarIndicator> ind_list, controlled_ind_list;
185 std::vector<LightBarCDAType> controlled_cda_type_list;
186
187 // Use CDAType if the field is not empty in the request
188 if (req->cda_list.size() != 0)
189 {
190 for (auto cda_type : req->cda_list)
191 {
192 // return false if invalid cda_type number
193 if (static_cast<uint8_t>(cda_type.type) >= INDICATOR_COUNT)
194 return false;
195 ind_list.push_back(lbm_->getIndicatorFromCDAType(static_cast<LightBarCDAType>(cda_type.type)));
196 }
197 }
198 else
199 {
200 for (auto indicator : req->ind_list)
201 {
202 // return false if invalid indicator number
203 if (static_cast<uint8_t>(indicator.indicator) >= INDICATOR_COUNT)
204 return false;
205 ind_list.push_back(static_cast<LightBarIndicator>(indicator.indicator));
206 }
207
208 }
209
210 controlled_ind_list = lbm_->requestControl(ind_list, req->requester_name);
211
212 for (auto indicator : controlled_ind_list)
213 {
214 try
215 {
216 // Some indicators do not have mapped CDAType
217 controlled_cda_type_list.push_back(lbm_->getCDATypeFromIndicator(indicator));
218 }
220 {
221 // 4 out of 8 does not have mapping, so skip
222 continue;
223 }
224 }
225
226 // Modify the response
227 resp->cda_list = lbm_->getMsg(controlled_cda_type_list);
228 resp->ind_list = lbm_->getMsg(controlled_ind_list);
229 return true;
230}
231
232bool LightBarManager::releaseControlCallBack(const std::shared_ptr<rmw_request_id_t>,
233 const std::shared_ptr<carma_msgs::srv::ReleaseIndicatorControl::Request> req,
234 std::shared_ptr<carma_msgs::srv::ReleaseIndicatorControl::Response> resp)
235{
236 std::vector<LightBarIndicator> ind_list;
237
238 // Use CDAType if the field is not empty in the request
239 if (req->cda_list.size() != 0)
240 {
241 for (auto cda_type : req->cda_list)
242 {
243 // return false if invalid indicator number
244 if (static_cast<uint8_t>(cda_type.type) >= INDICATOR_COUNT)
245 return false;
246 ind_list.push_back(lbm_->getIndicatorFromCDAType(static_cast<LightBarCDAType>(cda_type.type)));
247 }
248 }
249 else
250 {
251 for (auto indicator : req->ind_list)
252 {
253 // return false if invalid cda_type number
254 if (static_cast<uint8_t>(indicator.indicator) >= INDICATOR_COUNT)
255 return false;
256 ind_list.push_back(static_cast<LightBarIndicator>(indicator.indicator));
257 }
258 }
259 lbm_->releaseControl(ind_list, req->requester_name);
260 return true;
261}
262
264{
265 indicator_control_publisher_->publish(lbm_->getMsg(lbm_->getIndicatorControllers()));
266 return true;
267}
268
269void LightBarManager::stateChangeCallBack(carma_planning_msgs::msg::GuidanceState::UniquePtr msg_ptr)
270{
271 // Relay the msg to state machine
272 LightBarState prev_lightbar_state = lbm_->getCurrentState();
273 lbm_->handleStateChange(*msg_ptr);
274
275 // Change green lights depending on states, no need to check if its current owner, as it will always be for green lights
276 LightBarState curr_lightbar_state = lbm_->getCurrentState();
277 if (curr_lightbar_state != prev_lightbar_state)
278 {
279 switch(curr_lightbar_state)
280 {
281 case DISENGAGED:
282 turnOffAll();
283 break;
284 case ACTIVE:
286 break;
287 case ENGAGED:
289 break;
290 default:
291 break;
292 }
293 }
294}
295
296void LightBarManager::turnSignalCallback(automotive_platform_msgs::msg::TurnSignalCommand::UniquePtr msg_ptr)
297{
298 return processTurnSignal(*msg_ptr);
299}
300
301void LightBarManager::processTurnSignal(const automotive_platform_msgs::msg::TurnSignalCommand& msg)
302{
303 // if not automated
304 if (msg.mode != 1)
305 {
306 return;
307 }
308
309 // check if left or right signal should be controlled, or none at all
310 std::vector<lightbar_manager::LightBarIndicator> changed_turn_signal = lbm_->handleTurnSignal(msg);
311
312
313 if (changed_turn_signal.empty())
314 {
315 return; //no need to do anything if it is same turn signal changed
316 }
317
318 lightbar_manager::IndicatorStatus indicator_status;
319 // check if we should turn off or on given any indicator
320 if (msg.turn_signal == automotive_platform_msgs::msg::TurnSignalCommand::NONE)
321 {
323 }
324 else
325 {
326 indicator_status = lightbar_manager::IndicatorStatus::ON;
327 prev_owners_before_turn_ = lbm_->getIndicatorControllers(); // save the owner if new turn is starting
328
329 }
330 if (lbm_->requestControl(changed_turn_signal, node_name_).empty())
331 {
332 int response_code = 0;
333 response_code = setIndicator(changed_turn_signal[0], indicator_status, node_name_);
334 if (response_code != 0)
335 RCLCPP_ERROR_STREAM(rclcpp::get_logger("lightbar_manager"),"In Function " << __FUNCTION__ << ": LightBarManager was not able to set light of indicator ID:"
336 << changed_turn_signal[0] << ". Response code: " << response_code);
337 }
338 else
339 {
340 std::string turn_string = msg.turn_signal == automotive_platform_msgs::msg::TurnSignalCommand::LEFT ? "left" : "right";
341 RCLCPP_WARN_STREAM(rclcpp::get_logger("lightbar_manager"),"Lightbar was not able to take control of lightbar to indicate " << turn_string << "turn!");
342 return;
343 }
344
345 // release control if it is turning off and put back the previous owners
346 if (indicator_status == lightbar_manager::IndicatorStatus::OFF)
347 {
348 lbm_->releaseControl(changed_turn_signal, node_name_);
349 // we need to force set the <indicator, owner> mapping
350 // as series of requestControl may not be able to exactly achieve previous combination
351 lbm_->setIndicatorControllers(prev_owners_before_turn_);
352 // reset as the turn is finished
354 }
355}
356
357std::shared_ptr<LightBarManagerWorker> LightBarManager::getWorker()
358{
359 return lbm_;
360}
361
362int LightBarManager::setIndicator(LightBarIndicator ind, IndicatorStatus ind_status, const std::string& requester_name)
363{
364 // Handle the msg/service translation
365 int response_code = 0;
366 if (static_cast<uint8_t>(ind) >= INDICATOR_COUNT || static_cast<uint8_t>(ind_status) > 1)
367 {
368 // Invalid indicator ID or ind_status
369 response_code = 1;
370 return response_code;
371 }
372
373 // Check if the requester has control of this light
374 std::string current_controller = lbm_->getIndicatorControllers()[ind];
375 if (requester_name == "" || current_controller != requester_name)
376 {
377 RCLCPP_WARN_STREAM(rclcpp::get_logger("lightbar_manager"),requester_name << " failed to set the LightBarIndicator ID" << ind
378 << " as this was already controlled by " << current_controller);
379 response_code = 1;
380 return response_code;
381 }
382
383 std::vector<IndicatorStatus> light_status_proposed = lbm_->setIndicator(ind, ind_status, requester_name);
384 carma_driver_msgs::msg::LightBarStatus msg = lbm_->getLightBarStatusMsg(light_status_proposed);
385 auto srv = std::make_shared<carma_driver_msgs::srv::SetLights::Request>();
386 srv->set_state = msg;
387
388 auto resp = lightbar_driver_client_->async_send_request(srv);
389
390 auto future_status = resp.wait_for(std::chrono::milliseconds(100));
391 // Try to send the request
392 if (future_status == std::future_status::ready)
393 {
394 // if successful, update the local copy.
395 lbm_->light_status = light_status_proposed;
396 response_code = 0;
397 }
398 else
399 {
400 RCLCPP_WARN_STREAM(rclcpp::get_logger("lightbar_manager"),"In function: " << __FUNCTION__ << ": Failed to set lights. ROSservice call to the driver failed. ");
401 response_code = 2;
402 }
403 return response_code;
404
405}
406
407bool LightBarManager::setIndicatorCallBack(const std::shared_ptr<rmw_request_id_t>,
408 const std::shared_ptr<carma_driver_msgs::srv::SetLightBarIndicator::Request> req,
409 std::shared_ptr<carma_driver_msgs::srv::SetLightBarIndicator::Response> resp)
410{
411 LightBarIndicator indicator;
412 int response_code = 0;
413 if (req->cda_type.type != NULL)
414 indicator = lbm_->getIndicatorFromCDAType(static_cast<LightBarCDAType>(req->cda_type.type));
415 else
416 indicator = static_cast<LightBarIndicator>(req->indicator.indicator);
417
418 response_code = setIndicator(indicator, static_cast<IndicatorStatus>(req->state), req->requester_name);
419 resp->status_code = response_code;
420 if (response_code != 0)
421 return false;
422
423 return true;
424}
425
426} // namespace lightbar_manager
427
428
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_error(const rclcpp_lifecycle::State &)
carma_ros2_utils::CallbackReturn handle_on_shutdown(const rclcpp_lifecycle::State &)
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::CallbackReturn handle_on_deactivate(const rclcpp_lifecycle::State &)
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_
std::shared_ptr< LightBarManagerWorker > lbm_
carma_ros2_utils::CallbackReturn handle_on_cleanup(const rclcpp_lifecycle::State &)
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)
#define INDICATOR_COUNT
std::vector< std::string > lightbar_priorities
std::vector< std::string > lightbar_cda_table
std::vector< std::string > lightbar_ind_table