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

fix(behavior_velocity_planner): avoid duplicates in intersection module #1483

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 @@ -58,7 +58,7 @@ bool getObjectiveLanelets(
lanelet::LaneletMapConstPtr lanelet_map_ptr, lanelet::routing::RoutingGraphPtr routing_graph_ptr,
const int lane_id, const double detection_area_length, const double right_margin,
const double left_margin, std::vector<lanelet::ConstLanelets> * conflicting_lanelets_result,
std::vector<lanelet::ConstLanelets> * objective_lanelets_result,
lanelet::ConstLanelets * objective_lanelets_result,
std::vector<lanelet::ConstLanelets> * objective_lanelets_with_margin_result,
const rclcpp::Logger logger);

Expand Down Expand Up @@ -118,6 +118,9 @@ bool getStopPoseIndexFromMap(
std::vector<lanelet::CompoundPolygon3d> getPolygon3dFromLaneletsVec(
const std::vector<lanelet::ConstLanelets> & ll_vec, double clip_length);

std::vector<lanelet::CompoundPolygon3d> getPolygon3dFromLanelets(
const lanelet::ConstLanelets & ll_vec, double clip_length);

std::vector<int> getLaneletIdsFromLaneletsVec(const std::vector<lanelet::ConstLanelets> & ll_vec);

double calcArcLengthFromPath(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ bool IntersectionModule::modifyPathVelocity(
const auto routing_graph_ptr = planner_data_->route_handler_->getRoutingGraphPtr();

/* get detection area and conflicting area */
std::vector<lanelet::ConstLanelets> detection_area_lanelets;
lanelet::ConstLanelets detection_area_lanelets;
std::vector<lanelet::ConstLanelets> conflicting_area_lanelets;
std::vector<lanelet::ConstLanelets> detection_area_lanelets_with_margin;

Expand All @@ -102,15 +102,15 @@ bool IntersectionModule::modifyPathVelocity(
logger_);
std::vector<lanelet::CompoundPolygon3d> conflicting_areas = util::getPolygon3dFromLaneletsVec(
conflicting_area_lanelets, planner_param_.detection_area_length);
std::vector<lanelet::CompoundPolygon3d> detection_areas = util::getPolygon3dFromLaneletsVec(
detection_area_lanelets, planner_param_.detection_area_length);
std::vector<lanelet::CompoundPolygon3d> detection_areas =
util::getPolygon3dFromLanelets(detection_area_lanelets, planner_param_.detection_area_length);
std::vector<lanelet::CompoundPolygon3d> detection_areas_with_margin =
util::getPolygon3dFromLaneletsVec(
detection_area_lanelets_with_margin, planner_param_.detection_area_length);
std::vector<int> conflicting_area_lanelet_ids =
util::getLaneletIdsFromLaneletsVec(conflicting_area_lanelets);
std::vector<int> detection_area_lanelet_ids =
util::getLaneletIdsFromLaneletsVec(detection_area_lanelets);
util::getLaneletIdsFromLaneletsVec({detection_area_lanelets});

if (detection_areas.empty()) {
RCLCPP_DEBUG(logger_, "no detection area. skip computation.");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ bool MergeFromPrivateRoadModule::modifyPathVelocity(
const auto routing_graph_ptr = planner_data_->route_handler_->getRoutingGraphPtr();

/* get detection area */
std::vector<lanelet::ConstLanelets> detection_area_lanelets;
lanelet::ConstLanelets detection_area_lanelets;
std::vector<lanelet::ConstLanelets> conflicting_area_lanelets;
std::vector<lanelet::ConstLanelets> detection_area_lanelets_with_margin;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -337,7 +337,7 @@ bool getObjectiveLanelets(
lanelet::LaneletMapConstPtr lanelet_map_ptr, lanelet::routing::RoutingGraphPtr routing_graph_ptr,
const int lane_id, const double detection_area_length, double right_margin, double left_margin,
std::vector<lanelet::ConstLanelets> * conflicting_lanelets_result,
std::vector<lanelet::ConstLanelets> * objective_lanelets_result,
lanelet::ConstLanelets * objective_lanelets_result,
std::vector<lanelet::ConstLanelets> * objective_lanelets_with_margin_result,
const rclcpp::Logger logger)
{
Expand Down Expand Up @@ -399,21 +399,28 @@ bool getObjectiveLanelets(

// get possible lanelet path that reaches conflicting_lane longer than given length
const double length = detection_area_length;
std::vector<lanelet::ConstLanelets> objective_lanelets_sequences;
lanelet::ConstLanelets objective_and_preceding_lanelets;
std::set<lanelet::Id> objective_ids;
for (const auto & ll : objective_lanelets) {
// Preceding lanes does not include objective_lane so add them at the end
objective_lanelets_sequences.push_back(ll);
for (const auto & l : ll) {
const auto & inserted = objective_ids.insert(l.id());
if (inserted.second) objective_and_preceding_lanelets.push_back(l);
}
// get preceding lanelets without ego_lanelets
// to prevent the detection area from including the ego lanes and its' preceding lanes.
const auto lanelet_sequences = lanelet::utils::query::getPrecedingLaneletSequences(
routing_graph_ptr, ll.front(), length, ego_lanelets);
for (auto & l : lanelet_sequences) {
objective_lanelets_sequences.push_back(l);
for (const auto & ls : lanelet_sequences) {
for (const auto & l : ls) {
const auto & inserted = objective_ids.insert(l.id());
if (inserted.second) objective_and_preceding_lanelets.push_back(l);
}
}
}

*conflicting_lanelets_result = conflicting_lanelets_ex_yield_ego;
*objective_lanelets_result = objective_lanelets_sequences;
*objective_lanelets_result = objective_and_preceding_lanelets;
*objective_lanelets_with_margin_result = objective_lanelets_with_margin;

// set this flag true when debugging
Expand All @@ -432,10 +439,8 @@ bool getObjectiveLanelets(
for (const auto & l : objective_lanelets) {
ss_o << l.front().id() << ", ";
}
for (const auto & l : objective_lanelets_sequences) {
for (const auto & ll : l) {
ss_os << ll.id() << ", ";
}
for (const auto & l : objective_and_preceding_lanelets) {
ss_os << l.id() << ", ";
}
RCLCPP_INFO(
logger, "getObjectiveLanelets() conflict = %s yield = %s ego = %s", ss_c.str().c_str(),
Expand All @@ -459,6 +464,19 @@ std::vector<lanelet::CompoundPolygon3d> getPolygon3dFromLaneletsVec(
return p_vec;
}

std::vector<lanelet::CompoundPolygon3d> getPolygon3dFromLanelets(
const lanelet::ConstLanelets & ll_vec, double clip_length)
{
std::vector<lanelet::CompoundPolygon3d> p_vec;
for (const auto & ll : ll_vec) {
const double path_length = lanelet::utils::getLaneletLength3d({ll});
const auto polygon3d =
lanelet::utils::getPolygonFromArcLength({ll}, path_length - clip_length, path_length);
p_vec.push_back(polygon3d);
}
return p_vec;
}

std::vector<int> getLaneletIdsFromLaneletsVec(const std::vector<lanelet::ConstLanelets> & ll_vec)
{
std::vector<int> id_list;
Expand Down