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::PROTECTED_MOVEMENT_ALLOWED: // Solid Green no chance of conflict traffic
200 // (normally used with arrows)
201 return true;
202
203 // Unsupported light states
204 case lanelet::CarmaTrafficSignalState::PERMISSIVE_MOVEMENT_ALLOWED: // Solid Green there could be conflict traffic
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 = (early_arrival_state_by_algo_optional.get().second == lanelet::CarmaTrafficSignalState::PROTECTED_MOVEMENT_ALLOWED);
329
330 if (check_late)
331 can_make_late_arrival = (late_arrival_state_by_algo_optional.get().second == lanelet::CarmaTrafficSignalState::PROTECTED_MOVEMENT_ALLOWED);
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
341std::vector<lanelet::ConstLanelet> LCIStrategicPlugin::getLaneletsBetweenWithException(double start_downtrack,
342 double end_downtrack,
343 bool shortest_path_only,
344 bool bounds_inclusive) const
345{
346 std::vector<lanelet::ConstLanelet> crossed_lanelets =
347 wm_->getLaneletsBetween(start_downtrack, end_downtrack, shortest_path_only, bounds_inclusive);
348
349 if (crossed_lanelets.size() == 0)
350 {
351 throw std::invalid_argument("getLaneletsBetweenWithException called but inputs do not cross any lanelets going "
352 "from: " +
353 std::to_string(start_downtrack) + " to: " + std::to_string(end_downtrack));
354 }
355
356 return crossed_lanelets;
357}
358
359void LCIStrategicPlugin::handleStopping(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
360 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
361 const VehicleState& current_state,
362 const lanelet::CarmaTrafficSignalPtr& traffic_light,
363 const lanelet::ConstLanelet& entry_lanelet, const lanelet::ConstLanelet& exit_lanelet, const lanelet::ConstLanelet& current_lanelet,
364 double traffic_light_down_track,
365 bool is_emergency)
366{
367 double distance_remaining_to_traffic_light = traffic_light_down_track - current_state.downtrack;
368
369 // Identify the lanelets which will be crossed by approach maneuvers lane follow maneuver
370 std::vector<lanelet::ConstLanelet> crossed_lanelets =
371 getLaneletsBetweenWithException(current_state.downtrack, traffic_light_down_track, true, true);
372
373 double decel_rate = max_comfort_decel_norm_; // Kinematic |(v_f - v_i) / t = a|
374
375 if (is_emergency)
376 {
377 decel_rate = emergency_decel_norm_;
379 }
380 else
381 {
383 }
384
385 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "HANDLE_STOPPING: Planning stop and wait maneuver at decel_rate: " << decel_rate);
386
387 resp->new_plan.maneuvers.push_back(composeStopAndWaitManeuverMessage(
388 current_state.downtrack, traffic_light_down_track, current_state.speed, crossed_lanelets.front().id(),
389 crossed_lanelets.back().id(), current_state.stamp,
390 current_state.stamp + rclcpp::Duration(config_.min_maneuver_planning_period * 1e9), decel_rate));
391}
392
393
394void LCIStrategicPlugin::handleFailureCase(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
395 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
396 const VehicleState& current_state,
397 double current_state_speed,
398 double speed_limit,
399 double remaining_time,
400 lanelet::Id exit_lanelet_id,
401 const lanelet::CarmaTrafficSignalPtr& traffic_light,
402 double traffic_light_down_track, const TrajectoryParams& ts_params)
403{
404 double distance_remaining_to_traffic_light = traffic_light_down_track - current_state.downtrack;
405
406 // Identify the lanelets which will be crossed by approach maneuvers lane follow maneuver
407 std::vector<lanelet::ConstLanelet> crossed_lanelets =
408 getLaneletsBetweenWithException(current_state.downtrack, traffic_light_down_track, true, true);
409
410 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);
411
412 if (incomplete_traj_params.is_algorithm_successful == false)
413 {
414 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Failed to generate maneuver for edge cases...");
415 return;
416 }
417
418 resp->new_plan.maneuvers.push_back(composeTrajectorySmoothingManeuverMessage(current_state.downtrack, traffic_light_down_track, crossed_lanelets,
419 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));
420
421 double intersection_length = intersection_end_downtrack_.get() - traffic_light_down_track;
422
423 rclcpp::Time intersection_exit_time =
424 current_state.stamp + rclcpp::Duration(incomplete_traj_params.modified_remaining_time * 1e9) + rclcpp::Duration(intersection_length / incomplete_traj_params.modified_departure_speed * 1e9);
425
426 resp->new_plan.maneuvers.push_back(composeIntersectionTransitMessage(
427 traffic_light_down_track, intersection_end_downtrack_.get(), intersection_speed_.get(),
428 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()));
429
431}
432
433void LCIStrategicPlugin::handleCruisingUntilStop(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
434 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
435 const VehicleState& current_state,
436 double current_state_speed,
437 const lanelet::CarmaTrafficSignalPtr& traffic_light,
438 double traffic_light_down_track, const TrajectoryParams& ts_params)
439{
440 if (!ts_params.is_algorithm_successful || ts_params.case_num != TSCase::CASE_8)
441 {
442 RCLCPP_WARN_STREAM(rclcpp::get_logger("lci_strategic_plugin"),"handleCruisingUntilStop is called but it is not case_8");
443 return;
444 }
445
446 auto new_ts_params = ts_params;
447
448 double decel_rate = std::fabs(ts_params.a3_);
449
450 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "CASE_8: Planning cruise and stop with decel_rate: " << decel_rate);
451
452 new_ts_params.t3_ = new_ts_params.t2_;
453 new_ts_params.x3_ = new_ts_params.x2_;
454 new_ts_params.v3_ = new_ts_params.v2_;
455 new_ts_params.a3_ = new_ts_params.a2_;
456
457 // Identify the lanelets which will be crossed by approach maneuvers stopping part
458 std::vector<lanelet::ConstLanelet> lane_follow_crossed_lanelets =
459 getLaneletsBetweenWithException(new_ts_params.x1_, new_ts_params.x2_, true, true);
460
461 resp->new_plan.maneuvers.push_back(composeTrajectorySmoothingManeuverMessage(current_state.downtrack, new_ts_params.x2_, lane_follow_crossed_lanelets,
462 current_state_speed, new_ts_params.v2_, current_state.stamp, rclcpp::Time(new_ts_params.t2_ * 1e9), new_ts_params));
463
464 // Identify the lanelets which will be crossed by approach maneuvers stopping part
465 std::vector<lanelet::ConstLanelet> case_8_crossed_lanelets =
466 getLaneletsBetweenWithException(new_ts_params.x2_, traffic_light_down_track, true, true);
467
468 resp->new_plan.maneuvers.push_back(composeStopAndWaitManeuverMessage(
469 new_ts_params.x2_, traffic_light_down_track, new_ts_params.v2_, case_8_crossed_lanelets.front().id(),
470 case_8_crossed_lanelets.back().id(), rclcpp::Time(new_ts_params.t2_ * 1e9),
471 rclcpp::Time(new_ts_params.t2_ * 1e9) + rclcpp::Duration(config_.min_maneuver_planning_period * 1e9), decel_rate));
472
473 return;
474}
475
476void LCIStrategicPlugin::handleGreenSignalScenario(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
477 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
478 const VehicleState& current_state,
479 double current_state_speed,
480 const lanelet::CarmaTrafficSignalPtr& traffic_light,
481 const lanelet::ConstLanelet& entry_lanelet, const lanelet::ConstLanelet& exit_lanelet,
482 double traffic_light_down_track, const TrajectoryParams& ts_params, bool is_certainty_check_optional)
483{
484 if (!ts_params.is_algorithm_successful || ts_params.case_num == TSCase::CASE_8)
485 {
486 return;
487 }
488
489 rclcpp::Time light_arrival_time_by_algo = rclcpp::Time(ts_params.t3_ * 1e9);
490 double remaining_time = light_arrival_time_by_algo.seconds() - rclcpp::Time(req->header.stamp, RCL_SYSTEM_TIME).seconds();
491 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));
492 auto can_make_green_optional = canArriveAtGreenWithCertainty(light_arrival_time_by_algo, traffic_light);
493
494 // Identify the lanelets which will be crossed by approach maneuvers lane follow maneuver
495 std::vector<lanelet::ConstLanelet> crossed_lanelets =
496 getLaneletsBetweenWithException(current_state.downtrack, traffic_light_down_track, true, true);
497
498 // no change for maneuver if invalid light states
499 if (!can_make_green_optional)
500 return;
501
502 if (can_make_green_optional.get() || is_certainty_check_optional)
503 {
504 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");
505
506 resp->new_plan.maneuvers.push_back(composeTrajectorySmoothingManeuverMessage(current_state.downtrack, traffic_light_down_track, crossed_lanelets,
507 current_state_speed, ts_params.v3_, current_state.stamp, light_arrival_time_by_algo, ts_params));
508
509 double intersection_length = intersection_end_downtrack_.get() - traffic_light_down_track;
510
511 rclcpp::Time intersection_exit_time =
512 light_arrival_time_by_algo + rclcpp::Duration(intersection_length / intersection_speed_.get() * 1e9);
513
514 resp->new_plan.maneuvers.push_back(composeIntersectionTransitMessage(
515 traffic_light_down_track, intersection_end_downtrack_.get(), intersection_speed_.get(),
516 intersection_speed_.get(), light_arrival_time_by_algo, intersection_exit_time, crossed_lanelets.back().id(), crossed_lanelets.back().id()));
517 }
518}
519
520
521TrajectoryParams 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)
522{
523 //Requested maneuver needs to be modified to meet remaining_dist req
524 //by trying to get close to the target_speed and remaining_time as much as possible
525 TrajectoryParams return_params;
526 TrajectoryParams traj_upper;
527 TrajectoryParams traj_lower;
528
529 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "HANDLE_LAST_RESORT_CASE: Starting...");
530 double starting_downtrack = traffic_light_downtrack - remaining_downtrack;
531 double modified_remaining_time_upper; // upper meaning downtrack vs time trajectory is curved upwards
532 double modified_remaining_time_lower; // lower meaning downtrack vs time trajectory is curved lower
533 double modified_departure_speed_upper;
534 double modified_departure_speed_lower;
535 bool calculation_success_upper = true; // identifies places in codes where calculation can be invalid such as negative distance
536
537 // the upper ET
538 // accel case
539 traj_upper.t0_ = current_time;
540 traj_upper.v0_ = starting_speed;
541 traj_upper.x0_ = starting_downtrack;
542 traj_upper.is_algorithm_successful = true;
543 traj_upper.case_num = CASE_1;
544
545 if (departure_speed >= starting_speed)
546 {
547 if ((pow(departure_speed,2) - pow(starting_speed,2))/(2*max_comfort_accel_) >= remaining_downtrack)
548 {
549 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "HandleFailureCase -> Upper Trajectory -> Current Speed <= Desired Departure Speed, Actual Departure Speed < Desired Departure Speed");
550
551 modified_departure_speed_upper = sqrt(pow(starting_speed, 2) + (2 * max_comfort_accel_ * remaining_downtrack));
552 modified_remaining_time_upper = (modified_departure_speed_upper - starting_speed) / max_comfort_accel_;
553
554 traj_upper.t1_ = current_time + modified_remaining_time_upper;
555 traj_upper.v1_ = modified_departure_speed_upper;
556 traj_upper.a1_ = max_comfort_accel_;
557 traj_upper.x1_ = traffic_light_downtrack;
558
559 traj_upper.t2_ = traj_upper.t1_;
560 traj_upper.v2_ = traj_upper.v1_;
561 traj_upper.a2_ = traj_upper.a1_;
562 traj_upper.x2_ = traj_upper.x1_;
563
564 traj_upper.modified_departure_speed = modified_departure_speed_upper;
565 traj_upper.modified_remaining_time = modified_remaining_time_upper;
566 }
567 else // NOTE: most likely will not happen as it would have happened at trajectory smoothing part
568 {
569 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "HandleFailureCase -> Upper Trajectory -> Current Speed < Desired Departure Speed, Actual Departure Speed = Desired Departure Speed");
570
571 double cruising_distance = remaining_downtrack - (pow(departure_speed, 2) - pow(starting_speed, 2))/ ( 2 * max_comfort_accel_);
572 if (cruising_distance < -EPSILON)
573 {
574 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Detected calculation failure in upper case 2");
575 calculation_success_upper = false;
576 }
577 modified_remaining_time_upper = ((departure_speed - starting_speed) / max_comfort_accel_) + (cruising_distance / departure_speed);
578
579 traj_upper.t1_ = current_time + ((departure_speed - starting_speed) / max_comfort_accel_);
580 traj_upper.v1_ = departure_speed;
581 traj_upper.a1_ = max_comfort_accel_;
582 traj_upper.x1_ = starting_downtrack + (pow(departure_speed, 2) - pow(starting_speed, 2)) / (2 * max_comfort_accel_);
583
584 traj_upper.t2_ = current_time + modified_remaining_time_upper;
585 traj_upper.v2_ = departure_speed;
586 traj_upper.a2_ = 0;
587 traj_upper.x2_ = traffic_light_downtrack;
588
589 traj_upper.modified_departure_speed = departure_speed;
590 traj_upper.modified_remaining_time = modified_remaining_time_upper;
591 }
592 }
593
594 if (departure_speed < starting_speed) // NOTE: most cases will not run due to departure speed being equal to speed limit
595 {
596 if ((pow(departure_speed,2) - pow(starting_speed,2))/(2*max_comfort_decel_) >= remaining_downtrack)
597 {
598 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "HandleFailureCase -> Upper Trajectory -> Current Speed > Desired Departure Speed, Actual Departure Speed > Desired Departure Speed");
599
600 modified_departure_speed_upper = sqrt(pow(starting_speed, 2) + (2 * max_comfort_decel_ * remaining_downtrack));
601 modified_remaining_time_upper = (modified_departure_speed_upper - starting_speed) / max_comfort_decel_;
602
603 traj_upper.t1_ = current_time + modified_remaining_time_upper;
604 traj_upper.v1_ = modified_departure_speed_upper;
605 traj_upper.a1_ = max_comfort_decel_;
606 traj_upper.x1_ = traffic_light_downtrack;
607
608 traj_upper.t2_ = traj_upper.t1_;
609 traj_upper.v2_ = traj_upper.v1_;
610 traj_upper.a2_ = traj_upper.a1_;
611 traj_upper.x2_ = traj_upper.x1_;
612
613 traj_upper.modified_departure_speed = modified_departure_speed_upper;
614 traj_upper.modified_remaining_time = modified_remaining_time_upper;
615 }
616 else // NOTE: most likely will not happen as it would have happened at trajectory smoothing part
617 {
618 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "HandleFailureCase -> Upper Trajectory -> Current Speed > Desired Departure Speed, Actual Departure Speed = Desired Departure Speed");
619
620 double cruising_distance = remaining_downtrack - (pow(departure_speed, 2) - pow(starting_speed, 2))/ ( 2 * max_comfort_decel_);
621
622 if (cruising_distance < -EPSILON)
623 {
624 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Detected calculation failure in upper case 4");
625 calculation_success_upper = false;
626 }
627
628 modified_remaining_time_upper = cruising_distance / starting_speed + (departure_speed - starting_speed) / max_comfort_decel_ ;
629
630 traj_upper.t1_ = current_time + cruising_distance / starting_speed;
631 traj_upper.v1_ = starting_speed;
632 traj_upper.a1_ = 0.0;
633 traj_upper.x1_ = starting_downtrack + cruising_distance;
634
635 traj_upper.t2_ = current_time + modified_remaining_time_upper;
636 traj_upper.v2_ = departure_speed;
637 traj_upper.a2_ = max_comfort_decel_;
638 traj_upper.x2_ = traffic_light_downtrack;
639
640 traj_upper.modified_departure_speed = departure_speed;
641 traj_upper.modified_remaining_time = modified_remaining_time_upper;
642 }
643 }
644
645 traj_upper.t3_ = traj_upper.t2_;
646 traj_upper.v3_ = traj_upper.v2_;
647 traj_upper.a3_ = traj_upper.a2_;
648 traj_upper.x3_ = traj_upper.x2_;
649
650 // The lower ET
651 // (note that the distance is definitely not enough for deceleration to zero speed, therefore, modified_departure_speed will be greater than zero for sure!).
652 modified_departure_speed_lower = sqrt(pow(starting_speed, 2) + (2 * max_comfort_decel_ * remaining_downtrack));
653 modified_remaining_time_lower = (modified_departure_speed_lower - starting_speed) / max_comfort_decel_;
654
655 traj_lower.t0_ = current_time;
656 traj_lower.v0_ = starting_speed;
657 traj_lower.x0_ = starting_downtrack;
658 traj_lower.is_algorithm_successful = true;
659 traj_lower.case_num = CASE_1;
660
661 traj_lower.t1_ = current_time + modified_remaining_time_lower;
662 traj_lower.v1_ = modified_departure_speed_lower;
663 traj_lower.a1_ = max_comfort_decel_;
664 traj_lower.x1_ = traffic_light_downtrack;
665
666 traj_lower.t2_ = traj_lower.t1_;
667 traj_lower.v2_ = traj_lower.v1_;
668 traj_lower.a2_ = traj_lower.a1_;
669 traj_lower.x2_ = traj_lower.x1_;
670
671 traj_lower.t3_ = traj_lower.t2_;
672 traj_lower.v3_ = traj_lower.v2_;
673 traj_lower.a3_ = traj_lower.a2_;
674 traj_lower.x3_ = traj_lower.x2_;
675
676 traj_lower.modified_departure_speed = modified_departure_speed_lower;
677 traj_lower.modified_remaining_time = modified_remaining_time_upper;
678
679 // Pick UPPER or LOWER trajectory based on light
680 bool is_return_params_found = false;
681
682 if (calculation_success_upper)
683 {
684 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Checking this time!: " << current_time + modified_remaining_time_upper);
685
686 auto upper_optional = traffic_light->predictState(lanelet::time::timeFromSec(current_time + modified_remaining_time_upper));
687
688 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Checking this time! state: " << upper_optional.get().second);
689
690 if (!validLightState(upper_optional, rclcpp::Time((current_time + modified_remaining_time_upper) * 1e9)))
691 {
692 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));
693 }
694 else
695 {
696 if (upper_optional.get().second == lanelet::CarmaTrafficSignalState::PROTECTED_MOVEMENT_ALLOWED)
697 {
698 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Detected Upper GREEN case");
699 return_params = traj_upper;
700 is_return_params_found = true;
701 }
702 }
703 }
704
705 if (!is_return_params_found)
706 {
707 auto lower_optional = traffic_light->predictState(lanelet::time::timeFromSec(current_time + modified_remaining_time_lower));
708
709 if (!validLightState(lower_optional, rclcpp::Time((current_time + modified_remaining_time_lower) * 1e9)))
710 {
711 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));
712 }
713 else
714 {
715 if (lower_optional.get().second == lanelet::CarmaTrafficSignalState::PROTECTED_MOVEMENT_ALLOWED)
716 {
717 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Detected Lower GREEN case");
718 return_params = traj_lower;
719 is_return_params_found = true;
720 }
721 }
722 }
723
724 // Handle hard failure case such as nan or invalid states
725 if (is_return_params_found && !isnan(return_params.modified_departure_speed) && return_params.modified_departure_speed > epsilon_ &&
726 return_params.modified_departure_speed < speed_limit ) //80_mph
727 {
728 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Updated the speed, and using modified_departure_speed: " << return_params.modified_departure_speed);
729 print_params(return_params);
730 return return_params;
731 }
732 else
733 {
734 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Unable to handle edge case gracefully");
735 return_params = TrajectoryParams(); //reset
736 return_params.is_algorithm_successful = false;
737 return return_params;
738 }
739}
740
741
742void LCIStrategicPlugin::planWhenUNAVAILABLE(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
743 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp, const VehicleState& current_state,
744 const lanelet::CarmaTrafficSignalPtr& traffic_light, const lanelet::ConstLanelet& entry_lanelet, const lanelet::ConstLanelet& exit_lanelet, const lanelet::ConstLanelet& current_lanelet)
745{
746 // Reset intersection state since in this state we are not yet known to be in or approaching an intersection
747 intersection_speed_ = boost::none;
748 intersection_end_downtrack_ = boost::none;
749 double current_state_speed = std::max(current_state.speed, config_.algo_minimum_speed * 1.001);
750
751
752 if (!traffic_light)
753 {
754 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "No lights found along route. Returning maneuver plan unchanged");
755 return;
756 }
757
759 double max_comfort_decel = -1.0 * config_.vehicle_decel_limit * config_.vehicle_decel_limit_multiplier;
760
761 auto stop_line = traffic_light->getStopLine(entry_lanelet);
762
763 if (!stop_line)
764 {
765 throw std::invalid_argument("Given entry lanelet doesn't have stop_line...");
766 }
767
768 double traffic_light_down_track =
769 wm_->routeTrackPos(stop_line.get().front().basicPoint2d()).downtrack;
770
771 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "traffic_light_down_track: " << traffic_light_down_track);
772
773 double distance_remaining_to_traffic_light = traffic_light_down_track - current_state.downtrack;
774
775 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "distance_remaining_to_traffic_light: " << distance_remaining_to_traffic_light <<
776 ", current_state.downtrack: " << current_state.downtrack);
777
778 distance_remaining_to_tf_ = distance_remaining_to_traffic_light; // performance metric
779
780 auto speed_limit = findSpeedLimit(current_lanelet);
781
782 current_state_speed = std::min(speed_limit, current_state_speed);
783
784 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "speed_limit (free flow speed): " << speed_limit);
785
786 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "trajectory_smoothing_activation_distance: " << config_.trajectory_smoothing_activation_distance);
787
788 double stopping_dist = estimate_distance_to_stop(current_state_speed, config_.vehicle_decel_limit_multiplier *
789 config_.vehicle_decel_limit); //accepts positive decel
790
791 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Stopping distance: " << stopping_dist);
792
793 double plugin_activation_distance = std::max(stopping_dist, config_.min_approach_distance);
794
795 plugin_activation_distance = std::max(plugin_activation_distance, config_.trajectory_smoothing_activation_distance);
796
797 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "plugin_activation_distance: " << plugin_activation_distance);
798
799 if (distance_remaining_to_traffic_light <= plugin_activation_distance)
800 {
801 RCLCPP_INFO_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Within intersection range");
802 transition_table_.signal(TransitEvent::IN_STOPPING_RANGE); // Evaluate Signal and Run Trajectory Smoothing Algorithm
803 }
804 else
805 {
807 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Not within intersection range");
808 }
809
810}
811
812void LCIStrategicPlugin::planWhenAPPROACHING(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
813 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp, const VehicleState& current_state,
814 const lanelet::CarmaTrafficSignalPtr& traffic_light, const lanelet::ConstLanelet& entry_lanelet, const lanelet::ConstLanelet& exit_lanelet, const lanelet::ConstLanelet& current_lanelet)
815{
817
818 if (!traffic_light) // If we are in the approaching state and there is no longer any lights ahead of us then
819 // the vehicle must have crossed the stop bar
820 {
822 return;
823 }
824
825 double current_state_speed = std::max(current_state.speed, config_.algo_minimum_speed * 1.001);
826
827 auto stop_line = traffic_light->getStopLine(entry_lanelet);
828
829 if (!stop_line)
830 {
831 throw std::invalid_argument("Given entry lanelet doesn't have stop_line...");
832 }
833
834 double traffic_light_down_track =
835 wm_->routeTrackPos(stop_line.get().front().basicPoint2d()).downtrack;
836
837 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "traffic_light_down_track: " << traffic_light_down_track);
838
839 double distance_remaining_to_traffic_light = traffic_light_down_track - current_state.downtrack;
840
841 distance_remaining_to_tf_ = distance_remaining_to_traffic_light;
842
843 if (distance_remaining_to_traffic_light < 0) // there is small discrepancy between signal's routeTrackPos as well as current
844 { // downtrack calculated using veh_x,y from state. Therefore, it may have crossed it
845 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Crossed the bar distance_remaining_to_traffic_light: " << distance_remaining_to_traffic_light);
847 return;
848 }
849
850 // At this point we know the vehicle is within the activation distance and we know the current and next light phases
851 // All we need to now determine is if we should stop or if we should continue
852 lanelet::ConstLanelet intersection_lanelet;
853
854 auto route = wm_->getRoute()->shortestPath();
855 auto entry_llt_iter = std::find(route.begin(), route.end(), entry_lanelet);
856 if (entry_llt_iter != route.end())
857 {
858 intersection_lanelet = *(entry_llt_iter + 1);
859 }
860
861 if (intersection_lanelet.id() != lanelet::InvalId)
862 {
863 intersection_speed_ = findSpeedLimit(intersection_lanelet);
865 }
866 else
867 {
868 intersection_speed_ = findSpeedLimit(exit_lanelet);
869 }
870
871 intersection_speed_ = intersection_speed_.get() * 0.999; // so that speed_limit is not exactly same as departure or current speed
872
873 double speed_limit = findSpeedLimit(current_lanelet);
874
875 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
876
877 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "current_state_speed: " << current_state_speed);
878 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "intersection_speed_: " << intersection_speed_.get());
879 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "distance_remaining_to_traffic_light: " << distance_remaining_to_traffic_light);
880
882 wm_->routeTrackPos(exit_lanelet.centerline2d().front().basicPoint2d()).downtrack;
883
884 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "intersection_end_downtrack_: " << intersection_end_downtrack_.get());
885
886 // If the vehicle is at a stop trigger the stopped state
887 constexpr double HALF_MPH_IN_MPS = 0.22352;
888 if (current_state.speed < HALF_MPH_IN_MPS &&
889 fabs(distance_remaining_to_traffic_light) < config_.stopping_location_buffer)
890 {
891 transition_table_.signal(TransitEvent::STOPPED); // The vehicle has come to a stop at the light
892 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "CARMA has detected that the vehicle stopped at the stop bar. Transitioning to WAITING STATE");
893
894 return;
895 }
896
898
899 rclcpp::Time earliest_entry_time = current_state.stamp + get_earliest_entry_time(distance_remaining_to_traffic_light, speed_limit,
900 current_state_speed, intersection_speed_.get(), max_comfort_accel_, max_comfort_decel_);
901
902 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()));
903
904 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);
905
906 if (nearest_green_entry_time == rclcpp::Time(0))
907 return;
908
909 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Final nearest_green_entry_time: " << std::to_string(nearest_green_entry_time.seconds()));
910
911 auto et_state = traffic_light->predictState(lanelet::time::timeFromSec(nearest_green_entry_time.seconds()));
912 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Signal at ET: " << et_state.get().second);
913
915
916 double remaining_time = nearest_green_entry_time.seconds() - current_state.stamp.seconds();
917 double remaining_time_earliest_entry = earliest_entry_time.seconds() - current_state.stamp.seconds();
918 scheduled_entry_time_ = remaining_time; // performance metric
919 earliest_entry_time_ = remaining_time_earliest_entry; // performance metric
920
921 auto boundary_distances = get_delta_x(current_state_speed, intersection_speed_.get(), speed_limit, config_.algo_minimum_speed, max_comfort_accel_, max_comfort_decel_);
922 print_boundary_distances(boundary_distances); //debug
923
924 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);
925
926 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);
927 print_params(ts_params);
928
929 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "SPEED PROFILE CASE:" << ts_params.case_num);
930
932 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
933 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_);
934
935 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
936 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_);
937
938 double desired_distance_to_stop = pow(current_state.speed, 2)/(2 * max_comfort_decel_norm_ * config_.deceleration_fraction) + config_.desired_distance_to_stop_buffer;
939 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);
940
941 emergency_distance_to_stop = std::max(emergency_distance_to_stop, config_.stopping_location_buffer);
942 safe_distance_to_stop = std::max(safe_distance_to_stop, config_.stopping_location_buffer);
943 desired_distance_to_stop = std::max(desired_distance_to_stop, config_.stopping_location_buffer);
944
945 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "new emergency_distance_to_stop: " << emergency_distance_to_stop);
946 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "new safe_distance_to_stop: " << safe_distance_to_stop);
947 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "new desired_distance_to_stop: " << desired_distance_to_stop);
948
949 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);
950
951 // Basic RED signal violation check
952 if (distance_remaining_to_traffic_light <= emergency_distance_to_stop || last_case_num_ == TSCase::EMERGENCY_STOPPING)
953 {
954 if (in_tbd) // Given ET is in TBD, but vehicle is too close to intersection
955 {
956 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...");
957 }
958
959 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_
960
961 rclcpp::Time stopping_arrival_time =
962 current_state.stamp + rclcpp::Duration(stopping_time * 1e9);
963
964 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "stopping_arrival_time: " << std::to_string(stopping_arrival_time.seconds()));
965
966 auto stopping_arrival_state_optional = traffic_light->predictState(lanelet::time::timeFromSec(stopping_arrival_time.seconds()));
967
968 if (!validLightState(stopping_arrival_state_optional, stopping_arrival_time))
969 {
970 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()));
971 return;
972 }
973
974 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
975 {
976 RCLCPP_WARN_STREAM(rclcpp::get_logger("lci_strategic_plugin"),"Detected possible RED light violation! Stopping!");
977 handleStopping(req,resp, current_state, traffic_light, entry_lanelet, exit_lanelet, current_lanelet, traffic_light_down_track, true); //case_11
979
980 return;
981 }
982 }
983
984 // Check if the vehicle can arrive with certainty (Case 1-7)
985 if (ts_params.is_algorithm_successful && ts_params.case_num != TSCase::CASE_8 &&
986 (distance_remaining_to_traffic_light >= desired_distance_to_stop || !in_tbd) &&
987 is_entry_time_within_green_or_tbd) // ET cannot be explicitly inside RED or YELLOW in available future states, which is ERROR case
988 {
989 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
990
991 if (!resp->new_plan.maneuvers.empty()) // able to pass at green
992 {
993 last_case_num_ = ts_params.case_num;
994 return;
995 }
996
997 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");
998 ts_params = boundary_traj_params[7];
999 ts_params.is_algorithm_successful = true; //false correspond to cases when vehicle is beyond safe_distance to stop for case8
1000 ts_params.case_num = CASE_8;
1001 print_params(ts_params);
1002 }
1003
1004 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Not able to make it with certainty: NEW TSCase: " << ts_params.case_num);
1005 // if algorithm is NOT successful or if the vehicle cannot make the green light with certainty
1006
1007 if (desired_distance_to_stop < distance_remaining_to_traffic_light && last_case_num_ != TSCase::STOPPING) // do not switch from STOPPING to case8 again
1008 {
1009 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Way too early to stop. Cruising at CASE8");
1010 handleCruisingUntilStop(req, resp, current_state, current_state_speed, traffic_light, traffic_light_down_track, ts_params);
1011
1012 if (!resp->new_plan.maneuvers.empty())
1013 {
1015 return;
1016 }
1017 }
1018
1019 if ((safe_distance_to_stop <= distance_remaining_to_traffic_light && desired_distance_to_stop >= distance_remaining_to_traffic_light) ||
1020 last_case_num_ == TSCase::STOPPING) // if stopping continue stopping until transition to planwhenWAITING
1021 {
1022 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Planning stopping now. last case:" << static_cast<int>(last_case_num_));
1023 handleStopping(req,resp, current_state, traffic_light, entry_lanelet, exit_lanelet, current_lanelet, traffic_light_down_track); //case_9
1024 return;
1025 }
1026
1027 if (safe_distance_to_stop > distance_remaining_to_traffic_light)
1028 {
1029 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "No longer within safe distance to stop! Decide to continue stopping or continue into intersection");
1030
1031 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
1032 {
1033 // 3. if not able to stop nor reach target speed at green, attempt its best to reach the target parameters at the intersection
1034 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!");
1035
1036 handleFailureCase(req, resp, current_state, current_state_speed, speed_limit, remaining_time,
1037 exit_lanelet.id(), traffic_light, traffic_light_down_track, ts_params);
1038
1039 if (resp->new_plan.maneuvers.empty())
1040 {
1041 RCLCPP_WARN_STREAM(rclcpp::get_logger("lci_strategic_plugin"),"HANDLE_SAFETY: Planning forced slow-down... last case:" << static_cast<int>(last_case_num_));
1042 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
1043 }
1044 }
1045 else
1046 {
1047 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "HANDLE_SAFETY: Planning to keep stopping now. last case:" << static_cast<int>(last_case_num_));
1048 handleStopping(req,resp, current_state, traffic_light, entry_lanelet, exit_lanelet, current_lanelet, traffic_light_down_track); //case_9
1049 }
1050 }
1051
1052
1053}
1054
1055void LCIStrategicPlugin::planWhenWAITING(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
1056 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp, const VehicleState& current_state,
1057 const lanelet::CarmaTrafficSignalPtr& traffic_light, const lanelet::ConstLanelet& entry_lanelet, const lanelet::ConstLanelet& exit_lanelet, const lanelet::ConstLanelet& current_lanelet)
1058{
1060
1061 if (!traffic_light)
1062 {
1063 throw std::invalid_argument("While in WAITING state, the traffic lights disappeared.");
1064 }
1065
1066 auto stop_line = traffic_light->getStopLine(entry_lanelet);
1067
1068 if (!stop_line)
1069 {
1070 throw std::invalid_argument("Given entry lanelet doesn't have stop_line...");
1071 }
1072
1073 double traffic_light_down_track =
1074 wm_->routeTrackPos(stop_line.get().front().basicPoint2d()).downtrack;
1075
1076 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "traffic_light_down_track: "<< traffic_light_down_track);
1077
1078 double entering_time = current_state.stamp.seconds();
1079
1080 auto current_light_state_optional = traffic_light->predictState(lanelet::time::timeFromSec(entering_time));
1081
1082 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()));
1083 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "WAITING STATE: requested time to CURRENT STATE check: " << std::to_string(entering_time));
1084
1085 if (!validLightState(current_light_state_optional, rclcpp::Time(entering_time * 1e9)))
1086 return;
1087
1088 auto bool_optional_late_certainty = canArriveAtGreenWithCertainty(rclcpp::Time(entering_time * 1e9), traffic_light, true, false);
1089
1090 if (!bool_optional_late_certainty)
1091 {
1092 RCLCPP_ERROR_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Unable to resolve green light...");
1093 return;
1094 }
1095
1096 bool should_enter = true; //uc2
1097
1098 if (config_.enable_carma_streets_connection && entering_time > current_state.stamp.seconds()) //uc3
1099 should_enter = false;
1100
1101 if (current_light_state_optional.get().second == lanelet::CarmaTrafficSignalState::PROTECTED_MOVEMENT_ALLOWED &&
1102 bool_optional_late_certainty.get() && should_enter) // if can make with certainty
1103 {
1104 transition_table_.signal(TransitEvent::RED_TO_GREEN_LIGHT); // If the light is green send the light transition
1105 // signal
1106 return;
1107 }
1108
1109 // A fixed buffer to add to stopping maneuvers once the vehicle is already stopped to ensure that they can have their
1110 // trajectory planned
1111 constexpr double stop_maneuver_buffer = 10.0;
1112
1113 // If the light is not green then continue waiting by creating a stop and wait maneuver on top of the vehicle
1115
1116 resp->new_plan.maneuvers.push_back(composeStopAndWaitManeuverMessage(
1117 current_state.downtrack - stop_maneuver_buffer, traffic_light_down_track, current_state.speed,
1118 current_state.lane_id, current_state.lane_id, rclcpp::Time(entering_time * 1e9),
1119 rclcpp::Time(entering_time * 1e9) + rclcpp::Duration(config_.min_maneuver_planning_period * 1e9), stopping_accel));
1120}
1121
1122void LCIStrategicPlugin::planWhenDEPARTING(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
1123 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp, const VehicleState& current_state,
1124 double intersection_end_downtrack, double intersection_speed_limit)
1125{
1127
1128 if (current_state.downtrack > intersection_end_downtrack)
1129 {
1130 transition_table_.signal(TransitEvent::INTERSECTION_EXIT); // If we are past the most recent
1131 return;
1132 }
1133
1134 // Calculate exit time assuming constant acceleration
1135 rclcpp::Time intersection_exit_time =
1136 current_state.stamp +
1137 rclcpp::Duration(2.0 * (intersection_end_downtrack - current_state.downtrack) / (current_state.speed + intersection_speed_limit) * 1e9);
1138
1139 // Identify the lanelets which will be crossed by approach maneuvers lane follow maneuver
1140 std::vector<lanelet::ConstLanelet> crossed_lanelets =
1141 getLaneletsBetweenWithException(current_state.downtrack, intersection_end_downtrack, true, false);
1142
1143 // Compose intersection transit maneuver
1144 resp->new_plan.maneuvers.push_back(composeIntersectionTransitMessage(
1145 current_state.downtrack, intersection_end_downtrack, current_state.speed, intersection_speed_limit,
1146 current_state.stamp, intersection_exit_time, crossed_lanelets.back().id(), crossed_lanelets.back().id()));
1147}
1148
1150
1151void LCIStrategicPlugin::mobilityOperationCb(carma_v2x_msgs::msg::MobilityOperation::UniquePtr msg)
1152{
1153 if (msg->strategy == light_controlled_intersection_strategy_)
1154 {
1155 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Received Schedule message with id: " << msg->m_header.plan_id);
1157 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Approaching light Controlled Intersection: " << approaching_light_controlled_intersection_);
1158
1159 if (msg->m_header.recipient_id == config_.vehicle_id)
1160 {
1161 street_msg_timestamp_ = msg->m_header.timestamp;
1162 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "street_msg_timestamp_: " << street_msg_timestamp_);
1163 parseStrategyParams(msg->strategy_params);
1164 previous_strategy_params_ = msg->strategy_params;
1165 }
1166 }
1167
1168}
1169
1170void LCIStrategicPlugin::BSMCb(carma_v2x_msgs::msg::BSM::UniquePtr msg)
1171{
1172 std::vector<uint8_t> bsm_id_vec = msg->core_data.id;
1173 bsm_id_ = BSMHelper::BSMHelper::bsmIDtoString(bsm_id_vec);
1174 bsm_msg_count_ = msg->core_data.msg_count;
1175 bsm_sec_mark_ = msg->core_data.sec_mark;
1176}
1177
1178void LCIStrategicPlugin::parseStrategyParams(const std::string& strategy_params)
1179{
1180 // sample strategy_params: "et:1634067059"
1181 std::string params = strategy_params;
1182 std::vector<std::string> inputsParams;
1183 boost::algorithm::split(inputsParams, params, boost::is_any_of(","));
1184
1185 std::vector<std::string> et_parsed;
1186 boost::algorithm::split(et_parsed, inputsParams[0], boost::is_any_of(":"));
1187 auto new_scheduled_enter_time = std::stoull(et_parsed[1]);
1188
1189 if (scheduled_enter_time_ != new_scheduled_enter_time) //reset green buffer cache so it can be re-evaluated
1191
1192 scheduled_enter_time_ = new_scheduled_enter_time;
1193 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "scheduled_enter_time_: " << scheduled_enter_time_);
1194
1195}
1196
1197carma_v2x_msgs::msg::MobilityOperation LCIStrategicPlugin::generateMobilityOperation()
1198{
1199 carma_v2x_msgs::msg::MobilityOperation mo_;
1200 mo_.m_header.timestamp = now().nanoseconds()/1000000;
1201 mo_.m_header.sender_id = config_.vehicle_id;
1202 mo_.m_header.recipient_id = upcoming_id_;
1203 mo_.m_header.sender_bsm_id = bsm_id_;
1205
1206 double vehicle_acceleration_limit_ = config_.vehicle_accel_limit * config_.vehicle_accel_limit_multiplier;
1207 double vehicle_deceleration_limit_ = -1 * config_.vehicle_decel_limit * config_.vehicle_decel_limit_multiplier;
1208
1209 std::string intersection_turn_direction = "straight";
1210 if (intersection_turn_direction_ == TurnDirection::Right) intersection_turn_direction = "right";
1211 if (intersection_turn_direction_ == TurnDirection::Left) intersection_turn_direction = "left";
1212
1213 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
1214 ", max_decel: " + std::to_string(vehicle_deceleration_limit_) + ", react_time: " + std::to_string(config_.reaction_time) +
1215 ", 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
1216 ", turn_direction: " + intersection_turn_direction + ", msg_count: " + std::to_string(bsm_msg_count_) + ", sec_mark: " + std::to_string(bsm_sec_mark_);
1217
1218
1219 return mo_;
1220}
1221
1222TurnDirection LCIStrategicPlugin::getTurnDirectionAtIntersection(std::vector<lanelet::ConstLanelet> lanelets_list)
1223{
1224 TurnDirection turn_direction = TurnDirection::Straight;
1225 for (auto l:lanelets_list)
1226 {
1227 if(l.hasAttribute("turn_direction")) {
1228 std::string direction_attribute = l.attribute("turn_direction").value();
1229 if (direction_attribute == "right")
1230 {
1231 turn_direction = TurnDirection::Right;
1232 break;
1233 }
1234 else if (direction_attribute == "left")
1235 {
1236 turn_direction = TurnDirection::Left;
1237 break;
1238 }
1239 else turn_direction = TurnDirection::Straight;
1240 }
1241 else
1242 {
1243 // if there is no attribute, assumption is straight
1244 turn_direction = TurnDirection::Straight;
1245 }
1246
1247 }
1248 return turn_direction;
1249}
1250
1252{
1254 {
1255 carma_v2x_msgs::msg::MobilityOperation status_msg = generateMobilityOperation();
1256 mobility_operation_pub_->publish(status_msg);
1257 }
1258}
1259
1261
1263 std::shared_ptr<rmw_request_id_t> srv_header,
1264 carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
1265 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp)
1266{
1267 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
1268
1269 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "<<<<<<<<<<<<<<<<< STARTING LCI_STRATEGIC_PLAN!!!!!!!!! >>>>>>>>>>>>>>>>");
1270
1271 if (!wm_->getRoute())
1272 {
1273 RCLCPP_ERROR_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Could not plan maneuvers as route was not available");
1274 return;
1275 }
1276
1278 {
1280 {
1281 resp->new_plan.maneuvers = {};
1282 RCLCPP_WARN_STREAM(rclcpp::get_logger("lci_strategic_plugin"),"Not approaching light-controlled intersection so no maneuvers");
1283 return;
1284 }
1285
1286 bool is_empty_schedule_msg = (scheduled_enter_time_ == 0);
1287 if (is_empty_schedule_msg)
1288 {
1289 resp->new_plan.maneuvers = {};
1290 RCLCPP_WARN_STREAM(rclcpp::get_logger("lci_strategic_plugin"),"Receiving empty schedule message");
1291 return;
1292 }
1293 }
1294
1295 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Finding car information");
1296
1297 // Extract vehicle data from request
1298 VehicleState current_state = extractInitialState(req);
1299 if (transition_table_.getState() != TransitState::UNAVAILABLE && !req->prior_plan.maneuvers.empty())
1300 {
1301 RCLCPP_WARN_STREAM(rclcpp::get_logger("lci_strategic_plugin"),"State is NOT UNAVAILABLE AND Maneuvers in request is NOT empty");
1302 return;
1303 }
1304 // Get current traffic light information
1305 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "\n\nFinding traffic_light information");
1306
1307 auto inter_list = wm_->getSignalizedIntersectionsAlongRoute({ req->veh_x, req->veh_y });
1308 auto upcoming_id_= inter_list.front()->id();
1309
1310 auto traffic_list = wm_->getSignalsAlongRoute({ req->veh_x, req->veh_y });
1311
1312 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Found traffic lights of size: " << traffic_list.size());
1313
1314 auto current_lanelets = wm_->getLaneletsFromPoint({ req->veh_x, req->veh_y});
1315 lanelet::ConstLanelet current_lanelet;
1316
1317 if (current_lanelets.empty())
1318 {
1319 RCLCPP_ERROR_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Given vehicle position is not on the road! Returning...");
1320 return;
1321 }
1322
1323 // get the lanelet that is on the route in case overlapping ones found
1324 auto llt_on_route_optional = wm_->getFirstLaneletOnShortestPath(current_lanelets);
1325
1326 if (llt_on_route_optional){
1327 current_lanelet = llt_on_route_optional.value();
1328 }
1329 else{
1330 RCLCPP_WARN_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "When identifying the corresponding lanelet for requested maneuever's state, x: "
1331 << req->veh_x << ", y: " << req->veh_y << ", no possible lanelet was found to be on the shortest path."
1332 << "Picking arbitrary lanelet: " << current_lanelets[0].id() << ", instead");
1333 current_lanelet = current_lanelets[0];
1334 }
1335
1336 lanelet::CarmaTrafficSignalPtr nearest_traffic_signal = nullptr;
1337
1338 lanelet::ConstLanelet entry_lanelet;
1339 lanelet::ConstLanelet exit_lanelet;
1340
1341 for (auto signal : traffic_list)
1342 {
1343 auto optional_entry_exit = wm_->getEntryExitOfSignalAlongRoute(signal);
1344 // if signal is not matching our destination skip
1345 if (!optional_entry_exit)
1346 {
1347 RCLCPP_ERROR_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Did not find entry.exit along the route");
1348 continue;
1349 }
1350
1351 entry_lanelet = optional_entry_exit.get().first;
1352 exit_lanelet = optional_entry_exit.get().second;
1353
1354 nearest_traffic_signal = signal;
1355 break;
1356 }
1357
1358
1359 TransitState prev_state;
1360
1361 do
1362 {
1363 // Clear previous maneuvers planned by this plugin as guard against state change since each state generates an
1364 // independent set of maneuvers
1365 resp->new_plan = carma_planning_msgs::msg::ManeuverPlan();
1366
1367 prev_state = transition_table_.getState(); // Cache previous state to check if state has changed after 1 iteration
1368
1369 RCLCPP_INFO_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Planning in state: " << transition_table_.getState());
1370
1371 boost::optional<std::pair<boost::posix_time::ptime, lanelet::CarmaTrafficSignalState>> current_light_state_optional = boost::none;
1372 if (nearest_traffic_signal)
1373 {
1374 current_light_state_optional = nearest_traffic_signal->predictState(lanelet::time::timeFromSec(current_state.stamp.seconds()));
1375 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());
1376 if (current_light_state_optional.get().second == lanelet::CarmaTrafficSignalState::UNAVAILABLE || !current_light_state_optional)
1377 {
1378 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Signal state not available returning..." );
1379 return;
1380 }
1381 }
1382 switch (transition_table_.getState())
1383 {
1385 planWhenUNAVAILABLE(req, resp, current_state, nearest_traffic_signal, entry_lanelet, exit_lanelet, current_lanelet);
1386 break;
1387
1389 planWhenAPPROACHING(req, resp, current_state, nearest_traffic_signal, entry_lanelet, exit_lanelet, current_lanelet);
1390 break;
1391
1393 planWhenWAITING(req, resp, current_state, nearest_traffic_signal, entry_lanelet, exit_lanelet, current_lanelet);
1394 break;
1395
1397 // Reset intersection state since we are no longer in an intersection
1399 {
1400 throw std::invalid_argument("State is DEPARTING but the intersection variables are not available");
1401 }
1402 planWhenDEPARTING(req, resp, current_state, intersection_end_downtrack_.get(), intersection_speed_.get());
1403 break;
1404
1405 default:
1406 throw std::invalid_argument("LCIStrategic Strategic Plugin entered unknown state");
1407 break;
1408 }
1409
1410 } while (transition_table_.getState() != prev_state); // If the state has changed then continue looping
1411
1412 std::chrono::system_clock::time_point execution_end_time = std::chrono::system_clock::now(); // Planning complete
1413
1414 auto execution_duration = execution_end_time - execution_start_time;
1415 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "ExecutionTime lci_strategic_plugin: " << std::chrono::duration<double>(execution_duration).count());
1416
1417 return;
1418 // We need to evaluate the events so the state transitions can be triggered
1419}
1420
1421carma_planning_msgs::msg::Maneuver LCIStrategicPlugin::composeTrajectorySmoothingManeuverMessage(double start_dist, double end_dist, const std::vector<lanelet::ConstLanelet>& crossed_lanelets, double start_speed,
1422 double target_speed, rclcpp::Time start_time, rclcpp::Time end_time,
1423 const TrajectoryParams& tsp) const
1424{
1425 carma_planning_msgs::msg::Maneuver maneuver_msg;
1426 maneuver_msg.type = carma_planning_msgs::msg::Maneuver::LANE_FOLLOWING;
1427 maneuver_msg.lane_following_maneuver.parameters.negotiation_type =
1428 carma_planning_msgs::msg::ManeuverParameters::NO_NEGOTIATION;
1429 maneuver_msg.lane_following_maneuver.parameters.presence_vector =
1430 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;
1431 maneuver_msg.lane_following_maneuver.parameters.planning_tactical_plugin =
1433 maneuver_msg.lane_following_maneuver.parameters.planning_strategic_plugin =
1435 maneuver_msg.lane_following_maneuver.start_dist = start_dist;
1436 maneuver_msg.lane_following_maneuver.start_speed = start_speed;
1437 maneuver_msg.lane_following_maneuver.start_time = start_time;
1438 maneuver_msg.lane_following_maneuver.end_dist = end_dist;
1439 maneuver_msg.lane_following_maneuver.end_speed = target_speed;
1440 maneuver_msg.lane_following_maneuver.end_time = end_time;
1441
1442 maneuver_msg.lane_following_maneuver.parameters.string_valued_meta_data.push_back(light_controlled_intersection_strategy_);
1443
1444 maneuver_msg.lane_following_maneuver.parameters.float_valued_meta_data.push_back(tsp.a1_);
1445 maneuver_msg.lane_following_maneuver.parameters.float_valued_meta_data.push_back(tsp.v1_);
1446 maneuver_msg.lane_following_maneuver.parameters.float_valued_meta_data.push_back(tsp.x1_);
1447
1448 maneuver_msg.lane_following_maneuver.parameters.float_valued_meta_data.push_back(tsp.a2_);
1449 maneuver_msg.lane_following_maneuver.parameters.float_valued_meta_data.push_back(tsp.v2_);
1450 maneuver_msg.lane_following_maneuver.parameters.float_valued_meta_data.push_back(tsp.x2_);
1451
1452 maneuver_msg.lane_following_maneuver.parameters.float_valued_meta_data.push_back(tsp.a3_);
1453 maneuver_msg.lane_following_maneuver.parameters.float_valued_meta_data.push_back(tsp.v3_);
1454 maneuver_msg.lane_following_maneuver.parameters.float_valued_meta_data.push_back(tsp.x3_);
1455
1456 maneuver_msg.lane_following_maneuver.parameters.int_valued_meta_data.push_back(static_cast<int>(tsp.case_num));
1457 maneuver_msg.lane_following_maneuver.parameters.int_valued_meta_data.push_back(static_cast<int>(tsp.is_algorithm_successful));
1458
1459 for (auto llt : crossed_lanelets)
1460 {
1461 maneuver_msg.lane_following_maneuver.lane_ids.push_back(std::to_string(llt.id()));
1462 }
1463 // Start time and end time for maneuver are assigned in updateTimeProgress
1464
1465 RCLCPP_INFO_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Creating TrajectorySmoothingManeuver start dist: " << start_dist << " end dist: " << end_dist
1466 << " start_time: " << std::to_string(start_time.seconds())
1467 << " end_time: " << std::to_string(end_time.seconds()));
1468
1469 return maneuver_msg;
1470}
1471
1472carma_planning_msgs::msg::Maneuver LCIStrategicPlugin::composeStopAndWaitManeuverMessage(double current_dist, double end_dist,
1473 double start_speed,
1474 const lanelet::Id& starting_lane_id,
1475 const lanelet::Id& ending_lane_id,
1476 rclcpp::Time start_time, rclcpp::Time end_time, double stopping_accel) const
1477{
1478 carma_planning_msgs::msg::Maneuver maneuver_msg;
1479 maneuver_msg.type = carma_planning_msgs::msg::Maneuver::STOP_AND_WAIT;
1480 maneuver_msg.stop_and_wait_maneuver.parameters.negotiation_type = carma_planning_msgs::msg::ManeuverParameters::NO_NEGOTIATION;
1481 maneuver_msg.stop_and_wait_maneuver.parameters.presence_vector =
1482 carma_planning_msgs::msg::ManeuverParameters::HAS_TACTICAL_PLUGIN | carma_planning_msgs::msg::ManeuverParameters::HAS_FLOAT_META_DATA;
1483 maneuver_msg.stop_and_wait_maneuver.parameters.planning_tactical_plugin = config_.stop_and_wait_plugin_name;
1484 maneuver_msg.stop_and_wait_maneuver.parameters.planning_strategic_plugin = config_.strategic_plugin_name;
1485 maneuver_msg.stop_and_wait_maneuver.start_dist = current_dist;
1486 maneuver_msg.stop_and_wait_maneuver.end_dist = end_dist;
1487 maneuver_msg.stop_and_wait_maneuver.start_speed = start_speed;
1488 maneuver_msg.stop_and_wait_maneuver.start_time = start_time;
1489 maneuver_msg.stop_and_wait_maneuver.end_time = end_time;
1490 maneuver_msg.stop_and_wait_maneuver.starting_lane_id = std::to_string(starting_lane_id);
1491 maneuver_msg.stop_and_wait_maneuver.ending_lane_id = std::to_string(ending_lane_id);
1492
1493 // Set the meta data for the stop location buffer
1494 maneuver_msg.stop_and_wait_maneuver.parameters.float_valued_meta_data.push_back(config_.stopping_location_buffer);
1495 maneuver_msg.stop_and_wait_maneuver.parameters.float_valued_meta_data.push_back(stopping_accel);
1496
1497 RCLCPP_INFO_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Creating stop and wait start dist: " << current_dist << " end dist: " << end_dist
1498 << " start_time: " << std::to_string(start_time.seconds())
1499 << " end_time: " << std::to_string(end_time.seconds())
1500 << " stopping_accel: " << stopping_accel);
1501
1502 return maneuver_msg;
1503}
1504
1505carma_planning_msgs::msg::Maneuver LCIStrategicPlugin::composeIntersectionTransitMessage(double start_dist, double end_dist,
1506 double start_speed, double target_speed,
1507 rclcpp::Time start_time, rclcpp::Time end_time,
1508 const lanelet::Id& starting_lane_id,
1509 const lanelet::Id& ending_lane_id) const
1510{
1511 carma_planning_msgs::msg::Maneuver maneuver_msg;
1512 maneuver_msg.type = carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_STRAIGHT;
1513 maneuver_msg.intersection_transit_straight_maneuver.parameters.negotiation_type =
1514 carma_planning_msgs::msg::ManeuverParameters::NO_NEGOTIATION;
1515 maneuver_msg.intersection_transit_straight_maneuver.parameters.presence_vector =
1516 carma_planning_msgs::msg::ManeuverParameters::HAS_TACTICAL_PLUGIN;
1517 maneuver_msg.intersection_transit_straight_maneuver.parameters.planning_tactical_plugin =
1519 maneuver_msg.intersection_transit_straight_maneuver.parameters.planning_strategic_plugin =
1521 maneuver_msg.intersection_transit_straight_maneuver.start_dist = start_dist;
1522 maneuver_msg.intersection_transit_straight_maneuver.start_speed = start_speed;
1523 maneuver_msg.intersection_transit_straight_maneuver.start_time = start_time;
1524 maneuver_msg.intersection_transit_straight_maneuver.end_dist = end_dist;
1525 maneuver_msg.intersection_transit_straight_maneuver.end_speed = target_speed;
1526 maneuver_msg.intersection_transit_straight_maneuver.end_time = end_time;
1527 maneuver_msg.intersection_transit_straight_maneuver.starting_lane_id = std::to_string(starting_lane_id);
1528 maneuver_msg.intersection_transit_straight_maneuver.ending_lane_id = std::to_string(ending_lane_id);
1529
1530 // Start time and end time for maneuver are assigned in updateTimeProgress
1531
1532 RCLCPP_INFO_STREAM(rclcpp::get_logger("lci_strategic_plugin"), "Creating IntersectionTransitManeuver start dist: " << start_dist << " end dist: " << end_dist
1533 << " From lanelet: " << starting_lane_id
1534 << " to lanelet: " << ending_lane_id
1535 << " From start_time: " << std::to_string(start_time.seconds())
1536 << " to end_time: " << std::to_string(end_time.seconds()));
1537
1538 return maneuver_msg;
1539}
1540
1542{
1543 return true;
1544}
1545
1547{
1548 return "v1.0";
1549}
1550
1551} // namespace lci_strategic_plugin
1552
1553
1554#include "rclcpp_components/register_node_macro.hpp"
1555
1556// Register the component with class_loader
1557RCLCPP_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.
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.