17#include <rclcpp/rclcpp.hpp>
21#include <boost/uuid/uuid_generators.hpp>
22#include <boost/uuid/uuid_io.hpp>
23#include <lanelet2_core/geometry/Point.h>
24#include <trajectory_utils/trajectory_utils.hpp>
25#include <trajectory_utils/conversions/conversions.hpp>
28#include <Eigen/Geometry>
31#include <unordered_set>
33#include <carma_planning_msgs/msg/stop_and_wait_maneuver.hpp>
34#include <lanelet2_core/primitives/Lanelet.h>
35#include <lanelet2_core/geometry/LineString.h>
38#include <carma_planning_msgs/msg/trajectory_plan_point.hpp>
39#include <carma_planning_msgs/msg/trajectory_plan.hpp>
41#include <std_msgs/msg/float64.hpp>
44using oss = std::ostringstream;
49namespace std_ph = std::placeholders;
66 auto error_double = update_params<double>({
74 auto error_int = update_params<int>({
79 rcl_interfaces::msg::SetParametersResult result;
81 result.successful = !error_double && !error_int;
102 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Done loading parameters: " <<
config_);
108 return CallbackReturn::SUCCESS;
112 std::shared_ptr<rmw_request_id_t> srv_header,
113 carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req,
114 carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp)
116 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Starting stop controlled intersection trajectory planning");
118 if(req->maneuver_index_to_plan >= req->maneuver_plan.maneuvers.size())
120 throw std::invalid_argument(
121 "Stop Control Intersection Plugin asked to plan invalid maneuver index: " +
std::to_string(req->maneuver_index_to_plan) +
122 " for plan of size: " +
std::to_string(req->maneuver_plan.maneuvers.size()));
124 std::vector<carma_planning_msgs::msg::Maneuver> maneuver_plan;
125 for(
size_t i = req->maneuver_index_to_plan; i < req->maneuver_plan.maneuvers.size();
i++){
127 if((req->maneuver_plan.maneuvers[
i].type == carma_planning_msgs::msg::Maneuver::LANE_FOLLOWING || req->maneuver_plan.maneuvers[
i].type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_STRAIGHT
128 || req->maneuver_plan.maneuvers[
i].type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_LEFT_TURN || req->maneuver_plan.maneuvers[
i].type ==carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_RIGHT_TURN)
131 maneuver_plan.push_back(req->maneuver_plan.maneuvers[
i]);
132 resp->related_maneuvers.push_back(req->maneuver_plan.maneuvers[
i].type);
140 lanelet::BasicPoint2d veh_pos(req->vehicle_state.x_pos_global, req->vehicle_state.y_pos_global);
141 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Planning state x:"<<req->vehicle_state.x_pos_global <<
" , y: " << req->vehicle_state.y_pos_global);
143 double current_downtrack =
wm_->routeTrackPos(veh_pos).downtrack;
144 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Current_downtrack"<< current_downtrack);
146 std::vector<PointSpeedPair> points_and_target_speeds =
maneuvers_to_points( maneuver_plan,
wm_, req->vehicle_state);
147 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Maneuver to points size:"<< points_and_target_speeds.size());
150 carma_planning_msgs::msg::TrajectoryPlan trajectory;
151 trajectory.header.frame_id =
"map";
152 trajectory.header.stamp = req->header.stamp;
157 trajectory.initial_longitudinal_velocity = req->vehicle_state.longitudinal_vel;
160 for (
auto& p : trajectory.trajectory_points) {
165 resp->trajectory_plan = trajectory;
167 resp->maneuver_status.push_back(carma_planning_msgs::srv::PlanTrajectory::Response::MANEUVER_IN_PROGRESS);
173 std::vector<PointSpeedPair> points_and_target_speeds;
174 std::unordered_set<lanelet::Id> visited_lanelets;
176 lanelet::BasicPoint2d veh_pos(state.x_pos_global, state.y_pos_global);
177 double max_starting_downtrack =
wm_->routeTrackPos(veh_pos).downtrack;
178 double starting_speed = state.longitudinal_vel;
181 double starting_downtrack;
182 for (
const auto& maneuver : maneuvers)
184 if(maneuver.type != carma_planning_msgs::msg::Maneuver::LANE_FOLLOWING && maneuver.type != carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_STRAIGHT && maneuver.type != carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_LEFT_TURN
185 && maneuver.type !=carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_RIGHT_TURN ){
186 throw std::invalid_argument(
"Stop Controlled Intersection Tactical Plugin does not support this maneuver type");
192 if (starting_downtrack > max_starting_downtrack)
194 starting_downtrack = max_starting_downtrack;
202 std::vector<lanelet::BasicPoint2d> route_points = wm->sampleRoutePoints(
206 route_points.insert(route_points.begin(), veh_pos);
207 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Route geometery points size: "<<route_points.size());
210 throw std::invalid_argument(
"No case number specified for stop controlled intersection maneuver");
217 else if(case_num == 2){
220 else if(case_num == 3)
225 throw std::invalid_argument(
"The stop controlled intersection tactical plugin doesn't handle the case number requested");
229 return points_and_target_speeds;
233const carma_planning_msgs::msg::Maneuver& maneuver, std::vector<lanelet::BasicPoint2d>& route_geometry_points,
double starting_speed,
const carma_planning_msgs::msg::VehicleState& state){
235 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Planning for Case One");
242 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"a_acc received: "<< a_acc);
243 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"a_dec received: "<< a_dec);
244 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"t_acc received: "<< t_acc);
245 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"t_dec received: "<< t_dec);
246 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"speed before decel received: "<< speed_before_decel);
252 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Maneuver starting downtrack: "<< start_dist);
253 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Maneuver ending downtrack: "<< end_dist);
255 lanelet::BasicPoint2d state_point(state.x_pos_global, state.y_pos_global);
256 double route_starting_downtrack = wm->routeTrackPos(state_point).downtrack;
259 if(route_starting_downtrack < start_dist){
262 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Starting distance is less than maneuver start, updating parameters");
263 double dist_decel = pow(speed_before_decel, 2)/(2*std::abs(a_dec));
265 dist_acc = end_dist - dist_decel;
266 a_acc = (pow(speed_before_decel, 2) - pow(starting_speed,2))/(2*dist_acc);
267 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Updated a_acc: "<< a_acc);
271 dist_acc = (pow(speed_before_decel, 2) - pow(starting_speed, 2))/(2*a_acc);
274 std::vector<PointSpeedPair> points_and_target_speeds;
280 lanelet::BasicPoint2d prev_point = state_point;
281 double total_dist_covered = 0;
283 for(
size_t i = 1;
i < route_geometry_points.size();
i++){
284 lanelet::BasicPoint2d current_point = route_geometry_points[
i];
285 double delta_d = lanelet::geometry::distance2d(prev_point, current_point);
286 total_dist_covered += delta_d;
289 if(total_dist_covered <= dist_acc){
291 speed_i = sqrt(pow(starting_speed,2) + 2*a_acc*total_dist_covered);
295 speed_i = sqrt(std::max(pow(speed_before_decel,2) + 2*a_dec*(total_dist_covered - dist_acc),0.0));
303 p.
point = prev_point;
307 p.
point = route_geometry_points[
i];
309 prev_point = current_point;
311 points_and_target_speeds.push_back(p);
315 return points_and_target_speeds;
320const carma_planning_msgs::msg::Maneuver& maneuver, std::vector<lanelet::BasicPoint2d>& route_geometry_points,
double starting_speed){
321 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Planning for Case Two");
333 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Maneuver starting downtrack: "<< start_dist);
334 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Maneuver ending downtrack: "<< end_dist);
337 double route_starting_downtrack = wm->routeTrackPos(route_geometry_points[0]).downtrack;
342 if(route_starting_downtrack < start_dist){
345 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Starting distance is less than maneuver start, updating parameters");
346 dist_acc = starting_speed*t_acc + 0.5 * a_acc * pow(t_acc,2);
347 dist_decel = speed_before_decel*t_dec + 0.5 * a_dec * pow(t_dec,2);
348 dist_cruise = end_dist - route_starting_downtrack - (dist_acc + dist_decel);
352 dist_acc = starting_speed*t_acc + 0.5 * a_acc * pow(t_acc,2);
353 dist_cruise = speed_before_decel*t_cruise;
354 dist_decel = speed_before_decel*t_dec + 0.5 * a_dec * pow(t_dec,2);
358 double total_distance_needed = dist_acc + dist_cruise + dist_decel;
359 if(total_distance_needed - (end_dist - start_dist) >
epsilon_ ){
362 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Updating maneuver to meet start and end dist req.");
363 double delta_total_dist = total_distance_needed - (end_dist - start_dist);
364 dist_cruise -= delta_total_dist;
366 dist_acc += dist_cruise;
372 std::vector<PointSpeedPair> points_and_target_speeds;
378 lanelet::BasicPoint2d prev_point = route_geometry_points.front();
379 double total_dist_planned = 0;
380 double prev_speed = starting_speed;
381 for(
auto route_point : route_geometry_points){
382 lanelet::BasicPoint2d current_point = route_point;
383 double delta_d = lanelet::geometry::distance2d(prev_point, current_point);
384 total_dist_planned += delta_d;
388 if(total_dist_planned < dist_acc){
390 speed_i = sqrt(pow(starting_speed,2) + 2*a_acc*total_dist_planned);
392 else if(dist_cruise > 0 && total_dist_planned >= dist_acc && total_dist_planned <= (dist_acc + dist_cruise)){
394 speed_i = prev_speed;
398 speed_i = sqrt(std::max(pow(speed_before_decel,2) + 2*a_dec*(total_dist_planned - dist_acc - dist_cruise),0.0));
403 p.
point = prev_point;
407 p.
point = route_point;
408 p.
speed = std::min(speed_i,speed_before_decel);
409 prev_point = current_point;
411 points_and_target_speeds.push_back(p);
413 prev_speed = speed_i;
416 return points_and_target_speeds;
421const carma_planning_msgs::msg::Maneuver& maneuver, std::vector<lanelet::BasicPoint2d>& route_geometry_points,
double starting_speed){
422 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Planning for Case three");
429 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Maneuver starting downtrack: "<< start_dist);
430 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Maneuver ending downtrack: "<< end_dist);
433 double route_starting_downtrack = wm->routeTrackPos(route_geometry_points[0]).downtrack;
435 if(route_starting_downtrack < start_dist){
437 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Starting distance is less than maneuver start, updating parameters");
438 a_dec = pow(starting_speed, 2)/(2*(end_dist - route_starting_downtrack));
441 std::vector<PointSpeedPair> points_and_target_speeds;
447 lanelet::BasicPoint2d prev_point = route_geometry_points[0];
448 double total_dist_covered = 0;
450 for(
size_t i = 0;
i < route_geometry_points.size();
i++){
451 lanelet::BasicPoint2d current_point = route_geometry_points[
i];
452 double delta_d = lanelet::geometry::distance2d(prev_point, current_point);
453 total_dist_covered +=delta_d;
455 double speed_i = sqrt(std::max(pow(starting_speed,2) + 2 * a_dec * total_dist_covered, 0.0));
460 p.
point = prev_point;
464 p.
point = route_geometry_points[
i];
466 prev_point = current_point;
469 points_and_target_speeds.push_back(p);
474 return points_and_target_speeds;
478 const std::vector<PointSpeedPair>& points,
const carma_planning_msgs::msg::VehicleState& state,
const rclcpp::Time& state_time){
480 std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint> trajectory;
481 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"VehicleState: "
482 <<
" x: " << state.x_pos_global <<
" y: " << state.y_pos_global <<
" yaw: " << state.orientation
483 <<
" speed: " << state.longitudinal_vel);
486 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Nearest pt index: "<<nearest_pt_index);
487 std::vector<PointSpeedPair> future_points(points.begin() + nearest_pt_index + 1, points.end());
488 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Future points size: "<<future_points.size());
490 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Got time bound points with size:" << time_bound_points.size());
494 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Got back_and_future points with size: "<<back_and_future.size());
496 std::vector<double> speed_limits;
497 std::vector<lanelet::BasicPoint2d> curve_points;
503 throw std::invalid_argument(
"Could not fit a spline curve along the trajectory!");
506 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Got fit");
507 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Speed_limits.size(): "<<speed_limits.size());
509 std::vector<lanelet::BasicPoint2d> all_sampling_points;
510 all_sampling_points.reserve(1 + curve_points.size() * 2);
512 std::vector<double> distributed_speed_limits;
513 distributed_speed_limits.reserve(1+ curve_points.size() * 2);
521 int current_speed_index = 0;
522 size_t total_point_size = curve_points.size();
524 double step_threshold_for_next_speed = (double)total_step_along_curve / (
double)total_point_size;
525 double scaled_steps_along_curve = 0.0;
526 std::vector<double> better_curvature;
527 better_curvature.reserve(1 + curve_points.size() * 2);
529 for (
size_t steps_along_curve = 0; steps_along_curve < total_step_along_curve; steps_along_curve++)
531 lanelet::BasicPoint2d p = (*fit_curve)(scaled_steps_along_curve);
532 all_sampling_points.push_back(p);
534 better_curvature.push_back(
c);
536 if((
double) steps_along_curve > step_threshold_for_next_speed)
538 step_threshold_for_next_speed += (double)total_step_along_curve / (
double)total_point_size;
539 current_speed_index++;
541 distributed_speed_limits.push_back(speed_limits[current_speed_index]);
542 scaled_steps_along_curve += 1.0 / total_step_along_curve;
545 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Got sampled points with size:" << all_sampling_points.size());
550 std::vector<double> ideal_speeds =
554 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"Processed all points in computed fit");
555 std::vector<double> final_actual_speeds = constrained_speed_limits;
557 if (all_sampling_points.empty())
559 RCLCPP_WARN_STREAM(rclcpp::get_logger(
"stop_controlled_intersection_tactical_plugin"),
"No trajectory points could be generated");
565 std::vector<lanelet::BasicPoint2d> future_basic_points(all_sampling_points.begin() + nearest_pt_index + 1,
566 all_sampling_points.end());
567 std::vector<double> future_speeds(final_actual_speeds.begin() + nearest_pt_index + 1,
568 final_actual_speeds.end());
569 std::vector<double> future_yaw(final_yaw_values.begin() + nearest_pt_index + 1,
570 final_yaw_values.end());
573 lanelet::BasicPoint2d cur_veh_point(state.x_pos_global, state.y_pos_global);
575 future_basic_points.insert(future_basic_points.begin(),
577 future_speeds.insert(future_speeds.begin(), state.longitudinal_vel);
578 future_yaw.insert(future_yaw.begin(), state.orientation);
586 std::vector<double> times;
589 if(lanelet::geometry::distance2d(future_basic_points.back(), points.back().point) <
epsilon_){
590 final_actual_speeds.back() = 0.0;
593 trajectory_utils::conversions::speed_to_time(downtracks, final_actual_speeds, ×);
596 std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint> traj_points =
614#include "rclcpp_components/register_node_macro.hpp"
#define GET_MANEUVER_PROPERTY(mvr, property)
Macro definition to enable easier access to fields shared across the maneuver types.
std::string get_plugin_name() const
Return the name of this plugin.
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...
Class containing primary business logic for the Stop Controlled Intersection Tactical Plugin.
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > ¶meters)
std::string stop_controlled_intersection_strategy_
bool get_availability()
Get the availability status of this plugin based on the current operating environment....
carma_wm::WorldModelConstPtr wm_
StopControlledIntersectionTacticalPlugin(const rclcpp::NodeOptions &options)
StopControlledIntersectionTacticalPluginConfig config_
std::vector< PointSpeedPair > maneuvers_to_points(const std::vector< carma_planning_msgs::msg::Maneuver > &maneuvers, const carma_wm::WorldModelConstPtr &wm, const carma_planning_msgs::msg::VehicleState &state)
Converts a set of requested stop controlled intersection maneuvers to point speed limit pairs.
std::vector< PointSpeedPair > create_case_two_speed_profile(const carma_wm::WorldModelConstPtr &wm, const carma_planning_msgs::msg::Maneuver &maneuver, std::vector< lanelet::BasicPoint2d > &route_geometry_points, double starting_speed)
Creates a speed profile according to case two of the stop controlled intersection,...
void plan_trajectory_callback(std::shared_ptr< rmw_request_id_t >, carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req, carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp) override
Extending class provided callback which should return a planned trajectory based on the provided traj...
carma_ros2_utils::CallbackReturn on_configure_plugin() override
Method which is triggered when this plugin is moved from the UNCONFIGURED to INACTIVE states....
std::string get_version_id()
Returns the version id of this plugin.
std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > compose_trajectory_from_centerline(const std::vector< PointSpeedPair > &points, const carma_planning_msgs::msg::VehicleState &state, const rclcpp::Time &state_time)
Method converts a list of lanelet centerline points and current vehicle state into a usable list of t...
std::vector< PointSpeedPair > create_case_one_speed_profile(const carma_wm::WorldModelConstPtr &wm, const carma_planning_msgs::msg::Maneuver &maneuver, std::vector< lanelet::BasicPoint2d > &route_geometry_points, double starting_speed, const carma_planning_msgs::msg::VehicleState &states)
Creates a speed profile according to case one of the stop controlled intersection,...
std::vector< PointSpeedPair > create_case_three_speed_profile(const carma_wm::WorldModelConstPtr &wm, const carma_planning_msgs::msg::Maneuver &maneuver, std::vector< lanelet::BasicPoint2d > &route_geometry_points, double starting_speed)
Creates a speed profile according to case three of the stop controlled intersection,...
std::vector< double > moving_average_filter(const std::vector< double > input, int window_size, bool ignore_first_point=true)
Extremely simplie moving average filter.
void split_point_speed_pairs(const std::vector< PointSpeedPair > &points, std::vector< lanelet::BasicPoint2d > *basic_points, std::vector< double > *speeds)
Helper method to split a list of PointSpeedPair into separate point and speed lists.
int get_nearest_point_index(const std::vector< lanelet::BasicPoint2d > &points, const carma_planning_msgs::msg::VehicleState &state)
Returns the nearest point (in terms of cartesian 2d distance) to the provided vehicle pose in the pro...
std::unique_ptr< basic_autonomy::smoothing::SplineI > compute_fit(const std::vector< lanelet::BasicPoint2d > &basic_points)
Computes a spline based on the provided points.
int get_nearest_index_by_downtrack(const std::vector< lanelet::BasicPoint2d > &points, const carma_wm::WorldModelConstPtr &wm, double target_downtrack)
Returns the nearest "less than" point to the provided vehicle pose in the provided list by utilizing ...
std::vector< double > apply_speed_limits(const std::vector< double > speeds, const std::vector< double > speed_limits)
Applies the provided speed limits to the provided speeds such that each element is capped at its corr...
std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > trajectory_from_points_times_orientations(const std::vector< lanelet::BasicPoint2d > &points, const std::vector< double > ×, const std::vector< double > &yaws, rclcpp::Time startTime, const std::string &desired_controller_plugin)
Method combines input points, times, orientations, and an absolute start time to form a valid carma p...
double compute_curvature_at(const basic_autonomy::smoothing::SplineI &fit_curve, double step_along_the_curve)
Given the curvature fit, computes the curvature at the given step along the curve.
std::vector< PointSpeedPair > constrain_to_time_boundary(const std::vector< PointSpeedPair > &points, double time_span)
Reduces the input points to only those points that fit within the provided time boundary.
std::vector< PointSpeedPair > attach_past_points(const std::vector< PointSpeedPair > &points_set, std::vector< PointSpeedPair > future_points, const int nearest_pt_index, double back_distance)
Attaches back_distance length of points behind the future points.
auto to_string(const UtmZone &zone) -> std::string
std::vector< double > compute_tangent_orientations(const lanelet::BasicLineString2d ¢erline)
Compute an approximate orientation for the vehicle at each point along the provided centerline.
std::vector< double > compute_arc_lengths(const std::vector< lanelet::BasicPoint2d > &data)
Compute the arc length at each point around the curve.
std::shared_ptr< const WorldModel > WorldModelConstPtr
lanelet::BasicPoint2d point
Stuct containing the algorithm configuration values for the StopControlledIntersectionTacticalPlugin.
double trajectory_time_length
int curvature_moving_average_window_size
double lateral_accel_limit
double curve_resample_step_size
double centerline_sampling_spacing
int speed_moving_average_window_size