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(behavior_path_planner): keep original points in resampling of pull over #2478

Merged
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 @@ -172,6 +172,8 @@ class BehaviorPathPlannerNode : public rclcpp::Node
bool skipSmoothGoalConnection(
const std::vector<std::shared_ptr<SceneModuleStatus>> & statuses) const;

bool keepInputPoints(const std::vector<std::shared_ptr<SceneModuleStatus>> & statuses) const;

/**
* @brief skip smooth goal connection
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,8 @@ 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);

PathWithLaneId resamplePathWithSpline(const PathWithLaneId & path, double interval);
PathWithLaneId resamplePathWithSpline(
const PathWithLaneId & path, const double interval, const bool keep_input_points = false);

Path toPath(const PathWithLaneId & input);

Expand Down
21 changes: 19 additions & 2 deletions planning/behavior_path_planner/src/behavior_path_planner_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -781,8 +781,9 @@ PathWithLaneId::SharedPtr BehaviorPathPlannerNode::getPath(
connected_path = modifyPathForSmoothGoalConnection(*path);
}

const auto resampled_path =
util::resamplePathWithSpline(connected_path, planner_data_->parameters.path_interval);
const auto resampled_path = util::resamplePathWithSpline(
connected_path, planner_data_->parameters.path_interval,
keepInputPoints(module_status_ptr_vec));
return std::make_shared<PathWithLaneId>(resampled_path);
}

Expand Down Expand Up @@ -841,6 +842,22 @@ bool BehaviorPathPlannerNode::skipSmoothGoalConnection(
return false;
}

// This is a temporary process until motion planning can take the terminal pose into account
bool BehaviorPathPlannerNode::keepInputPoints(
const std::vector<std::shared_ptr<SceneModuleStatus>> & statuses) const
{
const auto target_module = "PullOver";

for (auto & status : statuses) {
if (status->is_waiting_approval || status->status == BT::NodeStatus::RUNNING) {
if (target_module == status->module_name) {
return true;
}
}
}
return false;
}

void BehaviorPathPlannerNode::onVelocity(const Odometry::ConstSharedPtr msg)
{
std::lock_guard<std::mutex> lock(mutex_pd_);
Expand Down
8 changes: 6 additions & 2 deletions planning/behavior_path_planner/src/path_utilities.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,8 @@ std::vector<double> calcPathArcLengthArray(
/**
* @brief resamplePathWithSpline
*/
PathWithLaneId resamplePathWithSpline(const PathWithLaneId & path, double interval)
PathWithLaneId resamplePathWithSpline(
const PathWithLaneId & path, const double interval, const bool keep_input_points)
{
if (path.points.size() < 2) {
return path;
Expand All @@ -66,7 +67,7 @@ PathWithLaneId resamplePathWithSpline(const PathWithLaneId & path, double interv
transformed_path.at(i) = path.points.at(i).point;
}

constexpr double epsilon = 0.01;
constexpr double epsilon = 0.2;
const auto has_almost_same_value = [&](const auto & vec, const auto x) {
if (vec.empty()) return false;
const auto has_close = [&](const auto v) { return std::abs(v - x) < epsilon; };
Expand All @@ -79,6 +80,9 @@ PathWithLaneId resamplePathWithSpline(const PathWithLaneId & path, double interv
for (size_t i = 0; i < path.points.size(); ++i) {
const double s = motion_utils::calcSignedArcLength(transformed_path, 0, i);
for (const auto & lane_id : path.points.at(i).lane_ids) {
if (keep_input_points && !has_almost_same_value(s_in, s)) {
s_in.push_back(s);
}
if (
std::find(unique_lane_ids.begin(), unique_lane_ids.end(), lane_id) !=
unique_lane_ids.end()) {
Expand Down