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.hpp
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C)2023 LEIDOS.
5 *
6 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
7 * use this file except in compliance with the License. You may obtain a copy of
8 * the License at
9 *
10 * http://www.apache.org/licenses/LICENSE-2.0
11 *
12 * Unless required by applicable law or agreed to in writing, software
13 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15 * License for the specific language governing permissions and limitations under
16 * the License.
17 */
18
19#include <rclcpp/rclcpp.hpp>
20#include <string>
21#include <carma_planning_msgs/srv/plan_maneuvers.hpp>
22#include <carma_v2x_msgs/msg/mobility_operation.hpp>
23#include <carma_v2x_msgs/msg/bsm.hpp>
26
27#include <bsm_helper/bsm_helper.h>
28#include <carma_wm/Geometry.hpp>
29#include <lanelet2_core/Forward.h>
30#include <gtest/gtest_prod.h>
31
32#include <lanelet2_extension/regulatory_elements/CarmaTrafficSignal.h>
36
37#include <tf2_ros/transform_listener.h>
38#include <tf2/LinearMath/Transform.h>
39#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
40#include <std_msgs/msg/int8.hpp>
41#include <std_msgs/msg/float64.hpp>
42#include <math.h>
43#include <algorithm>
45#include <carma_ros2_utils/carma_lifecycle_node.hpp>
46#include <optional>
47
49{
50
51enum class TurnDirection {
52 Straight,
53 Right,
54 Left
55};
56
61enum TSCase {
62 CASE_1 = 1,
63 CASE_2 = 2,
64 CASE_3 = 3,
65 CASE_4 = 4,
66 CASE_5 = 5,
67 CASE_6 = 6,
68 CASE_7 = 7,
69 CASE_8 = 8,
73 DEGRADED_TSCASE=12 // when not performing trajectory smoothing, but making through GREEN
74};
75
77{
78 double t0_ = 0;
79 double v0_ = 0;
80 double x0_ = 0;
81
82 double a1_ = 0;
83 double t1_ = 0;
84 double v1_ = 0;
85 double x1_ = 0;
86
87 double a2_ = 0;
88 double t2_ = 0;
89 double v2_ = 0;
90 double x2_ = 0;
91
92 double a3_ = 0;
93 double t3_ = 0;
94 double v3_ = 0;
95 double x3_ = 0;
96
99 double modified_departure_speed = -1.0; // modified departure speed if algorithm failed
100 double modified_remaining_time = -1.0; // modified departure time if algorithm failed
101};
102
104{
105 double dx1 = 0.0;
106 double dx2 = 0.0;
107 double dx3 = 0.0;
108 double dx4 = 0.0;
109 double dx5 = 0.0;
110};
111
113{
114public:
115
119 explicit LCIStrategicPlugin(const rclcpp::NodeOptions &);
120
128 std::shared_ptr<rmw_request_id_t> srv_header,
129 carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
130 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp);
131
135 rcl_interfaces::msg::SetParametersResult
136 parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters);
137
139 carma_ros2_utils::CallbackReturn on_configure_plugin();
140 carma_ros2_utils::CallbackReturn on_activate_plugin();
141
142 bool get_availability();
143 std::string get_version_id();
144
149
155 void mobilityOperationCb(carma_v2x_msgs::msg::MobilityOperation::UniquePtr msg);
156
160 void BSMCb(carma_v2x_msgs::msg::BSM::UniquePtr msg);
161
167 void parseStrategyParams(const std::string& strategy_params);
168
174 carma_v2x_msgs::msg::MobilityOperation generateMobilityOperation();
175
184 TurnDirection getTurnDirectionAtIntersection(std::vector<lanelet::ConstLanelet> lanelets_list);
185
190
195
196private:
197
199 // CARMA Streets Variables
200 // timestamp for msg received from carma streets
201 unsigned long long street_msg_timestamp_ = 0;
202 // scheduled enter time
203 unsigned long long scheduled_enter_time_ = 0;
205 std::string upcoming_id_ = "";
206
207 //BSM
208 std::string bsm_id_ = "default_bsm_id";
209 uint8_t bsm_msg_count_ = 0;
210 uint16_t bsm_sec_mark_ = 0;
211
212 // TS planning related variables
213 double max_comfort_accel_ = 2.0; // acceleration rates after applying miltiplier
214 double max_comfort_decel_ = -2.0;
217
218 boost::optional<rclcpp::Time> nearest_green_entry_time_cached_;
231
234
237
240
242 boost::optional<double> intersection_speed_;
243 boost::optional<double> intersection_end_downtrack_;
244 std::string light_controlled_intersection_strategy_ = "Carma/signalized_intersection"; // Strategy carma-streets is sending. Could be more verbose but needs to be changed on both ends
245
246 // TF listenser
247 tf2_ros::Buffer tf2_buffer_;
248 std::unique_ptr<tf2_ros::TransformListener> tf2_listener_;
249 tf2::Stamped<tf2::Transform> frontbumper_transform_;
251
252 double epsilon_ = 0.001; //Small constant to compare (double) 0.0 with
253 double accel_epsilon_ = 0.0001; //Small constant to compare (double) 0.0 with
254
257
258 // Timers
259 rclcpp::TimerBase::SharedPtr mob_op_pub_timer_;
260 rclcpp::TimerBase::SharedPtr ts_info_pub_timer_;
261
262 // Create subscribers
263 carma_ros2_utils::SubPtr<carma_v2x_msgs::msg::MobilityOperation> mob_operation_sub_;
264 carma_ros2_utils::SubPtr<carma_v2x_msgs::msg::BSM> bsm_sub_;
265
266 // Create publishers
267 carma_ros2_utils::PubPtr<carma_v2x_msgs::msg::MobilityOperation> mobility_operation_pub_;
268 carma_ros2_utils::PubPtr<std_msgs::msg::Int8> case_pub_;
269 carma_ros2_utils::PubPtr<std_msgs::msg::Float64> tf_distance_pub_;
270 carma_ros2_utils::PubPtr<std_msgs::msg::Float64> earliest_et_pub_;
271 carma_ros2_utils::PubPtr<std_msgs::msg::Float64> et_pub_;
272
277 {
278 rclcpp::Time stamp; // Timestamp of this state data
279 double downtrack; // The downtrack of the vehicle along the route at time stamp
280 double speed; // The speed of the vehicle at time stamp
281 lanelet::Id lane_id; // The current lane id of the vehicle at time stamp
282 };
283
289 bool isStateAllowedGreen(const lanelet::CarmaTrafficSignalState& state) const;
290
296 boost::posix_time::time_duration getMovementAllowedDuration(lanelet::CarmaTrafficSignalPtr traffic_light);
297
312 void planWhenUNAVAILABLE(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
313 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
314 const VehicleState& current_state,
315 const lanelet::CarmaTrafficSignalPtr& traffic_light,
316 const lanelet::ConstLanelet& entry_lanelet,
317 const lanelet::ConstLanelet& exit_lanelet,
318 const lanelet::ConstLanelet& current_lanelet);
319
335 void planWhenAPPROACHING(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
336 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
337 const VehicleState& current_state,
338 const lanelet::CarmaTrafficSignalPtr& traffic_light,
339 const lanelet::ConstLanelet& entry_lanelet,
340 const lanelet::ConstLanelet& exit_lanelet,
341 const lanelet::ConstLanelet& current_lanelet);
342
356 void planWhenWAITING(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
357 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
358 const VehicleState& current_state,
359 const lanelet::CarmaTrafficSignalPtr& traffic_light,
360 const lanelet::ConstLanelet& entry_lanelet,
361 const lanelet::ConstLanelet& exit_lanelet,
362 const lanelet::ConstLanelet& current_lanelet);
363
375 void planWhenDEPARTING(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
376 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
377 const VehicleState& current_state, double intersection_end_downtrack,
378 double intersection_speed_limit);
379
391 boost::optional<bool> canArriveAtGreenWithCertainty(const rclcpp::Time& light_arrival_time_by_algo, const lanelet::CarmaTrafficSignalPtr& traffic_light, bool check_late, bool check_early) const;
392
406 carma_planning_msgs::msg::Maneuver composeTrajectorySmoothingManeuverMessage(double start_dist, double end_dist, const std::vector<lanelet::ConstLanelet>& crossed_lanelets, double start_speed,
407 double target_speed, rclcpp::Time start_time, rclcpp::Time end_time,
408 const TrajectoryParams& tsp) const;
409
424 carma_planning_msgs::msg::Maneuver composeStopAndWaitManeuverMessage(double current_dist, double end_dist, double start_speed,
425 const lanelet::Id& starting_lane_id,
426 const lanelet::Id& ending_lane_id, rclcpp::Time start_time,
427 rclcpp::Time end_time, double stopping_accel) const;
428
443 carma_planning_msgs::msg::Maneuver composeIntersectionTransitMessage(double start_dist, double end_dist, double start_speed,
444 double target_speed, rclcpp::Time start_time, rclcpp::Time end_time,
445 const lanelet::Id& starting_lane_id,
446 const lanelet::Id& ending_lane_id) const;
447
448
464 void handleStopping(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
465 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
466 const VehicleState& current_state,
467 const lanelet::CarmaTrafficSignalPtr& traffic_light,
468 const lanelet::ConstLanelet& entry_lanelet, const lanelet::ConstLanelet& exit_lanelet, const lanelet::ConstLanelet& current_lanelet,
469 double traffic_light_down_track,
470 bool is_emergency = false);
471
487 void handleGreenSignalScenario(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
488 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
489 const VehicleState& current_state,
490 double current_state_speed,
491 const lanelet::CarmaTrafficSignalPtr& traffic_light,
492 const lanelet::ConstLanelet& entry_lanelet, const lanelet::ConstLanelet& exit_lanelet,
493 double traffic_light_down_track, const TrajectoryParams& ts_params, bool is_certainty_check_optional);
507 void handleCruisingUntilStop(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
508 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
509 const VehicleState& current_state,
510 double current_state_speed,
511 const lanelet::CarmaTrafficSignalPtr& traffic_light,
512 double traffic_light_down_track, const TrajectoryParams& ts_params);
513
531 void handleFailureCase(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
532 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
533 const VehicleState& current_state,
534 double current_state_speed,
535 double speed_limit,
536 double remaining_time,
537 lanelet::Id exit_lanelet_id,
538 const lanelet::CarmaTrafficSignalPtr& traffic_light,
539 double traffic_light_down_track, const TrajectoryParams& ts_params);
540
551 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);
552
560 bool supportedLightState(lanelet::CarmaTrafficSignalState state) const;
561
571 bool validLightState(const boost::optional<std::pair<boost::posix_time::ptime, lanelet::CarmaTrafficSignalState>>& optional_state,
572 const rclcpp::Time& source_time) const;
573
582 VehicleState extractInitialState(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req) const;
583
589 std::vector<lanelet::ConstLanelet> getLaneletsBetweenWithException(double start_downtrack, double end_downtrack,
590 bool shortest_path_only = false,
591 bool bounds_inclusive = true) const;
592
603 std::tuple<rclcpp::Time, bool, bool> get_final_entry_time_and_conditions(const VehicleState& current_state,
604 const rclcpp::Time& earliest_entry_time,
605 lanelet::CarmaTrafficSignalPtr traffic_light);
606
621 std::optional<rclcpp::Time> get_nearest_green_entry_time(const rclcpp::Time& current_time, const rclcpp::Time& earliest_entry_time, const lanelet::CarmaTrafficSignalPtr& signal, double minimum_required_green_time = 0.0) const;
622
632 rclcpp::Time get_eet_or_tbd(const rclcpp::Time& earliest_entry_time, const lanelet::CarmaTrafficSignalPtr& signal) const;
633
649 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;
650
666 double get_trajectory_smoothing_activation_distance(double time_remaining_at_free_flow, double full_cycle_duration, double current_speed, double speed_limit, double departure_speed, double max_accel, double max_decel) const;
667
680 double get_distance_to_accel_or_decel_twice (double free_flow_speed, double current_speed, double departure_speed, double max_accel, double max_decel) const;
681
697 double get_inflection_speed_value (double x, double x1, double x2, double free_flow_speed, double current_speed, double departure_speed, double max_accel, double max_decel) const;
698
710 double get_distance_to_accel_or_decel_once (double current_speed, double departure_speed, double max_accel, double max_decel) const;
711
720 double estimate_distance_to_stop(double v, double a) const;
721
730 double estimate_time_to_stop(double d, double v) const;
731
741 double findSpeedLimit(const lanelet::ConstLanelet& llt) const;
742
754 double calc_estimated_entry_time_left(double entry_dist, double current_speed, double departure_speed) const;
755
767 BoundaryDistances get_delta_x(double v0, double v1, double v_max, double v_min, double a_max, double a_min);
768
784 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);
785
789 void print_params(TrajectoryParams params);
790
795
799 TrajectoryParams ts_case1(double t, double et, double v0, double v1, double v_max, double a_max, double a_min, double x0, double x_end, double dx);
800 TrajectoryParams ts_case2(double t, double et, double v0, double v1, double a_max, double a_min, double x0, double x_end, double dx);
801 TrajectoryParams ts_case3(double t, double et, double v0, double v1, double a_max, double a_min, double x0, double x_end, double dx);
802 TrajectoryParams ts_case4(double t, double et, double v0, double v1, double v_min, double a_max, double a_min, double x0, double x_end, double dx);
803 TrajectoryParams ts_case5(double t, double et, double v0, double a_max, double a_min, double x0, double x_end, double dx);
804 TrajectoryParams ts_case6(double t, double et, double v0, double v_min, double a_min, double x0, double x_end, double dx, double dx3, TrajectoryParams traj6);
805 TrajectoryParams ts_case7(double t, double et, double v0, double v_min, double a_min, double x0, double x_end, double dx);
806 TrajectoryParams ts_case8(double dx, double dx5, TrajectoryParams traj8);
807
808 TrajectoryParams boundary_accel_or_decel_incomplete_upper(double t, double v0, double v1, double a_max, double a_min, double x0, double x_end, double dx);
809 TrajectoryParams boundary_accel_nocruise_notmaxspeed_decel(double t, double v0, double v1, double a_max, double a_min, double x0, double x_end, double dx);
810 TrajectoryParams boundary_accel_cruise_maxspeed_decel(double t, double v0, double v1, double v_max, double a_max, double a_min, double x0, double x_end, double dx);
811 TrajectoryParams boundary_accel_nocruise_maxspeed_decel(double t, double v0, double v1, double v_max, double a_max, double a_min, double x0, double x_end, double dx);
812 TrajectoryParams boundary_accel_or_decel_complete_upper(double t, double v0, double v1, double x0, double x_end, double dx);
813 TrajectoryParams boundary_decel_nocruise_notminspeed_accel(double t, double v0, double v1, double v_min, double a_max, double a_min, double x0, double x_end, double dx);
814 TrajectoryParams boundary_decel_nocruise_minspeed_accel_incomplete(double t, double v0, double v_min, double a_max, double a_min, double x0, double x_end, double dx);
815 TrajectoryParams boundary_decel_nocruise_minspeed_accel_complete(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);
816 TrajectoryParams boundary_decel_cruise_minspeed_accel(double t, double v0, double v1, double v_min, double a_max, double a_min, double x0, double x_end, double dx);
817 TrajectoryParams boundary_decel_cruise_minspeed(double t, double v0, double v_min, double a_min, double x0, double x_end, double dx);
818 TrajectoryParams boundary_decel_incomplete_lower(double t, double v0, double a_min, double x0, double x_end, double dx);
819 TrajectoryParams boundary_decel_cruise_minspeed_decel(double t, double v0, double v_min, double a_min, double x0, double x_end, double dx);
820
821 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);
822
823 //Unit Tests
824 FRIEND_TEST(LCIStrategicTestFixture, getDiscoveryMsg);
825 FRIEND_TEST(LCIStrategicTestFixture, supportedLightState);
826 FRIEND_TEST(LCIStrategicTestFixture, estimate_distance_to_stop);
827 FRIEND_TEST(LCIStrategicTestFixture, estimate_time_to_stop);
828 FRIEND_TEST(LCIStrategicTestFixture, extractInitialState);
829 FRIEND_TEST(LCIStrategicTestFixture, DISABLED_extractInitialState);
830
831 FRIEND_TEST(LCIStrategicTestFixture, validLightState);
836 FRIEND_TEST(LCIStrategicTestFixture, handleFailureCaseHelper);
837 FRIEND_TEST(LCIStrategicTestFixture, planWhenETInTBD);
838
839 // Algo Unit Tests
843 FRIEND_TEST(LCIStrategicTestFixture, get_nearest_green_entry_time);
844 FRIEND_TEST(LCIStrategicTestFixture, get_eet_or_tbd);
845 FRIEND_TEST(LCIStrategicTestFixture, get_earliest_entry_time);
846 FRIEND_TEST(LCIStrategicTestFixture, handleFailureCase);
847 FRIEND_TEST(LCIStrategicTestFixture, handleStopping);
848 FRIEND_TEST(LCIStrategicTestFixture, planManeuverCb);
849 FRIEND_TEST(LCIStrategicTestFixture, DISABLED_planManeuverCb);
850
851 FRIEND_TEST(LCIStrategicPluginTest, parseStrategyParamstest);
852 FRIEND_TEST(LCIStrategicPluginTest, moboperationcbtest);
853 FRIEND_TEST(LCIStrategicTestFixture, findSpeedLimit);
854 FRIEND_TEST(LCIStrategicTestFixture, DISABLED_planWhenETInTBD);
855
856
857
858
859
860};
861} // namespace lci_strategic_plugin
StrategicPlugin base class which can be extended by user provided plugins which wish to implement the...
tf2::Stamped< tf2::Transform > frontbumper_transform_
TrajectoryParams boundary_decel_nocruise_notminspeed_accel(double t, double v0, double v1, double v_min, double a_max, double a_min, double x0, double x_end, double dx)
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...
FRIEND_TEST(LCIStrategicTestFixture, get_nearest_green_entry_time)
TrajectoryParams boundary_decel_cruise_minspeed_decel(double t, double v0, double v_min, double a_min, double x0, double x_end, double dx)
FRIEND_TEST(LCIStrategicTestFixture, get_distance_to_accel_or_decel_once)
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 ...
double get_distance_to_accel_or_decel_twice(double free_flow_speed, double current_speed, double departure_speed, double max_accel, double max_decel) const
Get required distance to accel then decel, or vise versa - each at least once - to reach departure_sp...
rclcpp::Time get_eet_or_tbd(const rclcpp::Time &earliest_entry_time, const lanelet::CarmaTrafficSignalPtr &signal) const
Returns the later of earliest_entry_time or the end of the available signal states in the traffic_sig...
double estimate_time_to_stop(double d, double v) const
Helper method to use basic kinematics to compute an estimated stopping time from from the inputs.
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 ...
FRIEND_TEST(LCIStrategicTestFixture, estimate_time_to_stop)
FRIEND_TEST(LCIStrategicTestFixture, handleFailureCase)
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....
TrajectoryParams ts_case7(double t, double et, double v0, double v_min, double a_min, double x0, double x_end, double dx)
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_
TrajectoryParams boundary_accel_nocruise_maxspeed_decel(double t, double v0, double v1, double v_max, double a_max, double a_min, double x0, double x_end, double dx)
carma_wm::WorldModelConstPtr wm_
World Model pointer.
TrajectoryParams ts_case1(double t, double et, double v0, double v1, double v_max, double a_max, double a_min, double x0, double x_end, double dx)
Trajectory Smoothing Algorithm 8 cases. TSMO UC2, UC3 algorithm equations.
TrajectoryParams boundary_accel_or_decel_complete_upper(double t, double v0, double v1, double x0, double x_end, double dx)
std::optional< rclcpp::Time > get_nearest_green_entry_time(const rclcpp::Time &current_time, const rclcpp::Time &earliest_entry_time, const lanelet::CarmaTrafficSignalPtr &signal, double minimum_required_green_time=0.0) const
Provides the scheduled entry time for the vehicle in the future. This scheduled time is the earliest ...
FRIEND_TEST(LCIStrategicPluginTest, moboperationcbtest)
TrajectoryParams boundary_accel_or_decel_incomplete_upper(double t, double v0, double v1, double a_max, double a_min, double x0, double x_end, double dx)
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_
FRIEND_TEST(LCIStrategicTestFixture, findSpeedLimit)
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)
FRIEND_TEST(LCIStrategicTestFixture, get_distance_to_accel_or_decel_twice)
double calc_estimated_entry_time_left(double entry_dist, double current_speed, double departure_speed) const
calculate the time vehicle will enter to intersection with optimal deceleration
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....
FRIEND_TEST(LCIStrategicTestFixture, validLightState)
FRIEND_TEST(LCIStrategicTestFixture, planManeuverCb)
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_
boost::posix_time::time_duration getMovementAllowedDuration(lanelet::CarmaTrafficSignalPtr traffic_light)
Returns the duration for the allowed movements.
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_
TrajectoryParams boundary_accel_nocruise_notmaxspeed_decel(double t, double v0, double v1, double a_max, double a_min, double x0, double x_end, double dx)
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....
TrajectoryParams boundary_decel_nocruise_minspeed_accel_incomplete(double t, double v0, double v_min, double a_max, double a_min, double x0, double x_end, double dx)
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,...
FRIEND_TEST(LCIStrategicTestFixture, composeIntersectionTransitMessage)
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...
FRIEND_TEST(LCIStrategicTestFixture, handleFailureCaseHelper)
FRIEND_TEST(LCIStrategicTestFixture, DISABLED_planWhenETInTBD)
FRIEND_TEST(LCIStrategicTestFixture, composeStopAndWaitManeuverMessage)
LCIStrategicPlugin(const rclcpp::NodeOptions &)
Default constructor for RouteFollowingPlugin class.
TrajectoryParams boundary_accel_cruise_maxspeed_decel(double t, double v0, double v1, double v_max, double a_max, double a_min, double x0, double x_end, double dx)
TrajectoryParams boundary_decel_incomplete_lower(double t, double v0, double a_min, double x0, double x_end, double dx)
FRIEND_TEST(LCIStrategicTestFixture, DISABLED_extractInitialState)
TrajectoryParams ts_case6(double t, double et, double v0, double v_min, double a_min, double x0, double x_end, double dx, double dx3, TrajectoryParams traj6)
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,...
TrajectoryParams ts_case4(double t, double et, double v0, double v1, double v_min, double a_max, double a_min, double x0, double x_end, double dx)
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.
FRIEND_TEST(LCIStrategicTestFixture, composeTrajectorySmoothingManeuverMessage)
TrajectoryParams boundary_decel_cruise_minspeed_accel(double t, double v0, double v1, double v_min, double a_max, double a_min, double x0, double x_end, double dx)
FRIEND_TEST(LCIStrategicTestFixture, calc_estimated_entry_time_left)
FRIEND_TEST(LCIStrategicTestFixture, extractInitialState)
FRIEND_TEST(LCIStrategicTestFixture, get_eet_or_tbd)
void print_params(TrajectoryParams params)
Helper method to print TrajectoryParams.
void parseStrategyParams(const std::string &strategy_params)
parse strategy parameters
FRIEND_TEST(LCIStrategicTestFixture, estimate_distance_to_stop)
carma_v2x_msgs::msg::MobilityOperation generateMobilityOperation()
Generates Mobility Operation messages.
TrajectoryParams ts_case2(double t, double et, double v0, double v1, double a_max, double a_min, double x0, double x_end, double dx)
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...
TrajectoryParams boundary_decel_nocruise_minspeed_accel_complete(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)
double get_distance_to_accel_or_decel_once(double current_speed, double departure_speed, double max_accel, double max_decel) const
Get required distance to accel or decel to reach departure_speed with given speed and acceleration pa...
TrajectoryParams boundary_decel_cruise_minspeed(double t, double v0, double v_min, double a_min, double x0, double x_end, double dx)
double get_inflection_speed_value(double x, double x1, double x2, double free_flow_speed, double current_speed, double departure_speed, double max_accel, double max_decel) const
Get the speed between the acceleration and deceleration pieces.
double get_trajectory_smoothing_activation_distance(double time_remaining_at_free_flow, double full_cycle_duration, double current_speed, double speed_limit, double departure_speed, double max_accel, double max_decel) const
Gets maximum distance (nearest downtrack) the trajectory smoothing algorithm makes difference than si...
void publishTrajectorySmoothingInfo()
Publish trajectory smoothing info at a fixed rate.
carma_ros2_utils::PubPtr< carma_v2x_msgs::msg::MobilityOperation > mobility_operation_pub_
FRIEND_TEST(LCIStrategicTestFixture, DISABLED_planManeuverCb)
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.
FRIEND_TEST(LCIStrategicTestFixture, planWhenETInTBD)
TrajectoryParams ts_case8(double dx, double dx5, TrajectoryParams traj8)
FRIEND_TEST(LCIStrategicTestFixture, getLaneletsBetweenWithException)
std::string get_version_id()
Returns the version id of this plugin.
FRIEND_TEST(LCIStrategicPluginTest, parseStrategyParamstest)
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...
FRIEND_TEST(LCIStrategicTestFixture, handleStopping)
boost::optional< double > intersection_end_downtrack_
TrajectoryParams ts_case3(double t, double et, double v0, double v1, double a_max, double a_min, double x0, double x_end, double dx)
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.
FRIEND_TEST(LCIStrategicTestFixture, supportedLightState)
bool isStateAllowedGreen(const lanelet::CarmaTrafficSignalState &state) const
Method to check if the state is an allowed green movement state. Currently Permissive and Protected g...
TurnDirection getTurnDirectionAtIntersection(std::vector< lanelet::ConstLanelet > lanelets_list)
Determine the turn direction at intersection.
void plan_maneuvers_callback(std::shared_ptr< rmw_request_id_t > srv_header, carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req, carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp)
Service callback for arbitrator maneuver planning.
void planWhenAPPROACHING(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req, carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp, const VehicleState &current_state, const lanelet::CarmaTrafficSignalPtr &traffic_light, const lanelet::ConstLanelet &entry_lanelet, const lanelet::ConstLanelet &exit_lanelet, const lanelet::ConstLanelet &current_lanelet)
Method for performing maneuver planning when the current plugin state is TransitState::APPROACHING Th...
LCIStrategicStateTransitionTable transition_table_
State Machine Transition table.
TrajectoryParams ts_case5(double t, double et, double v0, double a_max, double a_min, double x0, double x_end, double dx)
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_
FRIEND_TEST(LCIStrategicTestFixture, getDiscoveryMsg)
rclcpp::TimerBase::SharedPtr ts_info_pub_timer_
carma_ros2_utils::PubPtr< std_msgs::msg::Float64 > et_pub_
FRIEND_TEST(LCIStrategicTestFixture, get_earliest_entry_time)
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.
Class defining the state transition table behavior for the LCIStrategic Strategic Plugin.
std::shared_ptr< const WorldModel > WorldModelConstPtr
Definition: WorldModel.hpp:452
TSCase
Struct representing trajectory smoothing algorithm parameters using distance and acceleration Based o...
Struct to store the configuration settings for the LCIStrategicPlugin class.
Struct representing a vehicle state for the purposes of planning.