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(behavior_path_planner): change the order of resampling and smooth goal connection #1381

Open
wants to merge 2 commits into
base: beta/v0.3.18.1
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 @@ -137,8 +137,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node
/**
* @brief extract path from behavior tree output
*/
std::pair<PathWithLaneId::SharedPtr, PathWithLaneId::SharedPtr> getPath(
const BehaviorModuleOutput & bt_out);
PathWithLaneId::SharedPtr getPath(const BehaviorModuleOutput & bt_out);

/**
* @brief extract path candidate from behavior tree output
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -478,14 +478,15 @@ void BehaviorPathPlannerNode::run()
const auto output = bt_manager_->run(planner_data_);

// path handling
const auto paths = getPath(output);
const auto path = paths.first;
const auto original_path = paths.second;
const auto original_path = getPath(output);

const auto path_candidate = getPathCandidate(output);
planner_data_->prev_output_path = path;
planner_data_->prev_output_path = original_path;

const auto path = original_path;
auto clipped_path = modifyPathForSmoothGoalConnection(*path);
clipped_path =
util::resamplePathWithSpline(clipped_path, planner_data_->parameters.path_interval);
clipPathLength(clipped_path);

if (!clipped_path.points.empty()) {
Expand Down Expand Up @@ -531,8 +532,7 @@ void BehaviorPathPlannerNode::run()
}

// output: spline interpolated path, original path
std::pair<PathWithLaneId::SharedPtr, PathWithLaneId::SharedPtr> BehaviorPathPlannerNode::getPath(
const BehaviorModuleOutput & bt_output)
PathWithLaneId::SharedPtr BehaviorPathPlannerNode::getPath(const BehaviorModuleOutput & bt_output)
{
// TODO(Horibe) do some error handling when path is not available.

Expand All @@ -542,9 +542,7 @@ std::pair<PathWithLaneId::SharedPtr, PathWithLaneId::SharedPtr> BehaviorPathPlan
RCLCPP_DEBUG(
get_logger(), "BehaviorTreeManager: output is %s.", bt_output.path ? "FOUND" : "NOT FOUND");

const auto resampled_path =
util::resamplePathWithSpline(*path, planner_data_->parameters.path_interval);
return std::make_pair(std::make_shared<PathWithLaneId>(resampled_path), path);
return path;
}

PathWithLaneId::SharedPtr BehaviorPathPlannerNode::getPathCandidate(
Expand Down
Loading