Skip to content

Commit 41e08dc

Browse files
authored
refactor(goal_planner): remove modified_goal in ThreadDafeData (#9010)
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 3eafb9b commit 41e08dc

File tree

4 files changed

+80
-79
lines changed

4 files changed

+80
-79
lines changed

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp

+5-2
Original file line numberDiff line numberDiff line change
@@ -372,10 +372,13 @@ class GoalPlannerModule : public SceneModuleInterface
372372
bool isStopped(
373373
std::deque<nav_msgs::msg::Odometry::ConstSharedPtr> & odometry_buffer, const double time);
374374
bool hasFinishedCurrentPath(const PullOverContextData & ctx_data);
375-
bool isOnModifiedGoal(const Pose & current_pose, const GoalPlannerParameters & parameters) const;
375+
bool isOnModifiedGoal(
376+
const Pose & current_pose, const std::optional<GoalCandidate> & modified_goal_opt,
377+
const GoalPlannerParameters & parameters) const;
376378
double calcModuleRequestLength() const;
377379
bool needPathUpdate(
378380
const Pose & current_pose, const double path_update_duration,
381+
const std::optional<GoalCandidate> & modified_goal_opt,
379382
const GoalPlannerParameters & parameters) const;
380383
bool isStuck(
381384
const PredictedObjects & static_target_objects, const PredictedObjects & dynamic_target_objects,
@@ -406,7 +409,7 @@ class GoalPlannerModule : public SceneModuleInterface
406409
BehaviorModuleOutput planPullOver(const PullOverContextData & context_data);
407410
BehaviorModuleOutput planPullOverAsOutput(const PullOverContextData & context_data);
408411
BehaviorModuleOutput planPullOverAsCandidate(const PullOverContextData & context_data);
409-
std::optional<std::pair<PullOverPath, GoalCandidate>> selectPullOverPath(
412+
std::optional<PullOverPath> selectPullOverPath(
410413
const PullOverContextData & context_data,
411414
const std::vector<PullOverPath> & pull_over_path_candidates,
412415
const GoalCandidates & goal_candidates) const;

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -54,8 +54,8 @@ struct PullOverPath
5454
size_t goal_id() const { return modified_goal_pose_.id; }
5555
size_t id() const { return id_; }
5656
Pose start_pose() const { return start_pose_; }
57-
Pose end_pose() const { return modified_goal_pose_.goal_pose; }
58-
GoalCandidate modified_goal_pose() const { return modified_goal_pose_; }
57+
Pose modified_goal_pose() const { return modified_goal_pose_.goal_pose; }
58+
GoalCandidate modified_goal() const { return modified_goal_pose_; }
5959

6060
std::vector<PathWithLaneId> & partial_paths() { return partial_paths_; }
6161
const std::vector<PathWithLaneId> & partial_paths() const { return partial_paths_; }

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/thread_data.hpp

-13
Original file line numberDiff line numberDiff line change
@@ -105,22 +105,12 @@ class ThreadSafeData
105105
return true;
106106
}
107107

108-
std::optional<PullOverPlannerType> getPullOverPlannerType() const
109-
{
110-
const std::lock_guard<std::recursive_mutex> lock(mutex_);
111-
if (!pull_over_path_) {
112-
return std::nullopt;
113-
}
114-
return pull_over_path_->type();
115-
};
116-
117108
void reset()
118109
{
119110
const std::lock_guard<std::recursive_mutex> lock(mutex_);
120111
pull_over_path_ = nullptr;
121112
pull_over_path_candidates_.clear();
122113
goal_candidates_.clear();
123-
modified_goal_pose_ = std::nullopt;
124114
last_path_update_time_ = std::nullopt;
125115
last_path_idx_increment_time_ = std::nullopt;
126116
closest_start_pose_ = std::nullopt;
@@ -135,7 +125,6 @@ class ThreadSafeData
135125

136126
DEFINE_SETTER_GETTER_WITH_MUTEX(std::vector<PullOverPath>, pull_over_path_candidates)
137127
DEFINE_SETTER_GETTER_WITH_MUTEX(GoalCandidates, goal_candidates)
138-
DEFINE_SETTER_GETTER_WITH_MUTEX(std::optional<GoalCandidate>, modified_goal_pose)
139128
DEFINE_SETTER_GETTER_WITH_MUTEX(std::optional<Pose>, closest_start_pose)
140129
DEFINE_SETTER_GETTER_WITH_MUTEX(std::optional<BehaviorModuleOutput>, last_previous_module_output)
141130
DEFINE_SETTER_GETTER_WITH_MUTEX(
@@ -168,7 +157,6 @@ class ThreadSafeData
168157
void set_no_lock(const std::vector<PullOverPath> & arg) { pull_over_path_candidates_ = arg; }
169158
void set_no_lock(const std::shared_ptr<PullOverPath> & arg) { set_pull_over_path_no_lock(arg); }
170159
void set_no_lock(const PullOverPath & arg) { set_pull_over_path_no_lock(arg); }
171-
void set_no_lock(const GoalCandidate & arg) { modified_goal_pose_ = arg; }
172160
void set_no_lock(const BehaviorModuleOutput & arg) { last_previous_module_output_ = arg; }
173161
void set_no_lock(const utils::path_safety_checker::CollisionCheckDebugMap & arg)
174162
{
@@ -179,7 +167,6 @@ class ThreadSafeData
179167
std::shared_ptr<PullOverPath> lane_parking_pull_over_path_{nullptr};
180168
std::vector<PullOverPath> pull_over_path_candidates_;
181169
GoalCandidates goal_candidates_{};
182-
std::optional<GoalCandidate> modified_goal_pose_;
183170
std::optional<rclcpp::Time> last_path_update_time_;
184171
std::optional<rclcpp::Time> last_path_idx_increment_time_;
185172
std::optional<Pose> closest_start_pose_{};

0 commit comments

Comments
 (0)