Skip to content

Commit bee9936

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 bee9936

File tree

2 files changed

+102
-86
lines changed

2 files changed

+102
-86
lines changed

planning/mission_planner/src/mission_planner/mission_planner.cpp

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

2929
#include <algorithm>
30+
#include <utility>
3031

3132
namespace mission_planner
3233
{
@@ -132,6 +133,8 @@ void MissionPlanner::on_reroute_availability(const RerouteAvailability::ConstSha
132133
void MissionPlanner::on_map(const HADMapBin::ConstSharedPtr msg)
133134
{
134135
map_ptr_ = msg;
136+
lanelet_map_ptr_ = std::make_shared<lanelet::LaneletMap>();
137+
lanelet::utils::conversion::fromBinMsg(*map_ptr_, lanelet_map_ptr_);
135138
}
136139

137140
Pose MissionPlanner::transform_pose(const Pose & pose, const Header & header)
@@ -394,7 +397,9 @@ LaneletRoute MissionPlanner::create_route(
394397
bool MissionPlanner::check_reroute_safety(
395398
const LaneletRoute & original_route, const LaneletRoute & target_route)
396399
{
397-
if (original_route.segments.empty() || target_route.segments.empty() || !map_ptr_ || !odometry_) {
400+
if (
401+
original_route.segments.empty() || target_route.segments.empty() || !map_ptr_ ||
402+
!lanelet_map_ptr_ || !odometry_) {
398403
RCLCPP_ERROR(get_logger(), "Check reroute safety failed. Route, map or odometry is not set.");
399404
return false;
400405
}
@@ -413,112 +418,119 @@ bool MissionPlanner::check_reroute_safety(
413418
return false;
414419
}
415420

416-
bool is_same = false;
417421
for (const auto & primitive : original_primitives) {
418422
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;
423+
const bool is_same =
424+
std::find_if(target_primitives.begin(), target_primitives.end(), has_same) !=
425+
target_primitives.end();
426+
if (!is_same) {
427+
return false;
445428
}
446429
}
430+
return true;
431+
};
447432

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;
433+
// =============================================================================================
434+
// NOTE: the target route is calculated while ego is driving on the original route, so basically
435+
// the first lane of the target route should be in the orginal route lanelets. So the common
436+
// segment interval matches the beginning of the target route. The exeception is that if ego is
437+
// on an intersection lanelet, getClosestLanelet() may not return the same lanelet which exists
438+
// in the original route. In that case the common segment interval does not match the beginnng of
439+
// the target lanelet
440+
// =============================================================================================
441+
const auto start_idx_opt =
442+
std::invoke([&]() -> std::optional<std::pair<size_t /* original */, size_t /* target */>> {
443+
for (size_t i = 0; i < original_route.segments.size(); ++i) {
444+
const auto & original_segment = original_route.segments.at(i).primitives;
445+
for (size_t j = 0; j < target_route.segments.size(); ++j) {
446+
const auto & target_segment = target_route.segments.at(j).primitives;
447+
if (hasSamePrimitives(original_segment, target_segment)) {
448+
return std::make_pair(i, j);
449+
}
450+
}
465451
}
466-
}
467-
468-
return std::nullopt;
469-
});
452+
return std::nullopt;
453+
});
470454
if (!start_idx_opt.has_value()) {
471455
RCLCPP_ERROR(
472456
get_logger(), "Check reroute safety failed. Cannot find the start index of the route.");
473457
return false;
474458
}
475-
const size_t start_idx = start_idx_opt.value();
459+
const auto [start_idx_original, start_idx_target] = start_idx_opt.value();
476460

477461
// 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) {
462+
size_t end_idx_original = start_idx_original;
463+
size_t end_idx_target = start_idx_target;
464+
for (size_t i = 1; i < target_route.segments.size() - start_idx_target; ++i) {
465+
if (start_idx_original + i > original_route.segments.size() - 1) {
481466
break;
482467
}
483468

484-
const auto & original_primitives = original_route.segments.at(start_idx + i).primitives;
485-
const auto & target_primitives = target_route.segments.at(i).primitives;
469+
const auto & original_primitives =
470+
original_route.segments.at(start_idx_original + i).primitives;
471+
const auto & target_primitives = target_route.segments.at(start_idx_target + i).primitives;
486472
if (!hasSamePrimitives(original_primitives, target_primitives)) {
487473
break;
488474
}
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_);
475+
end_idx_original = start_idx_original + i;
476+
end_idx_target = start_idx_target + i;
477+
}
478+
479+
// if the front of target route is not the front of common segment, it is expected that the front
480+
// of the target route is conflicting with another lane which is equal to original
481+
// route[start_idx_original-1]
482+
double accumulated_length = 0.0;
483+
484+
if (start_idx_target != 0 && start_idx_original > 1) {
485+
// compute distance from the current pose to the beginning of the common segment
486+
const auto current_pose = target_route.start_pose;
487+
const auto primitives = original_route.segments.at(start_idx_original - 1).primitives;
488+
lanelet::ConstLanelets start_lanelets;
489+
for (const auto & primitive : primitives) {
490+
const auto lanelet = lanelet_map_ptr_->laneletLayer.get(primitive.id);
491+
start_lanelets.push_back(lanelet);
492+
}
493+
// closest lanelet in start lanelets
494+
lanelet::ConstLanelet closest_lanelet;
495+
if (!lanelet::utils::query::getClosestLanelet(start_lanelets, current_pose, &closest_lanelet)) {
496+
RCLCPP_ERROR(get_logger(), "Check reroute safety failed. Cannot find the closest lanelet.");
497+
return false;
498+
}
495499

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-
}
500+
const auto & centerline_2d = lanelet::utils::to2D(closest_lanelet.centerline());
501+
const auto lanelet_point = lanelet::utils::conversion::toLaneletPoint(current_pose.position);
502+
const auto arc_coordinates = lanelet::geometry::toArcCoordinates(
503+
centerline_2d, lanelet::utils::to2D(lanelet_point).basicPoint());
504+
const double dist_to_current_pose = arc_coordinates.length;
505+
const double lanelet_length = lanelet::utils::getLaneletLength2d(closest_lanelet);
506+
accumulated_length = lanelet_length - dist_to_current_pose;
507+
} else {
508+
// compute distance from the current pose to the end of the current lanelet
509+
const auto current_pose = target_route.start_pose;
510+
const auto primitives = original_route.segments.at(start_idx_original).primitives;
511+
lanelet::ConstLanelets start_lanelets;
512+
for (const auto & primitive : primitives) {
513+
const auto lanelet = lanelet_map_ptr_->laneletLayer.get(primitive.id);
514+
start_lanelets.push_back(lanelet);
515+
}
516+
// closest lanelet in start lanelets
517+
lanelet::ConstLanelet closest_lanelet;
518+
if (!lanelet::utils::query::getClosestLanelet(start_lanelets, current_pose, &closest_lanelet)) {
519+
RCLCPP_ERROR(get_logger(), "Check reroute safety failed. Cannot find the closest lanelet.");
520+
return false;
521+
}
504522

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;
523+
const auto & centerline_2d = lanelet::utils::to2D(closest_lanelet.centerline());
524+
const auto lanelet_point = lanelet::utils::conversion::toLaneletPoint(current_pose.position);
525+
const auto arc_coordinates = lanelet::geometry::toArcCoordinates(
526+
centerline_2d, lanelet::utils::to2D(lanelet_point).basicPoint());
527+
const double dist_to_current_pose = arc_coordinates.length;
528+
const double lanelet_length = lanelet::utils::getLaneletLength2d(closest_lanelet);
529+
accumulated_length = lanelet_length - dist_to_current_pose;
510530
}
511531

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-
520532
// compute distance from the start_idx+1 to end_idx
521-
for (size_t i = start_idx + 1; i <= end_idx; ++i) {
533+
for (size_t i = start_idx_original + 1; i <= end_idx_original; ++i) {
522534
const auto primitives = original_route.segments.at(i).primitives;
523535
if (primitives.empty()) {
524536
break;
@@ -534,7 +546,7 @@ bool MissionPlanner::check_reroute_safety(
534546
}
535547

536548
// 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;
549+
const auto & target_end_primitives = target_route.segments.at(end_idx_target).primitives;
538550
const auto & target_goal = target_route.goal_pose;
539551
for (const auto & target_end_primitive : target_end_primitives) {
540552
const auto lanelet = lanelet_map_ptr_->laneletLayer.get(target_end_primitive.id);
@@ -546,8 +558,11 @@ bool MissionPlanner::check_reroute_safety(
546558
lanelet::utils::to2D(target_goal_position).basicPoint())
547559
.length;
548560
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);
561+
// NOTE: `accumulated_length` here contains the length of the entire target_end_primitive, so
562+
// the remaining distance from the goal to the end of the target_end_primitive needs to be
563+
// subtracted.
564+
const double remaining_dist = target_lanelet_length - dist_to_goal;
565+
accumulated_length = std::max(accumulated_length - remaining_dist, 0.0);
551566
break;
552567
}
553568
}

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)