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.
lci_strategic_plugin.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 */
18
19#define EPSILON 0.01
20
21#define GET_MANEUVER_PROPERTY(mvr, property) \
22 (((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_LEFT_TURN ? \
23 (mvr).intersection_transit_left_turn_maneuver.property : \
24 ((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_RIGHT_TURN ? \
25 (mvr).intersection_transit_right_turn_maneuver.property : \
26 ((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_STRAIGHT ? \
27 (mvr).intersection_transit_straight_maneuver.property : \
28 ((mvr).type == carma_planning_msgs::msg::Maneuver::LANE_CHANGE ? (mvr).lane_change_maneuver.property : \
29 (mvr).type == carma_planning_msgs::msg::Maneuver::LANE_FOLLOWING ? (mvr).lane_following_maneuver.property : \
30 throw new std::invalid_argument("GET_MANEUVER_" \
31 "PROPERTY " \
32 "(property) " \
33 "called on " \
34 "maneuver with " \
35 "invalid type " \
36 "id"))))))
37
39{
40 namespace std_ph = std::placeholders;
41
42LCIStrategicPlugin::LCIStrategicPlugin(const rclcpp::NodeOptions &options)
43 : carma_guidance_plugins::StrategicPlugin(options), tf2_buffer_(this->get_clock())
44{
46
47 config_.vehicle_accel_limit = declare_parameter<double>("vehicle_acceleration_limit", config_.vehicle_accel_limit);
48 config_.vehicle_decel_limit = declare_parameter<double>("vehicle_deceleration_limit", config_.vehicle_decel_limit);
49 config_.vehicle_decel_limit_multiplier = declare_parameter<double>("vehicle_decel_limit_multiplier", config_.vehicle_decel_limit_multiplier);
50 config_.vehicle_accel_limit_multiplier = declare_parameter<double>("vehicle_accel_limit_multiplier", config_.vehicle_accel_limit_multiplier);
51 config_.min_approach_distance = declare_parameter<double>("min_approach_distance", config_.min_approach_distance);
52 config_.trajectory_smoothing_activation_distance = declare_parameter<double>("trajectory_smoothing_activation_distance", config_.trajectory_smoothing_activation_distance);
53 config_.stopping_location_buffer = declare_parameter<double>("stopping_location_buffer", config_.stopping_location_buffer);
54 config_.green_light_time_buffer = declare_parameter<double>("green_light_time_buffer", config_.green_light_time_buffer);
55 config_.algo_minimum_speed = declare_parameter<double>("algo_minimum_speed", config_.algo_minimum_speed);
56 config_.deceleration_fraction = declare_parameter<double>("deceleration_fraction", config_.deceleration_fraction);
57 config_.desired_distance_to_stop_buffer = declare_parameter<double>("desired_distance_to_stop_buffer", config_.desired_distance_to_stop_buffer);
58 config_.min_maneuver_planning_period = declare_parameter<double>("min_maneuver_planning_period", config_.min_maneuver_planning_period);
59 config_.strategic_plugin_name = declare_parameter<std::string>("strategic_plugin_name", config_.strategic_plugin_name);
60 config_.lane_following_plugin_name = declare_parameter<std::string>("lane_following_plugin_name", config_.lane_following_plugin_name);
61 config_.stop_and_wait_plugin_name = declare_parameter<std::string>("stop_and_wait_plugin_name", config_.stop_and_wait_plugin_name);
62 config_.intersection_transit_plugin_name = declare_parameter<std::string>("intersection_transit_plugin_name", config_.intersection_transit_plugin_name);
63 config_.enable_carma_streets_connection = declare_parameter<bool>("enable_carma_streets_connection",config_.enable_carma_streets_connection);
64 config_.mobility_rate = declare_parameter<double>("mobility_rate", config_.mobility_rate);
65 config_.vehicle_id = declare_parameter<std::string>("vehicle_id", config_.vehicle_id);
66
71};
72
73carma_ros2_utils::CallbackReturn LCIStrategicPlugin::on_configure_plugin()
74{
75 // reset config
77
78 // clang-format off
79 get_parameter<double>("vehicle_acceleration_limit", config_.vehicle_accel_limit);
80 get_parameter<double>("vehicle_deceleration_limit", config_.vehicle_decel_limit);
81 get_parameter<double>("vehicle_decel_limit_multiplier", config_.vehicle_decel_limit_multiplier);
82 get_parameter<double>("vehicle_accel_limit_multiplier", config_.vehicle_accel_limit_multiplier);
83 get_parameter<double>("min_approach_distance", config_.min_approach_distance);
84 get_parameter<double>("trajectory_smoothing_activation_distance", config_.trajectory_smoothing_activation_distance);
85 get_parameter<double>("stopping_location_buffer", config_.stopping_location_buffer);
86 get_parameter<double>("green_light_time_buffer", config_.green_light_time_buffer);
87 get_parameter<double>("algo_minimum_speed", config_.algo_minimum_speed);
88 get_parameter<double>("deceleration_fraction", config_.deceleration_fraction);
89 get_parameter<double>("desired_distance_to_stop_buffer", config_.desired_distance_to_stop_buffer);
90 get_parameter<double>("min_maneuver_planning_period", config_.min_maneuver_planning_period);
91 get_parameter<std::string>("strategic_plugin_name", config_.strategic_plugin_name);
92 get_parameter<std::string>("lane_following_plugin_name", config_.lane_following_plugin_name);
93 get_parameter<std::string>("stop_and_wait_plugin_name", config_.stop_and_wait_plugin_name);
94 get_parameter<std::string>("intersection_transit_plugin_name", config_.intersection_transit_plugin_name);
95 get_parameter<bool>("enable_carma_streets_connection", config_.enable_carma_streets_connection);
96 get_parameter<double>("mobility_rate", config_.mobility_rate);
97 get_parameter<std::string>("vehicle_id", config_.vehicle_id);
98
103
104 // clang-format on
105
106 // Register runtime parameter update callback
107 add_on_set_parameters_callback(std::bind(&LCIStrategicPlugin::parameter_update_callback, this, std_ph::_1));
108
109 RCLCPP_INFO_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Done loading parameters: " << config_);
110
112
113 // Mobility Operation Subscriber
114 mob_operation_sub_ = create_subscription<carma_v2x_msgs::msg::MobilityOperation>("incoming_mobility_operation", 1,
115 std::bind(&LCIStrategicPlugin::mobilityOperationCb,this,std_ph::_1));
116
117 // BSM subscriber
118 bsm_sub_ = create_subscription<carma_v2x_msgs::msg::BSM>("bsm_outbound", 1,
119 std::bind(&LCIStrategicPlugin::BSMCb,this,std_ph::_1));
120
121 // set world model point form wm listener
123
124 // Setup publishers
125 mobility_operation_pub_ = create_publisher<carma_v2x_msgs::msg::MobilityOperation>("outgoing_mobility_operation", 1);
126 case_pub_ = create_publisher<std_msgs::msg::Int8>("lci_strategic_plugin/ts_case_num", 1);
127 tf_distance_pub_ = create_publisher<std_msgs::msg::Float64>("lci_strategic_plugin/distance_remaining_to_tf", 1);
128 earliest_et_pub_ = create_publisher<std_msgs::msg::Float64>("lci_strategic_plugin/earliest_entry_time", 1);
129 et_pub_ = create_publisher<std_msgs::msg::Float64>("lci_strategic_plugin/scheduled_entry_time", 1);
130
131 // Return success if everything initialized successfully
132 return CallbackReturn::SUCCESS;
133}
134
135rcl_interfaces::msg::SetParametersResult LCIStrategicPlugin::parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters)
136{
137 auto error_double = update_params<double>({
138 {"vehicle_acceleration_limit", config_.vehicle_accel_limit},
139 {"vehicle_deceleration_limit", config_.vehicle_decel_limit},
140 {"vehicle_decel_limit_multiplier", config_.vehicle_decel_limit_multiplier},
141 {"vehicle_accel_limit_multiplier", config_.vehicle_accel_limit_multiplier},
142 {"min_approach_distance", config_.min_approach_distance},
143 {"trajectory_smoothing_activation_distance", config_.trajectory_smoothing_activation_distance},
144 {"stopping_location_buffer", config_.stopping_location_buffer},
145 {"green_light_time_buffer", config_.green_light_time_buffer},
146 {"algo_minimum_speed", config_.algo_minimum_speed},
147 {"deceleration_fraction", config_.deceleration_fraction},
148 {"desired_distance_to_stop_buffer", config_.desired_distance_to_stop_buffer},
149 {"min_maneuver_planning_period", config_.min_maneuver_planning_period},
150 {"mobility_rate", config_.mobility_rate},
151 }, parameters);
152
153 rcl_interfaces::msg::SetParametersResult result;
154
155 result.successful = !error_double;
156
157 return result;
158}
159
161{
162 std_msgs::msg::Int8 case_num_msg;
163 std_msgs::msg::Float64 tf_distance;
164 std_msgs::msg::Float64 earliest_et;
165 std_msgs::msg::Float64 scheduled_et;
166
167 case_num_msg.data = static_cast<int>(last_case_num_);
168 tf_distance.data = distance_remaining_to_tf_;
169 earliest_et.data = earliest_entry_time_;
170 scheduled_et.data = scheduled_entry_time_;
171
172 case_pub_->publish(case_num_msg);
173 tf_distance_pub_->publish(tf_distance);
174 earliest_et_pub_->publish(earliest_et);
175 et_pub_->publish(scheduled_et);
176}
177
178carma_ros2_utils::CallbackReturn LCIStrategicPlugin::on_activate_plugin()
179{
180 mob_op_pub_timer_ = create_timer(get_clock(),
181 std::chrono::duration<double>(1/config_.mobility_rate),
183
184 ts_info_pub_timer_ = create_timer(get_clock(),
185 std::chrono::duration<double>(0.5),
187
188 return CallbackReturn::SUCCESS;
189}
190
191bool LCIStrategicPlugin::supportedLightState(lanelet::CarmaTrafficSignalState state) const
192{
193 switch (state)
194 {
195 // NOTE: Following cases are intentional fall through.
196 // Supported light states
197 case lanelet::CarmaTrafficSignalState::STOP_AND_REMAIN: // Solid Red
198 case lanelet::CarmaTrafficSignalState::PROTECTED_CLEARANCE: // Yellow Solid no chance of conflicting traffic
199 case lanelet::CarmaTrafficSignalState::PERMISSIVE_MOVEMENT_ALLOWED: // Solid Green there could be conflict traffic
200 case lanelet::CarmaTrafficSignalState::PROTECTED_MOVEMENT_ALLOWED: // Solid Green no chance of conflict traffic
201 // (normally used with arrows)
202 return true;
203
204 // Unsupported light states
205 case lanelet::CarmaTrafficSignalState::PERMISSIVE_CLEARANCE: // Yellow Solid there is a chance of conflicting
206 // traffic
207 case lanelet::CarmaTrafficSignalState::UNAVAILABLE: // No data available
208 case lanelet::CarmaTrafficSignalState::DARK: // Light is non-functional
209 case lanelet::CarmaTrafficSignalState::STOP_THEN_PROCEED: // Flashing Red
210
211 case lanelet::CarmaTrafficSignalState::PRE_MOVEMENT: // Yellow Red transition (Found only in the EU)
212 // (normally used with arrows)
213 case lanelet::CarmaTrafficSignalState::CAUTION_CONFLICTING_TRAFFIC: // Yellow Flashing
214 default:
215 return false;
216 }
217}
218
220{
221 tf2_listener_.reset(new tf2_ros::TransformListener(tf2_buffer_));
222 tf2_buffer_.setUsingDedicatedThread(true);
223 try
224 {
225 geometry_msgs::msg::TransformStamped tf2 = tf2_buffer_.lookupTransform("base_link", "vehicle_front", rclcpp::Time(0), rclcpp::Duration(20.0 * 1e9)); //save to local copy of transform 20 sec timeout
226 length_to_front_bumper_ = tf2.transform.translation.x;
227 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "length_to_front_bumper_: " << length_to_front_bumper_);
228
229 }
230 catch (const tf2::TransformException &ex)
231 {
232 RCLCPP_WARN_STREAM(rclcpp::get_logger("lci_strategic_plugin"), ex.what());
233 }
234}
235
236LCIStrategicPlugin::VehicleState LCIStrategicPlugin::extractInitialState(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req) const
237{
238 VehicleState state;
239 if (!req->prior_plan.maneuvers.empty())
240 {
241 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Provided with initial plan...");
242 state.stamp = GET_MANEUVER_PROPERTY(req->prior_plan.maneuvers.back(), end_time);
243 state.downtrack = GET_MANEUVER_PROPERTY(req->prior_plan.maneuvers.back(), end_dist);
244 state.speed = GET_MANEUVER_PROPERTY(req->prior_plan.maneuvers.back(), end_speed);
245 state.lane_id = getLaneletsBetweenWithException(state.downtrack, state.downtrack, true).front().id();
246 }
247 else
248 {
249 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "No initial plan provided...");
250
251 state.stamp = rclcpp::Time(req->header.stamp, RCL_SYSTEM_TIME);
252 state.downtrack = req->veh_downtrack;
253 state.speed = req->veh_logitudinal_velocity;
254 state.lane_id = stoi(req->veh_lane_id);
255 }
256 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "extractInitialState >>>> state.stamp: " << std::to_string(state.stamp.seconds()));
257 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "extractInitialState >>>> state.downtrack : " << state.downtrack );
258 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "extractInitialState >>>> state.speed: " << state.speed);
259 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "extractInitialState >>>> state.lane_id: " << state.lane_id);
260
261 return state;
262}
263
264double LCIStrategicPlugin::findSpeedLimit(const lanelet::ConstLanelet& llt) const
265{
266 lanelet::Optional<carma_wm::TrafficRulesConstPtr> traffic_rules = wm_->getTrafficRules();
267 if (traffic_rules)
268 {
269 return (*traffic_rules)->speedLimit(llt).speedLimit.value();
270 }
271 else
272 {
273 throw std::invalid_argument("Valid traffic rules object could not be built");
274 }
275}
276
277bool LCIStrategicPlugin::validLightState(const boost::optional<std::pair<boost::posix_time::ptime, lanelet::CarmaTrafficSignalState>>& optional_state,
278 const rclcpp::Time& source_time) const
279{
280 if (!optional_state)
281 {
282 RCLCPP_WARN_STREAM(rclcpp::get_logger("lci_strategic_plugin"),"Traffic light data not available for source_time " << std::to_string(source_time.seconds()));
283 return false;
284 }
285
286 lanelet::CarmaTrafficSignalState light_state = optional_state.get().second;
287
288 if (!supportedLightState(light_state))
289 {
290 RCLCPP_ERROR_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "LCIStrategic Plugin asked to handle CarmaTrafficSignalState: " << light_state
291 << " which is not supported.");
292 return false;
293 }
294
295 return true;
296}
297
298boost::optional<bool> LCIStrategicPlugin::canArriveAtGreenWithCertainty(const rclcpp::Time& light_arrival_time_by_algo, const lanelet::CarmaTrafficSignalPtr& traffic_light, bool check_late = true, bool check_early = true) const
299{
300 rclcpp::Time early_arrival_time_by_algo =
301 light_arrival_time_by_algo - rclcpp::Duration(config_.green_light_time_buffer * 1e9);
302
303 rclcpp::Time late_arrival_time_by_algo =
304 light_arrival_time_by_algo + rclcpp::Duration(config_.green_light_time_buffer * 1e9);
305
306 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "light_arrival_time_by_algo: " << std::to_string(light_arrival_time_by_algo.seconds()));
307 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "early_arrival_time_by_algo: " << std::to_string(early_arrival_time_by_algo.seconds()));
308 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "late_arrival_time_by_algo: " << std::to_string(late_arrival_time_by_algo.seconds()));
309
310 auto early_arrival_state_by_algo_optional = traffic_light->predictState(lanelet::time::timeFromSec(early_arrival_time_by_algo.seconds()));
311
312 if (!validLightState(early_arrival_state_by_algo_optional, early_arrival_time_by_algo))
313 return boost::none;
314
315 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "early_arrival_state_by_algo: " << early_arrival_state_by_algo_optional.get().second);
316
317 auto late_arrival_state_by_algo_optional = traffic_light->predictState(lanelet::time::timeFromSec(late_arrival_time_by_algo.seconds()));
318
319 if (!validLightState(late_arrival_state_by_algo_optional, late_arrival_time_by_algo))
320 return boost::none;
321
322 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "late_arrival_state_by_algo: " << late_arrival_state_by_algo_optional.get().second);
323
324 bool can_make_early_arrival = true;
325 bool can_make_late_arrival = true;
326
327 if (check_early)
328 can_make_early_arrival = isStateAllowedGreen(early_arrival_state_by_algo_optional.get().second);
329
330 if (check_late)
331 can_make_late_arrival = isStateAllowedGreen(late_arrival_state_by_algo_optional.get().second);
332
333 // We will cross the light on the green phase even if we arrive early or late
334 if (can_make_early_arrival && can_make_late_arrival) // Green light
335 return true;
336 else
337 return false;
338
339}
340
341bool LCIStrategicPlugin::isStateAllowedGreen(const lanelet::CarmaTrafficSignalState& state) const{
342 return state == lanelet::CarmaTrafficSignalState::PROTECTED_MOVEMENT_ALLOWED ||
343 state == lanelet::CarmaTrafficSignalState::PERMISSIVE_MOVEMENT_ALLOWED;
344}
345
346std::vector<lanelet::ConstLanelet> LCIStrategicPlugin::getLaneletsBetweenWithException(double start_downtrack,
347 double end_downtrack,
348 bool shortest_path_only,
349 bool bounds_inclusive) const
350{
351 std::vector<lanelet::ConstLanelet> crossed_lanelets =
352 wm_->getLaneletsBetween(start_downtrack, end_downtrack, shortest_path_only, bounds_inclusive);
353
354 if (crossed_lanelets.size() == 0)
355 {
356 throw std::invalid_argument("getLaneletsBetweenWithException called but inputs do not cross any lanelets going "
357 "from: " +
358 std::to_string(start_downtrack) + " to: " + std::to_string(end_downtrack));
359 }
360
361 return crossed_lanelets;
362}
363
364void LCIStrategicPlugin::handleStopping(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
365 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
366 const VehicleState& current_state,
367 const lanelet::CarmaTrafficSignalPtr& traffic_light,
368 const lanelet::ConstLanelet& entry_lanelet, const lanelet::ConstLanelet& exit_lanelet, const lanelet::ConstLanelet& current_lanelet,
369 double traffic_light_down_track,
370 bool is_emergency)
371{
372 double distance_remaining_to_traffic_light = traffic_light_down_track - current_state.downtrack;
373
374 // Identify the lanelets which will be crossed by approach maneuvers lane follow maneuver
375 std::vector<lanelet::ConstLanelet> crossed_lanelets =
376 getLaneletsBetweenWithException(current_state.downtrack, traffic_light_down_track, true, true);
377
378 double decel_rate = max_comfort_decel_norm_; // Kinematic |(v_f - v_i) / t = a|
379
380 if (is_emergency)
381 {
382 decel_rate = emergency_decel_norm_;
384 }
385 else
386 {
388 }
389
390 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "HANDLE_STOPPING: Planning stop and wait maneuver at decel_rate: " << decel_rate);
391
392 resp->new_plan.maneuvers.push_back(composeStopAndWaitManeuverMessage(
393 current_state.downtrack, traffic_light_down_track, current_state.speed, crossed_lanelets.front().id(),
394 crossed_lanelets.back().id(), current_state.stamp,
395 current_state.stamp + rclcpp::Duration(config_.min_maneuver_planning_period * 1e9), decel_rate));
396}
397
398
399void LCIStrategicPlugin::handleFailureCase(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
400 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
401 const VehicleState& current_state,
402 double current_state_speed,
403 double speed_limit,
404 double remaining_time,
405 lanelet::Id exit_lanelet_id,
406 const lanelet::CarmaTrafficSignalPtr& traffic_light,
407 double traffic_light_down_track, const TrajectoryParams& ts_params)
408{
409 double distance_remaining_to_traffic_light = traffic_light_down_track - current_state.downtrack;
410
411 // Identify the lanelets which will be crossed by approach maneuvers lane follow maneuver
412 std::vector<lanelet::ConstLanelet> crossed_lanelets =
413 getLaneletsBetweenWithException(current_state.downtrack, traffic_light_down_track, true, true);
414
415 auto incomplete_traj_params = handleFailureCaseHelper(traffic_light, current_state.stamp.seconds(), current_state_speed, intersection_speed_.get(), speed_limit, distance_remaining_to_traffic_light, traffic_light_down_track);
416
417 if (incomplete_traj_params.is_algorithm_successful == false)
418 {
419 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Failed to generate maneuver for edge cases...");
420 return;
421 }
422
423 resp->new_plan.maneuvers.push_back(composeTrajectorySmoothingManeuverMessage(current_state.downtrack, traffic_light_down_track, crossed_lanelets,
424 current_state_speed, incomplete_traj_params.modified_departure_speed, current_state.stamp, current_state.stamp + rclcpp::Duration(incomplete_traj_params.modified_remaining_time * 1e9), incomplete_traj_params));
425
426 double intersection_length = intersection_end_downtrack_.get() - traffic_light_down_track;
427
428 rclcpp::Time intersection_exit_time =
429 current_state.stamp + rclcpp::Duration(incomplete_traj_params.modified_remaining_time * 1e9) + rclcpp::Duration(intersection_length / incomplete_traj_params.modified_departure_speed * 1e9);
430
431 resp->new_plan.maneuvers.push_back(composeIntersectionTransitMessage(
432 traffic_light_down_track, intersection_end_downtrack_.get(), intersection_speed_.get(),
433 incomplete_traj_params.modified_departure_speed, current_state.stamp + rclcpp::Duration(incomplete_traj_params.modified_remaining_time * 1e9), intersection_exit_time, crossed_lanelets.back().id(), crossed_lanelets.back().id()));
434
436}
437
438void LCIStrategicPlugin::handleCruisingUntilStop(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
439 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
440 const VehicleState& current_state,
441 double current_state_speed,
442 const lanelet::CarmaTrafficSignalPtr& traffic_light,
443 double traffic_light_down_track, const TrajectoryParams& ts_params)
444{
445 if (!ts_params.is_algorithm_successful || ts_params.case_num != TSCase::CASE_8)
446 {
447 RCLCPP_WARN_STREAM(rclcpp::get_logger("lci_strategic_plugin"),"handleCruisingUntilStop is called but it is not case_8");
448 return;
449 }
450
451 auto new_ts_params = ts_params;
452
453 double decel_rate = std::fabs(ts_params.a3_);
454
455 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "CASE_8: Planning cruise and stop with decel_rate: " << decel_rate);
456
457 new_ts_params.t3_ = new_ts_params.t2_;
458 new_ts_params.x3_ = new_ts_params.x2_;
459 new_ts_params.v3_ = new_ts_params.v2_;
460 new_ts_params.a3_ = new_ts_params.a2_;
461
462 // Identify the lanelets which will be crossed by approach maneuvers stopping part
463 std::vector<lanelet::ConstLanelet> lane_follow_crossed_lanelets =
464 getLaneletsBetweenWithException(new_ts_params.x1_, new_ts_params.x2_, true, true);
465
466 resp->new_plan.maneuvers.push_back(composeTrajectorySmoothingManeuverMessage(current_state.downtrack, new_ts_params.x2_, lane_follow_crossed_lanelets,
467 current_state_speed, new_ts_params.v2_, current_state.stamp, rclcpp::Time(new_ts_params.t2_ * 1e9), new_ts_params));
468
469 // Identify the lanelets which will be crossed by approach maneuvers stopping part
470 std::vector<lanelet::ConstLanelet> case_8_crossed_lanelets =
471 getLaneletsBetweenWithException(new_ts_params.x2_, traffic_light_down_track, true, true);
472
473 resp->new_plan.maneuvers.push_back(composeStopAndWaitManeuverMessage(
474 new_ts_params.x2_, traffic_light_down_track, new_ts_params.v2_, case_8_crossed_lanelets.front().id(),
475 case_8_crossed_lanelets.back().id(), rclcpp::Time(new_ts_params.t2_ * 1e9),
476 rclcpp::Time(new_ts_params.t2_ * 1e9) + rclcpp::Duration(config_.min_maneuver_planning_period * 1e9), decel_rate));
477
478 return;
479}
480
481void LCIStrategicPlugin::handleGreenSignalScenario(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
482 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
483 const VehicleState& current_state,
484 double current_state_speed,
485 const lanelet::CarmaTrafficSignalPtr& traffic_light,
486 const lanelet::ConstLanelet& entry_lanelet, const lanelet::ConstLanelet& exit_lanelet,
487 double traffic_light_down_track, const TrajectoryParams& ts_params, bool is_certainty_check_optional)
488{
489 if (!ts_params.is_algorithm_successful || ts_params.case_num == TSCase::CASE_8)
490 {
491 return;
492 }
493
494 rclcpp::Time light_arrival_time_by_algo = rclcpp::Time(ts_params.t3_ * 1e9);
495 double remaining_time = light_arrival_time_by_algo.seconds() - rclcpp::Time(req->header.stamp, RCL_SYSTEM_TIME).seconds();
496 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Algo initially successful: New light_arrival_time_by_algo: " << std::to_string(light_arrival_time_by_algo.seconds()) << ", with remaining_time: " << std::to_string(remaining_time));
497 auto can_make_green_optional = canArriveAtGreenWithCertainty(light_arrival_time_by_algo, traffic_light);
498
499 // Identify the lanelets which will be crossed by approach maneuvers lane follow maneuver
500 std::vector<lanelet::ConstLanelet> crossed_lanelets =
501 getLaneletsBetweenWithException(current_state.downtrack, traffic_light_down_track, true, true);
502
503 // no change for maneuver if invalid light states
504 if (!can_make_green_optional)
505 return;
506
507 if (can_make_green_optional.get() || is_certainty_check_optional)
508 {
509 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "HANDLE_SUCCESSFULL: Algorithm successful, and able to make it at green with certainty. Planning traj smooth and intersection transit maneuvers");
510
511 resp->new_plan.maneuvers.push_back(composeTrajectorySmoothingManeuverMessage(current_state.downtrack, traffic_light_down_track, crossed_lanelets,
512 current_state_speed, ts_params.v3_, current_state.stamp, light_arrival_time_by_algo, ts_params));
513
514 double intersection_length = intersection_end_downtrack_.get() - traffic_light_down_track;
515
516 rclcpp::Time intersection_exit_time =
517 light_arrival_time_by_algo + rclcpp::Duration(intersection_length / intersection_speed_.get() * 1e9);
518
519 resp->new_plan.maneuvers.push_back(composeIntersectionTransitMessage(
520 traffic_light_down_track, intersection_end_downtrack_.get(), intersection_speed_.get(),
521 intersection_speed_.get(), light_arrival_time_by_algo, intersection_exit_time, crossed_lanelets.back().id(), crossed_lanelets.back().id()));
522 }
523}
524
525
526TrajectoryParams LCIStrategicPlugin::handleFailureCaseHelper(const lanelet::CarmaTrafficSignalPtr& traffic_light, double current_time, double starting_speed, double departure_speed, double speed_limit, double remaining_downtrack, double traffic_light_downtrack)
527{
528 //Requested maneuver needs to be modified to meet remaining_dist req
529 //by trying to get close to the target_speed and remaining_time as much as possible
530 TrajectoryParams return_params;
531 TrajectoryParams traj_upper;
532 TrajectoryParams traj_lower;
533
534 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "HANDLE_LAST_RESORT_CASE: Starting...");
535 double starting_downtrack = traffic_light_downtrack - remaining_downtrack;
536 double modified_remaining_time_upper; // upper meaning downtrack vs time trajectory is curved upwards
537 double modified_remaining_time_lower; // lower meaning downtrack vs time trajectory is curved lower
538 double modified_departure_speed_upper;
539 double modified_departure_speed_lower;
540 bool calculation_success_upper = true; // identifies places in codes where calculation can be invalid such as negative distance
541
542 // the upper ET
543 // accel case
544 traj_upper.t0_ = current_time;
545 traj_upper.v0_ = starting_speed;
546 traj_upper.x0_ = starting_downtrack;
547 traj_upper.is_algorithm_successful = true;
548 traj_upper.case_num = CASE_1;
549
550 if (departure_speed >= starting_speed)
551 {
552 if ((pow(departure_speed,2) - pow(starting_speed,2))/(2*max_comfort_accel_) >= remaining_downtrack)
553 {
554 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "HandleFailureCase -> Upper Trajectory -> Current Speed <= Desired Departure Speed, Actual Departure Speed < Desired Departure Speed");
555
556 modified_departure_speed_upper = sqrt(pow(starting_speed, 2) + (2 * max_comfort_accel_ * remaining_downtrack));
557 modified_remaining_time_upper = (modified_departure_speed_upper - starting_speed) / max_comfort_accel_;
558
559 traj_upper.t1_ = current_time + modified_remaining_time_upper;
560 traj_upper.v1_ = modified_departure_speed_upper;
561 traj_upper.a1_ = max_comfort_accel_;
562 traj_upper.x1_ = traffic_light_downtrack;
563
564 traj_upper.t2_ = traj_upper.t1_;
565 traj_upper.v2_ = traj_upper.v1_;
566 traj_upper.a2_ = traj_upper.a1_;
567 traj_upper.x2_ = traj_upper.x1_;
568
569 traj_upper.modified_departure_speed = modified_departure_speed_upper;
570 traj_upper.modified_remaining_time = modified_remaining_time_upper;
571 }
572 else // NOTE: most likely will not happen as it would have happened at trajectory smoothing part
573 {
574 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "HandleFailureCase -> Upper Trajectory -> Current Speed < Desired Departure Speed, Actual Departure Speed = Desired Departure Speed");
575
576 double cruising_distance = remaining_downtrack - (pow(departure_speed, 2) - pow(starting_speed, 2))/ ( 2 * max_comfort_accel_);
577 if (cruising_distance < -EPSILON)
578 {
579 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Detected calculation failure in upper case 2");
580 calculation_success_upper = false;
581 }
582 modified_remaining_time_upper = ((departure_speed - starting_speed) / max_comfort_accel_) + (cruising_distance / departure_speed);
583
584 traj_upper.t1_ = current_time + ((departure_speed - starting_speed) / max_comfort_accel_);
585 traj_upper.v1_ = departure_speed;
586 traj_upper.a1_ = max_comfort_accel_;
587 traj_upper.x1_ = starting_downtrack + (pow(departure_speed, 2) - pow(starting_speed, 2)) / (2 * max_comfort_accel_);
588
589 traj_upper.t2_ = current_time + modified_remaining_time_upper;
590 traj_upper.v2_ = departure_speed;
591 traj_upper.a2_ = 0;
592 traj_upper.x2_ = traffic_light_downtrack;
593
594 traj_upper.modified_departure_speed = departure_speed;
595 traj_upper.modified_remaining_time = modified_remaining_time_upper;
596 }
597 }
598
599 if (departure_speed < starting_speed) // NOTE: most cases will not run due to departure speed being equal to speed limit
600 {
601 if ((pow(departure_speed,2) - pow(starting_speed,2))/(2*max_comfort_decel_) >= remaining_downtrack)
602 {
603 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "HandleFailureCase -> Upper Trajectory -> Current Speed > Desired Departure Speed, Actual Departure Speed > Desired Departure Speed");
604
605 modified_departure_speed_upper = sqrt(pow(starting_speed, 2) + (2 * max_comfort_decel_ * remaining_downtrack));
606 modified_remaining_time_upper = (modified_departure_speed_upper - starting_speed) / max_comfort_decel_;
607
608 traj_upper.t1_ = current_time + modified_remaining_time_upper;
609 traj_upper.v1_ = modified_departure_speed_upper;
610 traj_upper.a1_ = max_comfort_decel_;
611 traj_upper.x1_ = traffic_light_downtrack;
612
613 traj_upper.t2_ = traj_upper.t1_;
614 traj_upper.v2_ = traj_upper.v1_;
615 traj_upper.a2_ = traj_upper.a1_;
616 traj_upper.x2_ = traj_upper.x1_;
617
618 traj_upper.modified_departure_speed = modified_departure_speed_upper;
619 traj_upper.modified_remaining_time = modified_remaining_time_upper;
620 }
621 else // NOTE: most likely will not happen as it would have happened at trajectory smoothing part
622 {
623 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "HandleFailureCase -> Upper Trajectory -> Current Speed > Desired Departure Speed, Actual Departure Speed = Desired Departure Speed");
624
625 double cruising_distance = remaining_downtrack - (pow(departure_speed, 2) - pow(starting_speed, 2))/ ( 2 * max_comfort_decel_);
626
627 if (cruising_distance < -EPSILON)
628 {
629 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Detected calculation failure in upper case 4");
630 calculation_success_upper = false;
631 }
632
633 modified_remaining_time_upper = cruising_distance / starting_speed + (departure_speed - starting_speed) / max_comfort_decel_ ;
634
635 traj_upper.t1_ = current_time + cruising_distance / starting_speed;
636 traj_upper.v1_ = starting_speed;
637 traj_upper.a1_ = 0.0;
638 traj_upper.x1_ = starting_downtrack + cruising_distance;
639
640 traj_upper.t2_ = current_time + modified_remaining_time_upper;
641 traj_upper.v2_ = departure_speed;
642 traj_upper.a2_ = max_comfort_decel_;
643 traj_upper.x2_ = traffic_light_downtrack;
644
645 traj_upper.modified_departure_speed = departure_speed;
646 traj_upper.modified_remaining_time = modified_remaining_time_upper;
647 }
648 }
649
650 traj_upper.t3_ = traj_upper.t2_;
651 traj_upper.v3_ = traj_upper.v2_;
652 traj_upper.a3_ = traj_upper.a2_;
653 traj_upper.x3_ = traj_upper.x2_;
654
655 // The lower ET
656 // (note that the distance is definitely not enough for deceleration to zero speed, therefore, modified_departure_speed will be greater than zero for sure!).
657 modified_departure_speed_lower = sqrt(pow(starting_speed, 2) + (2 * max_comfort_decel_ * remaining_downtrack));
658 modified_remaining_time_lower = (modified_departure_speed_lower - starting_speed) / max_comfort_decel_;
659
660 traj_lower.t0_ = current_time;
661 traj_lower.v0_ = starting_speed;
662 traj_lower.x0_ = starting_downtrack;
663 traj_lower.is_algorithm_successful = true;
664 traj_lower.case_num = CASE_1;
665
666 traj_lower.t1_ = current_time + modified_remaining_time_lower;
667 traj_lower.v1_ = modified_departure_speed_lower;
668 traj_lower.a1_ = max_comfort_decel_;
669 traj_lower.x1_ = traffic_light_downtrack;
670
671 traj_lower.t2_ = traj_lower.t1_;
672 traj_lower.v2_ = traj_lower.v1_;
673 traj_lower.a2_ = traj_lower.a1_;
674 traj_lower.x2_ = traj_lower.x1_;
675
676 traj_lower.t3_ = traj_lower.t2_;
677 traj_lower.v3_ = traj_lower.v2_;
678 traj_lower.a3_ = traj_lower.a2_;
679 traj_lower.x3_ = traj_lower.x2_;
680
681 traj_lower.modified_departure_speed = modified_departure_speed_lower;
682 traj_lower.modified_remaining_time = modified_remaining_time_upper;
683
684 // Pick UPPER or LOWER trajectory based on light
685 bool is_return_params_found = false;
686
687 if (calculation_success_upper)
688 {
689 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Checking this time!: " << current_time + modified_remaining_time_upper);
690
691 auto upper_optional = traffic_light->predictState(lanelet::time::timeFromSec(current_time + modified_remaining_time_upper));
692
693 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Checking this time! state: " << upper_optional.get().second);
694
695 if (!validLightState(upper_optional, rclcpp::Time((current_time + modified_remaining_time_upper) * 1e9)))
696 {
697 RCLCPP_ERROR_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Unable to resolve give signal for modified_remaining_time_upper: " << std::to_string(current_time + modified_remaining_time_upper));
698 }
699 else
700 {
701 if (isStateAllowedGreen(upper_optional.get().second))
702 {
703 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Detected Upper GREEN case");
704 return_params = traj_upper;
705 is_return_params_found = true;
706 }
707 }
708 }
709
710 if (!is_return_params_found)
711 {
712 auto lower_optional = traffic_light->predictState(lanelet::time::timeFromSec(current_time + modified_remaining_time_lower));
713
714 if (!validLightState(lower_optional, rclcpp::Time((current_time + modified_remaining_time_lower) * 1e9)))
715 {
716 RCLCPP_ERROR_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Unable to resolve give signal for modified_remaining_time_lower:" << std::to_string(current_time + modified_remaining_time_lower));
717 }
718 else
719 {
720 if (isStateAllowedGreen(lower_optional.get().second))
721 {
722 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Detected Lower GREEN case");
723 return_params = traj_lower;
724 is_return_params_found = true;
725 }
726 }
727 }
728
729 // Handle hard failure case such as nan or invalid states
730 if (is_return_params_found && !isnan(return_params.modified_departure_speed) && return_params.modified_departure_speed > epsilon_ &&
731 return_params.modified_departure_speed < speed_limit ) //80_mph
732 {
733 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Updated the speed, and using modified_departure_speed: " << return_params.modified_departure_speed);
734 print_params(return_params);
735 return return_params;
736 }
737 else
738 {
739 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Unable to handle edge case gracefully");
740 return_params = TrajectoryParams(); //reset
741 return_params.is_algorithm_successful = false;
742 return return_params;
743 }
744}
745
746
747void LCIStrategicPlugin::planWhenUNAVAILABLE(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
748 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp, const VehicleState& current_state,
749 const lanelet::CarmaTrafficSignalPtr& traffic_light, const lanelet::ConstLanelet& entry_lanelet, const lanelet::ConstLanelet& exit_lanelet, const lanelet::ConstLanelet& current_lanelet)
750{
751 // Reset intersection state since in this state we are not yet known to be in or approaching an intersection
752 intersection_speed_ = boost::none;
753 intersection_end_downtrack_ = boost::none;
754 double current_state_speed = std::max(current_state.speed, config_.algo_minimum_speed * 1.001);
755
756
757 if (!traffic_light)
758 {
759 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "No lights found along route. Returning maneuver plan unchanged");
760 return;
761 }
762
764 double max_comfort_decel = -1.0 * config_.vehicle_decel_limit * config_.vehicle_decel_limit_multiplier;
765
766 auto stop_line = traffic_light->getStopLine(entry_lanelet);
767
768 if (!stop_line)
769 {
770 throw std::invalid_argument("Given entry lanelet doesn't have stop_line...");
771 }
772
773 double traffic_light_down_track =
774 wm_->routeTrackPos(stop_line.get().front().basicPoint2d()).downtrack;
775
776 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "traffic_light_down_track: " << traffic_light_down_track);
777
778 double distance_remaining_to_traffic_light = traffic_light_down_track - current_state.downtrack;
779
780 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "distance_remaining_to_traffic_light: " << distance_remaining_to_traffic_light <<
781 ", current_state.downtrack: " << current_state.downtrack);
782
783 distance_remaining_to_tf_ = distance_remaining_to_traffic_light; // performance metric
784
785 auto speed_limit = findSpeedLimit(current_lanelet);
786
787 current_state_speed = std::min(speed_limit, current_state_speed);
788
789 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "speed_limit (free flow speed): " << speed_limit);
790
791 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "trajectory_smoothing_activation_distance: " << config_.trajectory_smoothing_activation_distance);
792
793 double stopping_dist = estimate_distance_to_stop(current_state_speed, config_.vehicle_decel_limit_multiplier *
794 config_.vehicle_decel_limit); //accepts positive decel
795
796 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Stopping distance: " << stopping_dist);
797
798 double plugin_activation_distance = std::max(stopping_dist, config_.min_approach_distance);
799
800 plugin_activation_distance = std::max(plugin_activation_distance, config_.trajectory_smoothing_activation_distance);
801
802 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "plugin_activation_distance: " << plugin_activation_distance);
803
804 if (distance_remaining_to_traffic_light <= plugin_activation_distance)
805 {
806 RCLCPP_INFO_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Within intersection range");
807 transition_table_.signal(TransitEvent::IN_STOPPING_RANGE); // Evaluate Signal and Run Trajectory Smoothing Algorithm
808 }
809 else
810 {
812 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Not within intersection range");
813 }
814
815}
816
817void LCIStrategicPlugin::planWhenAPPROACHING(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
818 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp, const VehicleState& current_state,
819 const lanelet::CarmaTrafficSignalPtr& traffic_light, const lanelet::ConstLanelet& entry_lanelet, const lanelet::ConstLanelet& exit_lanelet, const lanelet::ConstLanelet& current_lanelet)
820{
822
823 if (!traffic_light) // If we are in the approaching state and there is no longer any lights ahead of us then
824 // the vehicle must have crossed the stop bar
825 {
827 return;
828 }
829
830 double current_state_speed = std::max(current_state.speed, config_.algo_minimum_speed * 1.001);
831
832 auto stop_line = traffic_light->getStopLine(entry_lanelet);
833
834 if (!stop_line)
835 {
836 throw std::invalid_argument("Given entry lanelet doesn't have stop_line...");
837 }
838
839 double traffic_light_down_track =
840 wm_->routeTrackPos(stop_line.get().front().basicPoint2d()).downtrack;
841
842 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "traffic_light_down_track: " << traffic_light_down_track);
843
844 double distance_remaining_to_traffic_light = traffic_light_down_track - current_state.downtrack;
845
846 distance_remaining_to_tf_ = distance_remaining_to_traffic_light;
847
848 if (distance_remaining_to_traffic_light < 0) // there is small discrepancy between signal's routeTrackPos as well as current
849 { // downtrack calculated using veh_x,y from state. Therefore, it may have crossed it
850 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Crossed the bar distance_remaining_to_traffic_light: " << distance_remaining_to_traffic_light);
852 return;
853 }
854
855 // At this point we know the vehicle is within the activation distance and we know the current and next light phases
856 // All we need to now determine is if we should stop or if we should continue
857 lanelet::ConstLanelet intersection_lanelet;
858
859 auto route = wm_->getRoute()->shortestPath();
860 auto entry_llt_iter = std::find(route.begin(), route.end(), entry_lanelet);
861 if (entry_llt_iter != route.end())
862 {
863 intersection_lanelet = *(entry_llt_iter + 1);
864 }
865
866 if (intersection_lanelet.id() != lanelet::InvalId)
867 {
868 intersection_speed_ = findSpeedLimit(intersection_lanelet);
870 }
871 else
872 {
873 intersection_speed_ = findSpeedLimit(exit_lanelet);
874 }
875
876 intersection_speed_ = intersection_speed_.get() * 0.999; // so that speed_limit is not exactly same as departure or current speed
877
878 double speed_limit = findSpeedLimit(current_lanelet);
879
880 current_state_speed = std::min(current_state_speed, speed_limit - 5 * epsilon_); // so that current_speed is not exactly same as departure or speed limit
881
882 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "current_state_speed: " << current_state_speed);
883 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "intersection_speed_: " << intersection_speed_.get());
884 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "distance_remaining_to_traffic_light: " << distance_remaining_to_traffic_light);
885
887 wm_->routeTrackPos(exit_lanelet.centerline2d().front().basicPoint2d()).downtrack;
888
889 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "intersection_end_downtrack_: " << intersection_end_downtrack_.get());
890
891 // If the vehicle is at a stop trigger the stopped state
892 constexpr double HALF_MPH_IN_MPS = 0.22352;
893 if (current_state.speed < HALF_MPH_IN_MPS &&
894 fabs(distance_remaining_to_traffic_light) < config_.stopping_location_buffer)
895 {
896 transition_table_.signal(TransitEvent::STOPPED); // The vehicle has come to a stop at the light
897 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "CARMA has detected that the vehicle stopped at the stop bar. Transitioning to WAITING STATE");
898
899 return;
900 }
901
903
904 rclcpp::Time earliest_entry_time = current_state.stamp + get_earliest_entry_time(distance_remaining_to_traffic_light, speed_limit,
905 current_state_speed, intersection_speed_.get(), max_comfort_accel_, max_comfort_decel_);
906
907 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "earliest_entry_time: " << std::to_string(earliest_entry_time.seconds()) << ", with : " << std::to_string((earliest_entry_time - current_state.stamp).seconds()) << " left at: " << std::to_string(current_state.stamp.seconds()));
908
909 auto [nearest_green_entry_time, is_entry_time_within_green_or_tbd, in_tbd] = get_final_entry_time_and_conditions(current_state, earliest_entry_time, traffic_light);
910
911 if (nearest_green_entry_time == rclcpp::Time(0))
912 return;
913
914 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Final nearest_green_entry_time: " << std::to_string(nearest_green_entry_time.seconds()));
915
916 auto et_state = traffic_light->predictState(lanelet::time::timeFromSec(nearest_green_entry_time.seconds()));
917 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Signal at ET: " << et_state.get().second);
918
920
921 double remaining_time = nearest_green_entry_time.seconds() - current_state.stamp.seconds();
922 double remaining_time_earliest_entry = earliest_entry_time.seconds() - current_state.stamp.seconds();
923 scheduled_entry_time_ = remaining_time; // performance metric
924 earliest_entry_time_ = remaining_time_earliest_entry; // performance metric
925
926 auto boundary_distances = get_delta_x(current_state_speed, intersection_speed_.get(), speed_limit, config_.algo_minimum_speed, max_comfort_accel_, max_comfort_decel_);
927 print_boundary_distances(boundary_distances); //debug
928
929 auto boundary_traj_params = get_boundary_traj_params(rclcpp::Time(req->header.stamp, RCL_SYSTEM_TIME).seconds(), current_state_speed, intersection_speed_.get(), speed_limit, config_.algo_minimum_speed, max_comfort_accel_, max_comfort_decel_, current_state.downtrack, traffic_light_down_track, distance_remaining_to_traffic_light, boundary_distances);
930
931 TrajectoryParams ts_params = get_ts_case(rclcpp::Time(req->header.stamp, RCL_SYSTEM_TIME).seconds(), nearest_green_entry_time.seconds(), current_state_speed, intersection_speed_.get(), speed_limit, config_.algo_minimum_speed, max_comfort_accel_, max_comfort_decel_, current_state.downtrack, traffic_light_down_track, distance_remaining_to_traffic_light, boundary_distances, boundary_traj_params);
932 print_params(ts_params);
933
934 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "SPEED PROFILE CASE:" << ts_params.case_num);
935
937 double emergency_distance_to_stop = pow(current_state.speed, 2)/(2 * emergency_decel_norm_) + config_.stopping_location_buffer / 2; //Idea is to aim the middle part of stopping buffer
938 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "emergency_distance_to_stop at emergency_decel_norm_ (with stopping_location_buffer/2): " << emergency_distance_to_stop << ", emergency_decel_norm_: " << emergency_decel_norm_);
939
940 double safe_distance_to_stop = pow(current_state.speed, 2)/(2 * max_comfort_decel_norm_) + config_.stopping_location_buffer / 2; //Idea is to aim the middle part of stopping buffer
941 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "safe_distance_to_stop at max_comfort_decel (with stopping_location_buffer/2): " << safe_distance_to_stop << ", max_comfort_decel_norm_: " << max_comfort_decel_norm_);
942
943 double desired_distance_to_stop = pow(current_state.speed, 2)/(2 * max_comfort_decel_norm_ * config_.deceleration_fraction) + config_.desired_distance_to_stop_buffer;
944 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "desired_distance_to_stop at: " << desired_distance_to_stop << ", where effective deceleration rate is: " << max_comfort_decel_norm_ * config_.deceleration_fraction);
945
946 emergency_distance_to_stop = std::max(emergency_distance_to_stop, config_.stopping_location_buffer);
947 safe_distance_to_stop = std::max(safe_distance_to_stop, config_.stopping_location_buffer);
948 desired_distance_to_stop = std::max(desired_distance_to_stop, config_.stopping_location_buffer);
949
950 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "new emergency_distance_to_stop: " << emergency_distance_to_stop);
951 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "new safe_distance_to_stop: " << safe_distance_to_stop);
952 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "new desired_distance_to_stop: " << desired_distance_to_stop);
953
954 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "distance_remaining_to_traffic_light: " << distance_remaining_to_traffic_light << ", current_state.speed: " << current_state.speed);
955
956 // Basic RED signal violation check
957 if (distance_remaining_to_traffic_light <= emergency_distance_to_stop || last_case_num_ == TSCase::EMERGENCY_STOPPING)
958 {
959 if (in_tbd) // Given ET is in TBD, but vehicle is too close to intersection
960 {
961 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "ET is still in TBD despite the vehicle being in desired distance to start stopping. Trying to handle this edge case gracefully...");
962 }
963
964 double stopping_time = current_state.speed / 1.5 / max_comfort_decel_norm_; //one half the acceleration (twice the acceleration to stop) to account for emergency case, see emergency_decel_norm_
965
966 rclcpp::Time stopping_arrival_time =
967 current_state.stamp + rclcpp::Duration(stopping_time * 1e9);
968
969 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "stopping_arrival_time: " << std::to_string(stopping_arrival_time.seconds()));
970
971 auto stopping_arrival_state_optional = traffic_light->predictState(lanelet::time::timeFromSec(stopping_arrival_time.seconds()));
972
973 if (!validLightState(stopping_arrival_state_optional, stopping_arrival_time))
974 {
975 RCLCPP_ERROR_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Unable to resolve give signal for stopping_arrival_state_optional: " << std::to_string(stopping_arrival_time.seconds()));
976 return;
977 }
978
979 if (stopping_arrival_state_optional.get().second == lanelet::CarmaTrafficSignalState::STOP_AND_REMAIN || last_case_num_ == TSCase::EMERGENCY_STOPPING) // if once started emergency stopped, keep doing it to avoid jerkiness
980 {
981 RCLCPP_WARN_STREAM(rclcpp::get_logger("lci_strategic_plugin"),"Detected possible RED light violation! Stopping!");
982 handleStopping(req,resp, current_state, traffic_light, entry_lanelet, exit_lanelet, current_lanelet, traffic_light_down_track, true); //case_11
984
985 return;
986 }
987 }
988
989 // Check if the vehicle can arrive with certainty (Case 1-7)
990 if (ts_params.is_algorithm_successful && ts_params.case_num != TSCase::CASE_8 &&
991 (distance_remaining_to_traffic_light >= desired_distance_to_stop || !in_tbd) &&
992 is_entry_time_within_green_or_tbd) // ET cannot be explicitly inside RED or YELLOW in available future states, which is ERROR case
993 {
994 handleGreenSignalScenario(req, resp, current_state, current_state_speed, traffic_light, entry_lanelet, exit_lanelet, traffic_light_down_track, ts_params, in_tbd); //in_tbd means optional to check certainty arrival at green
995
996 if (!resp->new_plan.maneuvers.empty()) // able to pass at green
997 {
998 last_case_num_ = ts_params.case_num;
999 return;
1000 }
1001
1002 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Not able to make it with certainty: TSCase: " << ts_params.case_num << ", changing it to 8");
1003 ts_params = boundary_traj_params[7];
1004 ts_params.is_algorithm_successful = true; //false correspond to cases when vehicle is beyond safe_distance to stop for case8
1005 ts_params.case_num = CASE_8;
1006 print_params(ts_params);
1007 }
1008
1009 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Not able to make it with certainty: NEW TSCase: " << ts_params.case_num);
1010 // if algorithm is NOT successful or if the vehicle cannot make the green light with certainty
1011
1012 if (desired_distance_to_stop < distance_remaining_to_traffic_light && last_case_num_ != TSCase::STOPPING) // do not switch from STOPPING to case8 again
1013 {
1014 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Way too early to stop. Cruising at CASE8");
1015 handleCruisingUntilStop(req, resp, current_state, current_state_speed, traffic_light, traffic_light_down_track, ts_params);
1016
1017 if (!resp->new_plan.maneuvers.empty())
1018 {
1020 return;
1021 }
1022 }
1023
1024 if ((safe_distance_to_stop <= distance_remaining_to_traffic_light && desired_distance_to_stop >= distance_remaining_to_traffic_light) ||
1025 last_case_num_ == TSCase::STOPPING) // if stopping continue stopping until transition to planwhenWAITING
1026 {
1027 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Planning stopping now. last case:" << static_cast<int>(last_case_num_));
1028 handleStopping(req,resp, current_state, traffic_light, entry_lanelet, exit_lanelet, current_lanelet, traffic_light_down_track); //case_9
1029 return;
1030 }
1031
1032 if (safe_distance_to_stop > distance_remaining_to_traffic_light)
1033 {
1034 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "No longer within safe distance to stop! Decide to continue stopping or continue into intersection");
1035
1036 if (last_case_num_ != TSCase::STOPPING && last_case_num_ != TSCase::UNAVAILABLE && last_case_num_ != TSCase::CASE_8) //case 1-7 or emergency stop or handlefailure
1037 {
1038 // 3. if not able to stop nor reach target speed at green, attempt its best to reach the target parameters at the intersection
1039 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "HANDLE_LAST_RESORT: The vehicle is not able to stop at red/yellow light nor is able to reach target speed at green. Attempting its best to pass through at green!");
1040
1041 handleFailureCase(req, resp, current_state, current_state_speed, speed_limit, remaining_time,
1042 exit_lanelet.id(), traffic_light, traffic_light_down_track, ts_params);
1043
1044 if (resp->new_plan.maneuvers.empty())
1045 {
1046 RCLCPP_WARN_STREAM(rclcpp::get_logger("lci_strategic_plugin"),"HANDLE_SAFETY: Planning forced slow-down... last case:" << static_cast<int>(last_case_num_));
1047 handleStopping(req,resp, current_state, traffic_light, entry_lanelet, exit_lanelet, current_lanelet, traffic_light_down_track, true); //case_11 emergency case with twice the normal deceleration
1048 }
1049 }
1050 else
1051 {
1052 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "HANDLE_SAFETY: Planning to keep stopping now. last case:" << static_cast<int>(last_case_num_));
1053 handleStopping(req,resp, current_state, traffic_light, entry_lanelet, exit_lanelet, current_lanelet, traffic_light_down_track); //case_9
1054 }
1055 }
1056
1057
1058}
1059
1060void LCIStrategicPlugin::planWhenWAITING(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
1061 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp, const VehicleState& current_state,
1062 const lanelet::CarmaTrafficSignalPtr& traffic_light, const lanelet::ConstLanelet& entry_lanelet, const lanelet::ConstLanelet& exit_lanelet, const lanelet::ConstLanelet& current_lanelet)
1063{
1065
1066 if (!traffic_light)
1067 {
1068 throw std::invalid_argument("While in WAITING state, the traffic lights disappeared.");
1069 }
1070
1071 auto stop_line = traffic_light->getStopLine(entry_lanelet);
1072
1073 if (!stop_line)
1074 {
1075 throw std::invalid_argument("Given entry lanelet doesn't have stop_line...");
1076 }
1077
1078 double traffic_light_down_track =
1079 wm_->routeTrackPos(stop_line.get().front().basicPoint2d()).downtrack;
1080
1081 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "traffic_light_down_track: "<< traffic_light_down_track);
1082
1083 double entering_time = current_state.stamp.seconds();
1084
1085 auto current_light_state_optional = traffic_light->predictState(lanelet::time::timeFromSec(entering_time));
1086
1087 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "WAITING STATE: requested time to rclcpp::Time(req->header.stamp, RCL_SYSTEM_TIME) check: " << std::to_string(rclcpp::Time(req->header.stamp, RCL_SYSTEM_TIME).seconds()));
1088 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "WAITING STATE: requested time to CURRENT STATE check: " << std::to_string(entering_time));
1089
1090 if (!validLightState(current_light_state_optional, rclcpp::Time(entering_time * 1e9)))
1091 return;
1092
1093 auto bool_optional_late_certainty = canArriveAtGreenWithCertainty(rclcpp::Time(entering_time * 1e9), traffic_light, true, false);
1094
1095 if (!bool_optional_late_certainty)
1096 {
1097 RCLCPP_ERROR_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Unable to resolve green light...");
1098 return;
1099 }
1100
1101 bool should_enter = true; //uc2
1102
1103 if (config_.enable_carma_streets_connection && entering_time > current_state.stamp.seconds()) //uc3
1104 should_enter = false;
1105
1106 if (isStateAllowedGreen(current_light_state_optional.get().second) && bool_optional_late_certainty.get() && should_enter) // if can make with certainty
1107 {
1108 transition_table_.signal(TransitEvent::RED_TO_GREEN_LIGHT); // If the light is green send the light transition
1109 // signal
1110 return;
1111 }
1112
1113 // A fixed buffer to add to stopping maneuvers once the vehicle is already stopped to ensure that they can have their
1114 // trajectory planned
1115 constexpr double stop_maneuver_buffer = 10.0;
1116
1117 // If the light is not green then continue waiting by creating a stop and wait maneuver on top of the vehicle
1119
1120 resp->new_plan.maneuvers.push_back(composeStopAndWaitManeuverMessage(
1121 current_state.downtrack - stop_maneuver_buffer, traffic_light_down_track, current_state.speed,
1122 current_state.lane_id, current_state.lane_id, rclcpp::Time(entering_time * 1e9),
1123 rclcpp::Time(entering_time * 1e9) + rclcpp::Duration(config_.min_maneuver_planning_period * 1e9), stopping_accel));
1124}
1125
1126void LCIStrategicPlugin::planWhenDEPARTING(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
1127 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp, const VehicleState& current_state,
1128 double intersection_end_downtrack, double intersection_speed_limit)
1129{
1131
1132 if (current_state.downtrack > intersection_end_downtrack)
1133 {
1134 transition_table_.signal(TransitEvent::INTERSECTION_EXIT); // If we are past the most recent
1135 return;
1136 }
1137
1138 // Calculate exit time assuming constant acceleration
1139 rclcpp::Time intersection_exit_time =
1140 current_state.stamp +
1141 rclcpp::Duration(2.0 * (intersection_end_downtrack - current_state.downtrack) / (current_state.speed + intersection_speed_limit) * 1e9);
1142
1143 // Identify the lanelets which will be crossed by approach maneuvers lane follow maneuver
1144 std::vector<lanelet::ConstLanelet> crossed_lanelets =
1145 getLaneletsBetweenWithException(current_state.downtrack, intersection_end_downtrack, true, false);
1146
1147 // Compose intersection transit maneuver
1148 resp->new_plan.maneuvers.push_back(composeIntersectionTransitMessage(
1149 current_state.downtrack, intersection_end_downtrack, current_state.speed, intersection_speed_limit,
1150 current_state.stamp, intersection_exit_time, crossed_lanelets.back().id(), crossed_lanelets.back().id()));
1151}
1152
1154
1155void LCIStrategicPlugin::mobilityOperationCb(carma_v2x_msgs::msg::MobilityOperation::UniquePtr msg)
1156{
1157 if (msg->strategy == light_controlled_intersection_strategy_)
1158 {
1159 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Received Schedule message with id: " << msg->m_header.plan_id);
1161 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Approaching light Controlled Intersection: " << approaching_light_controlled_intersection_);
1162
1163 if (msg->m_header.recipient_id == config_.vehicle_id)
1164 {
1165 street_msg_timestamp_ = msg->m_header.timestamp;
1166 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "street_msg_timestamp_: " << street_msg_timestamp_);
1167 parseStrategyParams(msg->strategy_params);
1168 previous_strategy_params_ = msg->strategy_params;
1169 }
1170 }
1171
1172}
1173
1174void LCIStrategicPlugin::BSMCb(carma_v2x_msgs::msg::BSM::UniquePtr msg)
1175{
1176 std::vector<uint8_t> bsm_id_vec = msg->core_data.id;
1177 bsm_id_ = BSMHelper::BSMHelper::bsmIDtoString(bsm_id_vec);
1178 bsm_msg_count_ = msg->core_data.msg_count;
1179 bsm_sec_mark_ = msg->core_data.sec_mark;
1180}
1181
1182void LCIStrategicPlugin::parseStrategyParams(const std::string& strategy_params)
1183{
1184 // sample strategy_params: "et:1634067059"
1185 std::string params = strategy_params;
1186 std::vector<std::string> inputsParams;
1187 boost::algorithm::split(inputsParams, params, boost::is_any_of(","));
1188
1189 std::vector<std::string> et_parsed;
1190 boost::algorithm::split(et_parsed, inputsParams[0], boost::is_any_of(":"));
1191 auto new_scheduled_enter_time = std::stoull(et_parsed[1]);
1192
1193 if (scheduled_enter_time_ != new_scheduled_enter_time) //reset green buffer cache so it can be re-evaluated
1195
1196 scheduled_enter_time_ = new_scheduled_enter_time;
1197 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "scheduled_enter_time_: " << scheduled_enter_time_);
1198
1199}
1200
1201carma_v2x_msgs::msg::MobilityOperation LCIStrategicPlugin::generateMobilityOperation()
1202{
1203 carma_v2x_msgs::msg::MobilityOperation mo_;
1204 mo_.m_header.timestamp = now().nanoseconds()/1000000;
1205 mo_.m_header.sender_id = config_.vehicle_id;
1206 mo_.m_header.recipient_id = upcoming_id_;
1207 mo_.m_header.sender_bsm_id = bsm_id_;
1209
1210 double vehicle_acceleration_limit_ = config_.vehicle_accel_limit * config_.vehicle_accel_limit_multiplier;
1211 double vehicle_deceleration_limit_ = -1 * config_.vehicle_decel_limit * config_.vehicle_decel_limit_multiplier;
1212
1213 std::string intersection_turn_direction = "straight";
1214 if (intersection_turn_direction_ == TurnDirection::Right) intersection_turn_direction = "right";
1215 if (intersection_turn_direction_ == TurnDirection::Left) intersection_turn_direction = "left";
1216
1217 mo_.strategy_params = "access: 1, max_accel: " + std::to_string(vehicle_acceleration_limit_) + // NOTE: Access currently set to 1 at all times since its not specified by streets
1218 ", max_decel: " + std::to_string(vehicle_deceleration_limit_) + ", react_time: " + std::to_string(config_.reaction_time) +
1219 ", min_gap: " + std::to_string(config_.min_gap) + ", depart_pos: 0" + // NOTE: Departure position set to 0 at all times since it's not specified by streets
1220 ", turn_direction: " + intersection_turn_direction + ", msg_count: " + std::to_string(bsm_msg_count_) + ", sec_mark: " + std::to_string(bsm_sec_mark_);
1221
1222
1223 return mo_;
1224}
1225
1226TurnDirection LCIStrategicPlugin::getTurnDirectionAtIntersection(std::vector<lanelet::ConstLanelet> lanelets_list)
1227{
1228 TurnDirection turn_direction = TurnDirection::Straight;
1229 for (auto l:lanelets_list)
1230 {
1231 if(l.hasAttribute("turn_direction")) {
1232 std::string direction_attribute = l.attribute("turn_direction").value();
1233 if (direction_attribute == "right")
1234 {
1235 turn_direction = TurnDirection::Right;
1236 break;
1237 }
1238 else if (direction_attribute == "left")
1239 {
1240 turn_direction = TurnDirection::Left;
1241 break;
1242 }
1243 else turn_direction = TurnDirection::Straight;
1244 }
1245 else
1246 {
1247 // if there is no attribute, assumption is straight
1248 turn_direction = TurnDirection::Straight;
1249 }
1250
1251 }
1252 return turn_direction;
1253}
1254
1256{
1258 {
1259 carma_v2x_msgs::msg::MobilityOperation status_msg = generateMobilityOperation();
1260 mobility_operation_pub_->publish(status_msg);
1261 }
1262}
1263
1265
1267 std::shared_ptr<rmw_request_id_t> srv_header,
1268 carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
1269 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp)
1270{
1271 std::chrono::system_clock::time_point execution_start_time = std::chrono::system_clock::now(); // Start timing the execution time for planning so it can be logged
1272
1273 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "<<<<<<<<<<<<<<<<< STARTING LCI_STRATEGIC_PLAN!!!!!!!!! >>>>>>>>>>>>>>>>");
1274
1275 if (!wm_->getRoute())
1276 {
1277 RCLCPP_ERROR_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Could not plan maneuvers as route was not available");
1278 return;
1279 }
1280
1282 {
1284 {
1285 resp->new_plan.maneuvers = {};
1286 RCLCPP_WARN_STREAM(rclcpp::get_logger("lci_strategic_plugin"),"Not approaching light-controlled intersection so no maneuvers");
1287 return;
1288 }
1289
1290 bool is_empty_schedule_msg = (scheduled_enter_time_ == 0);
1291 if (is_empty_schedule_msg)
1292 {
1293 resp->new_plan.maneuvers = {};
1294 RCLCPP_WARN_STREAM(rclcpp::get_logger("lci_strategic_plugin"),"Receiving empty schedule message");
1295 return;
1296 }
1297 }
1298
1299 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Finding car information");
1300
1301 // Extract vehicle data from request
1302 VehicleState current_state = extractInitialState(req);
1303 if (transition_table_.getState() != TransitState::UNAVAILABLE && !req->prior_plan.maneuvers.empty())
1304 {
1305 RCLCPP_WARN_STREAM(rclcpp::get_logger("lci_strategic_plugin"),"State is NOT UNAVAILABLE AND Maneuvers in request is NOT empty");
1306 return;
1307 }
1308 // Get current traffic light information
1309 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "\n\nFinding traffic_light information");
1310
1311 auto inter_list = wm_->getSignalizedIntersectionsAlongRoute({ req->veh_x, req->veh_y });
1312 auto upcoming_id_= inter_list.front()->id();
1313
1314 auto traffic_list = wm_->getSignalsAlongRoute({ req->veh_x, req->veh_y });
1315
1316 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Found traffic lights of size: " << traffic_list.size());
1317
1318 auto current_lanelets = wm_->getLaneletsFromPoint({ req->veh_x, req->veh_y});
1319 lanelet::ConstLanelet current_lanelet;
1320
1321 if (current_lanelets.empty())
1322 {
1323 RCLCPP_ERROR_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Given vehicle position is not on the road! Returning...");
1324 return;
1325 }
1326
1327 // get the lanelet that is on the route in case overlapping ones found
1328 auto llt_on_route_optional = wm_->getFirstLaneletOnShortestPath(current_lanelets);
1329
1330 if (llt_on_route_optional){
1331 current_lanelet = llt_on_route_optional.value();
1332 }
1333 else{
1334 RCLCPP_WARN_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "When identifying the corresponding lanelet for requested maneuever's state, x: "
1335 << req->veh_x << ", y: " << req->veh_y << ", no possible lanelet was found to be on the shortest path."
1336 << "Picking arbitrary lanelet: " << current_lanelets[0].id() << ", instead");
1337 current_lanelet = current_lanelets[0];
1338 }
1339
1340 lanelet::CarmaTrafficSignalPtr nearest_traffic_signal = nullptr;
1341
1342 lanelet::ConstLanelet entry_lanelet;
1343 lanelet::ConstLanelet exit_lanelet;
1344
1345 for (auto signal : traffic_list)
1346 {
1347 auto optional_entry_exit = wm_->getEntryExitOfSignalAlongRoute(signal);
1348 // if signal is not matching our destination skip
1349 if (!optional_entry_exit)
1350 {
1351 RCLCPP_ERROR_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Did not find entry.exit along the route");
1352 continue;
1353 }
1354
1355 entry_lanelet = optional_entry_exit.get().first;
1356 exit_lanelet = optional_entry_exit.get().second;
1357
1358 nearest_traffic_signal = signal;
1359 break;
1360 }
1361
1362
1363 TransitState prev_state;
1364
1365 do
1366 {
1367 // Clear previous maneuvers planned by this plugin as guard against state change since each state generates an
1368 // independent set of maneuvers
1369 resp->new_plan = carma_planning_msgs::msg::ManeuverPlan();
1370
1371 prev_state = transition_table_.getState(); // Cache previous state to check if state has changed after 1 iteration
1372
1373 RCLCPP_INFO_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Planning in state: " << transition_table_.getState());
1374
1375 boost::optional<std::pair<boost::posix_time::ptime, lanelet::CarmaTrafficSignalState>> current_light_state_optional = boost::none;
1376 if (nearest_traffic_signal)
1377 {
1378 current_light_state_optional = nearest_traffic_signal->predictState(lanelet::time::timeFromSec(current_state.stamp.seconds()));
1379 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Real-time current signal: " << current_light_state_optional.get().second << ", for Id: " << nearest_traffic_signal->id());
1380 if (current_light_state_optional.get().second == lanelet::CarmaTrafficSignalState::UNAVAILABLE || !current_light_state_optional)
1381 {
1382 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Signal state not available returning..." );
1383 return;
1384 }
1385 }
1386 switch (transition_table_.getState())
1387 {
1389 planWhenUNAVAILABLE(req, resp, current_state, nearest_traffic_signal, entry_lanelet, exit_lanelet, current_lanelet);
1390 break;
1391
1393 planWhenAPPROACHING(req, resp, current_state, nearest_traffic_signal, entry_lanelet, exit_lanelet, current_lanelet);
1394 break;
1395
1397 planWhenWAITING(req, resp, current_state, nearest_traffic_signal, entry_lanelet, exit_lanelet, current_lanelet);
1398 break;
1399
1401 // Reset intersection state since we are no longer in an intersection
1403 {
1404 throw std::invalid_argument("State is DEPARTING but the intersection variables are not available");
1405 }
1406 planWhenDEPARTING(req, resp, current_state, intersection_end_downtrack_.get(), intersection_speed_.get());
1407 break;
1408
1409 default:
1410 throw std::invalid_argument("LCIStrategic Strategic Plugin entered unknown state");
1411 break;
1412 }
1413
1414 } while (transition_table_.getState() != prev_state); // If the state has changed then continue looping
1415
1416 std::chrono::system_clock::time_point execution_end_time = std::chrono::system_clock::now(); // Planning complete
1417
1418 auto execution_duration = execution_end_time - execution_start_time;
1419 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "ExecutionTime lci_strategic_plugin: " << std::chrono::duration<double>(execution_duration).count());
1420
1421 return;
1422 // We need to evaluate the events so the state transitions can be triggered
1423}
1424
1425carma_planning_msgs::msg::Maneuver LCIStrategicPlugin::composeTrajectorySmoothingManeuverMessage(double start_dist, double end_dist, const std::vector<lanelet::ConstLanelet>& crossed_lanelets, double start_speed,
1426 double target_speed, rclcpp::Time start_time, rclcpp::Time end_time,
1427 const TrajectoryParams& tsp) const
1428{
1429 carma_planning_msgs::msg::Maneuver maneuver_msg;
1430 maneuver_msg.type = carma_planning_msgs::msg::Maneuver::LANE_FOLLOWING;
1431 maneuver_msg.lane_following_maneuver.parameters.negotiation_type =
1432 carma_planning_msgs::msg::ManeuverParameters::NO_NEGOTIATION;
1433 maneuver_msg.lane_following_maneuver.parameters.presence_vector =
1434 carma_planning_msgs::msg::ManeuverParameters::HAS_TACTICAL_PLUGIN | carma_planning_msgs::msg::ManeuverParameters::HAS_FLOAT_META_DATA | carma_planning_msgs::msg::ManeuverParameters::HAS_INT_META_DATA;
1435 maneuver_msg.lane_following_maneuver.parameters.planning_tactical_plugin =
1437 maneuver_msg.lane_following_maneuver.parameters.planning_strategic_plugin =
1439 maneuver_msg.lane_following_maneuver.start_dist = start_dist;
1440 maneuver_msg.lane_following_maneuver.start_speed = start_speed;
1441 maneuver_msg.lane_following_maneuver.start_time = start_time;
1442 maneuver_msg.lane_following_maneuver.end_dist = end_dist;
1443 maneuver_msg.lane_following_maneuver.end_speed = target_speed;
1444 maneuver_msg.lane_following_maneuver.end_time = end_time;
1445
1446 maneuver_msg.lane_following_maneuver.parameters.string_valued_meta_data.push_back(light_controlled_intersection_strategy_);
1447
1448 maneuver_msg.lane_following_maneuver.parameters.float_valued_meta_data.push_back(tsp.a1_);
1449 maneuver_msg.lane_following_maneuver.parameters.float_valued_meta_data.push_back(tsp.v1_);
1450 maneuver_msg.lane_following_maneuver.parameters.float_valued_meta_data.push_back(tsp.x1_);
1451
1452 maneuver_msg.lane_following_maneuver.parameters.float_valued_meta_data.push_back(tsp.a2_);
1453 maneuver_msg.lane_following_maneuver.parameters.float_valued_meta_data.push_back(tsp.v2_);
1454 maneuver_msg.lane_following_maneuver.parameters.float_valued_meta_data.push_back(tsp.x2_);
1455
1456 maneuver_msg.lane_following_maneuver.parameters.float_valued_meta_data.push_back(tsp.a3_);
1457 maneuver_msg.lane_following_maneuver.parameters.float_valued_meta_data.push_back(tsp.v3_);
1458 maneuver_msg.lane_following_maneuver.parameters.float_valued_meta_data.push_back(tsp.x3_);
1459
1460 maneuver_msg.lane_following_maneuver.parameters.int_valued_meta_data.push_back(static_cast<int>(tsp.case_num));
1461 maneuver_msg.lane_following_maneuver.parameters.int_valued_meta_data.push_back(static_cast<int>(tsp.is_algorithm_successful));
1462
1463 for (auto llt : crossed_lanelets)
1464 {
1465 maneuver_msg.lane_following_maneuver.lane_ids.push_back(std::to_string(llt.id()));
1466 }
1467 // Start time and end time for maneuver are assigned in updateTimeProgress
1468
1469 RCLCPP_INFO_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Creating TrajectorySmoothingManeuver start dist: " << start_dist << " end dist: " << end_dist
1470 << " start_time: " << std::to_string(start_time.seconds())
1471 << " end_time: " << std::to_string(end_time.seconds()));
1472
1473 return maneuver_msg;
1474}
1475
1476carma_planning_msgs::msg::Maneuver LCIStrategicPlugin::composeStopAndWaitManeuverMessage(double current_dist, double end_dist,
1477 double start_speed,
1478 const lanelet::Id& starting_lane_id,
1479 const lanelet::Id& ending_lane_id,
1480 rclcpp::Time start_time, rclcpp::Time end_time, double stopping_accel) const
1481{
1482 carma_planning_msgs::msg::Maneuver maneuver_msg;
1483 maneuver_msg.type = carma_planning_msgs::msg::Maneuver::STOP_AND_WAIT;
1484 maneuver_msg.stop_and_wait_maneuver.parameters.negotiation_type = carma_planning_msgs::msg::ManeuverParameters::NO_NEGOTIATION;
1485 maneuver_msg.stop_and_wait_maneuver.parameters.presence_vector =
1486 carma_planning_msgs::msg::ManeuverParameters::HAS_TACTICAL_PLUGIN | carma_planning_msgs::msg::ManeuverParameters::HAS_FLOAT_META_DATA;
1487 maneuver_msg.stop_and_wait_maneuver.parameters.planning_tactical_plugin = config_.stop_and_wait_plugin_name;
1488 maneuver_msg.stop_and_wait_maneuver.parameters.planning_strategic_plugin = config_.strategic_plugin_name;
1489 maneuver_msg.stop_and_wait_maneuver.start_dist = current_dist;
1490 maneuver_msg.stop_and_wait_maneuver.end_dist = end_dist;
1491 maneuver_msg.stop_and_wait_maneuver.start_speed = start_speed;
1492 maneuver_msg.stop_and_wait_maneuver.start_time = start_time;
1493 maneuver_msg.stop_and_wait_maneuver.end_time = end_time;
1494 maneuver_msg.stop_and_wait_maneuver.starting_lane_id = std::to_string(starting_lane_id);
1495 maneuver_msg.stop_and_wait_maneuver.ending_lane_id = std::to_string(ending_lane_id);
1496
1497 // Set the meta data for the stop location buffer
1498 maneuver_msg.stop_and_wait_maneuver.parameters.float_valued_meta_data.push_back(config_.stopping_location_buffer);
1499 maneuver_msg.stop_and_wait_maneuver.parameters.float_valued_meta_data.push_back(stopping_accel);
1500
1501 RCLCPP_INFO_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Creating stop and wait start dist: " << current_dist << " end dist: " << end_dist
1502 << " start_time: " << std::to_string(start_time.seconds())
1503 << " end_time: " << std::to_string(end_time.seconds())
1504 << " stopping_accel: " << stopping_accel);
1505
1506 return maneuver_msg;
1507}
1508
1509carma_planning_msgs::msg::Maneuver LCIStrategicPlugin::composeIntersectionTransitMessage(double start_dist, double end_dist,
1510 double start_speed, double target_speed,
1511 rclcpp::Time start_time, rclcpp::Time end_time,
1512 const lanelet::Id& starting_lane_id,
1513 const lanelet::Id& ending_lane_id) const
1514{
1515 carma_planning_msgs::msg::Maneuver maneuver_msg;
1516 maneuver_msg.type = carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_STRAIGHT;
1517 maneuver_msg.intersection_transit_straight_maneuver.parameters.negotiation_type =
1518 carma_planning_msgs::msg::ManeuverParameters::NO_NEGOTIATION;
1519 maneuver_msg.intersection_transit_straight_maneuver.parameters.presence_vector =
1520 carma_planning_msgs::msg::ManeuverParameters::HAS_TACTICAL_PLUGIN;
1521 maneuver_msg.intersection_transit_straight_maneuver.parameters.planning_tactical_plugin =
1523 maneuver_msg.intersection_transit_straight_maneuver.parameters.planning_strategic_plugin =
1525 maneuver_msg.intersection_transit_straight_maneuver.start_dist = start_dist;
1526 maneuver_msg.intersection_transit_straight_maneuver.start_speed = start_speed;
1527 maneuver_msg.intersection_transit_straight_maneuver.start_time = start_time;
1528 maneuver_msg.intersection_transit_straight_maneuver.end_dist = end_dist;
1529 maneuver_msg.intersection_transit_straight_maneuver.end_speed = target_speed;
1530 maneuver_msg.intersection_transit_straight_maneuver.end_time = end_time;
1531 maneuver_msg.intersection_transit_straight_maneuver.starting_lane_id = std::to_string(starting_lane_id);
1532 maneuver_msg.intersection_transit_straight_maneuver.ending_lane_id = std::to_string(ending_lane_id);
1533
1534 // Start time and end time for maneuver are assigned in updateTimeProgress
1535
1536 RCLCPP_INFO_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Creating IntersectionTransitManeuver start dist: " << start_dist << " end dist: " << end_dist
1537 << " From lanelet: " << starting_lane_id
1538 << " to lanelet: " << ending_lane_id
1539 << " From start_time: " << std::to_string(start_time.seconds())
1540 << " to end_time: " << std::to_string(end_time.seconds()));
1541
1542 return maneuver_msg;
1543}
1544
1546{
1547 return true;
1548}
1549
1551{
1552 return "v1.0";
1553}
1554
1555} // namespace lci_strategic_plugin
1556
1557
1558#include "rclcpp_components/register_node_macro.hpp"
1559
1560// Register the component with class_loader
1561RCLCPP_COMPONENTS_REGISTER_NODE(lci_strategic_plugin::LCIStrategicPlugin)
virtual carma_wm::WorldModelConstPtr get_world_model() final
Method to return the default world model provided as a convience by this base class If this method or...
void handleStopping(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req, carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp, const VehicleState &current_state, const lanelet::CarmaTrafficSignalPtr &traffic_light, const lanelet::ConstLanelet &entry_lanelet, const lanelet::ConstLanelet &exit_lanelet, const lanelet::ConstLanelet &current_lanelet, double traffic_light_down_track, bool is_emergency=false)
This function returns stopping maneuver if the vehicle is able to stop at red and in safe stopping di...
void handleGreenSignalScenario(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req, carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp, const VehicleState &current_state, double current_state_speed, const lanelet::CarmaTrafficSignalPtr &traffic_light, const lanelet::ConstLanelet &entry_lanelet, const lanelet::ConstLanelet &exit_lanelet, double traffic_light_down_track, const TrajectoryParams &ts_params, bool is_certainty_check_optional)
This function returns valid maneuvers if the vehicle is able to utilize trajectory smoothing paramete...
void lookupFrontBumperTransform()
Lookup transfrom from front bumper to base link.
LCIStrategicPluginConfig config_
Config containing configurable algorithm parameters.
boost::optional< bool > canArriveAtGreenWithCertainty(const rclcpp::Time &light_arrival_time_by_algo, const lanelet::CarmaTrafficSignalPtr &traffic_light, bool check_late, bool check_early) const
Return true if the car can arrive at given arrival time within green light time buffer.
BoundaryDistances get_delta_x(double v0, double v1, double v_max, double v_min, double a_max, double a_min)
Get boundary distances used to compare against current state in order to create trajectory smoothing ...
carma_ros2_utils::CallbackReturn on_activate_plugin()
Method which is triggered when this plugin is moved from the INACTIVE to ACTIVE states....
bool validLightState(const boost::optional< std::pair< boost::posix_time::ptime, lanelet::CarmaTrafficSignalState > > &optional_state, const rclcpp::Time &source_time) const
Helper method that checks both if the input optional light state is set and if the state it contains ...
TrajectoryParams handleFailureCaseHelper(const lanelet::CarmaTrafficSignalPtr &traffic_light, double current_time, double starting_speed, double departure_speed, double speed_limit, double remaining_downtrack, double traffic_light_downtrack)
Helper function to handleFailureCase that modifies ts_params to desired new parameters....
VehicleState extractInitialState(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req) const
Helper method to extract the initial vehicle state from the planning request method based on if the p...
boost::optional< rclcpp::Time > nearest_green_entry_time_cached_
carma_wm::WorldModelConstPtr wm_
World Model pointer.
void mobilityOperationCb(carma_v2x_msgs::msg::MobilityOperation::UniquePtr msg)
callback function for mobility operation
carma_ros2_utils::PubPtr< std_msgs::msg::Float64 > tf_distance_pub_
double findSpeedLimit(const lanelet::ConstLanelet &llt) const
Given a Lanelet, find it's associated Speed Limit.
carma_planning_msgs::msg::Maneuver composeTrajectorySmoothingManeuverMessage(double start_dist, double end_dist, const std::vector< lanelet::ConstLanelet > &crossed_lanelets, double start_speed, double target_speed, rclcpp::Time start_time, rclcpp::Time end_time, const TrajectoryParams &tsp) const
Compose a trajectory smoothing maneuver msg (sent as transit maneuver message)
rclcpp::Duration get_earliest_entry_time(double remaining_distance, double free_flow_speed, double current_speed, double departure_speed, double max_accel, double max_decel) const
Gets the earliest entry time into the intersection that is kinematically possible for the vehicle....
void planWhenDEPARTING(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req, carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp, const VehicleState &current_state, double intersection_end_downtrack, double intersection_speed_limit)
Method for performing maneuver planning when the current plugin state is TransitState::DEPARTING Ther...
carma_ros2_utils::SubPtr< carma_v2x_msgs::msg::MobilityOperation > mob_operation_sub_
carma_ros2_utils::CallbackReturn on_configure_plugin()
Method which is triggered when this plugin is moved from the UNCONFIGURED to INACTIVE states....
carma_ros2_utils::SubPtr< carma_v2x_msgs::msg::BSM > bsm_sub_
carma_ros2_utils::PubPtr< std_msgs::msg::Int8 > case_pub_
bool get_availability()
Get the availability status of this plugin based on the current operating environment....
void handleFailureCase(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req, carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp, const VehicleState &current_state, double current_state_speed, double speed_limit, double remaining_time, lanelet::Id exit_lanelet_id, const lanelet::CarmaTrafficSignalPtr &traffic_light, double traffic_light_down_track, const TrajectoryParams &ts_params)
When the vehicle is not able to successfully run the algorithm or not able to stop,...
std::tuple< rclcpp::Time, bool, bool > get_final_entry_time_and_conditions(const VehicleState &current_state, const rclcpp::Time &earliest_entry_time, lanelet::CarmaTrafficSignalPtr traffic_light)
Get the final entry time from either vehicle's own internal ET calculation (TSMO UC2) or from carma-s...
LCIStrategicPlugin(const rclcpp::NodeOptions &)
Default constructor for RouteFollowingPlugin class.
std::vector< lanelet::ConstLanelet > getLaneletsBetweenWithException(double start_downtrack, double end_downtrack, bool shortest_path_only=false, bool bounds_inclusive=true) const
Helper method which calls carma_wm::WorldModel::getLaneletsBetween(start_downtrack,...
void planWhenWAITING(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req, carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp, const VehicleState &current_state, const lanelet::CarmaTrafficSignalPtr &traffic_light, const lanelet::ConstLanelet &entry_lanelet, const lanelet::ConstLanelet &exit_lanelet, const lanelet::ConstLanelet &current_lanelet)
Method for performing maneuver planning when the current plugin state is TransitState::WAITING Theref...
void BSMCb(carma_v2x_msgs::msg::BSM::UniquePtr msg)
BSM callback function.
void print_params(TrajectoryParams params)
Helper method to print TrajectoryParams.
void parseStrategyParams(const std::string &strategy_params)
parse strategy parameters
carma_v2x_msgs::msg::MobilityOperation generateMobilityOperation()
Generates Mobility Operation messages.
carma_ros2_utils::PubPtr< std_msgs::msg::Float64 > earliest_et_pub_
TrajectoryParams get_ts_case(double t, double et, double v0, double v1, double v_max, double v_min, double a_max, double a_min, double x0, double x_end, double dx, BoundaryDistances boundary_distances, std::vector< TrajectoryParams > params)
void planWhenUNAVAILABLE(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req, carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp, const VehicleState &current_state, const lanelet::CarmaTrafficSignalPtr &traffic_light, const lanelet::ConstLanelet &entry_lanelet, const lanelet::ConstLanelet &exit_lanelet, const lanelet::ConstLanelet &current_lanelet)
Method for performing maneuver planning when the current plugin state is TransitState::UNAVAILABLE Th...
void publishTrajectorySmoothingInfo()
Publish trajectory smoothing info at a fixed rate.
carma_ros2_utils::PubPtr< carma_v2x_msgs::msg::MobilityOperation > mobility_operation_pub_
carma_planning_msgs::msg::Maneuver composeStopAndWaitManeuverMessage(double current_dist, double end_dist, double start_speed, const lanelet::Id &starting_lane_id, const lanelet::Id &ending_lane_id, rclcpp::Time start_time, rclcpp::Time end_time, double stopping_accel) const
Compose a stop and wait maneuver message based on input params.
std::string get_version_id()
Returns the version id of this plugin.
void handleCruisingUntilStop(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req, carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp, const VehicleState &current_state, double current_state_speed, const lanelet::CarmaTrafficSignalPtr &traffic_light, double traffic_light_down_track, const TrajectoryParams &ts_params)
This function returns valid maneuvers if the vehicle is able to utilize trajectory smoothing paramete...
boost::optional< double > intersection_end_downtrack_
double estimate_distance_to_stop(double v, double a) const
Helper method to use basic kinematics to compute an estimated stopping distance from from the inputs.
bool isStateAllowedGreen(const lanelet::CarmaTrafficSignalState &state) const
Method to check if the state is an allowed green movement state. Currently Permissive and Protected g...
TurnDirection getTurnDirectionAtIntersection(std::vector< lanelet::ConstLanelet > lanelets_list)
Determine the turn direction at intersection.
void plan_maneuvers_callback(std::shared_ptr< rmw_request_id_t > srv_header, carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req, carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp)
Service callback for arbitrator maneuver planning.
void planWhenAPPROACHING(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req, carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp, const VehicleState &current_state, const lanelet::CarmaTrafficSignalPtr &traffic_light, const lanelet::ConstLanelet &entry_lanelet, const lanelet::ConstLanelet &exit_lanelet, const lanelet::ConstLanelet &current_lanelet)
Method for performing maneuver planning when the current plugin state is TransitState::APPROACHING Th...
LCIStrategicStateTransitionTable transition_table_
State Machine Transition table.
std::vector< TrajectoryParams > get_boundary_traj_params(double t, double v0, double v1, double v_max, double v_min, double a_max, double a_min, double x0, double x_end, double dx, BoundaryDistances boundary_distances)
Get all possible trajectory smoothing parameters for each segments. Later this will be used to genera...
TSCase last_case_num_
Useful metrics for LCI Plugin.
void print_boundary_distances(BoundaryDistances delta_xs)
Helper method to print TrajectoryParams.
boost::optional< double > intersection_speed_
Cache variables for storing the current intersection state between state machine transitions.
void publishMobilityOperation()
Publish mobility operation at a fixed rate.
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > &parameters)
Callback for dynamic parameter updates.
bool supportedLightState(lanelet::CarmaTrafficSignalState state) const
Helper method to evaluate if the given traffic light state is supported by this plugin.
std::unique_ptr< tf2_ros::TransformListener > tf2_listener_
rclcpp::TimerBase::SharedPtr ts_info_pub_timer_
carma_ros2_utils::PubPtr< std_msgs::msg::Float64 > et_pub_
rclcpp::TimerBase::SharedPtr mob_op_pub_timer_
carma_planning_msgs::msg::Maneuver composeIntersectionTransitMessage(double start_dist, double end_dist, double start_speed, double target_speed, rclcpp::Time start_time, rclcpp::Time end_time, const lanelet::Id &starting_lane_id, const lanelet::Id &ending_lane_id) const
Compose a intersection transit maneuver message based on input params.
TransitState getState() const
Returns the current state.
void signal(TransitEvent signal)
Trigger signal for the transition table.
#define EPSILON
#define GET_MANEUVER_PROPERTY(mvr, property)
auto to_string(const UtmZone &zone) -> std::string
Definition: utm_zone.cpp:21
TransitState
Enum describing the possible states of the LCIStrategic Strategic Plugin.
Definition: lci_states.hpp:25
Struct to store the configuration settings for the LCIStrategicPlugin class.
bool enable_carma_streets_connection
Bool: Enable carma streets connection.
std::string vehicle_id
License plate of the vehicle.
double trajectory_smoothing_activation_distance
Downtrack distance until nearest intersection where the Trajectory Smoothing algorithm should activat...
double algo_minimum_speed
Minimum allowable speed TS algorithm in m/s.
double vehicle_accel_limit_multiplier
A multiplier to apply to the maximum allowable vehicle acceleration limit so we plan under our capabi...
double min_maneuver_planning_period
The minimum period in seconds which a maneuver plan must cover if the plugin wishes to control the wh...
double green_light_time_buffer
A buffer in seconds around the green phase which will reduce the phase length such that vehicle still...
std::string stop_and_wait_plugin_name
The name of the plugin to use for stop and wait trajectory planning.
double stopping_location_buffer
A buffer infront of the stopping location which will still be considered a valid stop....
double reaction_time
Double: Vehicle reaction time to a received schedule in seconds (approximate value,...
double vehicle_decel_limit
The maximum allowable vehicle deceleration limit in m/s.
double vehicle_decel_limit_multiplier
A multiplier to apply to the maximum allowable vehicle deceleration limit so we plan under our capabi...
double min_approach_distance
The minimum distance in meters that the vehicle can be at before requiring a transition to the APPROA...
double vehicle_accel_limit
The maximum allowable vehicle acceleration limit in m/s.
std::string strategic_plugin_name
The name to use for this plugin during comminications with the arbitrator.
double mobility_rate
Double: Mobility operation rate.
double desired_distance_to_stop_buffer
Double: Desired distance to stop buffer in meters.
double min_gap
Double: Minimum inter-vehicle gap.
Struct representing a vehicle state for the purposes of planning.