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.
stop_and_wait_plugin::StopandWait Class Reference

#include <stop_and_wait_plugin.hpp>

Collaboration diagram for stop_and_wait_plugin::StopandWait:
Collaboration graph

Public Member Functions

 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. More...
 
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. More...
 
std::vector< PointSpeedPairmaneuvers_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. More...
 
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 trajectory points for trajectory planning. More...
 
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. More...
 
std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > trajectory_from_points_times_orientations (const std::vector< lanelet::BasicPoint2d > &points, const std::vector< double > &times, const std::vector< double > &yaws, rclcpp::Time startTime)
 
void set_yield_client (carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > client)
 set the yield service More...
 

Private Attributes

double epsilon_ = 0.001
 
std::string plugin_name_
 
std::string version_id_
 
carma_wm::WorldModelConstPtr wm_
 
StopandWaitConfig config_
 
std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > nh_
 
carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > yield_client_
 

Detailed Description

Definition at line 50 of file stop_and_wait_plugin.hpp.

Constructor & Destructor Documentation

◆ StopandWait()

stop_and_wait_plugin::StopandWait::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.

Definition at line 51 of file stop_and_wait_plugin.cpp.

56 : version_id_ (version_id),plugin_name_(plugin_name),config_(config),nh_(nh), wm_(wm)
57{};
carma_wm::WorldModelConstPtr wm_
std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > nh_
string version_id

Member Function Documentation

◆ compose_trajectory_from_centerline()

std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > stop_and_wait_plugin::StopandWait::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 trajectory points for trajectory planning.

Parameters
pointsThe set of points that define the current lane the vehicle is in and are defined based on the request planning maneuvers. These points must be in the same lane as the vehicle and must extend in front of it though it is fine if they also extend behind it.
stateThe current state of the vehicle
initial_speedReturns the initial_speed used to generate the trajectory
Returns
A list of trajectory points to send to the carma planning stack

Definition at line 233 of file stop_and_wait_plugin.cpp.

236{
237 std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint> plan;
238 if (points.size() == 0)
239 {
240 RCLCPP_WARN_STREAM(rclcpp::get_logger("stop_and_wait_plugin"),"No points to use as trajectory in stop and wait plugin");
241 return plan;
242 }
243
244 std::vector<PointSpeedPair> final_points;
245
246 double half_stopping_buffer = stop_location_buffer * 0.5;
247 double remaining_distance = stop_location - half_stopping_buffer - starting_downtrack; // Target to stop in the middle of the buffer
248
249 double target_accel = stopping_acceleration * config_.accel_limit_multiplier;
250 double req_dist = (starting_speed * starting_speed) /
251 (2.0 * target_accel); // Distance needed to go from current speed to 0 at target accel
252
253 // In cases where the vehicle is not able to stop before the half_stopping_buffer the remaining distance becomes negative
254 // which will cause the target accel in this loop to be negative and make the vehicle speed up
255 while (remaining_distance <= 0.0)
256 {
257 if(remaining_distance <= (stop_location - starting_downtrack))
258 {
259 //Add additional distance to remaining to allow vehicle to stop within buffer
260 remaining_distance += 0.2;
261 }
262 else{
263 break;
264 }
265 }
266
267 if (req_dist > remaining_distance)
268 {
269
270 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_and_wait_plugin"),"Target Accel Update From: " << target_accel);
271 target_accel =
272 (starting_speed * starting_speed) / (2.0 * remaining_distance); // If we cannot reach the end point it the
273 // required distance update the accel target
274 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_and_wait_plugin"),"Target Accel Update To: " << target_accel);
275 }
276
277
278 std::vector<double> inverse_downtracks; // Store downtracks in reverse
279 inverse_downtracks.reserve(points.size());
280 final_points.reserve(points.size());
281
282 PointSpeedPair prev_pair = points.back();
283 prev_pair.speed = 0.0;
284 final_points.push_back(prev_pair); // Store the points in reverse
285 inverse_downtracks.push_back(0);
286
287 bool reached_end = false;
288 for (int i = points.size() - 2; i >= 0; i--)
289 { // NOTE: Do not use size_t for i type here as -- with > 0 will result in overflow
290
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;
294
295 if (new_downtrack < half_stopping_buffer) { // Points after (when viewed not in reverse) the midpoint of the buffer should be 0 speed
296 PointSpeedPair pair = points[i];
297 pair.speed = 0;
298 final_points.push_back(pair); // Store the points in reverse
299 inverse_downtracks.push_back(new_downtrack);
300 prev_pair = pair;
301 continue;
302 }
303
304 if (reached_end || v_i >= starting_speed)
305 { // We are walking backward, so if the prev speed is greater than or equal to the starting speed then we are done
306 // backtracking
307 reached_end = true;
308 PointSpeedPair pair = points[i];
309 pair.speed = starting_speed;
310 final_points.push_back(pair); // Store the points in reverse
311 inverse_downtracks.push_back(new_downtrack);
312 prev_pair = pair;
313 continue; // continue until loop end
314 }
315
316 double v_f = sqrt(v_i * v_i + 2 * target_accel * dx);
317
318 PointSpeedPair pair = points[i];
319 pair.speed = std::min(v_f, starting_speed);
320 final_points.push_back(pair); // Store the points in reverse
321 inverse_downtracks.push_back(new_downtrack);
322
323 prev_pair = pair;
324 }
325
326 // Now we have a trajectory that decelerates from our end point to somewhere in the maneuver
327 std::reverse(final_points.begin(),
328 final_points.end());
329
330 std::vector<double> speeds;
331 std::vector<lanelet::BasicPoint2d> raw_points;
332 splitPointSpeedPairs(final_points, &raw_points, &speeds);
333
334 // Convert the inverted downtracks back to regular downtracks
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(),
338 downtracks.end());
339
340 bool in_range = false;
341 double stopped_downtrack = 0;
342 lanelet::BasicPoint2d stopped_point;
343
344 bool vehicle_in_buffer = downtracks.back() < stop_location_buffer;
345
346 std::vector<double> filtered_speeds = basic_autonomy::smoothing::moving_average_filter(speeds, config_.moving_average_window_size);
347
348 for (size_t i = 0; i < filtered_speeds.size(); i++)
349 { // Apply minimum speed constraint
350 double downtrack = downtracks[i];
351
352 constexpr double one_mph_in_mps = 0.44704;
353
354 if (downtracks.back() - downtrack < stop_location_buffer && filtered_speeds[i] < config_.crawl_speed + one_mph_in_mps)
355 { // if we are within the stopping buffer and going at near crawl speed then command stop
356
357 // To avoid any issues in control plugin behavior we only command 0 if the vehicle is inside the buffer
358 if (vehicle_in_buffer || (i == filtered_speeds.size() - 1)) { // Vehicle is in the buffer
359 filtered_speeds[i] = 0.0;
360 } else { // Vehicle is not in the buffer so fill buffer with crawl speed
361 filtered_speeds[i] = std::max(filtered_speeds[i], config_.crawl_speed);
362 }
363
364 }
365 else
366 {
367 filtered_speeds[i] = std::max(filtered_speeds[i], config_.crawl_speed);
368 }
369 }
370
371 std::vector<double> times;
372 trajectory_utils::conversions::speed_to_time(downtracks, filtered_speeds, &times);
373
374 for (size_t i = 0; i < times.size(); i++)
375 {
376 if (times[i] != 0 && !std::isnormal(times[i]) && i != 0)
377 { // If the time
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]);
379 // NOTE: overriding the timestamps in assumption that pure_pursuit_wrapper will detect it as stopping case
380 times[i] = times[i - 1];
381 }
382 }
383
384 std::vector<double> yaws = carma_wm::geometry::compute_tangent_orientations(raw_points);
385
386 for (size_t i = 0; i < points.size(); i++)
387 {
388 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_and_wait_plugin"),"1d: " << downtracks[i] << " t: " << times[i] << " v: " << filtered_speeds[i]);
389 }
390
391 auto traj = trajectory_from_points_times_orientations(raw_points, times, yaws, start_time);
392
393 while (rclcpp::Time(traj.back().target_time) - rclcpp::Time(traj.front().target_time) < rclcpp::Duration(config_.minimal_trajectory_duration * 1e9))
394 {
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);
397 new_point.planner_plugin_name = plugin_name_;
398 traj.push_back(new_point);
399 }
400
401 if (!filtered_speeds.empty())
402 initial_speed = filtered_speeds.front(); //modify initial_speed variable passed by reference
403
404 return traj;
405}
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.
std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > trajectory_from_points_times_orientations(const std::vector< lanelet::BasicPoint2d > &points, const std::vector< double > &times, 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.
Definition: filters.cpp:24
std::vector< double > compute_tangent_orientations(const lanelet::BasicLineString2d &centerline)
Compute an approximate orientation for the vehicle at each point along the provided centerline.
Definition: Geometry.cpp:559
basic_autonomy::waypoint_generation::PointSpeedPair PointSpeedPair

References StopandWaitConfig::accel_limit_multiplier, carma_wm::geometry::compute_tangent_orientations(), config_, StopandWaitConfig::crawl_speed, process_bag::i, StopandWaitConfig::minimal_trajectory_duration, basic_autonomy::smoothing::moving_average_filter(), StopandWaitConfig::moving_average_window_size, plugin_name_, stop_and_wait_plugin::PointSpeedPair::point, stop_and_wait_plugin::PointSpeedPair::speed, splitPointSpeedPairs(), StopandWaitConfig::stop_timestep, and trajectory_from_points_times_orientations().

Referenced by plan_trajectory_cb().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ maneuvers_to_points()

std::vector< PointSpeedPair > stop_and_wait_plugin::StopandWait::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.

Parameters
maneuversThe list of maneuvers to convert
max_starting_downtrackThe maximum downtrack that is allowed for the first maneuver. This should be set to the vehicle position or earlier. If the first maneuver exceeds this then it's downtrack will be shifted to this value.

ASSUMPTION: Since the vehicle is trying to stop the assumption made is that the speed limit is irrelevant. ASSUMPTION: The provided maneuver lies on the route shortest path

Returns
List of centerline points paired with speed limits. All output points will have speed matching state.logitudinal_velocity

Definition at line 169 of file stop_and_wait_plugin.cpp.

172{
173 std::vector<PointSpeedPair> points_and_target_speeds;
174 std::unordered_set<lanelet::Id> visited_lanelets;
175
176 carma_planning_msgs::msg::StopAndWaitManeuver stop_and_wait_maneuver = maneuvers[0].stop_and_wait_maneuver;
177
178 lanelet::BasicPoint2d veh_pos(state.x_pos_global, state.y_pos_global);
179 double starting_downtrack = wm_->routeTrackPos(veh_pos).downtrack; // The vehicle position
180 double starting_speed = state.longitudinal_vel;
181
182 // Sample the lanelet centerline at fixed increments.
183 // std::min call here is a guard against starting_downtrack being within 1m of the maneuver end_dist
184 // in this case the sampleRoutePoints method will return a single point allowing execution to continue
185 std::vector<lanelet::BasicPoint2d> route_points = wm->sampleRoutePoints(
186 std::min(starting_downtrack + config_.centerline_sampling_spacing, stop_and_wait_maneuver.end_dist),
187 stop_and_wait_maneuver.end_dist, config_.centerline_sampling_spacing);
188
189
190 route_points.insert(route_points.begin(), veh_pos);
191
192
193 for (const auto& p : route_points)
194 {
195 PointSpeedPair pair;
196 pair.point = p;
197 pair.speed = starting_speed; // NOTE: Since the vehicle is trying to stop the assumption made is that the speed limit is irrelevant.
198 points_and_target_speeds.push_back(pair);
199 }
200
201 return points_and_target_speeds;
202}

References StopandWaitConfig::centerline_sampling_spacing, config_, stop_and_wait_plugin::PointSpeedPair::point, stop_and_wait_plugin::PointSpeedPair::speed, and wm_.

Referenced by plan_trajectory_cb().

Here is the caller graph for this function:

◆ plan_trajectory_cb()

bool stop_and_wait_plugin::StopandWait::plan_trajectory_cb ( carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr  req,
carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr  resp 
)

Service callback for trajectory planning.

Parameters
reqThe service request
respThe service response
Returns
True if success. False otherwise

Definition at line 59 of file stop_and_wait_plugin.cpp.

60{
61 std::chrono::system_clock::time_point start_time = std::chrono::system_clock::now(); // Start timing the execution time for planning so it can be logged
62 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_and_wait_plugin"),"Starting stop&wait planning");
63
64 if (req->maneuver_index_to_plan >= req->maneuver_plan.maneuvers.size())
65 {
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()));
69 }
70
71 if (req->maneuver_plan.maneuvers[req->maneuver_index_to_plan].type != carma_planning_msgs::msg::Maneuver::STOP_AND_WAIT)
72 {
73 throw std::invalid_argument("StopAndWait plugin asked to plan non STOP_AND_WAIT maneuver");
74 }
75
76 lanelet::BasicPoint2d veh_pos(req->vehicle_state.x_pos_global, req->vehicle_state.y_pos_global);
77
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);
79
80 if (req->vehicle_state.longitudinal_vel < epsilon_)
81 {
82 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_and_wait_plugin"),"Detected that car is already stopped! Ignoring the request to plan Stop&Wait");
83
84 return true;
85 }
86
87 double current_downtrack = wm_->routeTrackPos(veh_pos).downtrack;
88
89 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_and_wait_plugin"),"Current_downtrack" << current_downtrack);
90
91 if (req->maneuver_plan.maneuvers[req->maneuver_index_to_plan].stop_and_wait_maneuver.end_dist < current_downtrack)
92 {
93 throw std::invalid_argument("StopAndWait plugin asked to plan maneuver that ends earlier than the current state.");
94 }
95
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);
98
99 std::string maneuver_id = req->maneuver_plan.maneuvers[req->maneuver_index_to_plan].stop_and_wait_maneuver.parameters.maneuver_id;
100
101 RCLCPP_INFO_STREAM(rclcpp::get_logger("stop_and_wait_plugin"),"Maneuver not yet planned, planning new trajectory");
102
103 // Maneuver input is valid so continue with execution
104 std::vector<carma_planning_msgs::msg::Maneuver> maneuver_plan = { req->maneuver_plan.maneuvers[req->maneuver_index_to_plan] };
105
106 std::vector<PointSpeedPair> points_and_target_speeds = maneuvers_to_points(
107 maneuver_plan, wm_, req->vehicle_state); // Now have 1m downsampled points from cur to endpoint
108
109 // Trajectory plan
110 carma_planning_msgs::msg::TrajectoryPlan trajectory;
111 trajectory.header.frame_id = "map";
112 trajectory.header.stamp = req->header.stamp;
113 trajectory.trajectory_id = boost::uuids::to_string(boost::uuids::random_generator()());
114
115 // Extract the stopping buffer used to consider a stopping behavior complete
116 double stop_location_buffer = config_.default_stopping_buffer; // If no maneuver meta data is provided we will use the default buffer
117
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)
121 {
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");
124 }
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];
127
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);
130 }
131 else{
132 throw std::invalid_argument("stop and wait maneuver message missing required float meta data");
133 }
134
135 double initial_speed = req->vehicle_state.longitudinal_vel; //will be modified after compose_trajectory_from_centerline
136
137 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_and_wait_plugin"),"Original size: " << points_and_target_speeds.size());
138
139 trajectory.trajectory_points = compose_trajectory_from_centerline(
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);
142
143 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("stop_and_wait_plugin"),"Trajectory points size:" << trajectory.trajectory_points.size());
144
145 trajectory.initial_longitudinal_velocity = initial_speed;
146
147 resp->trajectory_plan = trajectory;
148
149 // Yield for potential obstacles in the road
150 // Aside from the flag, yield_plugin should not be called on invalid trajectories
151 if (config_.enable_object_avoidance && resp->trajectory_plan.trajectory_points.size() >= 2)
152 {
154 }
155 else
156 {
157 RCLCPP_DEBUG(rclcpp::get_logger("stop_and_wait_plugin"), "Ignored Object Avoidance");
158 }
159
160 std::chrono::system_clock::time_point end_time = std::chrono::system_clock::now(); // Planning complete
161
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());
164
165 return true;
166}
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.
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...
carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > yield_client_
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
Definition: utm_zone.cpp:21

References compose_trajectory_from_centerline(), config_, StopandWaitConfig::default_stopping_buffer, StopandWaitConfig::enable_object_avoidance, epsilon_, maneuvers_to_points(), basic_autonomy::waypoint_generation::modify_trajectory_to_yield_to_obstacles(), nh_, StopandWaitConfig::tactical_plugin_service_call_timeout, carma_cooperative_perception::to_string(), wm_, and yield_client_.

Here is the call graph for this function:

◆ set_yield_client()

void stop_and_wait_plugin::StopandWait::set_yield_client ( carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory >  client)

set the yield service

Parameters
yield_srvinput yield service

Definition at line 421 of file stop_and_wait_plugin.cpp.

422{
423 yield_client_ = client;
424}

References yield_client_.

◆ splitPointSpeedPairs()

void stop_and_wait_plugin::StopandWait::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.

Definition at line 407 of file stop_and_wait_plugin.cpp.

410{
411 basic_points->reserve(points.size());
412 speeds->reserve(points.size());
413
414 for (const auto& p : points)
415 {
416 basic_points->push_back(p.point);
417 speeds->push_back(p.speed);
418 }
419}

Referenced by compose_trajectory_from_centerline().

Here is the caller graph for this function:

◆ trajectory_from_points_times_orientations()

std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > stop_and_wait_plugin::StopandWait::trajectory_from_points_times_orientations ( const std::vector< lanelet::BasicPoint2d > &  points,
const std::vector< double > &  times,
const std::vector< double > &  yaws,
rclcpp::Time  startTime 
)

Definition at line 204 of file stop_and_wait_plugin.cpp.

207{
208 if (points.size() != times.size() || points.size() != yaws.size())
209 {
210 throw std::invalid_argument("All input vectors must have the same size");
211 }
212
213 std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint> traj;
214 traj.reserve(points.size());
215
216 for (size_t i = 0; i < points.size(); i++)
217 {
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();
223 tpp.yaw = yaws[i];
224 tpp.planner_plugin_name = plugin_name_;
225 tpp.controller_plugin_name = "default";
226
227 traj.push_back(tpp);
228 }
229
230 return traj;
231}

References process_bag::i, and plugin_name_.

Referenced by compose_trajectory_from_centerline().

Here is the caller graph for this function:

Member Data Documentation

◆ config_

StopandWaitConfig stop_and_wait_plugin::StopandWait::config_
private

◆ epsilon_

double stop_and_wait_plugin::StopandWait::epsilon_ = 0.001
private

Definition at line 121 of file stop_and_wait_plugin.hpp.

Referenced by plan_trajectory_cb().

◆ nh_

std::shared_ptr<carma_ros2_utils::CarmaLifecycleNode> stop_and_wait_plugin::StopandWait::nh_
private

Definition at line 128 of file stop_and_wait_plugin.hpp.

Referenced by plan_trajectory_cb().

◆ plugin_name_

std::string stop_and_wait_plugin::StopandWait::plugin_name_
private

◆ version_id_

std::string stop_and_wait_plugin::StopandWait::version_id_
private

Definition at line 125 of file stop_and_wait_plugin.hpp.

◆ wm_

carma_wm::WorldModelConstPtr stop_and_wait_plugin::StopandWait::wm_
private

Definition at line 126 of file stop_and_wait_plugin.hpp.

Referenced by maneuvers_to_points(), and plan_trajectory_cb().

◆ yield_client_

carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory> stop_and_wait_plugin::StopandWait::yield_client_
private

Definition at line 130 of file stop_and_wait_plugin.hpp.

Referenced by plan_trajectory_cb(), and set_yield_client().


The documentation for this class was generated from the following files: