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.
traffic_incident_parser_worker.hpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2019-2022 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 <rclcpp/rclcpp.hpp>
20#include <carma_v2x_msgs/msg/mobility_operation.hpp>
21#include <carma_v2x_msgs/msg/traffic_control_message_v01.hpp>
22#include <carma_v2x_msgs/msg/traffic_control_message.hpp>
23#include <std_msgs/msg/string.hpp>
24#include <functional>
25#include <iostream>
26#include <string>
27#include <sstream>
28#include <iostream>
29#include <string>
30#include <cstring>
31#include <vector>
32#include <algorithm>
33#include <sstream>
34#include <lanelet2_extension/projection/local_frame_projector.h>
35#include <lanelet2_core/geometry/Lanelet.h>
36#include <lanelet2_routing/RoutingGraph.h>
38#include <std_msgs/msg/string.h>
39#include <carma_wm/Geometry.hpp>
40
42
44{
45
46 public:
47
48 using PublishTrafficControlCallback = std::function<void(const carma_v2x_msgs::msg::TrafficControlMessage&)>;
49
54 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger, rclcpp::Clock::SharedPtr clock);
55
60 void georeferenceCallback(std_msgs::msg::String::UniquePtr projection_msg);
61
68 void mobilityOperationCallback(carma_v2x_msgs::msg::MobilityOperation::UniquePtr mobility_msg);
69
75 bool mobilityMessageParser(std::string mobility_strategy_params);
76
83 std::string stringParserHelper(std::string str, unsigned long str_index) const;
84
90 std::vector<carma_v2x_msgs::msg::TrafficControlMessageV01> composeTrafficControlMesssages();
91
96 lanelet::BasicPoint2d getIncidentOriginPoint() const;
97
105 void getAdjacentForwardCenterlines(const lanelet::ConstLanelets& adjacentSet,
106 const lanelet::BasicPoint2d& start_point, double downtrack, std::vector<std::vector<lanelet::BasicPoint2d>>* forward_lanes) const;
107
115 void getAdjacentReverseCenterlines(const lanelet::ConstLanelets& adjacentSet,
116 const lanelet::BasicPoint2d& start_point, double uptrack, std::vector<std::vector<lanelet::BasicPoint2d>>* reverse_lanes) const;
117
118 double latitude = 0.0;
119 double longitude = 0.0;
120 double down_track = 0.0;
121 double up_track = 0.0;
122 double min_gap = 0.0;
123 double speed_advisory = 0.0;
124 std::string event_reason;
125 std::string event_type;
126
128
129 private:
130
131 lanelet::BasicPoint2d local_point_;
132 std::string projection_msg_;
133 PublishTrafficControlCallback traffic_control_pub_;// local copy of external object publihsers
135 // Logger interface
136 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_;
137
138 rclcpp::Clock::SharedPtr clock_;
139};
140
141} // namespace traffic_incident_parser
std::function< void(const carma_v2x_msgs::msg::TrafficControlMessage &)> PublishTrafficControlCallback
std::string stringParserHelper(std::string str, unsigned long str_index) const
Function to help convert string to double data type.
TrafficIncidentParserWorker(carma_wm::WorldModelConstPtr wm, const PublishTrafficControlCallback &traffic_control_pub, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger, rclcpp::Clock::SharedPtr clock)
TrafficIncidentParserWorker constructor.
lanelet::BasicPoint2d getIncidentOriginPoint() const
Function to convert internally saved incident origin point from lat/lon to local map frame.
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_
std::vector< carma_v2x_msgs::msg::TrafficControlMessageV01 > composeTrafficControlMesssages()
Algorithm for extracting the closed lanelet from internally saved mobility message (or geofence) para...
bool mobilityMessageParser(std::string mobility_strategy_params)
Function to help parse incoming mobility operation messages to required format.
void georeferenceCallback(std_msgs::msg::String::UniquePtr projection_msg)
Callback for the georeference subscriber used to set the map projection.
void getAdjacentForwardCenterlines(const lanelet::ConstLanelets &adjacentSet, const lanelet::BasicPoint2d &start_point, double downtrack, std::vector< std::vector< lanelet::BasicPoint2d > > *forward_lanes) const
Helper method to compute the concatenated centerlines of the lanes in front of the emergency vehicle ...
void mobilityOperationCallback(carma_v2x_msgs::msg::MobilityOperation::UniquePtr mobility_msg)
Function to receive the incoming mobility operation message from the message node and publish the geo...
void getAdjacentReverseCenterlines(const lanelet::ConstLanelets &adjacentSet, const lanelet::BasicPoint2d &start_point, double uptrack, std::vector< std::vector< lanelet::BasicPoint2d > > *reverse_lanes) const
Helper method that is identical to getAdjacentForwardCenterlines except it works in reverse using upt...
std::shared_ptr< const WorldModel > WorldModelConstPtr
Definition: WorldModel.hpp:452