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

perf(goal_planner): reduce unnecessary recursive lock guard #8465

Merged
merged 2 commits into from
Aug 16, 2024
Merged
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 @@ -143,38 +143,21 @@
void set_pull_over_path(const PullOverPath & path)
{
const std::lock_guard<std::recursive_mutex> lock(mutex_);
pull_over_path_ = std::make_shared<PullOverPath>(path);
if (path.type != PullOverPlannerType::NONE && path.type != PullOverPlannerType::FREESPACE) {
lane_parking_pull_over_path_ = std::make_shared<PullOverPath>(path);
}

last_path_update_time_ = clock_->now();
set_pull_over_path_no_lock(path);

Check warning on line 146 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

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

Added line #L146 was not covered by tests
}

void set_pull_over_path(const std::shared_ptr<PullOverPath> & path)
{
const std::lock_guard<std::recursive_mutex> lock(mutex_);
pull_over_path_ = path;
if (path->type != PullOverPlannerType::NONE && path->type != PullOverPlannerType::FREESPACE) {
lane_parking_pull_over_path_ = path;
}
last_path_update_time_ = clock_->now();
set_pull_over_path_no_lock(path);

Check warning on line 152 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

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

Added line #L152 was not covered by tests
}

template <typename... Args>
void set(Args... args)
{
std::lock_guard<std::recursive_mutex> lock(mutex_);
(..., set(args));
(..., set_no_lock(args));
}
void set(const GoalCandidates & arg) { set_goal_candidates(arg); }
void set(const std::vector<PullOverPath> & arg) { set_pull_over_path_candidates(arg); }
void set(const std::shared_ptr<PullOverPath> & arg) { set_pull_over_path(arg); }
void set(const PullOverPath & arg) { set_pull_over_path(arg); }
void set(const GoalCandidate & arg) { set_modified_goal_pose(arg); }
void set(const BehaviorModuleOutput & arg) { set_last_previous_module_output(arg); }
void set(const PreviousPullOverData & arg) { set_prev_data(arg); }
void set(const CollisionCheckDebugMap & arg) { set_collision_check(arg); }

void clearPullOverPath()
{
Expand Down Expand Up @@ -232,6 +215,34 @@
DEFINE_SETTER_GETTER_WITH_MUTEX(PredictedObjects, dynamic_target_objects)

private:
void set_pull_over_path_no_lock(const PullOverPath & path)

Check warning on line 218 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

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

Added line #L218 was not covered by tests
{
pull_over_path_ = std::make_shared<PullOverPath>(path);

Check warning on line 220 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

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

Added line #L220 was not covered by tests
if (path.type != PullOverPlannerType::NONE && path.type != PullOverPlannerType::FREESPACE) {
lane_parking_pull_over_path_ = std::make_shared<PullOverPath>(path);

Check warning on line 222 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

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

Added line #L222 was not covered by tests
}

last_path_update_time_ = clock_->now();

Check warning on line 225 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

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

Added line #L225 was not covered by tests
}

void set_pull_over_path_no_lock(const std::shared_ptr<PullOverPath> & path)

Check warning on line 228 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

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

Added line #L228 was not covered by tests
{
pull_over_path_ = path;
if (path->type != PullOverPlannerType::NONE && path->type != PullOverPlannerType::FREESPACE) {
lane_parking_pull_over_path_ = path;
}
last_path_update_time_ = clock_->now();

Check warning on line 234 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

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

Added line #L234 was not covered by tests
}

void set_no_lock(const GoalCandidates & arg) { goal_candidates_ = arg; }
void set_no_lock(const std::vector<PullOverPath> & arg) { pull_over_path_candidates_ = arg; }

Check warning on line 238 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp#L237-L238

Added lines #L237 - L238 were not covered by tests
void set_no_lock(const std::shared_ptr<PullOverPath> & arg) { set_pull_over_path_no_lock(arg); }
void set_no_lock(const PullOverPath & arg) { set_pull_over_path_no_lock(arg); }

Check warning on line 240 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

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

Added line #L240 was not covered by tests
void set_no_lock(const GoalCandidate & arg) { modified_goal_pose_ = arg; }
void set_no_lock(const BehaviorModuleOutput & arg) { last_previous_module_output_ = arg; }
void set_no_lock(const PreviousPullOverData & arg) { prev_data_ = arg; }
void set_no_lock(const CollisionCheckDebugMap & arg) { collision_check_ = arg; }

std::shared_ptr<PullOverPath> pull_over_path_{nullptr};
std::shared_ptr<PullOverPath> lane_parking_pull_over_path_{nullptr};
std::vector<PullOverPath> pull_over_path_candidates_;
Expand Down
Loading