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(goal_planner): fix publishing new modified goal #4302

Merged
merged 2 commits into from
Jul 18, 2023
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 @@ -128,7 +128,6 @@ class GoalPlannerModule : public SceneModuleInterface
// goal searcher
std::shared_ptr<GoalSearcherBase> goal_searcher_;
std::optional<GoalCandidate> modified_goal_pose_;
std::optional<size_t> prev_goal_id_;
Pose refined_goal_pose_;
GoalCandidates goal_candidates_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -575,8 +575,9 @@ void BehaviorPathPlannerNode::run()
if (
output.modified_goal &&
/* has changed modified goal */ (
!planner_data_->prev_modified_goal ||
planner_data_->prev_modified_goal->uuid != output.modified_goal->uuid)) {
!planner_data_->prev_modified_goal || tier4_autoware_utils::calcDistance2d(
planner_data_->prev_modified_goal->pose.position,
output.modified_goal->pose.position) > 0.01)) {
PoseWithUuidStamped modified_goal = *(output.modified_goal);
modified_goal.header.stamp = path->header.stamp;
planner_data_->prev_modified_goal = modified_goal;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,6 @@ void GoalPlannerModule::resetStatus()
pull_over_path_candidates_.clear();
closest_start_pose_.reset();
goal_candidates_.clear();
prev_goal_id_.reset();
}

// This function is needed for waiting for planner_data_
Expand Down Expand Up @@ -621,7 +620,6 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output)
setDrivableAreaInfo(output);

setModifiedGoal(output);
prev_goal_id_ = modified_goal_pose_->id;

// set hazard and turn signal
if (status_.has_decided_path) {
Expand Down