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

feat(lane_change): update resamplePath function for target section #2622

Merged
Merged
Show file tree
Hide file tree
Changes from 2 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 @@ -41,8 +41,18 @@ std::vector<double> calcPathArcLengthArray(
const PathWithLaneId & path, const size_t start = 0,
const size_t end = std::numeric_limits<size_t>::max(), const double offset = 0.0);

/**
* @brief resample path by spline with constant interval distance
* @param [in] path original path to be resampled
* @param [in] interval constant interval distance
* @param [in] keep_input_points original points are kept in the resampled points
* @param [in] target_section target section defined by arclength if you want to resample a part of
* the path
* @return resampled path
*/
PathWithLaneId resamplePathWithSpline(
const PathWithLaneId & path, const double interval, const bool keep_input_points = false);
const PathWithLaneId & path, const double interval, const bool keep_input_points = false,
const std::pair<double, double> target_section = {0.0, std::numeric_limits<double>::max()});

Path toPath(const PathWithLaneId & input);

Expand Down
13 changes: 8 additions & 5 deletions planning/behavior_path_planner/src/path_utilities.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,8 @@ std::vector<double> calcPathArcLengthArray(
* @brief resamplePathWithSpline
*/
PathWithLaneId resamplePathWithSpline(
const PathWithLaneId & path, const double interval, const bool keep_input_points)
const PathWithLaneId & path, const double interval, const bool keep_input_points,
const std::pair<double, double> target_section)
{
if (path.points.size() < 2) {
return path;
Expand Down Expand Up @@ -96,16 +97,18 @@ PathWithLaneId resamplePathWithSpline(

std::vector<double> s_out = s_in;

const double path_len = motion_utils::calcArcLength(transformed_path);
for (double s = 0.0; s < path_len; s += interval) {
const auto start_s = std::max(target_section.first, 0.0);
const auto end_s =
std::min(target_section.second, motion_utils::calcArcLength(transformed_path));
for (double s = start_s; s < end_s; s += interval) {
if (!has_almost_same_value(s_out, s)) {
s_out.push_back(s);
}
}

// Insert Terminal Point
if (!has_almost_same_value(s_out, path_len)) {
s_out.push_back(path_len);
if (!has_almost_same_value(s_out, end_s)) {
s_out.push_back(end_s);
}

// Insert Stop Point
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -546,7 +546,8 @@ PathWithLaneId getReferencePathFromTargetLane(
constexpr auto resampling_dt{0.2};
const auto resample_interval =
std::max(lane_changing_distance / min_resampling_points, lane_changing_speed * resampling_dt);
return util::resamplePathWithSpline(lane_changing_reference_path, resample_interval);
return util::resamplePathWithSpline(
lane_changing_reference_path, resample_interval, true, {0.0, lane_changing_distance});
}

PathWithLaneId getReferencePathFromTargetLane(
Expand Down