Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(lane_departure_checker): check shoulder lane #2614

Merged
merged 1 commit into from
Jan 12, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ struct Input
lanelet::LaneletMapPtr lanelet_map{};
LaneletRoute::ConstSharedPtr route{};
lanelet::ConstLanelets route_lanelets{};
lanelet::ConstLanelets shoulder_lanelets{};
Trajectory::ConstSharedPtr reference_trajectory{};
Trajectory::ConstSharedPtr predicted_trajectory{};
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,7 @@ class LaneDepartureCheckerNode : public rclcpp::Node
geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose_;
nav_msgs::msg::Odometry::ConstSharedPtr current_odom_;
lanelet::LaneletMapPtr lanelet_map_;
lanelet::ConstLanelets shoulder_lanelets_;
lanelet::traffic_rules::TrafficRulesPtr traffic_rules_;
lanelet::routing::RoutingGraphPtr routing_graph_;
LaneletRoute::ConstSharedPtr route_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,15 @@ Output LaneDepartureChecker::update(const Input & input)
output.vehicle_passing_areas = createVehiclePassingAreas(output.vehicle_footprints);
output.processing_time_map["createVehiclePassingAreas"] = stop_watch.toc(true);

output.candidate_lanelets = getCandidateLanelets(input.route_lanelets, output.vehicle_footprints);
const auto candidate_road_lanelets =
getCandidateLanelets(input.route_lanelets, output.vehicle_footprints);
const auto candidate_shoulder_lanelets =
getCandidateLanelets(input.shoulder_lanelets, output.vehicle_footprints);
output.candidate_lanelets = candidate_road_lanelets;
output.candidate_lanelets.insert(
output.candidate_lanelets.end(), candidate_shoulder_lanelets.begin(),
candidate_shoulder_lanelets.end());

output.processing_time_map["getCandidateLanelets"] = stop_watch.toc(true);

output.will_leave_lane = willLeaveLane(output.candidate_lanelets, output.vehicle_footprints);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -197,6 +197,10 @@ void LaneDepartureCheckerNode::onLaneletMapBin(const HADMapBin::ConstSharedPtr m
{
lanelet_map_ = std::make_shared<lanelet::LaneletMap>();
lanelet::utils::conversion::fromBinMsg(*msg, lanelet_map_, &traffic_rules_, &routing_graph_);

// get all shoulder lanes
lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_);
shoulder_lanelets_ = lanelet::utils::query::shoulderLanelets(all_lanelets);
}

void LaneDepartureCheckerNode::onRoute(const LaneletRoute::ConstSharedPtr msg) { route_ = msg; }
Expand Down Expand Up @@ -313,6 +317,7 @@ void LaneDepartureCheckerNode::onTimer()
input_.lanelet_map = lanelet_map_;
input_.route = route_;
input_.route_lanelets = route_lanelets_;
input_.shoulder_lanelets = shoulder_lanelets_;
input_.reference_trajectory = reference_trajectory_;
input_.predicted_trajectory = predicted_trajectory_;
processing_time_map["Node: setInputData"] = stop_watch.toc(true);
Expand Down