Carma-platform v4.10.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.
plan_delegator.cpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2022-2023 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
16
17#include <stdexcept>
18#include <carma_wm/Geometry.hpp>
19#include "plan_delegator.hpp"
20
21namespace plan_delegator
22{
23 namespace std_ph = std::placeholders;
24
25 namespace
26 {
32 void setManeuverStartingLaneletId(carma_planning_msgs::msg::Maneuver& mvr, lanelet::Id start_id) {
33 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"),"Updating maneuver starting_lane_id to " << start_id);
34
35 switch(mvr.type) {
36 case carma_planning_msgs::msg::Maneuver::LANE_CHANGE:
37 mvr.lane_change_maneuver.starting_lane_id = std::to_string(start_id);
38 break;
39 case carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_STRAIGHT:
40 mvr.intersection_transit_straight_maneuver.starting_lane_id = std::to_string(start_id);
41 break;
42 case carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_LEFT_TURN:
43 mvr.intersection_transit_left_turn_maneuver.starting_lane_id = std::to_string(start_id);
44 break;
45 case carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_RIGHT_TURN:
46 mvr.intersection_transit_right_turn_maneuver.starting_lane_id = std::to_string(start_id);
47 break;
48 case carma_planning_msgs::msg::Maneuver::STOP_AND_WAIT:
49 mvr.stop_and_wait_maneuver.starting_lane_id = std::to_string(start_id);
50 break;
51 default:
52 throw std::invalid_argument("Maneuver type does not have starting and ending lane ids");
53 }
54 }
55
61 void setManeuverEndingLaneletId(carma_planning_msgs::msg::Maneuver& mvr, lanelet::Id end_id) {
62 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"),"Updating maneuver ending_lane_id to " << end_id);
63
64 switch(mvr.type) {
65 case carma_planning_msgs::msg::Maneuver::LANE_CHANGE:
66 mvr.lane_change_maneuver.ending_lane_id = std::to_string(end_id);
67 break;
68 case carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_STRAIGHT:
69 mvr.intersection_transit_straight_maneuver.ending_lane_id = std::to_string(end_id);
70 break;
71 case carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_LEFT_TURN:
72 mvr.intersection_transit_left_turn_maneuver.ending_lane_id = std::to_string(end_id);
73 break;
74 case carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_RIGHT_TURN:
75 mvr.intersection_transit_right_turn_maneuver.ending_lane_id = std::to_string(end_id);
76 break;
77 case carma_planning_msgs::msg::Maneuver::STOP_AND_WAIT:
78 mvr.stop_and_wait_maneuver.ending_lane_id = std::to_string(end_id);
79 break;
80 default:
81 throw std::invalid_argument("Maneuver type does not have starting and ending lane ids");
82 }
83 }
84
90 std::string getManeuverStartingLaneletId(carma_planning_msgs::msg::Maneuver mvr) {
91 switch(mvr.type) {
92 case carma_planning_msgs::msg::Maneuver::LANE_CHANGE:
93 return mvr.lane_change_maneuver.starting_lane_id;
94 case carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_STRAIGHT:
95 return mvr.intersection_transit_straight_maneuver.starting_lane_id;
96 case carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_LEFT_TURN:
97 return mvr.intersection_transit_left_turn_maneuver.starting_lane_id;
98 case carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_RIGHT_TURN:
99 return mvr.intersection_transit_right_turn_maneuver.starting_lane_id;
100 case carma_planning_msgs::msg::Maneuver::STOP_AND_WAIT:
101 return mvr.stop_and_wait_maneuver.starting_lane_id;
102 default:
103 throw std::invalid_argument("Maneuver type does not have starting and ending lane ids");
104 }
105 }
106
112 std::string getManeuverEndingLaneletId(carma_planning_msgs::msg::Maneuver mvr) {
113 switch(mvr.type) {
114 case carma_planning_msgs::msg::Maneuver::LANE_CHANGE:
115 return mvr.lane_change_maneuver.ending_lane_id;
116 case carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_STRAIGHT:
117 return mvr.intersection_transit_straight_maneuver.ending_lane_id;
118 case carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_LEFT_TURN:
119 return mvr.intersection_transit_left_turn_maneuver.ending_lane_id;
120 case carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_RIGHT_TURN:
121 return mvr.intersection_transit_right_turn_maneuver.ending_lane_id;
122 case carma_planning_msgs::msg::Maneuver::STOP_AND_WAIT:
123 return mvr.stop_and_wait_maneuver.ending_lane_id;
124 default:
125 throw std::invalid_argument("Maneuver type does not have starting and ending lane ids");
126 }
127 }
128 } //namespace
129
130
131 PlanDelegator::PlanDelegator(const rclcpp::NodeOptions &options) : carma_ros2_utils::CarmaLifecycleNode(options),
132 tf2_buffer_(std::make_shared<tf2_ros::Buffer>(this->get_clock())),
133 wml_(this->get_node_base_interface(), this->get_node_logging_interface(),
134 this->get_node_topics_interface(), this->get_node_parameters_interface())
135 {
136 // Create initial config
137 config_ = Config();
138
139 config_.planning_topic_prefix = declare_parameter<std::string>("planning_topic_prefix", config_.planning_topic_prefix);
140 config_.planning_topic_suffix = declare_parameter<std::string>("planning_topic_suffix", config_.planning_topic_suffix);
141 config_.trajectory_planning_rate = declare_parameter<double>("trajectory_planning_rate", config_.trajectory_planning_rate);
142 config_.max_trajectory_duration = declare_parameter<double>("trajectory_duration_threshold", config_.max_trajectory_duration);
143 config_.min_crawl_speed = declare_parameter<double>("min_speed", config_.min_crawl_speed);
144 config_.duration_to_signal_before_lane_change = declare_parameter<double>("duration_to_signal_before_lane_change", config_.duration_to_signal_before_lane_change);
145 config_.max_traj_generation_reattempt = declare_parameter<int>("max_traj_generation_reattempt", config_.max_traj_generation_reattempt);
146 config_.tactical_plugin_service_call_timeout = declare_parameter<int>("tactical_plugin_service_call_timeout", config_.tactical_plugin_service_call_timeout);
147 }
148
149 carma_ros2_utils::CallbackReturn PlanDelegator::handle_on_configure(const rclcpp_lifecycle::State &)
150 {
151 // Reset config
152 config_ = Config();
153
154 get_parameter<std::string>("planning_topic_prefix", config_.planning_topic_prefix);
155 get_parameter<std::string>("planning_topic_suffix", config_.planning_topic_suffix);
156 get_parameter<double>("trajectory_planning_rate", config_.trajectory_planning_rate);
157 get_parameter<double>("trajectory_duration_threshold", config_.max_trajectory_duration);
158 get_parameter<double>("min_speed", config_.min_crawl_speed);
159 get_parameter<double>("duration_to_signal_before_lane_change", config_.duration_to_signal_before_lane_change);
160 get_parameter<int>("tactical_plugin_service_call_timeout", config_.tactical_plugin_service_call_timeout);
161 get_parameter<int>("max_traj_generation_reattempt", config_.max_traj_generation_reattempt);
162
163 RCLCPP_INFO_STREAM(rclcpp::get_logger("plan_delegator"),"Done loading parameters: " << config_);
164
165 // Setup publishers
166 traj_pub_ = create_publisher<carma_planning_msgs::msg::TrajectoryPlan>("plan_trajectory", 5);
167 upcoming_lane_change_status_pub_ = create_publisher<carma_planning_msgs::msg::UpcomingLaneChangeStatus>("upcoming_lane_change_status", 1);
168 turn_signal_command_pub_ = create_publisher<autoware_msgs::msg::LampCmd>("lamp_cmd", 1);
169
170 // Setup subscribers
171 plan_sub_ = create_subscription<carma_planning_msgs::msg::ManeuverPlan>("final_maneuver_plan", 5, std::bind(&PlanDelegator::maneuverPlanCallback, this, std_ph::_1));
172 twist_sub_ = create_subscription<geometry_msgs::msg::TwistStamped>("current_velocity", 5,
173 [this](geometry_msgs::msg::TwistStamped::UniquePtr twist) {this->latest_twist_ = *twist;});
174 pose_sub_ = create_subscription<geometry_msgs::msg::PoseStamped>("current_pose", 5, std::bind(&PlanDelegator::poseCallback, this, std_ph::_1));
175 guidance_state_sub_ = create_subscription<carma_planning_msgs::msg::GuidanceState>("guidance_state", 5, std::bind(&PlanDelegator::guidanceStateCallback, this, std_ph::_1));
176
179 return CallbackReturn::SUCCESS;
180 }
181
182 carma_ros2_utils::CallbackReturn PlanDelegator::handle_on_activate(const rclcpp_lifecycle::State &)
183 {
184 timer_callback_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
185 traj_timer_ = create_timer(get_clock(),
186 std::chrono::milliseconds((int)(1 / config_.trajectory_planning_rate * 1000)),
188 return CallbackReturn::SUCCESS;
189 }
190
191 void PlanDelegator::guidanceStateCallback(carma_planning_msgs::msg::GuidanceState::UniquePtr msg)
192 {
194 }
195
196 void PlanDelegator::maneuverPlanCallback(carma_planning_msgs::msg::ManeuverPlan::UniquePtr plan)
197 {
198 RCLCPP_INFO_STREAM(rclcpp::get_logger("plan_delegator"),"Received request to delegate plan ID " << std::string(plan->maneuver_plan_id));
199 // do basic check to see if the input is valid
200 auto copy_plan = *plan;
202 if (isManeuverPlanValid(copy_plan))
203 {
204 latest_maneuver_plan_ = copy_plan;
205 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"),"Received plan with " << latest_maneuver_plan_.maneuvers.size() << " maneuvers");
206
207 // Update the parameters associated with each maneuver
208 for (auto& maneuver : latest_maneuver_plan_.maneuvers) {
209 updateManeuverParameters(maneuver);
210 }
211 }
212 else {
213 RCLCPP_WARN_STREAM(rclcpp::get_logger("plan_delegator"),"Received empty plan, no maneuvers found in plan ID " << std::string(plan->maneuver_plan_id));
214 }
215
216 // Update upcoming_lane_change_information_ and current_lane_change_information_ based on the received maneuver plan
217 if(!latest_maneuver_plan_.maneuvers.empty()){
218 // Get ego vehicle's current downtrack
219 lanelet::BasicPoint2d current_loc(latest_pose_.pose.position.x, latest_pose_.pose.position.y);
220 double current_downtrack = wm_->routeTrackPos(current_loc).downtrack;
221
222 // Set upcoming_lane_change_information_ based on the first found lane change in the plan that begins after current_downtrack, if one exists
223 upcoming_lane_change_information_ = boost::optional<LaneChangeInformation>(); // Reset to empty optional
224 for(const auto& maneuver : latest_maneuver_plan_.maneuvers){
225 if(maneuver.type == carma_planning_msgs::msg::Maneuver::LANE_CHANGE){
226 if(current_downtrack >= maneuver.lane_change_maneuver.start_dist){
227 // Skip this lane change maneuver since ego vehicle has passed the lane change start point (this is not an 'upcoming' lane change)
228 continue;
229 }
230 else{
231 LaneChangeInformation upcoming_lane_change_information = getLaneChangeInformation(maneuver);
232 upcoming_lane_change_information_ = boost::optional<LaneChangeInformation>(upcoming_lane_change_information);
233 break;
234 }
235 }
236 }
237
238 // Set current_lane_change_information_ if the first maneuver is a lane change
239 current_lane_change_information_ = boost::optional<LaneChangeInformation>(); // Reset to empty optional
240 if(latest_maneuver_plan_.maneuvers[0].type == carma_planning_msgs::msg::Maneuver::LANE_CHANGE){
241 LaneChangeInformation current_lane_change_information = getLaneChangeInformation(latest_maneuver_plan_.maneuvers[0]);
242 current_lane_change_information_ = boost::optional<LaneChangeInformation>(current_lane_change_information);
243 }
244 }
245 }
246
247 void PlanDelegator::poseCallback(geometry_msgs::msg::PoseStamped::UniquePtr pose_msg)
248 {
249 latest_pose_ = *pose_msg;
250
251 // Publish the upcoming lane change status
253
254 // Publish the current turn signal command
256 }
257
258 LaneChangeInformation PlanDelegator::getLaneChangeInformation(const carma_planning_msgs::msg::Maneuver& lane_change_maneuver){
259 LaneChangeInformation lane_change_information;
260
261 lane_change_information.starting_downtrack = lane_change_maneuver.lane_change_maneuver.start_dist;
262
263 // Get the starting and ending lanelets for this lane change maneuver
264 lanelet::ConstLanelet starting_lanelet = wm_->getMap()->laneletLayer.get(std::stoi(lane_change_maneuver.lane_change_maneuver.starting_lane_id));
265 lanelet::ConstLanelet ending_lanelet = wm_->getMap()->laneletLayer.get(std::stoi(lane_change_maneuver.lane_change_maneuver.ending_lane_id));
266
267 // Determine if lane change is a left or right lane change and update lane_change_information accordingly
268 bool shared_boundary_found = false;
269
270 lanelet::ConstLanelet current_lanelet = starting_lanelet;
271
272 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"), "Searching for shared boundary with starting lanechange lanelet " << std::to_string(current_lanelet.id()) << " and ending lanelet " << std::to_string(ending_lanelet.id()));
273 while(!shared_boundary_found){
274 // Assumption: Adjacent lanelets share lane boundary
275
276 if(current_lanelet.leftBound() == ending_lanelet.rightBound()){
277 // If current lanelet's left lane boundary matches the ending lanelet's right lane boundary, it is a left lane change
278 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"), "Lanelet " << std::to_string(current_lanelet.id()) << " shares left boundary with " << std::to_string(ending_lanelet.id()));
279 lane_change_information.is_right_lane_change = false;
280 shared_boundary_found = true;
281 }
282 else if(current_lanelet.rightBound() == ending_lanelet.leftBound()){
283 // If current lanelet's right lane boundary matches the ending lanelet's left lane boundary, it is a right lane change
284 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"), "Lanelet " << std::to_string(current_lanelet.id()) << " shares right boundary with " << std::to_string(ending_lanelet.id()));
285 lane_change_information.is_right_lane_change = true;
286 shared_boundary_found = true;
287 }
288 else{
289 // If there are no following lanelets on route, lanechange should be completing before reaching it
290 if(wm_->getMapRoutingGraph()->following(current_lanelet, false).empty())
291 {
292 // Maneuver requires we travel further before completing lane change, but there is no routable lanelet directly ahead;
293 // in this case we have reached a lanelet which does not have a routable lanelet ahead and isn't adjacent to the lanelet where lane change ends.
294 // A lane change should have already happened at this point
295 throw(std::invalid_argument("No following lanelets from current lanelet reachable without a lane change, incorrectly chosen end lanelet"));
296 }
297
298 current_lanelet = wm_->getMapRoutingGraph()->following(current_lanelet, false).front();
299 if(current_lanelet.id() == starting_lanelet.id()){
300 //Looped back to starting lanelet
301 throw(std::invalid_argument("No lane change in path"));
302 }
303 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"), "Now checking for shared lane boundary with lanelet " << std::to_string(current_lanelet.id()) << " and ending lanelet " << std::to_string(ending_lanelet.id()));
304 }
305 }
306
307 return lane_change_information;
308 }
309
310 void PlanDelegator::publishUpcomingLaneChangeStatus(const boost::optional<LaneChangeInformation>& upcoming_lane_change_information){
311 // Initialize an UpcomingLaneChangeStatus message, which will be populated based on upcoming_lane_change_information
312 carma_planning_msgs::msg::UpcomingLaneChangeStatus upcoming_lane_change_status;
313
314 // Update upcoming_lane_change_status
315 if(upcoming_lane_change_information){
316 // Get the downtrack distance between the ego vehicle and the start of the upcoming lane change maneuver
317 lanelet::BasicPoint2d current_loc(latest_pose_.pose.position.x, latest_pose_.pose.position.y);
318 double current_downtrack = wm_->routeTrackPos(current_loc).downtrack;
319 upcoming_lane_change_status.downtrack_until_lanechange = std::max(0.0, upcoming_lane_change_information.get().starting_downtrack - current_downtrack);
320
321 // Set upcoming lane change status as a right lane change or left lane change
322 if(upcoming_lane_change_information.get().is_right_lane_change){
323 upcoming_lane_change_status.lane_change = carma_planning_msgs::msg::UpcomingLaneChangeStatus::RIGHT;
324 }
325 else{
326 upcoming_lane_change_status.lane_change = carma_planning_msgs::msg::UpcomingLaneChangeStatus::LEFT;
327 }
328 }
329 else{
330 upcoming_lane_change_status.lane_change = carma_planning_msgs::msg::UpcomingLaneChangeStatus::NONE;
331 }
332
333 // Publish upcoming_lane_change_status
334 upcoming_lane_change_status_pub_->publish(upcoming_lane_change_status);
335
336 // Store UpcomingLaneChangeStatus in upcoming_lane_change_status_
337 upcoming_lane_change_status_ = upcoming_lane_change_status;
338 }
339
340 void PlanDelegator::publishTurnSignalCommand(const boost::optional<LaneChangeInformation>& current_lane_change_information, const carma_planning_msgs::msg::UpcomingLaneChangeStatus& upcoming_lane_change_status)
341 {
342 // Initialize turn signal command message
343 // NOTE: A LampCmd message can have its 'r' OR 'l' field set to 1 to indicate an activated right or left turn signal, respectively. Both fields cannot be set to 1 at the same time.
344 autoware_msgs::msg::LampCmd turn_signal_command;
345
346 // Publish turn signal command with priority placed on the current lane change, if one exists
347 if(current_lane_change_information){
348 // Publish turn signal command for the current lane change based on the lane change direction
349 if(current_lane_change_information.get().is_right_lane_change){
350 turn_signal_command.r = 1;
351 }
352 else{
353 turn_signal_command.l = 1;
354 }
355 turn_signal_command_pub_->publish(turn_signal_command);
356 }
357 else if(upcoming_lane_change_status.lane_change != carma_planning_msgs::msg::UpcomingLaneChangeStatus::NONE){
358 // Only publish turn signal command for upcoming lane change if it will begin in less than the time defined by config_.duration_to_signal_before_lane_change
359 if((upcoming_lane_change_status.downtrack_until_lanechange / latest_twist_.twist.linear.x) <= config_.duration_to_signal_before_lane_change){
360 if(upcoming_lane_change_status.lane_change == carma_planning_msgs::msg::UpcomingLaneChangeStatus::RIGHT){
361 turn_signal_command.r = 1;
362 }
363 else{
364 turn_signal_command.l = 1;
365 }
366 turn_signal_command_pub_->publish(turn_signal_command);
367 }
368 }
369 else{
370 // Publish turn signal command with neither turn signal activated
371 turn_signal_command_pub_->publish(turn_signal_command);
372 }
373
374 // Store turn signal command in latest_turn_signal_command_
375 latest_turn_signal_command_ = turn_signal_command;
376 }
377
378 carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory> PlanDelegator::getPlannerClientByName(const std::string& planner_name)
379 {
380 if(planner_name.size() == 0)
381 {
382 throw std::invalid_argument("Invalid trajectory planner name because it has zero length!");
383 }
384 if(trajectory_planners_.find(planner_name) == trajectory_planners_.end())
385 {
386 RCLCPP_INFO_STREAM(rclcpp::get_logger("plan_delegator"),"Discovered new trajectory planner: " << planner_name);
387
388 trajectory_planners_.emplace(
389 planner_name, create_client<carma_planning_msgs::srv::PlanTrajectory>(config_.planning_topic_prefix + planner_name + config_.planning_topic_suffix));
390 }
391 return trajectory_planners_[planner_name];
392 }
393
394 bool PlanDelegator::isManeuverPlanValid(const carma_planning_msgs::msg::ManeuverPlan& maneuver_plan) const noexcept
395 {
396 // currently it only checks if maneuver list is empty
397 return !maneuver_plan.maneuvers.empty();
398 }
399
400 bool PlanDelegator::isTrajectoryValid(const carma_planning_msgs::msg::TrajectoryPlan& trajectory_plan) const noexcept
401 {
402 // currently it only checks if trajectory contains less than 2 points
403 return !(trajectory_plan.trajectory_points.size() < 2);
404 }
405
406 bool PlanDelegator::isManeuverExpired(const carma_planning_msgs::msg::Maneuver& maneuver, rclcpp::Time current_time) const
407 {
408 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"), "maneuver start time:" << std::to_string(rclcpp::Time(GET_MANEUVER_PROPERTY(maneuver, start_time)).seconds()));
409 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"), "maneuver end time:" << std::to_string(rclcpp::Time(GET_MANEUVER_PROPERTY(maneuver, end_time)).seconds()));
410 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"), "current time:" << std::to_string(now().seconds()));
411 bool isexpired = rclcpp::Time(GET_MANEUVER_PROPERTY(maneuver, end_time), get_clock()->get_clock_type()) <= current_time; // TODO maneuver expiration should maybe be based off of distance not time? https://github.com/usdot-fhwa-stol/carma-platform/issues/1107
412 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"), "isexpired:" << isexpired);
413 // TODO: temporary disabling expiration check
414 return false;
415 }
416
417 std::shared_ptr<carma_planning_msgs::srv::PlanTrajectory::Request>
419 const carma_planning_msgs::msg::TrajectoryPlan& latest_trajectory_plan,
420 const carma_planning_msgs::msg::ManeuverPlan& locked_maneuver_plan,
421 const uint16_t& current_maneuver_index) const
422 {
423 auto plan_req = std::make_shared<carma_planning_msgs::srv::PlanTrajectory::Request>();
424 plan_req->maneuver_plan = locked_maneuver_plan;
425
426 // set current vehicle state if we have NOT planned any previous trajectories
427 if(latest_trajectory_plan.trajectory_points.empty())
428 {
429 plan_req->header.stamp = latest_pose_.header.stamp;
430 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"), "latest_pose_.header.stamp: " << std::to_string(rclcpp::Time(latest_pose_.header.stamp).seconds()));
431 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"), "plan_req->header.stamp: " << std::to_string(rclcpp::Time(plan_req->header.stamp).seconds()));
432
433 plan_req->vehicle_state.longitudinal_vel = latest_twist_.twist.linear.x;
434 plan_req->vehicle_state.x_pos_global = latest_pose_.pose.position.x;
435 plan_req->vehicle_state.y_pos_global = latest_pose_.pose.position.y;
436 double roll, pitch, yaw;
437 carma_wm::geometry::rpyFromQuaternion(latest_pose_.pose.orientation, roll, pitch, yaw);
438 plan_req->vehicle_state.orientation = yaw;
439 plan_req->maneuver_index_to_plan = current_maneuver_index;
440 }
441 // set vehicle state based on last two planned trajectory points
442 else
443 {
444 carma_planning_msgs::msg::TrajectoryPlanPoint last_point = latest_trajectory_plan.trajectory_points.back();
445 carma_planning_msgs::msg::TrajectoryPlanPoint second_last_point = *(latest_trajectory_plan.trajectory_points.rbegin() + 1);
446 plan_req->vehicle_state.x_pos_global = last_point.x;
447 plan_req->vehicle_state.y_pos_global = last_point.y;
448 auto distance_diff = std::sqrt(std::pow(last_point.x - second_last_point.x, 2) + std::pow(last_point.y - second_last_point.y, 2));
449 rclcpp::Duration time_diff = rclcpp::Time(last_point.target_time) - rclcpp::Time(second_last_point.target_time);
450 auto time_diff_sec = time_diff.seconds();
451 plan_req->maneuver_index_to_plan = current_maneuver_index;
452 // this assumes the vehicle does not have significant lateral velocity
453 plan_req->header.stamp = latest_trajectory_plan.trajectory_points.back().target_time;
454 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"), "plan_req->header.stamp: " << std::to_string(rclcpp::Time(plan_req->header.stamp).seconds()));
455
456 plan_req->vehicle_state.longitudinal_vel = distance_diff / time_diff_sec;
457 // TODO develop way to set yaw value for future points
458 }
459 return plan_req;
460 }
461
462 bool PlanDelegator::isTrajectoryLongEnough(const carma_planning_msgs::msg::TrajectoryPlan& plan) const noexcept
463 {
464 rclcpp::Duration time_diff = rclcpp::Time(plan.trajectory_points.back().target_time) - rclcpp::Time(plan.trajectory_points.front().target_time);
465 return time_diff.seconds() >= config_.max_trajectory_duration;
466 }
467
468 void PlanDelegator::updateManeuverParameters(carma_planning_msgs::msg::Maneuver& maneuver)
469 {
470 if (!wm_->getMap())
471 {
472 RCLCPP_ERROR_STREAM(rclcpp::get_logger("plan_delegator"), "Map is not set yet");
473 return;
474 }
475
476 // Update maneuver starting and ending downtrack distances
477 double original_start_dist = GET_MANEUVER_PROPERTY(maneuver, start_dist);
478 double original_end_dist = GET_MANEUVER_PROPERTY(maneuver, end_dist);
479 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"),"Changing maneuver distances for planner: " << GET_MANEUVER_PROPERTY(maneuver, parameters.planning_tactical_plugin));
480 double adjusted_start_dist = original_start_dist - length_to_front_bumper_;
481 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"),"original_start_dist:" << original_start_dist);
482 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"),"adjusted_start_dist:" << adjusted_start_dist);
483 double adjusted_end_dist = original_end_dist - length_to_front_bumper_;
484 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"),"original_end_dist:" << original_end_dist);
485 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"),"adjusted_end_dist:" << adjusted_end_dist);
486 SET_MANEUVER_PROPERTY(maneuver, start_dist, adjusted_start_dist);
487 SET_MANEUVER_PROPERTY(maneuver, end_dist, adjusted_end_dist);
488
489 // Shift maneuver starting and ending lanelets
490 // NOTE: Assumes that maneuver start and end downtrack distances have not been shifted by more than one lanelet
491 if(maneuver.type == carma_planning_msgs::msg::Maneuver::LANE_FOLLOWING && !maneuver.lane_following_maneuver.lane_ids.empty()){
492 // (1) Add new beginning lanelet to maneuver if necessary and (2) remove ending lanelet from maneuver if necessary
493
494 // Obtain the original starting lanelet from the maneuver
495 lanelet::Id original_starting_lanelet_id = std::stoi(maneuver.lane_following_maneuver.lane_ids.front());
496 lanelet::ConstLanelet original_starting_lanelet = wm_->getMap()->laneletLayer.get(original_starting_lanelet_id);
497
498 // Get the downtrack of the start of the original starting lanelet
499 lanelet::BasicPoint2d original_starting_lanelet_centerline_start_point = lanelet::utils::to2D(original_starting_lanelet.centerline()).front();
500 double original_starting_lanelet_centerline_start_point_dt = wm_->routeTrackPos(original_starting_lanelet_centerline_start_point).downtrack;
501
502 if(adjusted_start_dist < original_starting_lanelet_centerline_start_point_dt){
503
504 auto previous_lanelets = wm_->getMapRoutingGraph()->previous(original_starting_lanelet, false);
505
506 if(!previous_lanelets.empty()){
507
508 auto llt_on_route_optional = wm_->getFirstLaneletOnShortestPath(previous_lanelets);
509
510 lanelet::ConstLanelet previous_lanelet_to_add;
511
512 if (llt_on_route_optional){
513 previous_lanelet_to_add = llt_on_route_optional.value();
514 }
515 else{
516 RCLCPP_WARN_STREAM(rclcpp::get_logger("plan_delegator"), "When adjusting maneuver for lane follow, no previous lanelet found on the shortest path for lanelet "
517 << original_starting_lanelet.id() << ". Picking arbitrary lanelet: " << previous_lanelets[0].id() << ", instead");
518 previous_lanelet_to_add = previous_lanelets[0];
519 }
520
521 // lane_ids array is ordered by increasing downtrack, so this new starting lanelet is inserted at the front
522 maneuver.lane_following_maneuver.lane_ids.insert(maneuver.lane_following_maneuver.lane_ids.begin(), std::to_string(previous_lanelet_to_add.id()));
523
524 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"), "Inserted lanelet " << std::to_string(previous_lanelet_to_add.id()) << " to beginning of maneuver.");
525 }
526 else{
527 RCLCPP_WARN_STREAM(rclcpp::get_logger("plan_delegator"), "No previous lanelet was found for lanelet " << original_starting_lanelet.id());
528 }
529 }
530
531 // Obtain the maneuver ending lanelet
532 lanelet::Id original_ending_lanelet_id = std::stoi(maneuver.lane_following_maneuver.lane_ids.back());
533 lanelet::ConstLanelet original_ending_lanelet = wm_->getMap()->laneletLayer.get(original_ending_lanelet_id);
534
535 // Get the downtrack of the start of the maneuver ending lanelet
536 lanelet::BasicPoint2d original_ending_lanelet_centerline_start_point = lanelet::utils::to2D(original_ending_lanelet.centerline()).front();
537 double original_ending_lanelet_centerline_start_point_dt = wm_->routeTrackPos(original_ending_lanelet_centerline_start_point).downtrack;
538
539 if(adjusted_end_dist < original_ending_lanelet_centerline_start_point_dt){
540 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"),"Original ending lanelet " << original_ending_lanelet.id() << " removed from lane_ids since the updated maneuver no longer crosses it");
541
542 // lane_ids array is ordered by increasing downtrack, so the last element in the array corresponds to the original ending lanelet
543 maneuver.lane_following_maneuver.lane_ids.pop_back();
544 }
545 }
546 else if (maneuver.type != carma_planning_msgs::msg::Maneuver::LANE_FOLLOWING){
547 // (1) Update starting maneuver lanelet if necessary and (2) Update ending maneuver lanelet if necessary
548
549 // Obtain the original starting lanelet from the maneuver
550 lanelet::Id original_starting_lanelet_id = std::stoi(getManeuverStartingLaneletId(maneuver));
551 lanelet::ConstLanelet original_starting_lanelet = wm_->getMap()->laneletLayer.get(original_starting_lanelet_id);
552
553 // Get the downtrack of the start of the lanelet
554 lanelet::BasicPoint2d original_starting_lanelet_centerline_start_point = lanelet::utils::to2D(original_starting_lanelet.centerline()).front();
555 double original_starting_lanelet_centerline_start_point_dt = wm_->routeTrackPos(original_starting_lanelet_centerline_start_point).downtrack;
556
557 if(adjusted_start_dist < original_starting_lanelet_centerline_start_point_dt){
558 auto previous_lanelets = wm_->getMapRoutingGraph()->previous(original_starting_lanelet, false);
559 if(!previous_lanelets.empty()){
560 auto llt_on_route_optional = wm_->getFirstLaneletOnShortestPath(previous_lanelets);
561 lanelet::ConstLanelet previous_lanelet_to_add;
562
563 if (llt_on_route_optional){
564 previous_lanelet_to_add = llt_on_route_optional.value();
565 }
566 else{
567 RCLCPP_WARN_STREAM(rclcpp::get_logger("plan_delegator"), "When adjusting non-lane follow maneuver, no previous lanelet found on the shortest path for lanelet "
568 << original_starting_lanelet.id() << ". Picking arbitrary lanelet: " << previous_lanelets[0].id() << ", instead");
569 previous_lanelet_to_add = previous_lanelets[0];
570 }
571 setManeuverStartingLaneletId(maneuver, previous_lanelet_to_add.id());
572 }
573 else{
574 RCLCPP_WARN_STREAM(rclcpp::get_logger("plan_delegator"), "No previous lanelet was found for lanelet " << original_starting_lanelet.id());
575 }
576 }
577
578 // Obtain the original ending lanelet from the maneuver
579 lanelet::Id original_ending_lanelet_id = std::stoi(getManeuverEndingLaneletId(maneuver));
580 lanelet::ConstLanelet original_ending_lanelet = wm_->getMap()->laneletLayer.get(original_ending_lanelet_id);
581
582 // Get the downtrack of the start of the ending lanelet
583 lanelet::BasicPoint2d original_ending_lanelet_centerline_start_point = lanelet::utils::to2D(original_ending_lanelet.centerline()).front();
584 double original_ending_lanelet_centerline_start_point_dt = wm_->routeTrackPos(original_ending_lanelet_centerline_start_point).downtrack;
585
586 if(adjusted_end_dist < original_ending_lanelet_centerline_start_point_dt){
587 auto previous_lanelets = wm_->getMapRoutingGraph()->previous(original_ending_lanelet, false);
588
589 if(!previous_lanelets.empty()){
590 setManeuverEndingLaneletId(maneuver, previous_lanelets[0].id());
591 }
592 else{
593 RCLCPP_WARN_STREAM(rclcpp::get_logger("plan_delegator"), "No previous lanelet was found for lanelet " << original_starting_lanelet.id());
594 }
595 }
596 }
597 }
598
599 carma_planning_msgs::msg::TrajectoryPlan PlanDelegator::planTrajectory()
600 {
601 carma_planning_msgs::msg::TrajectoryPlan latest_trajectory_plan;
602 bool full_plan_generation_failed = false;
604 {
605 RCLCPP_INFO_STREAM(rclcpp::get_logger("plan_delegator"),"Guidance is not engaged. Plan delegator will not plan trajectory.");
606 return latest_trajectory_plan;
607 }
608 // latest_maneuver_plan may get updated, so local copy to avoid race condition
609 auto locked_maneuver_plan = latest_maneuver_plan_;
610
611 // Flag for the first received trajectory plan service response
612 bool first_trajectory_plan = true;
613
614 // Track the index of the starting maneuver in the maneuver plan that this trajectory plan service request is for
615 uint16_t current_maneuver_index = 0;
616
617 // Loop through maneuver list to make service call to applicable Tactical Plugin
618 while(current_maneuver_index < locked_maneuver_plan.maneuvers.size())
619 {
620 auto& maneuver = locked_maneuver_plan.maneuvers[current_maneuver_index];
621
622 // ignore expired maneuvers
623 if(isManeuverExpired(maneuver, get_clock()->now()))
624 {
625 RCLCPP_INFO_STREAM(rclcpp::get_logger("plan_delegator"),"Dropping expired maneuver: " << GET_MANEUVER_PROPERTY(maneuver, parameters.maneuver_id));
626 // Update the maneuver plan index for the next loop
627 ++current_maneuver_index;
628 continue;
629 }
630 lanelet::BasicPoint2d current_loc(latest_pose_.pose.position.x, latest_pose_.pose.position.y);
631 double current_downtrack = wm_->routeTrackPos(current_loc).downtrack;
632 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"),"current_downtrack" << current_downtrack);
633 double maneuver_end_dist = GET_MANEUVER_PROPERTY(maneuver, end_dist);
634 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"),"maneuver_end_dist" << maneuver_end_dist);
635
636 // ignore maneuver that is passed.
637 if (current_downtrack > maneuver_end_dist)
638 {
639 RCLCPP_INFO_STREAM(rclcpp::get_logger("plan_delegator"),"Dropping passed maneuver: " << GET_MANEUVER_PROPERTY(maneuver, parameters.maneuver_id));
640 // Update the maneuver plan index for the next loop
641 ++current_maneuver_index;
642 continue;
643 }
644
645 // get corresponding ros service client for plan trajectory
646 auto maneuver_planner = GET_MANEUVER_PROPERTY(maneuver, parameters.planning_tactical_plugin);
647
648 auto client = getPlannerClientByName(maneuver_planner);
649
650 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"),"Current planner: " << maneuver_planner);
651
652 // compose service request
653 auto plan_req = composePlanTrajectoryRequest(
654 latest_trajectory_plan, locked_maneuver_plan, current_maneuver_index);
655
656 auto future_response = client->async_send_request(plan_req);
657
658 auto future_status = future_response.wait_for(std::chrono::milliseconds(config_.tactical_plugin_service_call_timeout));
659
660 if (future_status != std::future_status::ready)
661 {
662 RCLCPP_WARN_STREAM(rclcpp::get_logger("plan_delegator"),"Unsuccessful service call to trajectory planner:" << maneuver_planner << " for plan ID " << std::string(locked_maneuver_plan.maneuver_plan_id));
663 // if one service call fails, it should end plan immediately because it is there is no point to generate plan with empty space
664 full_plan_generation_failed = true;
665 break;
666 }
667
668 // If successful service request
669 auto plan_response = future_response.get();
670 // validate trajectory before add to the plan
671 if(!isTrajectoryValid(plan_response->trajectory_plan))
672 {
673 RCLCPP_WARN_STREAM(rclcpp::get_logger("plan_delegator"),
674 "Found invalid trajectory with less than 2 trajectory "
675 << "points for maneuver_plan_id: "
676 << std::string(locked_maneuver_plan.maneuver_plan_id));
677 full_plan_generation_failed = true;
678 break;
679 }
680 //Remove duplicate point from start of trajectory
681 if(latest_trajectory_plan.trajectory_points.size() != 0 &&
682 latest_trajectory_plan.trajectory_points.back().target_time == plan_response->trajectory_plan.trajectory_points.front().target_time)
683 {
684 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"),"Removing duplicate point for planner: " << maneuver_planner);
685 plan_response->trajectory_plan.trajectory_points.erase(plan_response->trajectory_plan.trajectory_points.begin());
686 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"),"plan_response->trajectory_plan size: " << plan_response->trajectory_plan.trajectory_points.size());
687 }
688 latest_trajectory_plan.trajectory_points.insert(latest_trajectory_plan.trajectory_points.end(),
689 plan_response->trajectory_plan.trajectory_points.begin(),
690 plan_response->trajectory_plan.trajectory_points.end());
691 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"),"new latest_trajectory_plan size: " << latest_trajectory_plan.trajectory_points.size());
692
693 // Assign the trajectory plan's initial longitudinal velocity based on the first tactical plugin's response
694 if(first_trajectory_plan == true)
695 {
696 latest_trajectory_plan.initial_longitudinal_velocity = plan_response->trajectory_plan.initial_longitudinal_velocity;
697 first_trajectory_plan = false;
698 }
699
700 if(isTrajectoryLongEnough(latest_trajectory_plan))
701 {
702 RCLCPP_INFO_STREAM(rclcpp::get_logger("plan_delegator"),"Plan Trajectory completed for " << std::string(locked_maneuver_plan.maneuver_plan_id));
703 break;
704 }
705
706 // Update the maneuver plan index based on the last maneuver index converted to a trajectory
707 // This is required since inlanecruising_plugin can plan a trajectory over contiguous LANE_FOLLOWING maneuvers
708 if(plan_response->related_maneuvers.size() > 0)
709 {
710 current_maneuver_index = plan_response->related_maneuvers.back() + 1;
711 }
712 }
713
714 if (full_plan_generation_failed)
715 {
716 RCLCPP_WARN_STREAM(rclcpp::get_logger("plan_delegator"),
717 "Plan_delegator's current run wasn't fully able to generate trajectory!");
718
719 carma_planning_msgs::msg::TrajectoryPlan empty_plan;
720 return empty_plan;
721 }
722
723 return latest_trajectory_plan;
724 }
725
727 {
728 // Guidance not engaged or haven't received a maneuver plan yet
730 {
731 return;
732 }
733 carma_planning_msgs::msg::TrajectoryPlan trajectory_plan = planTrajectory();
734
735 // Check if planned trajectory is valid before send out
736 if(isTrajectoryValid(trajectory_plan))
737 {
738 trajectory_plan.header.stamp = get_clock()->now();
739 last_successful_traj_ = trajectory_plan;
740 traj_pub_->publish(trajectory_plan);
742 }
743 else
744 {
746 RCLCPP_WARN_STREAM(rclcpp::get_logger("plan_delegator"),
747 "Guidance is engaged, but new planned trajectory has less than 2 points. " <<
748 "It will not be published! Consecutive failure count: "
750
751 // Case where traj generation fails after a successful one
752 if (last_successful_traj_.has_value()
755 {
756 RCLCPP_WARN_STREAM(rclcpp::get_logger("plan_delegator"),
757 "Instead, last available trajectory is published with outdated timestamp of:"
759 rclcpp::Time(last_successful_traj_.value().header.stamp).seconds()));
760 traj_pub_->publish(last_successful_traj_.value());
761 }
762 // Case where traj generation fails from the beginning.
763 // Attempt replanning for configured number of tries before throwing runtime error.
764 else if (!last_successful_traj_.has_value() &&
766 {
767 RCLCPP_WARN_STREAM(rclcpp::get_logger("plan_delegator"),
768 "Instead, tried publishing last available trajectory, but it's not available!");
769 }
770 else
771 {
772 RCLCPP_ERROR_STREAM(rclcpp::get_logger("plan_delegator"),
773 "No valid trajectory is available to publish! "
774 "Please check the planner plugins and their configurations.");
775 throw std::runtime_error("No valid trajectory is available to publish!");
776 }
777 }
778 }
779
781 {
782 tf2_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf2_buffer_);
783 tf2_buffer_->setUsingDedicatedThread(true);
784 try
785 {
786 geometry_msgs::msg::TransformStamped tf = tf2_buffer_->lookupTransform("base_link", "vehicle_front", rclcpp::Time(0), rclcpp::Duration(20.0, 0)); //save to local copy of transform 20 sec timeout
787 length_to_front_bumper_ = tf.transform.translation.x;
788 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("plan_delegator"),"length_to_front_bumper_: " << length_to_front_bumper_);
789
790 }
791 catch (const tf2::TransformException &ex)
792 {
793 RCLCPP_WARN_STREAM(rclcpp::get_logger("plan_delegator"), ex.what());
794 }
795 }
796
797} // namespace plan_delegator
798
799
800#include "rclcpp_components/register_node_macro.hpp"
801
802// Register the component with class_loader
803RCLCPP_COMPONENTS_REGISTER_NODE(plan_delegator::PlanDelegator)
#define GET_MANEUVER_PROPERTY(mvr, property)
Macro definition to enable easier access to fields shared across the maneuver types.
WorldModelConstPtr getWorldModel()
Returns a pointer to an intialized world model instance.
Definition: WMListener.cpp:184
void onTrajPlanTick()
Callback function for triggering trajectory planning.
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::GuidanceState > guidance_state_sub_
carma_planning_msgs::msg::TrajectoryPlan planTrajectory()
Plan trajectory based on latest maneuver plan via ROS service call to plugins.
LaneChangeInformation getLaneChangeInformation(const carma_planning_msgs::msg::Maneuver &lane_change_maneuver)
Function for generating a LaneChangeInformation object from a provided lane change maneuver.
carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > getPlannerClientByName(const std::string &planner_name)
Get PlanTrajectory service client by plugin name and create new PlanTrajectory service client if spec...
void poseCallback(geometry_msgs::msg::PoseStamped::UniquePtr pose_msg)
Callback function for vehicle pose subscriber. Updates latest_pose_ and makes calls to publishUpcomin...
carma_wm::WorldModelConstPtr wm_
carma_ros2_utils::SubPtr< geometry_msgs::msg::TwistStamped > twist_sub_
std::shared_ptr< carma_planning_msgs::srv::PlanTrajectory::Request > composePlanTrajectoryRequest(const carma_planning_msgs::msg::TrajectoryPlan &latest_trajectory_plan, const carma_planning_msgs::msg::ManeuverPlan &locked_maneuver_plan, const uint16_t &current_maneuver_index) const
Generate new PlanTrajecory service request based on current planning progress.
carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &)
boost::optional< LaneChangeInformation > upcoming_lane_change_information_
carma_ros2_utils::PubPtr< carma_planning_msgs::msg::UpcomingLaneChangeStatus > upcoming_lane_change_status_pub_
carma_planning_msgs::msg::UpcomingLaneChangeStatus upcoming_lane_change_status_
bool isTrajectoryValid(const carma_planning_msgs::msg::TrajectoryPlan &trajectory_plan) const noexcept
Example if a trajectory plan contains at least two trajectory points.
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &)
bool isManeuverExpired(const carma_planning_msgs::msg::Maneuver &maneuver, rclcpp::Time current_time) const
Example if a maneuver end time has passed current system time.
void guidanceStateCallback(carma_planning_msgs::msg::GuidanceState::UniquePtr plan)
Callback function of guidance state subscriber.
void updateManeuverParameters(carma_planning_msgs::msg::Maneuver &maneuver)
Update the starting downtrack, ending downtrack, and maneuver-specific Lanelet ID parameters associat...
rclcpp::TimerBase::SharedPtr traj_timer_
std::shared_ptr< tf2_ros::TransformListener > tf2_listener_
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::ManeuverPlan > plan_sub_
bool isTrajectoryLongEnough(const carma_planning_msgs::msg::TrajectoryPlan &plan) const noexcept
Example if a trajectory plan is longer than configured time thresheld.
carma_planning_msgs::msg::ManeuverPlan latest_maneuver_plan_
carma_ros2_utils::PubPtr< carma_planning_msgs::msg::TrajectoryPlan > traj_pub_
carma_ros2_utils::PubPtr< autoware_msgs::msg::LampCmd > turn_signal_command_pub_
boost::optional< LaneChangeInformation > current_lane_change_information_
std::unordered_map< std::string, carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > > trajectory_planners_
bool isManeuverPlanValid(const carma_planning_msgs::msg::ManeuverPlan &maneuver_plan) const noexcept
Example if a maneuver plan contains at least one maneuver.
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseStamped > pose_sub_
geometry_msgs::msg::TwistStamped latest_twist_
std::optional< carma_planning_msgs::msg::TrajectoryPlan > last_successful_traj_
rclcpp::CallbackGroup::SharedPtr timer_callback_group_
void lookupFrontBumperTransform()
Lookup transfrom from front bumper to base link.
geometry_msgs::msg::PoseStamped latest_pose_
PlanDelegator(const rclcpp::NodeOptions &)
PlanDelegator constructor.
void maneuverPlanCallback(carma_planning_msgs::msg::ManeuverPlan::UniquePtr plan)
Callback function of maneuver plan subscriber.
std::shared_ptr< tf2_ros::Buffer > tf2_buffer_
autoware_msgs::msg::LampCmd latest_turn_signal_command_
void publishTurnSignalCommand(const boost::optional< LaneChangeInformation > &current_lane_change_information, const carma_planning_msgs::msg::UpcomingLaneChangeStatus &upcoming_lane_change_status)
Function for processing an optional LaneChangeInformation object pertaining to the currently-occurrin...
void publishUpcomingLaneChangeStatus(const boost::optional< LaneChangeInformation > &upcoming_lane_change_information)
Function for processing an optional LaneChangeInformation object pertaining to an upcoming lane chang...
auto to_string(const UtmZone &zone) -> std::string
Definition: utm_zone.cpp:21
void rpyFromQuaternion(const tf2::Quaternion &q, double &roll, double &pitch, double &yaw)
Extract extrinsic roll-pitch-yaw from quaternion.
Definition: Geometry.cpp:52
std::string getManeuverEndingLaneletId(carma_planning_msgs::msg::Maneuver mvr)
Anonymous function to get the ending lanelet id for all maneuver types except lane following....
void setManeuverEndingLaneletId(carma_planning_msgs::msg::Maneuver &mvr, lanelet::Id end_id)
Anonymous function to set the ending_lane_id for all maneuver types except lane following....
std::string getManeuverStartingLaneletId(carma_planning_msgs::msg::Maneuver mvr)
Anonymous function to get the starting lanelet id for all maneuver types except lane following....
void setManeuverStartingLaneletId(carma_planning_msgs::msg::Maneuver &mvr, lanelet::Id start_id)
Anonymous function to set the starting_lane_id for all maneuver types except lane following....
#define SET_MANEUVER_PROPERTY(mvr, property, value)
std::string planning_topic_suffix
std::string planning_topic_prefix
double duration_to_signal_before_lane_change
Convenience struct for storing information regarding a lane change maneuver.