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(mission_planner): fix reroute interval calculation #6448

Closed
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
114 changes: 62 additions & 52 deletions planning/mission_planner/src/mission_planner/mission_planner.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2019 Autoware Foundation

Check notice on line 1 in planning/mission_planner/src/mission_planner/mission_planner.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 5.52 to 5.56, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -29,6 +29,7 @@
#include <algorithm>
#include <array>
#include <random>
#include <utility>

namespace
{
Expand Down Expand Up @@ -174,7 +175,7 @@
map_ptr_ = msg;
}

PoseStamped MissionPlanner::transform_pose(const PoseStamped & input)
PoseStamped MissionPlanner::transform_pose(const PoseStamped & input) const
{
PoseStamped output;
geometry_msgs::msg::TransformStamped transform;
Expand Down Expand Up @@ -728,162 +729,171 @@
}

bool MissionPlanner::check_reroute_safety(
const LaneletRoute & original_route, const LaneletRoute & target_route)
const LaneletRoute & original_route, const LaneletRoute & target_route) const
{
if (original_route.segments.empty() || target_route.segments.empty() || !map_ptr_ || !odometry_) {
RCLCPP_ERROR(get_logger(), "Check reroute safety failed. Route, map or odometry is not set.");
return false;
}

const auto current_velocity = odometry_->twist.twist.linear.x;

// if vehicle is stopped, do not check safety
if (current_velocity < 0.01) {
return true;
}

auto hasSamePrimitives = [](
const std::vector<LaneletPrimitive> & original_primitives,
const std::vector<LaneletPrimitive> & target_primitives) {
if (original_primitives.size() != target_primitives.size()) {
return false;
}

bool is_same = false;
for (const auto & primitive : original_primitives) {
const auto has_same = [&](const auto & p) { return p.id == primitive.id; };
is_same = std::find_if(target_primitives.begin(), target_primitives.end(), has_same) !=
target_primitives.end();
const bool is_same =
std::find_if(target_primitives.begin(), target_primitives.end(), has_same) !=
target_primitives.end();
if (is_same) {
return true;
}
}
return is_same;
return false;
};

// find idx of original primitives that matches the target primitives
const auto start_idx_opt = std::invoke([&]() -> std::optional<size_t> {
/*
* find the index of the original route that has same idx with the front segment of the new
* route
*
* start_idx
* +-----------+-----------+-----------+-----------+-----------+
* | | | | | |
* +-----------+-----------+-----------+-----------+-----------+
* | | | | | |
* +-----------+-----------+-----------+-----------+-----------+
* original original original original original
* target target target
*/
const auto target_front_primitives = target_route.segments.front().primitives;
for (size_t i = 0; i < original_route.segments.size(); ++i) {
const auto & original_primitives = original_route.segments.at(i).primitives;
if (hasSamePrimitives(original_primitives, target_front_primitives)) {
return i;
const auto start_idx_opt =
std::invoke([&]() -> std::optional<std::pair<size_t /* original */, size_t /* target */>> {
/*
* find the index of the original route that has same idx with the front segment of the new
* route
*
* start_idx == 2
* +--------------+--------------+--------------+--------------+-------------+
* | | | | | |
* +--------------+--------------+--------------+--------------+-------------+
* | | | | | |
* +--------------+--------------+--------------+--------------+-------------+
* original[0] original[1] original[2] original[3] original[4]
* target[0] target[1] target[2]
*/
const auto target_front_primitives = target_route.segments.front().primitives;
for (size_t i = 0; i < original_route.segments.size(); ++i) {
const auto & original_primitives = original_route.segments.at(i).primitives;
if (hasSamePrimitives(original_primitives, target_front_primitives)) {
return std::make_pair(i, 0);
}
}
}

/*
* find the target route that has same idx with the front segment of the original route
*
* start_idx
* +-----------+-----------+-----------+-----------+-----------+
* | | | | | |
* +-----------+-----------+-----------+-----------+-----------+
* | | | | | |
* +-----------+-----------+-----------+-----------+-----------+
*                original original original
* target target target target target
*/
const auto original_front_primitives = original_route.segments.front().primitives;
for (size_t i = 0; i < target_route.segments.size(); ++i) {
const auto & target_primitives = target_route.segments.at(i).primitives;
if (hasSamePrimitives(target_primitives, original_front_primitives)) {
return 0;
/*
* find the target route that has same idx with the front segment of the original route
*
* start_idx == 0
* +--------------+--------------+--------------+--------------+-------------+
* | | | | | |
* +--------------+--------------+--------------+--------------+-------------+
* | | | | | |
* +--------------+--------------+--------------+--------------+-------------+
* original[0] original[1] original[2]
* target[0] target[1] target[2] target[3] target[4]
*/
const auto original_front_primitives = original_route.segments.front().primitives;
for (size_t i = 0; i < target_route.segments.size(); ++i) {
const auto & target_primitives = target_route.segments.at(i).primitives;
if (hasSamePrimitives(target_primitives, original_front_primitives)) {
return std::make_pair(0, i);
}
}
}

return std::nullopt;
});
return std::nullopt;
});
if (!start_idx_opt.has_value()) {
RCLCPP_ERROR(
get_logger(), "Check reroute safety failed. Cannot find the start index of the route.");
return false;
}
const size_t start_idx = start_idx_opt.value();
const auto [start_idx, start_idx_target] = start_idx_opt.value();

// find last idx that matches the target primitives
size_t end_idx = start_idx;
for (size_t i = 1; i < target_route.segments.size(); ++i) {
size_t end_idx_target = start_idx_target;
for (size_t i = 1; i < target_route.segments.size() - start_idx_target; ++i) {
if (start_idx + i > original_route.segments.size() - 1) {
break;
}

const auto & original_primitives = original_route.segments.at(start_idx + i).primitives;
const auto & target_primitives = target_route.segments.at(i).primitives;
const auto & target_primitives = target_route.segments.at(start_idx_target + i).primitives;
if (!hasSamePrimitives(original_primitives, target_primitives)) {
break;
}
end_idx = start_idx + i;
end_idx_target = end_idx_target + i;
}

// create map
auto lanelet_map_ptr_ = std::make_shared<lanelet::LaneletMap>();
lanelet::utils::conversion::fromBinMsg(*map_ptr_, lanelet_map_ptr_);

// compute distance from the current pose to the end of the current lanelet
const auto current_pose = target_route.start_pose;
const auto primitives = original_route.segments.at(start_idx).primitives;
lanelet::ConstLanelets start_lanelets;
for (const auto & primitive : primitives) {
const auto lanelet = lanelet_map_ptr_->laneletLayer.get(primitive.id);
start_lanelets.push_back(lanelet);
}

// get closest lanelet in start lanelets
lanelet::ConstLanelet closest_lanelet;
if (!lanelet::utils::query::getClosestLanelet(start_lanelets, current_pose, &closest_lanelet)) {
RCLCPP_ERROR(get_logger(), "Check reroute safety failed. Cannot find the closest lanelet.");
return false;
}

const auto & centerline_2d = lanelet::utils::to2D(closest_lanelet.centerline());
const auto lanelet_point = lanelet::utils::conversion::toLaneletPoint(current_pose.position);
const auto arc_coordinates = lanelet::geometry::toArcCoordinates(
centerline_2d, lanelet::utils::to2D(lanelet_point).basicPoint());
const double dist_to_current_pose = arc_coordinates.length;
const double lanelet_length = lanelet::utils::getLaneletLength2d(closest_lanelet);
double accumulated_length = lanelet_length - dist_to_current_pose;

// compute distance from the start_idx+1 to end_idx
for (size_t i = start_idx + 1; i <= end_idx; ++i) {
const auto primitives = original_route.segments.at(i).primitives;
if (primitives.empty()) {
break;
}

std::vector<double> lanelets_length(primitives.size());
for (size_t primitive_idx = 0; primitive_idx < primitives.size(); ++primitive_idx) {
const auto & primitive = primitives.at(primitive_idx);
const auto & lanelet = lanelet_map_ptr_->laneletLayer.get(primitive.id);
lanelets_length.at(primitive_idx) = (lanelet::utils::getLaneletLength2d(lanelet));
}
accumulated_length += *std::min_element(lanelets_length.begin(), lanelets_length.end());
}

// check if the goal is inside of the target terminal lanelet
const auto & target_end_primitives = target_route.segments.at(end_idx - start_idx).primitives;
const auto & target_end_primitives = target_route.segments.at(end_idx_target).primitives;
const auto & target_goal = target_route.goal_pose;
for (const auto & target_end_primitive : target_end_primitives) {
const auto lanelet = lanelet_map_ptr_->laneletLayer.get(target_end_primitive.id);
if (lanelet::utils::isInLanelet(target_goal, lanelet)) {
const auto target_goal_position =
lanelet::utils::conversion::toLaneletPoint(target_goal.position);
const double dist_to_goal = lanelet::geometry::toArcCoordinates(
lanelet::utils::to2D(lanelet.centerline()),
lanelet::utils::to2D(target_goal_position).basicPoint())
.length;
const double target_lanelet_length = lanelet::utils::getLaneletLength2d(lanelet);
const double dist = target_lanelet_length - dist_to_goal;
accumulated_length = std::max(accumulated_length - dist, 0.0);
// NOTE: `accumulated_length` here contains the length of the entire target_end_primitive, so
// the remaining distance from the goal to the end of the target_end_primitive needs to be
// subtracted.
const double remaining_dist = target_lanelet_length - dist_to_goal;
accumulated_length = std::max(accumulated_length - remaining_dist, 0.0);

Check warning on line 896 in planning/mission_planner/src/mission_planner/mission_planner.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

MissionPlanner::check_reroute_safety increases in cyclomatic complexity from 24 to 25, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

Check notice on line 896 in planning/mission_planner/src/mission_planner/mission_planner.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Bumpy Road Ahead

MissionPlanner::check_reroute_safety increases from 5 to 6 logical blocks with deeply nested code, threshold is one single block per function. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.
break;
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ class MissionPlanner : public rclcpp::Node
std::string map_frame_;
tf2_ros::Buffer tf_buffer_;
tf2_ros::TransformListener tf_listener_;
PoseStamped transform_pose(const PoseStamped & input);
PoseStamped transform_pose(const PoseStamped & input) const;

rclcpp::Subscription<Odometry>::SharedPtr sub_odometry_;
rclcpp::Subscription<HADMapBin>::SharedPtr sub_vector_map_;
Expand Down Expand Up @@ -144,7 +144,8 @@ class MissionPlanner : public rclcpp::Node

double reroute_time_threshold_{10.0};
double minimum_reroute_length_{30.0};
bool check_reroute_safety(const LaneletRoute & original_route, const LaneletRoute & target_route);
bool check_reroute_safety(
const LaneletRoute & original_route, const LaneletRoute & target_route) const;

std::shared_ptr<LaneletRoute> normal_route_{nullptr};
std::shared_ptr<LaneletRoute> mrm_route_{nullptr};
Expand Down
Loading