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

refactor(path_generator): avoid using fixed-size array #353

Open
wants to merge 3 commits into
base: main
Choose a base branch
from
Open
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 @@ -23,8 +23,6 @@
#include <limits>
#include <memory>
#include <optional>
#include <string>
#include <unordered_map>
#include <utility>
#include <vector>

Expand All @@ -34,10 +32,12 @@ using autoware_internal_planning_msgs::msg::PathPointWithLaneId;
using autoware_internal_planning_msgs::msg::PathWithLaneId;
using autoware_vehicle_msgs::msg::TurnIndicatorsCommand;

const std::unordered_map<std::string, uint8_t> turn_signal_command_map = {
{"left", TurnIndicatorsCommand::ENABLE_LEFT},
{"right", TurnIndicatorsCommand::ENABLE_RIGHT},
{"straight", TurnIndicatorsCommand::DISABLE}};
template <typename T>
struct PathRange
{
T left;
T right;
};

namespace utils
{
Expand Down Expand Up @@ -142,7 +142,7 @@ std::optional<double> get_first_self_intersection_arc_length(
* @param s_end longitudinal distance of end of bound on centerline
* @return cropped bounds (left / right)
*/
std::array<std::vector<geometry_msgs::msg::Point>, 2> get_path_bounds(
PathRange<std::vector<geometry_msgs::msg::Point>> get_path_bounds(
const lanelet::LaneletSequence & lanelet_sequence, const double s_start, const double s_end);

/**
Expand All @@ -162,7 +162,7 @@ std::vector<geometry_msgs::msg::Point> crop_line_string(
* @param s_centerline longitudinal distance of point on centerline
* @return longitudinal distance of projected point (left / right)
*/
std::array<double, 2> get_arc_length_on_bounds(
PathRange<double> get_arc_length_on_bounds(
const lanelet::LaneletSequence & lanelet_sequence, const double s_centerline);

/**
Expand All @@ -172,7 +172,7 @@ std::array<double, 2> get_arc_length_on_bounds(
* @param s_right_bound longitudinal distance of point on left bound
* @return longitudinal distance of projected point (left / right)
*/
std::array<std::optional<double>, 2> get_arc_length_on_centerline(
PathRange<std::optional<double>> get_arc_length_on_centerline(
const lanelet::LaneletSequence & lanelet_sequence, const std::optional<double> & s_left_bound,
const std::optional<double> & s_right_bound);

Expand Down
35 changes: 17 additions & 18 deletions planning/autoware_path_generator/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,8 @@
#include <algorithm>
#include <limits>
#include <memory>
#include <string>
#include <unordered_map>
#include <utility>
#include <vector>

Expand All @@ -40,6 +42,11 @@ namespace utils
{
namespace
{
const std::unordered_map<std::string, uint8_t> turn_signal_command_map = {
{"left", TurnIndicatorsCommand::ENABLE_LEFT},
{"right", TurnIndicatorsCommand::ENABLE_RIGHT},
{"straight", TurnIndicatorsCommand::DISABLE}};

template <typename T>
bool exists(const std::vector<T> & vec, const T & item)
{
Expand Down Expand Up @@ -244,13 +251,11 @@ std::optional<double> get_first_intersection_arc_length(
{
std::optional<double> s_intersection{std::nullopt};

const auto s_start_bounds = get_arc_length_on_bounds(lanelet_sequence, s_start);
const double s_start_left_bound = s_start_bounds.at(0);
const double s_start_right_bound = s_start_bounds.at(1);
const auto [s_start_left_bound, s_start_right_bound] =
get_arc_length_on_bounds(lanelet_sequence, s_start);

const auto s_end_bound = get_arc_length_on_bounds(lanelet_sequence, s_end);
const double s_end_left_bound = s_end_bound.at(0);
const double s_end_right_bound = s_end_bound.at(1);
const auto [s_end_left_bound, s_end_right_bound] =
get_arc_length_on_bounds(lanelet_sequence, s_end);

const auto cropped_centerline = lanelet::utils::to2D(to_lanelet_points(crop_line_string(
to_geometry_msgs_points(
Expand Down Expand Up @@ -285,10 +290,8 @@ std::optional<double> get_first_intersection_arc_length(
return s;
}();

const auto s_bounds_on_centerline =
const auto [s_left, s_right] =
get_arc_length_on_centerline(lanelet_sequence, s_left_bound, s_right_bound);
const auto s_left = s_bounds_on_centerline.at(0);
const auto s_right = s_bounds_on_centerline.at(1);

if (s_left && s_right) {
s_intersection = std::min(s_left, s_right);
Expand All @@ -302,14 +305,12 @@ std::optional<double> get_first_intersection_arc_length(
lanelet::BasicPoints2d intersections;
boost::geometry::intersection(cropped_left_bound, cropped_right_bound, intersections);
for (const auto & intersection : intersections) {
const auto s_bounds_on_centerline = get_arc_length_on_centerline(
const auto [s_left, s_right] = get_arc_length_on_centerline(
lanelet_sequence,
s_start_left_bound +
lanelet::geometry::toArcCoordinates(cropped_left_bound, intersection).length,
s_start_right_bound +
lanelet::geometry::toArcCoordinates(cropped_right_bound, intersection).length);
const auto s_left = s_bounds_on_centerline.at(0);
const auto s_right = s_bounds_on_centerline.at(1);
const auto s_mutual = [&]() {
if (s_left && s_right) {
return std::max(s_left, s_right);
Expand Down Expand Up @@ -358,10 +359,8 @@ std::optional<double> get_first_intersection_arc_length(
return s;
}();

const auto s_bounds_on_centerline =
const auto [s_left, s_right] =
get_arc_length_on_centerline(lanelet_sequence, s_left_bound, s_right_bound);
const auto s_left = s_bounds_on_centerline.at(0);
const auto s_right = s_bounds_on_centerline.at(1);

const auto s_start_edge = [&]() {
if (s_left && s_right) {
Expand Down Expand Up @@ -427,7 +426,7 @@ std::optional<double> get_first_self_intersection_arc_length(
return std::nullopt;
}

std::array<std::vector<geometry_msgs::msg::Point>, 2> get_path_bounds(
PathRange<std::vector<geometry_msgs::msg::Point>> get_path_bounds(
const lanelet::LaneletSequence & lanelet_sequence, const double s_start, const double s_end)
{
const auto [s_left_start, s_right_start] = get_arc_length_on_bounds(lanelet_sequence, s_start);
Expand Down Expand Up @@ -455,7 +454,7 @@ std::vector<geometry_msgs::msg::Point> crop_line_string(
return trajectory->restore();
}

std::array<double, 2> get_arc_length_on_bounds(
PathRange<double> get_arc_length_on_bounds(
const lanelet::LaneletSequence & lanelet_sequence, const double s_centerline)
{
auto s = 0.;
Expand Down Expand Up @@ -487,7 +486,7 @@ std::array<double, 2> get_arc_length_on_bounds(
return {s_centerline, s_centerline};
}

std::array<std::optional<double>, 2> get_arc_length_on_centerline(
PathRange<std::optional<double>> get_arc_length_on_centerline(
const lanelet::LaneletSequence & lanelet_sequence, const std::optional<double> & s_left_bound,
const std::optional<double> & s_right_bound)
{
Expand Down
Loading