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>
27#include <carma_ros2_utils/carma_lifecycle_node.hpp>
29#include <Eigen/Geometry>
32#include <unordered_set>
35#include <carma_planning_msgs/msg/stop_and_wait_maneuver.hpp>
37#include <carma_planning_msgs/msg/trajectory_plan_point.hpp>
38#include <carma_planning_msgs/msg/trajectory_plan.hpp>
39#include <lanelet2_core/primitives/Lanelet.h>
40#include <lanelet2_core/geometry/LineString.h>
43#include <std_msgs/msg/float64.hpp>
46using oss = std::ostringstream;
54 const std::string& plugin_name,
56 : version_id_ (
version_id),plugin_name_(plugin_name),config_(config),nh_(nh), wm_(wm)
59bool StopandWait::plan_trajectory_cb(carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req, carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp)
61 std::chrono::system_clock::time_point start_time = std::chrono::system_clock::now();
62 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_and_wait_plugin"),
"Starting stop&wait planning");
64 if (req->maneuver_index_to_plan >= req->maneuver_plan.maneuvers.size())
66 throw std::invalid_argument(
67 "StopAndWait plugin asked to plan invalid maneuver index: " +
std::to_string(req->maneuver_index_to_plan) +
68 " for plan of size: " +
std::to_string(req->maneuver_plan.maneuvers.size()));
71 if (req->maneuver_plan.maneuvers[req->maneuver_index_to_plan].type != carma_planning_msgs::msg::Maneuver::STOP_AND_WAIT)
73 throw std::invalid_argument(
"StopAndWait plugin asked to plan non STOP_AND_WAIT maneuver");
76 lanelet::BasicPoint2d veh_pos(req->vehicle_state.x_pos_global, req->vehicle_state.y_pos_global);
78 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_and_wait_plugin"),
"planning state x:" << req->vehicle_state.x_pos_global <<
", y: " << req->vehicle_state.y_pos_global <<
", speed: " << req->vehicle_state.longitudinal_vel);
80 if (req->vehicle_state.longitudinal_vel <
epsilon_)
82 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_and_wait_plugin"),
"Detected that car is already stopped! Ignoring the request to plan Stop&Wait");
87 double current_downtrack =
wm_->routeTrackPos(veh_pos).downtrack;
89 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_and_wait_plugin"),
"Current_downtrack" << current_downtrack);
91 if (req->maneuver_plan.maneuvers[req->maneuver_index_to_plan].stop_and_wait_maneuver.end_dist < current_downtrack)
93 throw std::invalid_argument(
"StopAndWait plugin asked to plan maneuver that ends earlier than the current state.");
96 resp->related_maneuvers.push_back(req->maneuver_index_to_plan);
97 resp->maneuver_status.push_back(carma_planning_msgs::srv::PlanTrajectory::Response::MANEUVER_IN_PROGRESS);
99 std::string maneuver_id = req->maneuver_plan.maneuvers[req->maneuver_index_to_plan].stop_and_wait_maneuver.parameters.maneuver_id;
101 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"stop_and_wait_plugin"),
"Maneuver not yet planned, planning new trajectory");
104 std::vector<carma_planning_msgs::msg::Maneuver> maneuver_plan = { req->maneuver_plan.maneuvers[req->maneuver_index_to_plan] };
107 maneuver_plan,
wm_, req->vehicle_state);
110 carma_planning_msgs::msg::TrajectoryPlan trajectory;
111 trajectory.header.frame_id =
"map";
112 trajectory.header.stamp = req->header.stamp;
118 double stopping_accel = 0.0;
119 if (maneuver_plan[0].stop_and_wait_maneuver.parameters.presence_vector &
120 carma_planning_msgs::msg::ManeuverParameters::HAS_FLOAT_META_DATA)
122 if(maneuver_plan[0].stop_and_wait_maneuver.parameters.float_valued_meta_data.size() < 2){
123 throw std::invalid_argument(
"stop and wait maneuver message missing required meta data");
125 stop_location_buffer = maneuver_plan[0].stop_and_wait_maneuver.parameters.float_valued_meta_data[0];
126 stopping_accel = maneuver_plan[0].stop_and_wait_maneuver.parameters.float_valued_meta_data[1];
128 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_and_wait_plugin"),
"Using stop buffer from meta data: " << stop_location_buffer);
129 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_and_wait_plugin"),
"Using stopping acceleration from meta data: "<< stopping_accel);
132 throw std::invalid_argument(
"stop and wait maneuver message missing required float meta data");
135 double initial_speed = req->vehicle_state.longitudinal_vel;
137 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_and_wait_plugin"),
"Original size: " << points_and_target_speeds.size());
140 points_and_target_speeds, current_downtrack, req->vehicle_state.longitudinal_vel,
141 maneuver_plan[0].stop_and_wait_maneuver.end_dist, stop_location_buffer, req->header.stamp, stopping_accel, initial_speed);
143 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_and_wait_plugin"),
"Trajectory points size:" << trajectory.trajectory_points.size());
145 trajectory.initial_longitudinal_velocity = initial_speed;
147 resp->trajectory_plan = trajectory;
157 RCLCPP_DEBUG(rclcpp::get_logger(
"stop_and_wait_plugin"),
"Ignored Object Avoidance");
160 std::chrono::system_clock::time_point end_time = std::chrono::system_clock::now();
162 auto duration = end_time - start_time;
163 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_and_wait_plugin"),
"ExecutionTime Stop&Wait Trajectory: " << std::chrono::duration<double>(duration).count());
171 const carma_planning_msgs::msg::VehicleState& state)
173 std::vector<PointSpeedPair> points_and_target_speeds;
174 std::unordered_set<lanelet::Id> visited_lanelets;
176 carma_planning_msgs::msg::StopAndWaitManeuver stop_and_wait_maneuver = maneuvers[0].stop_and_wait_maneuver;
178 lanelet::BasicPoint2d veh_pos(state.x_pos_global, state.y_pos_global);
179 double starting_downtrack =
wm_->routeTrackPos(veh_pos).downtrack;
180 double starting_speed = state.longitudinal_vel;
185 std::vector<lanelet::BasicPoint2d> route_points = wm->sampleRoutePoints(
190 route_points.insert(route_points.begin(), veh_pos);
193 for (
const auto& p : route_points)
197 pair.
speed = starting_speed;
198 points_and_target_speeds.push_back(pair);
201 return points_and_target_speeds;
205 const std::vector<lanelet::BasicPoint2d>& points,
const std::vector<double>& times,
const std::vector<double>& yaws,
206 rclcpp::Time startTime)
208 if (points.size() != times.size() || points.size() != yaws.size())
210 throw std::invalid_argument(
"All input vectors must have the same size");
213 std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint> traj;
214 traj.reserve(points.size());
216 for (
size_t i = 0;
i < points.size();
i++)
218 carma_planning_msgs::msg::TrajectoryPlanPoint tpp;
219 rclcpp::Duration relative_time(times[
i] * 1e9);
220 tpp.target_time = startTime + relative_time;
221 tpp.x = points[
i].x();
222 tpp.y = points[
i].y();
225 tpp.controller_plugin_name =
"default";
234 const std::vector<PointSpeedPair>& points,
double starting_downtrack,
double starting_speed,
double stop_location,
235 double stop_location_buffer, rclcpp::Time start_time,
double stopping_acceleration,
double& initial_speed)
237 std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint> plan;
238 if (points.size() == 0)
240 RCLCPP_WARN_STREAM(rclcpp::get_logger(
"stop_and_wait_plugin"),
"No points to use as trajectory in stop and wait plugin");
244 std::vector<PointSpeedPair> final_points;
246 double half_stopping_buffer = stop_location_buffer * 0.5;
247 double remaining_distance = stop_location - half_stopping_buffer - starting_downtrack;
250 double req_dist = (starting_speed * starting_speed) /
251 (2.0 * target_accel);
255 while (remaining_distance <= 0.0)
257 if(remaining_distance <= (stop_location - starting_downtrack))
260 remaining_distance += 0.2;
267 if (req_dist > remaining_distance)
270 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_and_wait_plugin"),
"Target Accel Update From: " << target_accel);
272 (starting_speed * starting_speed) / (2.0 * remaining_distance);
274 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_and_wait_plugin"),
"Target Accel Update To: " << target_accel);
278 std::vector<double> inverse_downtracks;
279 inverse_downtracks.reserve(points.size());
280 final_points.reserve(points.size());
283 prev_pair.
speed = 0.0;
284 final_points.push_back(prev_pair);
285 inverse_downtracks.push_back(0);
287 bool reached_end =
false;
288 for (
int i = points.size() - 2;
i >= 0;
i--)
291 double v_i = prev_pair.
speed;
292 double dx = lanelet::geometry::distance2d(prev_pair.
point, points[
i].point);
293 double new_downtrack = inverse_downtracks.back() + dx;
295 if (new_downtrack < half_stopping_buffer) {
298 final_points.push_back(pair);
299 inverse_downtracks.push_back(new_downtrack);
304 if (reached_end || v_i >= starting_speed)
309 pair.
speed = starting_speed;
310 final_points.push_back(pair);
311 inverse_downtracks.push_back(new_downtrack);
316 double v_f = sqrt(v_i * v_i + 2 * target_accel * dx);
319 pair.
speed = std::min(v_f, starting_speed);
320 final_points.push_back(pair);
321 inverse_downtracks.push_back(new_downtrack);
327 std::reverse(final_points.begin(),
330 std::vector<double> speeds;
331 std::vector<lanelet::BasicPoint2d> raw_points;
335 double max_downtrack = inverse_downtracks.back();
336 std::vector<double> downtracks = lanelet::utils::transform(inverse_downtracks, [max_downtrack](
const auto& d) {
return max_downtrack - d; });
337 std::reverse(downtracks.begin(),
340 bool in_range =
false;
341 double stopped_downtrack = 0;
342 lanelet::BasicPoint2d stopped_point;
344 bool vehicle_in_buffer = downtracks.back() < stop_location_buffer;
348 for (
size_t i = 0;
i < filtered_speeds.size();
i++)
350 double downtrack = downtracks[
i];
352 constexpr double one_mph_in_mps = 0.44704;
354 if (downtracks.back() - downtrack < stop_location_buffer && filtered_speeds[
i] <
config_.
crawl_speed + one_mph_in_mps)
358 if (vehicle_in_buffer || (
i == filtered_speeds.size() - 1)) {
359 filtered_speeds[
i] = 0.0;
371 std::vector<double> times;
372 trajectory_utils::conversions::speed_to_time(downtracks, filtered_speeds, ×);
374 for (
size_t i = 0;
i < times.size();
i++)
376 if (times[
i] != 0 && !std::isnormal(times[
i]) &&
i != 0)
378 RCLCPP_WARN_STREAM(rclcpp::get_logger(
"stop_and_wait_plugin"),
"Detected non-normal (nan, inf, etc.) time. Making it same as before: " << times[
i-1]);
380 times[
i] = times[
i - 1];
386 for (
size_t i = 0;
i < points.size();
i++)
388 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"stop_and_wait_plugin"),
"1d: " << downtracks[
i] <<
" t: " << times[
i] <<
" v: " << filtered_speeds[
i]);
395 carma_planning_msgs::msg::TrajectoryPlanPoint new_point = traj.back();
396 new_point.target_time = rclcpp::Time(new_point.target_time) + rclcpp::Duration(
config_.
stop_timestep * 1e9);
398 traj.push_back(new_point);
401 if (!filtered_speeds.empty())
402 initial_speed = filtered_speeds.front();
408 std::vector<lanelet::BasicPoint2d>* basic_points,
409 std::vector<double>* speeds)
const
411 basic_points->reserve(points.size());
412 speeds->reserve(points.size());
414 for (
const auto& p : points)
416 basic_points->push_back(p.point);
417 speeds->push_back(p.speed);
carma_wm::WorldModelConstPtr wm_
StopandWaitConfig config_
void splitPointSpeedPairs(const std::vector< PointSpeedPair > &points, std::vector< lanelet::BasicPoint2d > *basic_points, std::vector< double > *speeds) const
Helper method to split a list of PointSpeedPair into separate point and speed lists.
void set_yield_client(carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > client)
set the yield service
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_AND_WAIT maneuvers to point speed limit pairs.
bool plan_trajectory_cb(carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req, carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp)
Service callback for trajectory planning.
std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > compose_trajectory_from_centerline(const std::vector< PointSpeedPair > &points, double starting_downtrack, double starting_speed, double stop_location, double stop_location_buffer, rclcpp::Time start_time, double stopping_acceleration, double &initial_speed)
Method converts a list of lanelet centerline points and current vehicle state into a usable list of t...
StopandWait(std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > nh, carma_wm::WorldModelConstPtr wm, const StopandWaitConfig &config, const std::string &plugin_name, const std::string &version_id)
Constructor.
std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > nh_
carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > yield_client_
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)
std::vector< double > moving_average_filter(const std::vector< double > input, int window_size, bool ignore_first_point=true)
Extremely simplie moving average filter.
carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr modify_trajectory_to_yield_to_obstacles(const std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > &node_handler, const carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr &req, const carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr &resp, const carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > &yield_client, int yield_plugin_service_call_timeout)
Applies a yield trajectory to the original trajectory set in response.
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::shared_ptr< const WorldModel > WorldModelConstPtr
Stuct containing the algorithm configuration values for the stop_and_wait_plugin.
double centerline_sampling_spacing
bool enable_object_avoidance
int tactical_plugin_service_call_timeout
double default_stopping_buffer
double accel_limit_multiplier
double minimal_trajectory_duration
double moving_average_window_size
Convenience class for pairing 2d points with speeds.
lanelet::BasicPoint2d point