23    namespace std_ph = std::placeholders;
 
   33            RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"plan_delegator"),
"Updating maneuver starting_lane_id to " << start_id);
 
   36                case carma_planning_msgs::msg::Maneuver::LANE_CHANGE:
 
   37                    mvr.lane_change_maneuver.starting_lane_id = 
std::to_string(start_id);
 
   39                case carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_STRAIGHT:
 
   40                    mvr.intersection_transit_straight_maneuver.starting_lane_id = 
std::to_string(start_id);
 
   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);
 
   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);
 
   48                case carma_planning_msgs::msg::Maneuver::STOP_AND_WAIT:
 
   49                    mvr.stop_and_wait_maneuver.starting_lane_id = 
std::to_string(start_id);
 
   52                    throw std::invalid_argument(
"Maneuver type does not have starting and ending lane ids");
 
   62            RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"plan_delegator"),
"Updating maneuver ending_lane_id to " << end_id);
 
   65                case carma_planning_msgs::msg::Maneuver::LANE_CHANGE:
 
   68                case carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_STRAIGHT:
 
   69                    mvr.intersection_transit_straight_maneuver.ending_lane_id = 
std::to_string(end_id);
 
   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);
 
   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);
 
   77                case carma_planning_msgs::msg::Maneuver::STOP_AND_WAIT:
 
   78                    mvr.stop_and_wait_maneuver.ending_lane_id = 
std::to_string(end_id);
 
   81                    throw std::invalid_argument(
"Maneuver type does not have starting and ending lane ids");
 
   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;
 
  103                    throw std::invalid_argument(
"Maneuver type does not have starting and ending lane ids");
 
  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;
 
  125                    throw std::invalid_argument(
"Maneuver type does not have starting and ending lane ids");
 
  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())
 
  163        RCLCPP_INFO_STREAM(rclcpp::get_logger(
"plan_delegator"),
"Done loading parameters: " << 
config_);
 
  166        traj_pub_ = create_publisher<carma_planning_msgs::msg::TrajectoryPlan>(
"plan_trajectory", 5);
 
  172        twist_sub_ = create_subscription<geometry_msgs::msg::TwistStamped>(
"current_velocity", 5,
 
  173            [
this](geometry_msgs::msg::TwistStamped::UniquePtr twist) {this->
latest_twist_ = *twist;});
 
  179        return CallbackReturn::SUCCESS;
 
  188         return CallbackReturn::SUCCESS;
 
  198        RCLCPP_INFO_STREAM(rclcpp::get_logger(
"plan_delegator"),
"Received request to delegate plan ID " << std::string(plan->maneuver_plan_id));
 
  200        auto copy_plan = *plan;
 
  205            RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"plan_delegator"),
"Received plan with " << 
latest_maneuver_plan_.maneuvers.size() << 
" maneuvers");
 
  213            RCLCPP_WARN_STREAM(rclcpp::get_logger(
"plan_delegator"),
"Received empty plan, no maneuvers found in plan ID " << std::string(plan->maneuver_plan_id));
 
  220            double current_downtrack = 
wm_->routeTrackPos(current_loc).downtrack;
 
  225                if(maneuver.type == carma_planning_msgs::msg::Maneuver::LANE_CHANGE){
 
  226                    if(current_downtrack >= maneuver.lane_change_maneuver.start_dist){
 
  261        lane_change_information.
starting_downtrack = lane_change_maneuver.lane_change_maneuver.start_dist;
 
  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));
 
  268        bool shared_boundary_found = 
false;
 
  270        lanelet::ConstLanelet current_lanelet = starting_lanelet;
 
  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){
 
  276            if(current_lanelet.leftBound() == ending_lanelet.rightBound()){
 
  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()));
 
  280                shared_boundary_found = 
true;
 
  282            else if(current_lanelet.rightBound() == ending_lanelet.leftBound()){
 
  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()));
 
  286                shared_boundary_found = 
true;
 
  290                if(
wm_->getMapRoutingGraph()->following(current_lanelet, 
false).empty())
 
  295                    throw(std::invalid_argument(
"No following lanelets from current lanelet reachable without a lane change, incorrectly chosen end lanelet"));
 
  298                current_lanelet = 
wm_->getMapRoutingGraph()->following(current_lanelet, 
false).front();
 
  299                if(current_lanelet.id() == starting_lanelet.id()){
 
  301                    throw(std::invalid_argument(
"No lane change in path"));
 
  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()));
 
  307        return lane_change_information;
 
  312        carma_planning_msgs::msg::UpcomingLaneChangeStatus upcoming_lane_change_status;
 
  315        if(upcoming_lane_change_information){
 
  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);
 
  322            if(upcoming_lane_change_information.get().is_right_lane_change){
 
  323                upcoming_lane_change_status.lane_change = carma_planning_msgs::msg::UpcomingLaneChangeStatus::RIGHT;
 
  326                upcoming_lane_change_status.lane_change = carma_planning_msgs::msg::UpcomingLaneChangeStatus::LEFT;
 
  330            upcoming_lane_change_status.lane_change = carma_planning_msgs::msg::UpcomingLaneChangeStatus::NONE;
 
  340    void PlanDelegator::publishTurnSignalCommand(
const boost::optional<LaneChangeInformation>& current_lane_change_information, 
const carma_planning_msgs::msg::UpcomingLaneChangeStatus& upcoming_lane_change_status)
 
  344        autoware_msgs::msg::LampCmd turn_signal_command;
 
  347        if(current_lane_change_information){
 
  349            if(current_lane_change_information.get().is_right_lane_change){
 
  350                turn_signal_command.r = 1;
 
  353                turn_signal_command.l = 1;
 
  357        else if(upcoming_lane_change_status.lane_change != carma_planning_msgs::msg::UpcomingLaneChangeStatus::NONE){
 
  360                if(upcoming_lane_change_status.lane_change == carma_planning_msgs::msg::UpcomingLaneChangeStatus::RIGHT){
 
  361                    turn_signal_command.r = 1;
 
  364                    turn_signal_command.l = 1;
 
  380        if(planner_name.size() == 0)
 
  382            throw std::invalid_argument(
"Invalid trajectory planner name because it has zero length!");
 
  386            RCLCPP_INFO_STREAM(rclcpp::get_logger(
"plan_delegator"),
"Discovered new trajectory planner: " << planner_name);
 
  397        return !maneuver_plan.maneuvers.empty();
 
  403        return !(trajectory_plan.trajectory_points.size() < 2);
 
  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; 
 
  412        RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"plan_delegator"), 
"isexpired:" << isexpired);
 
  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 
  423        auto plan_req = std::make_shared<carma_planning_msgs::srv::PlanTrajectory::Request>();
 
  424        plan_req->maneuver_plan = locked_maneuver_plan;
 
  427        if(latest_trajectory_plan.trajectory_points.empty())
 
  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()));
 
  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;
 
  438            plan_req->vehicle_state.orientation = yaw;
 
  439            plan_req->maneuver_index_to_plan = current_maneuver_index;
 
  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;
 
  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()));
 
  456            plan_req->vehicle_state.longitudinal_vel = distance_diff / time_diff_sec;
 
  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;
 
  472            RCLCPP_ERROR_STREAM(rclcpp::get_logger(
"plan_delegator"), 
"Map is not set yet");
 
  479        RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"plan_delegator"),
"Changing maneuver distances for planner: " << 
GET_MANEUVER_PROPERTY(maneuver, parameters.planning_tactical_plugin));
 
  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);
 
  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);
 
  491        if(maneuver.type == carma_planning_msgs::msg::Maneuver::LANE_FOLLOWING && !maneuver.lane_following_maneuver.lane_ids.empty()){
 
  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);
 
  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;
 
  502            if(adjusted_start_dist < original_starting_lanelet_centerline_start_point_dt){
 
  504                auto previous_lanelets = 
wm_->getMapRoutingGraph()->previous(original_starting_lanelet, 
false);
 
  506                if(!previous_lanelets.empty()){
 
  508                    auto llt_on_route_optional = 
wm_->getFirstLaneletOnShortestPath(previous_lanelets);
 
  510                    lanelet::ConstLanelet previous_lanelet_to_add;
 
  512                    if (llt_on_route_optional){
 
  513                        previous_lanelet_to_add = llt_on_route_optional.value();
 
  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];
 
  522                    maneuver.lane_following_maneuver.lane_ids.insert(maneuver.lane_following_maneuver.lane_ids.begin(), 
std::to_string(previous_lanelet_to_add.id()));
 
  524                    RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"plan_delegator"), 
"Inserted lanelet " << 
std::to_string(previous_lanelet_to_add.id()) << 
" to beginning of maneuver.");
 
  527                    RCLCPP_WARN_STREAM(rclcpp::get_logger(
"plan_delegator"), 
"No previous lanelet was found for lanelet " << original_starting_lanelet.id());
 
  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);
 
  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;
 
  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");
 
  543                maneuver.lane_following_maneuver.lane_ids.pop_back();
 
  546        else if (maneuver.type != carma_planning_msgs::msg::Maneuver::LANE_FOLLOWING){
 
  551            lanelet::ConstLanelet original_starting_lanelet = 
wm_->getMap()->laneletLayer.get(original_starting_lanelet_id);
 
  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;
 
  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;
 
  563                    if (llt_on_route_optional){
 
  564                        previous_lanelet_to_add = llt_on_route_optional.value();
 
  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];
 
  574                    RCLCPP_WARN_STREAM(rclcpp::get_logger(
"plan_delegator"), 
"No previous lanelet was found for lanelet " << original_starting_lanelet.id());
 
  580            lanelet::ConstLanelet original_ending_lanelet = 
wm_->getMap()->laneletLayer.get(original_ending_lanelet_id);
 
  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;
 
  586            if(adjusted_end_dist < original_ending_lanelet_centerline_start_point_dt){
 
  587                auto previous_lanelets = 
wm_->getMapRoutingGraph()->previous(original_ending_lanelet, 
false);
 
  589                if(!previous_lanelets.empty()){
 
  593                    RCLCPP_WARN_STREAM(rclcpp::get_logger(
"plan_delegator"), 
"No previous lanelet was found for lanelet " << original_starting_lanelet.id());
 
  601        carma_planning_msgs::msg::TrajectoryPlan latest_trajectory_plan;
 
  602        bool full_plan_generation_failed = 
false;
 
  605            RCLCPP_INFO_STREAM(rclcpp::get_logger(
"plan_delegator"),
"Guidance is not engaged. Plan delegator will not plan trajectory.");
 
  606            return latest_trajectory_plan;
 
  612        bool first_trajectory_plan = 
true;
 
  615        uint16_t current_maneuver_index = 0;
 
  618        while(current_maneuver_index < locked_maneuver_plan.maneuvers.size())
 
  620            auto& maneuver = locked_maneuver_plan.maneuvers[current_maneuver_index];
 
  625                RCLCPP_INFO_STREAM(rclcpp::get_logger(
"plan_delegator"),
"Dropping expired maneuver: " << 
GET_MANEUVER_PROPERTY(maneuver, parameters.maneuver_id));
 
  627                ++current_maneuver_index;
 
  631            double current_downtrack = 
wm_->routeTrackPos(current_loc).downtrack;
 
  632            RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"plan_delegator"),
"current_downtrack" << current_downtrack);
 
  634            RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"plan_delegator"),
"maneuver_end_dist" << maneuver_end_dist);
 
  637            if (current_downtrack > maneuver_end_dist)
 
  639                RCLCPP_INFO_STREAM(rclcpp::get_logger(
"plan_delegator"),
"Dropping passed maneuver: " << 
GET_MANEUVER_PROPERTY(maneuver, parameters.maneuver_id));
 
  641                ++current_maneuver_index;
 
  650            RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"plan_delegator"),
"Current planner: " << maneuver_planner);
 
  654                latest_trajectory_plan, locked_maneuver_plan, current_maneuver_index);
 
  656            auto future_response = client->async_send_request(plan_req);
 
  660            if (future_status != std::future_status::ready)
 
  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));
 
  664                full_plan_generation_failed = 
true;
 
  669            auto plan_response = future_response.get();
 
  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;
 
  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)
 
  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());
 
  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());
 
  694            if(first_trajectory_plan == 
true)
 
  696                latest_trajectory_plan.initial_longitudinal_velocity = plan_response->trajectory_plan.initial_longitudinal_velocity;
 
  697                first_trajectory_plan = 
false;
 
  702                RCLCPP_INFO_STREAM(rclcpp::get_logger(
"plan_delegator"),
"Plan Trajectory completed for " << std::string(locked_maneuver_plan.maneuver_plan_id));
 
  708            if(plan_response->related_maneuvers.size() > 0)
 
  710                current_maneuver_index = plan_response->related_maneuvers.back() + 1;
 
  714        if (full_plan_generation_failed)
 
  716            RCLCPP_WARN_STREAM(rclcpp::get_logger(
"plan_delegator"),
 
  717                "Plan_delegator's current run wasn't fully able to generate trajectory!");
 
  719            carma_planning_msgs::msg::TrajectoryPlan empty_plan;
 
  723        return latest_trajectory_plan;
 
  733        carma_planning_msgs::msg::TrajectoryPlan trajectory_plan = 
planTrajectory();
 
  738            trajectory_plan.header.stamp = get_clock()->now();
 
  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: " 
  756                RCLCPP_WARN_STREAM(rclcpp::get_logger(
"plan_delegator"),
 
  757                    "Instead, last available trajectory is published with outdated timestamp of:" 
  767                RCLCPP_WARN_STREAM(rclcpp::get_logger(
"plan_delegator"),
 
  768                    "Instead, tried publishing last available trajectory, but it's not available!");
 
  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!");
 
  786            geometry_msgs::msg::TransformStamped tf = 
tf2_buffer_->lookupTransform(
"base_link", 
"vehicle_front", rclcpp::Time(0), rclcpp::Duration(20.0, 0)); 
 
  788            RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"plan_delegator"),
"length_to_front_bumper_: " << 
length_to_front_bumper_);
 
  791        catch (
const tf2::TransformException &ex)
 
  793            RCLCPP_WARN_STREAM(rclcpp::get_logger(
"plan_delegator"), ex.what());
 
  800#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.
WorldModelConstPtr getWorldModel()
Returns a pointer to an intialized world model instance.
void onTrajPlanTick()
Callback function for triggering trajectory planning.
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::GuidanceState > guidance_state_sub_
bool received_maneuver_plan_
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...
int consecutive_traj_gen_failure_num_
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 ¤t_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_
double length_to_front_bumper_
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 > ¤t_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...
carma_wm::WMListener wml_
auto to_string(const UtmZone &zone) -> std::string
void rpyFromQuaternion(const tf2::Quaternion &q, double &roll, double &pitch, double &yaw)
Extract extrinsic roll-pitch-yaw from quaternion.
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)
double trajectory_planning_rate
std::string planning_topic_suffix
int max_traj_generation_reattempt
std::string planning_topic_prefix
int tactical_plugin_service_call_timeout
double duration_to_signal_before_lane_change
double max_trajectory_duration