19#include <rclcpp/rclcpp.hpp>
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>
27#include <bsm_helper/bsm_helper.h>
29#include <lanelet2_core/Forward.h>
30#include <gtest/gtest_prod.h>
32#include <lanelet2_extension/regulatory_elements/CarmaTrafficSignal.h>
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>
45#include <carma_ros2_utils/carma_lifecycle_node.hpp>
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);
135 rcl_interfaces::msg::SetParametersResult
160 void BSMCb(carma_v2x_msgs::msg::BSM::UniquePtr msg);
264 carma_ros2_utils::SubPtr<carma_v2x_msgs::msg::BSM>
bsm_sub_;
268 carma_ros2_utils::PubPtr<std_msgs::msg::Int8>
case_pub_;
271 carma_ros2_utils::PubPtr<std_msgs::msg::Float64>
et_pub_;
313 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
315 const lanelet::CarmaTrafficSignalPtr& traffic_light,
316 const lanelet::ConstLanelet& entry_lanelet,
317 const lanelet::ConstLanelet& exit_lanelet,
318 const lanelet::ConstLanelet& current_lanelet);
336 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
338 const lanelet::CarmaTrafficSignalPtr& traffic_light,
339 const lanelet::ConstLanelet& entry_lanelet,
340 const lanelet::ConstLanelet& exit_lanelet,
341 const lanelet::ConstLanelet& current_lanelet);
356 void planWhenWAITING(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
357 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
359 const lanelet::CarmaTrafficSignalPtr& traffic_light,
360 const lanelet::ConstLanelet& entry_lanelet,
361 const lanelet::ConstLanelet& exit_lanelet,
362 const lanelet::ConstLanelet& current_lanelet);
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);
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;
407 double target_speed, rclcpp::Time start_time, rclcpp::Time end_time,
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;
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;
464 void handleStopping(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
465 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
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);
488 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
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);
508 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
510 double current_state_speed,
511 const lanelet::CarmaTrafficSignalPtr& traffic_light,
531 void handleFailureCase(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
532 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp,
534 double current_state_speed,
536 double remaining_time,
537 lanelet::Id exit_lanelet_id,
538 const lanelet::CarmaTrafficSignalPtr& traffic_light,
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);
571 bool validLightState(
const boost::optional<std::pair<boost::posix_time::ptime, lanelet::CarmaTrafficSignalState>>& optional_state,
572 const rclcpp::Time& source_time)
const;
590 bool shortest_path_only =
false,
591 bool bounds_inclusive =
true)
const;
604 const rclcpp::Time& earliest_entry_time,
605 lanelet::CarmaTrafficSignalPtr traffic_light);
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;
632 rclcpp::Time
get_eet_or_tbd(
const rclcpp::Time& earliest_entry_time,
const lanelet::CarmaTrafficSignalPtr& signal)
const;
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;
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;
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;
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);
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);
805 TrajectoryParams ts_case7(
double t,
double et,
double v0,
double v_min,
double a_min,
double x0,
double x_end,
double dx);
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);
829 FRIEND_TEST(LCIStrategicTestFixture, DISABLED_extractInitialState);
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 ¤t_state, const lanelet::CarmaTrafficSignalPtr &traffic_light, const lanelet::ConstLanelet &entry_lanelet, const lanelet::ConstLanelet &exit_lanelet, const lanelet::ConstLanelet ¤t_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 ¤t_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 ¤t_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_
double emergency_decel_norm_
FRIEND_TEST(LCIStrategicTestFixture, findSpeedLimit)
unsigned long long scheduled_enter_time_
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)
double max_comfort_decel_norm_
FRIEND_TEST(LCIStrategicTestFixture, planManeuverCb)
void planWhenDEPARTING(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req, carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp, const VehicleState ¤t_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_
tf2_ros::Buffer tf2_buffer_
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 ¤t_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 ¤t_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)
unsigned long long street_msg_timestamp_
double length_to_front_bumper_
FRIEND_TEST(LCIStrategicTestFixture, DISABLED_planWhenETInTBD)
double max_comfort_accel_
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 ¤t_state, const lanelet::CarmaTrafficSignalPtr &traffic_light, const lanelet::ConstLanelet &entry_lanelet, const lanelet::ConstLanelet &exit_lanelet, const lanelet::ConstLanelet ¤t_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)
double distance_remaining_to_tf_
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 ¤t_state, const lanelet::CarmaTrafficSignalPtr &traffic_light, const lanelet::ConstLanelet &entry_lanelet, const lanelet::ConstLanelet &exit_lanelet, const lanelet::ConstLanelet ¤t_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...
double max_comfort_decel_
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_
TurnDirection intersection_turn_direction_
FRIEND_TEST(LCIStrategicTestFixture, DISABLED_planManeuverCb)
std::string previous_strategy_params_
bool approaching_light_controlled_intersection_
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 light_controlled_intersection_strategy_
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 ¤t_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)
double earliest_entry_time_
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.
double scheduled_entry_time_
void planWhenAPPROACHING(carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req, carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp, const VehicleState ¤t_state, const lanelet::CarmaTrafficSignalPtr &traffic_light, const lanelet::ConstLanelet &entry_lanelet, const lanelet::ConstLanelet &exit_lanelet, const lanelet::ConstLanelet ¤t_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 > ¶meters)
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
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.
bool is_algorithm_successful
double modified_remaining_time
double modified_departure_speed