Skip to content

Commit

Permalink
Revert "fix(goal_planner): fix freespace planning chattering (autowar…
Browse files Browse the repository at this point in the history
…efoundation#8981)"

This reverts commit 2113aa1.
  • Loading branch information
TetsuKawa committed Dec 6, 2024
1 parent 40b591d commit e0357cd
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,13 @@ MarkerArray createLaneletPolygonMarkerArray(
MarkerArray createNumObjectsToAvoidTextsMarkerArray(
const GoalCandidates & goal_candidates, std::string && ns,
const std_msgs::msg::ColorRGBA & color);

std::string makePathPriorityDebugMessage(
const std::vector<size_t> & sorted_path_indices,
const std::vector<PullOverPath> & pull_over_path_candidates,
const std::map<size_t, size_t> & goal_id_to_index, const GoalCandidates & goal_candidates,
const std::map<size_t, double> & path_id_to_rough_margin_map,
const std::function<bool(const PullOverPath &)> & isSoftMargin,
const std::function<bool(const PullOverPath &)> & isHighCurvature);
/**
* @brief combine two points
* @param points lane points
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1456,8 +1456,6 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput()
return getPreviousModuleOutput();
}

const bool is_freespace =
thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE;
if (
hasNotDecidedPath(
planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_,
Expand Down Expand Up @@ -1504,7 +1502,7 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput()

// return to lane parking if it is possible
if (
is_freespace && thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE &&
thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE &&
canReturnToLaneParking()) {
thread_safe_data_.set_pull_over_path(thread_safe_data_.get_lane_parking_pull_over_path());
}
Expand Down

0 comments on commit e0357cd

Please sign in to comment.