Skip to content

Commit 06eb3d3

Browse files
committed
fix(mission_planner): find the first common interval naively for main/mrm reroute check
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent b86a00d commit 06eb3d3

File tree

2 files changed

+100
-87
lines changed

2 files changed

+100
-87
lines changed

planning/mission_planner/src/mission_planner/mission_planner.cpp

+99-87
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@
2727
#include <lanelet2_core/geometry/LineString.h>
2828

2929
#include <algorithm>
30-
30+
#include <utility>
3131
namespace mission_planner
3232
{
3333

@@ -132,6 +132,8 @@ void MissionPlanner::on_reroute_availability(const RerouteAvailability::ConstSha
132132
void MissionPlanner::on_map(const HADMapBin::ConstSharedPtr msg)
133133
{
134134
map_ptr_ = msg;
135+
lanelet_map_ptr_ = std::make_shared<lanelet::LaneletMap>();
136+
lanelet::utils::conversion::fromBinMsg(*map_ptr_, lanelet_map_ptr_);
135137
}
136138

137139
Pose MissionPlanner::transform_pose(const Pose & pose, const Header & header)
@@ -394,7 +396,9 @@ LaneletRoute MissionPlanner::create_route(
394396
bool MissionPlanner::check_reroute_safety(
395397
const LaneletRoute & original_route, const LaneletRoute & target_route)
396398
{
397-
if (original_route.segments.empty() || target_route.segments.empty() || !map_ptr_ || !odometry_) {
399+
if (
400+
original_route.segments.empty() || target_route.segments.empty() || !map_ptr_ ||
401+
!lanelet_map_ptr_ || !odometry_) {
398402
RCLCPP_ERROR(get_logger(), "Check reroute safety failed. Route, map or odometry is not set.");
399403
return false;
400404
}
@@ -413,112 +417,117 @@ bool MissionPlanner::check_reroute_safety(
413417
return false;
414418
}
415419

416-
bool is_same = false;
417420
for (const auto & primitive : original_primitives) {
418421
const auto has_same = [&](const auto & p) { return p.id == primitive.id; };
419-
is_same = std::find_if(target_primitives.begin(), target_primitives.end(), has_same) !=
420-
target_primitives.end();
421-
}
422-
return is_same;
423-
};
424-
425-
// find idx of original primitives that matches the target primitives
426-
const auto start_idx_opt = std::invoke([&]() -> std::optional<size_t> {
427-
/*
428-
* find the index of the original route that has same idx with the front segment of the new
429-
* route
430-
*
431-
* start_idx
432-
* +-----------+-----------+-----------+-----------+-----------+
433-
* | | | | | |
434-
* +-----------+-----------+-----------+-----------+-----------+
435-
* | | | | | |
436-
* +-----------+-----------+-----------+-----------+-----------+
437-
* original original original original original
438-
* target target target
439-
*/
440-
const auto target_front_primitives = target_route.segments.front().primitives;
441-
for (size_t i = 0; i < original_route.segments.size(); ++i) {
442-
const auto & original_primitives = original_route.segments.at(i).primitives;
443-
if (hasSamePrimitives(original_primitives, target_front_primitives)) {
444-
return i;
422+
const bool is_same =
423+
std::find_if(target_primitives.begin(), target_primitives.end(), has_same) !=
424+
target_primitives.end();
425+
if (!is_same) {
426+
return false;
445427
}
446428
}
429+
return true;
430+
};
447431

448-
/*
449-
* find the target route that has same idx with the front segment of the original route
450-
*
451-
* start_idx
452-
* +-----------+-----------+-----------+-----------+-----------+
453-
* | | | | | |
454-
* +-----------+-----------+-----------+-----------+-----------+
455-
* | | | | | |
456-
* +-----------+-----------+-----------+-----------+-----------+
457-
* original original original
458-
* target target target target target
459-
*/
460-
const auto original_front_primitives = original_route.segments.front().primitives;
461-
for (size_t i = 0; i < target_route.segments.size(); ++i) {
462-
const auto & target_primitives = target_route.segments.at(i).primitives;
463-
if (hasSamePrimitives(target_primitives, original_front_primitives)) {
464-
return 0;
432+
// =============================================================================================
433+
// NOTE: the target route is calculated while ego is driving on the original route, so basically
434+
// the first lane of the target route should be in the orginal route lanelets. So the common
435+
// segment interval matches the beginning of the target route. The exeception is that if ego is
436+
// on an intersection lanelet, getClosestLanelet() may not return the same lanelet which exists
437+
// in the original route. In that case the common segment interval does not match the beginnng of
438+
// the target lanelet
439+
// =============================================================================================
440+
const auto start_idx_opt =
441+
std::invoke([&]() -> std::optional<std::pair<size_t /* original */, size_t /* target */>> {
442+
for (size_t i = 0; i < original_route.segments.size(); ++i) {
443+
const auto & original_segment = original_route.segments.at(i).primitives;
444+
for (size_t j = 0; j < target_route.segments.size(); ++j) {
445+
const auto & target_segment = target_route.segments.at(j).primitives;
446+
if (hasSamePrimitives(original_segment, target_segment)) {
447+
return std::make_pair(i, j);
448+
}
449+
}
465450
}
466-
}
467-
468-
return std::nullopt;
469-
});
451+
return std::nullopt;
452+
});
470453
if (!start_idx_opt.has_value()) {
471454
RCLCPP_ERROR(
472455
get_logger(), "Check reroute safety failed. Cannot find the start index of the route.");
473456
return false;
474457
}
475-
const size_t start_idx = start_idx_opt.value();
458+
const auto [start_idx_original, start_idx_target] = start_idx_opt.value();
476459

477460
// find last idx that matches the target primitives
478-
size_t end_idx = start_idx;
479-
for (size_t i = 1; i < target_route.segments.size(); ++i) {
480-
if (start_idx + i > original_route.segments.size() - 1) {
461+
size_t end_idx_original = start_idx_original;
462+
size_t end_idx_target = start_idx_target;
463+
for (size_t i = 1; i < target_route.segments.size() - start_idx_target; ++i) {
464+
if (start_idx_original + i > original_route.segments.size() - 1) {
481465
break;
482466
}
483467

484-
const auto & original_primitives = original_route.segments.at(start_idx + i).primitives;
485-
const auto & target_primitives = target_route.segments.at(i).primitives;
468+
const auto & original_primitives =
469+
original_route.segments.at(start_idx_original + i).primitives;
470+
const auto & target_primitives = target_route.segments.at(start_idx_target + i).primitives;
486471
if (!hasSamePrimitives(original_primitives, target_primitives)) {
487472
break;
488473
}
489-
end_idx = start_idx + i;
490-
}
491-
492-
// create map
493-
auto lanelet_map_ptr_ = std::make_shared<lanelet::LaneletMap>();
494-
lanelet::utils::conversion::fromBinMsg(*map_ptr_, lanelet_map_ptr_);
474+
end_idx_original = start_idx_original + i;
475+
end_idx_target = start_idx_target + i;
476+
}
477+
478+
// if the front of target route is not the front of common segment, it is expected that the front
479+
// of the target route is conflicting with another lane which is equal to original
480+
// route[start_idx_original-1]
481+
double accumulated_length = 0.0;
482+
483+
if (start_idx_target != 0 && start_idx_original > 1) {
484+
// compute distance from the current pose to the beginning of the common segment
485+
const auto current_pose = target_route.start_pose;
486+
const auto primitives = original_route.segments.at(start_idx_original - 1).primitives;
487+
lanelet::ConstLanelets start_lanelets;
488+
for (const auto & primitive : primitives) {
489+
const auto lanelet = lanelet_map_ptr_->laneletLayer.get(primitive.id);
490+
start_lanelets.push_back(lanelet);
491+
}
492+
// closest lanelet in start lanelets
493+
lanelet::ConstLanelet closest_lanelet;
494+
if (!lanelet::utils::query::getClosestLanelet(start_lanelets, current_pose, &closest_lanelet)) {
495+
return false;
496+
}
495497

496-
// compute distance from the current pose to the end of the current lanelet
497-
const auto current_pose = target_route.start_pose;
498-
const auto primitives = original_route.segments.at(start_idx).primitives;
499-
lanelet::ConstLanelets start_lanelets;
500-
for (const auto & primitive : primitives) {
501-
const auto lanelet = lanelet_map_ptr_->laneletLayer.get(primitive.id);
502-
start_lanelets.push_back(lanelet);
503-
}
498+
const auto & centerline_2d = lanelet::utils::to2D(closest_lanelet.centerline());
499+
const auto lanelet_point = lanelet::utils::conversion::toLaneletPoint(current_pose.position);
500+
const auto arc_coordinates = lanelet::geometry::toArcCoordinates(
501+
centerline_2d, lanelet::utils::to2D(lanelet_point).basicPoint());
502+
const double dist_to_current_pose = arc_coordinates.length;
503+
const double lanelet_length = lanelet::utils::getLaneletLength2d(closest_lanelet);
504+
accumulated_length = lanelet_length - dist_to_current_pose;
505+
} else {
506+
// compute distance from the current pose to the end of the current lanelet
507+
const auto current_pose = target_route.start_pose;
508+
const auto primitives = original_route.segments.at(start_idx_original).primitives;
509+
lanelet::ConstLanelets start_lanelets;
510+
for (const auto & primitive : primitives) {
511+
const auto lanelet = lanelet_map_ptr_->laneletLayer.get(primitive.id);
512+
start_lanelets.push_back(lanelet);
513+
}
514+
// closest lanelet in start lanelets
515+
lanelet::ConstLanelet closest_lanelet;
516+
if (!lanelet::utils::query::getClosestLanelet(start_lanelets, current_pose, &closest_lanelet)) {
517+
return false;
518+
}
504519

505-
// get closest lanelet in start lanelets
506-
lanelet::ConstLanelet closest_lanelet;
507-
if (!lanelet::utils::query::getClosestLanelet(start_lanelets, current_pose, &closest_lanelet)) {
508-
RCLCPP_ERROR(get_logger(), "Check reroute safety failed. Cannot find the closest lanelet.");
509-
return false;
520+
const auto & centerline_2d = lanelet::utils::to2D(closest_lanelet.centerline());
521+
const auto lanelet_point = lanelet::utils::conversion::toLaneletPoint(current_pose.position);
522+
const auto arc_coordinates = lanelet::geometry::toArcCoordinates(
523+
centerline_2d, lanelet::utils::to2D(lanelet_point).basicPoint());
524+
const double dist_to_current_pose = arc_coordinates.length;
525+
const double lanelet_length = lanelet::utils::getLaneletLength2d(closest_lanelet);
526+
accumulated_length = lanelet_length - dist_to_current_pose;
510527
}
511528

512-
const auto & centerline_2d = lanelet::utils::to2D(closest_lanelet.centerline());
513-
const auto lanelet_point = lanelet::utils::conversion::toLaneletPoint(current_pose.position);
514-
const auto arc_coordinates = lanelet::geometry::toArcCoordinates(
515-
centerline_2d, lanelet::utils::to2D(lanelet_point).basicPoint());
516-
const double dist_to_current_pose = arc_coordinates.length;
517-
const double lanelet_length = lanelet::utils::getLaneletLength2d(closest_lanelet);
518-
double accumulated_length = lanelet_length - dist_to_current_pose;
519-
520529
// compute distance from the start_idx+1 to end_idx
521-
for (size_t i = start_idx + 1; i <= end_idx; ++i) {
530+
for (size_t i = start_idx_original + 1; i <= end_idx_original; ++i) {
522531
const auto primitives = original_route.segments.at(i).primitives;
523532
if (primitives.empty()) {
524533
break;
@@ -534,7 +543,7 @@ bool MissionPlanner::check_reroute_safety(
534543
}
535544

536545
// check if the goal is inside of the target terminal lanelet
537-
const auto & target_end_primitives = target_route.segments.at(end_idx - start_idx).primitives;
546+
const auto & target_end_primitives = target_route.segments.at(end_idx_target).primitives;
538547
const auto & target_goal = target_route.goal_pose;
539548
for (const auto & target_end_primitive : target_end_primitives) {
540549
const auto lanelet = lanelet_map_ptr_->laneletLayer.get(target_end_primitive.id);
@@ -546,8 +555,11 @@ bool MissionPlanner::check_reroute_safety(
546555
lanelet::utils::to2D(target_goal_position).basicPoint())
547556
.length;
548557
const double target_lanelet_length = lanelet::utils::getLaneletLength2d(lanelet);
549-
const double dist = target_lanelet_length - dist_to_goal;
550-
accumulated_length = std::max(accumulated_length - dist, 0.0);
558+
// NOTE: `accumulated_length` here contains the length of the entire target_end_primitive, so
559+
// the remaining distance from the goal to the end of the target_end_primitive needs to be
560+
// subtracted.
561+
const double remaining_dist = target_lanelet_length - dist_to_goal;
562+
accumulated_length = std::max(accumulated_length - remaining_dist, 0.0);
551563
break;
552564
}
553565
}

planning/mission_planner/src/mission_planner/mission_planner.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -93,6 +93,7 @@ class MissionPlanner : public rclcpp::Node
9393
RerouteAvailability::ConstSharedPtr reroute_availability_;
9494
RouteState state_;
9595
LaneletRoute::ConstSharedPtr current_route_;
96+
lanelet::LaneletMapPtr lanelet_map_ptr_{nullptr};
9697

9798
void on_odometry(const Odometry::ConstSharedPtr msg);
9899
void on_map(const HADMapBin::ConstSharedPtr msg);

0 commit comments

Comments
 (0)