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_planenr): not reset when receving new route #3966

Merged
merged 2 commits into from
Jun 13, 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 @@ -152,8 +152,10 @@ class GoalPlannerModule : public SceneModuleInterface

tier4_autoware_utils::LinearRing2d vehicle_footprint_;

// save last time and pose
// save last time and pose
#ifdef USE_OLD_ARCHITECTURE
std::unique_ptr<rclcpp::Time> last_received_time_;
#endif
std::unique_ptr<rclcpp::Time> last_approved_time_;
std::unique_ptr<rclcpp::Time> last_increment_time_;
std::unique_ptr<rclcpp::Time> last_path_update_time_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -488,26 +488,37 @@ void GoalPlannerModule::returnToLaneParking()

void GoalPlannerModule::generateGoalCandidates()
{
// initialize when receiving new route
const auto & route_handler = planner_data_->route_handler;

// with old architecture, module instance is not cleared when new route is received
// so need to reset status here.
#ifdef USE_OLD_ARCHITECTURE
// initialize when receiving new route
if (!last_received_time_ || *last_received_time_ != route_handler->getRouteHeader().stamp) {
// Initialize parallel parking planner status
// this process causes twice reset when receiving first route.
resetStatus();

// calculate goal candidates
const Pose goal_pose = route_handler->getGoalPose();
refined_goal_pose_ = calcRefinedGoal(goal_pose);
if (allow_goal_modification_) {
goal_searcher_->setPlannerData(planner_data_);
goal_candidates_ = goal_searcher_->search(refined_goal_pose_);
} else {
GoalCandidate goal_candidate{};
goal_candidate.goal_pose = goal_pose;
goal_candidate.distance_from_original_goal = 0.0;
goal_candidates_.push_back(goal_candidate);
}
}
last_received_time_ = std::make_unique<rclcpp::Time>(route_handler->getRouteHeader().stamp);

#else
// todo: move this check out of this function after old architecture is removed
if (!goal_candidates_.empty()) {
return;
}
#endif

// calculate goal candidates
const Pose goal_pose = route_handler->getGoalPose();
refined_goal_pose_ = calcRefinedGoal(goal_pose);
if (allow_goal_modification_) {
goal_searcher_->setPlannerData(planner_data_);
goal_candidates_ = goal_searcher_->search(refined_goal_pose_);
} else {
GoalCandidate goal_candidate{};
goal_candidate.goal_pose = goal_pose;
goal_candidate.distance_from_original_goal = 0.0;
goal_candidates_.push_back(goal_candidate);
}
}

BehaviorModuleOutput GoalPlannerModule::plan()
Expand Down