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.
light_controlled_intersection_tactical_plugin.hpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 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 <functional>
21#include <boost/uuid/uuid_generators.hpp>
22#include <boost/uuid/uuid_io.hpp>
23#include <boost/geometry.hpp>
24#include <boost/shared_ptr.hpp>
25#include <lanelet2_core/geometry/Point.h>
26#include <lanelet2_core/primitives/Lanelet.h>
27#include <lanelet2_core/geometry/LineString.h>
28#include <carma_planning_msgs/msg/trajectory_plan_point.hpp>
29#include <carma_planning_msgs/msg/trajectory_plan.hpp>
30#include <carma_planning_msgs/srv/plan_trajectory.hpp>
31#include <carma_planning_msgs/msg/maneuver.hpp>
32#include <autoware_msgs/msg/lane.hpp>
33#include <carma_debug_ros2_msgs/msg/trajectory_curvature_speeds.hpp>
36
38
45#define GET_MANEUVER_PROPERTY(mvr, property)\
46 (((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_LEFT_TURN ? (mvr).intersection_transit_left_turn_maneuver.property :\
47 ((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_RIGHT_TURN ? (mvr).intersection_transit_right_turn_maneuver.property :\
48 ((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_STRAIGHT ? (mvr).intersection_transit_straight_maneuver.property :\
49 ((mvr).type == carma_planning_msgs::msg::Maneuver::LANE_FOLLOWING ? (mvr).lane_following_maneuver.property :\
50 throw std::invalid_argument("GET_MANEUVER_PROPERTY (property) called on maneuver with invalid type id " + std::to_string((mvr).type)))))))
51
53{
57
58 enum TSCase {
59 CASE_1 = 1,
60 CASE_2 = 2,
61 CASE_3 = 3,
62 CASE_4 = 4,
63 CASE_5 = 5,
64 CASE_6 = 6,
65 CASE_7 = 7,
66 CASE_8 = 8,
67 };
68
70 double a1_ = 0;
71 double v1_ = 0;
72 double x1_ = 0;
73
74 double a2_ = 0;
75 double v2_ = 0;
76 double x2_ = 0;
77
78 double a3_ = 0;
79 double v3_ = 0;
80 double x3_ = 0;
81 };
82
88 {
89
90 private:
91 // World Model object
93
94 // Config for this object
96
97 std::shared_ptr<carma_ros2_utils::CarmaLifecycleNode> nh_;
98
99 // CARMA Streets Variables
100 // timestamp for msg received from carma streets
101 uint32_t street_msg_timestamp_ = 0.0;
102 // scheduled stop time
103 uint32_t scheduled_stop_time_ = 0.0;
104 // scheduled enter time
105 uint32_t scheduled_enter_time_ = 0.0;
106 // scheduled depart time
108 // scheduled latest depart time
110 // flag to show if the vehicle is allowed in intersection
111 bool is_allowed_int_ = false;
112
113 double speed_limit_ = 11.176; // Approximate speed limit; 25 mph by default
114 boost::optional<TSCase> last_case_;
115 boost::optional<bool> is_last_case_successful_;
116 carma_planning_msgs::msg::TrajectoryPlan last_trajectory_;
117 carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory> yield_client_;
118
119 carma_planning_msgs::msg::VehicleState ending_state_before_buffer_; //state before applying extra points for curvature calculation that are removed later
120
121 double epsilon_ = 0.001; //Small constant to compare (double) 0.0 with
122
123 // downtrack of host vehicle
124 double current_downtrack_ = 0.0;
125
126 double last_successful_ending_downtrack_; // if algorithm was successful, this is traffic_light_downtrack
127 double last_successful_scheduled_entry_time_; // if algorithm was successful, this is also scheduled entry time (ET in TSMO UC2 Algo)
128
129 std::string plugin_name_;
130 carma_debug_ros2_msgs::msg::TrajectoryCurvatureSpeeds debug_msg_;
131 std::vector<double> last_final_speeds_;
132
133 std::string light_controlled_intersection_strategy_ = "Carma/signalized_intersection"; // Strategy carma-streets is sending. Could be more verbose but needs to be changed on both ends
134
147 void applyTrajectorySmoothingAlgorithm(const carma_wm::WorldModelConstPtr& wm, std::vector<PointSpeedPair>& points_and_target_speeds, double start_dist, double remaining_dist,
148 double starting_speed, double departure_speed, TrajectoryParams tsp);
149
159 void applyOptimizedTargetSpeedProfile(const carma_planning_msgs::msg::Maneuver& maneuver, const double starting_speed, std::vector<PointSpeedPair>& points_and_target_speeds);
160
174 std::vector<PointSpeedPair> createGeometryProfile(const std::vector<carma_planning_msgs::msg::Maneuver> &maneuvers, double max_starting_downtrack,const carma_wm::WorldModelConstPtr &wm,
175 carma_planning_msgs::msg::VehicleState &ending_state_before_buffer,const carma_planning_msgs::msg::VehicleState& state,
176 const GeneralTrajConfig &general_config, const DetailedTrajConfig &detailed_config);
177
187 double findSpeedLimit(const lanelet::ConstLanelet& llt, const carma_wm::WorldModelConstPtr &wm) const;
188
191 FRIEND_TEST(LCITacticalPluginTest, createGeometryProfile);
192 FRIEND_TEST(LCITacticalPluginTest, planTrajectoryCB);
193 FRIEND_TEST(LCITacticalPluginTest, setConfig);
194
195 public:
196
200 LightControlledIntersectionTacticalPlugin(carma_wm::WorldModelConstPtr wm, const Config& config, const std::string& plugin_name,
201 std::shared_ptr<carma_ros2_utils::CarmaLifecycleNode> nh);
202
208 void planTrajectoryCB(
209 carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req,
210 carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp);
211
217 void set_yield_client(carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory> client);
218
223 void setConfig(const Config& config);
224 };
225
226} // light_controlled_intersection_tactical_plugin
Class containing primary business logic for the Light Controlled Intersection Tactical Plugin.
void planTrajectoryCB(carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req, carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp)
Function to process the light controlled intersection tactical plugin service call for trajectory pla...
void applyTrajectorySmoothingAlgorithm(const carma_wm::WorldModelConstPtr &wm, std::vector< PointSpeedPair > &points_and_target_speeds, double start_dist, double remaining_dist, double starting_speed, double departure_speed, TrajectoryParams tsp)
Creates a speed profile according to case one or two of the light controlled intersection,...
FRIEND_TEST(LCITacticalPluginTest, applyOptimizedTargetSpeedProfile)
void applyOptimizedTargetSpeedProfile(const carma_planning_msgs::msg::Maneuver &maneuver, const double starting_speed, std::vector< PointSpeedPair > &points_and_target_speeds)
Apply optimized target speeds to the trajectory determined for fixed-time and actuated signals....
double findSpeedLimit(const lanelet::ConstLanelet &llt, const carma_wm::WorldModelConstPtr &wm) const
Given a Lanelet, find it's associated Speed Limit.
FRIEND_TEST(LCITacticalPluginTest, applyTrajectorySmoothingAlgorithm)
void set_yield_client(carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > client)
set the yield service
LightControlledIntersectionTacticalPlugin(carma_wm::WorldModelConstPtr wm, const Config &config, const std::string &plugin_name, std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > nh)
LightControlledIntersectionTacticalPlugin constructor.
std::vector< PointSpeedPair > createGeometryProfile(const std::vector< carma_planning_msgs::msg::Maneuver > &maneuvers, double max_starting_downtrack, const carma_wm::WorldModelConstPtr &wm, carma_planning_msgs::msg::VehicleState &ending_state_before_buffer, const carma_planning_msgs::msg::VehicleState &state, const GeneralTrajConfig &general_config, const DetailedTrajConfig &detailed_config)
Creates geometry profile to return a point speed pair struct for INTERSECTION_TRANSIT maneuver types ...
std::shared_ptr< const WorldModel > WorldModelConstPtr
Definition: WorldModel.hpp:452
basic_autonomy::waypoint_generation::PointSpeedPair PointSpeedPair
basic_autonomy::waypoint_generation::DetailedTrajConfig DetailedTrajConfig
basic_autonomy::waypoint_generation::GeneralTrajConfig GeneralTrajConfig
Stuct containing the algorithm configuration values for light_controlled_intersection_tactical_plugin...