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

refactor(goal_planner): separate thread safe data #5493

Merged
merged 2 commits into from
Nov 10, 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 @@ -68,38 +68,30 @@
using behavior_path_planner::utils::path_safety_checker::TargetObjectsOnLane;
using tier4_autoware_utils::Polygon2d;

enum class PathType {
NONE = 0,
SHIFT,
ARC_FORWARD,
ARC_BACKWARD,
FREESPACE,
};
#define DEFINE_SETTER(TYPE, NAME) \
public: \
void set_##NAME(const TYPE & value) \
{ \
NAME##_ = value; \
}

#define DEFINE_SETTER_GETTER(TYPE, NAME) \
public: \
void set_##NAME(const TYPE & value) \
{ \
const std::lock_guard<std::recursive_mutex> lock(mutex_); \
NAME##_ = value; \
} \
\
TYPE get_##NAME() const \
{ \
const std::lock_guard<std::recursive_mutex> lock(mutex_); \
return NAME##_; \
#define DEFINE_GETTER(TYPE, NAME) \
public: \
TYPE get_##NAME() const \
{ \
return NAME##_; \
}

#define DEFINE_SETTER_GETTER(TYPE, NAME) \
DEFINE_SETTER(TYPE, NAME) \
DEFINE_GETTER(TYPE, NAME)

class PullOverStatus
{
public:
explicit PullOverStatus(std::recursive_mutex & mutex) : mutex_(mutex) {}

// Reset all data members to their initial states
void reset()
{
std::lock_guard<std::recursive_mutex> lock(mutex_);
pull_over_path_ = nullptr;
lane_parking_pull_over_path_ = nullptr;
current_path_idx_ = 0;
require_increment_ = true;
Expand All @@ -109,16 +101,12 @@
pull_over_lanes_.clear();
lanes_.clear();
has_decided_path_ = false;
is_safe_static_objects_ = false;
is_safe_dynamic_objects_ = false;
prev_is_safe_ = false;
prev_found_path_ = false;
prev_is_safe_dynamic_objects_ = false;
has_decided_velocity_ = false;
has_requested_approval_ = false;
is_ready_ = false;
}

DEFINE_SETTER_GETTER(std::shared_ptr<PullOverPath>, pull_over_path)
DEFINE_SETTER_GETTER(std::shared_ptr<PullOverPath>, lane_parking_pull_over_path)
DEFINE_SETTER_GETTER(size_t, current_path_idx)
DEFINE_SETTER_GETTER(bool, require_increment)
Expand All @@ -128,24 +116,14 @@
DEFINE_SETTER_GETTER(lanelet::ConstLanelets, pull_over_lanes)
DEFINE_SETTER_GETTER(std::vector<DrivableLanes>, lanes)
DEFINE_SETTER_GETTER(bool, has_decided_path)
DEFINE_SETTER_GETTER(bool, is_safe_static_objects)
DEFINE_SETTER_GETTER(bool, is_safe_dynamic_objects)
DEFINE_SETTER_GETTER(bool, prev_is_safe)
DEFINE_SETTER_GETTER(bool, prev_found_path)
DEFINE_SETTER_GETTER(bool, prev_is_safe_dynamic_objects)
DEFINE_SETTER_GETTER(bool, has_decided_velocity)
DEFINE_SETTER_GETTER(bool, has_requested_approval)
DEFINE_SETTER_GETTER(bool, is_ready)
DEFINE_SETTER_GETTER(std::shared_ptr<rclcpp::Time>, last_increment_time)
DEFINE_SETTER_GETTER(std::shared_ptr<rclcpp::Time>, last_path_update_time)
DEFINE_SETTER_GETTER(std::optional<GoalCandidate>, modified_goal_pose)
DEFINE_SETTER_GETTER(Pose, refined_goal_pose)
DEFINE_SETTER_GETTER(GoalCandidates, goal_candidates)
DEFINE_SETTER_GETTER(Pose, closest_goal_candidate_pose)
DEFINE_SETTER_GETTER(std::vector<PullOverPath>, pull_over_path_candidates)
DEFINE_SETTER_GETTER(std::optional<Pose>, closest_start_pose)

private:
std::shared_ptr<PullOverPath> pull_over_path_{nullptr};
std::shared_ptr<PullOverPath> lane_parking_pull_over_path_{nullptr};
size_t current_path_idx_{0};
bool require_increment_{true};
Expand All @@ -155,32 +133,134 @@
lanelet::ConstLanelets pull_over_lanes_{};
std::vector<DrivableLanes> lanes_{};
bool has_decided_path_{false};
bool is_safe_static_objects_{false};
bool is_safe_dynamic_objects_{false};
bool prev_is_safe_{false};
bool prev_found_path_{false};
bool prev_is_safe_dynamic_objects_{false};
bool has_decided_velocity_{false};
bool has_requested_approval_{false};
bool is_ready_{false};

// save last time and pose
std::shared_ptr<rclcpp::Time> last_increment_time_;
std::shared_ptr<rclcpp::Time> last_path_update_time_;

// goal modification
std::optional<GoalCandidate> modified_goal_pose_;
Pose refined_goal_pose_{};
GoalCandidates goal_candidates_{};
Pose closest_goal_candidate_pose_{};
};

#undef DEFINE_SETTER
#undef DEFINE_GETTER
#undef DEFINE_SETTER_GETTER

#define DEFINE_SETTER_WITH_MUTEX(TYPE, NAME) \
public: \
void set_##NAME(const TYPE & value) \
{ \
const std::lock_guard<std::recursive_mutex> lock(mutex_); \
NAME##_ = value; \
}

#define DEFINE_GETTER_WITH_MUTEX(TYPE, NAME) \
public: \
TYPE get_##NAME() const \
{ \
const std::lock_guard<std::recursive_mutex> lock(mutex_); \
return NAME##_; \
}

#define DEFINE_SETTER_GETTER_WITH_MUTEX(TYPE, NAME) \
DEFINE_SETTER_WITH_MUTEX(TYPE, NAME) \
DEFINE_GETTER_WITH_MUTEX(TYPE, NAME)

class ThreadSafeData
{
public:
ThreadSafeData(std::recursive_mutex & mutex, rclcpp::Clock::SharedPtr clock)
: mutex_(mutex), clock_(clock)
{
}

bool incrementPathIndex()

Check warning on line 177 in planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp#L177

Added line #L177 was not covered by tests
{
const std::lock_guard<std::recursive_mutex> lock(mutex_);

Check warning on line 179 in planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp#L179

Added line #L179 was not covered by tests
if (pull_over_path_->incrementPathIndex()) {
last_path_idx_increment_time_ = clock_->now();
return true;

Check warning on line 182 in planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp#L182

Added line #L182 was not covered by tests
}
return false;
}

void set_pull_over_path(const PullOverPath & value)

Check warning on line 187 in planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp#L187

Added line #L187 was not covered by tests
{
const std::lock_guard<std::recursive_mutex> lock(mutex_);

Check warning on line 189 in planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp#L189

Added line #L189 was not covered by tests
pull_over_path_ = std::make_shared<PullOverPath>(value);
last_path_update_time_ = clock_->now();
}

Check warning on line 192 in planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp#L192

Added line #L192 was not covered by tests

void set_pull_over_path(const std::shared_ptr<PullOverPath> & value)

Check warning on line 194 in planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp#L194

Added line #L194 was not covered by tests
{
const std::lock_guard<std::recursive_mutex> lock(mutex_);

Check warning on line 196 in planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp#L196

Added line #L196 was not covered by tests
pull_over_path_ = value;
last_path_update_time_ = clock_->now();
}

Check warning on line 199 in planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp#L199

Added line #L199 was not covered by tests

void clearPullOverPath()

Check warning on line 201 in planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp#L201

Added line #L201 was not covered by tests
{
const std::lock_guard<std::recursive_mutex> lock(mutex_);

Check warning on line 203 in planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp#L203

Added line #L203 was not covered by tests
pull_over_path_ = nullptr;
}

Check warning on line 205 in planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp#L205

Added line #L205 was not covered by tests

bool foundPullOverPath() const

Check warning on line 207 in planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp#L207

Added line #L207 was not covered by tests
{
const std::lock_guard<std::recursive_mutex> lock(mutex_);

Check warning on line 209 in planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp#L209

Added line #L209 was not covered by tests
if (!pull_over_path_) {
return false;
}

return pull_over_path_->isValidPath();

Check warning on line 214 in planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp#L214

Added line #L214 was not covered by tests
}

PullOverPlannerType getPullOverPlannerType() const

Check warning on line 217 in planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp#L217

Added line #L217 was not covered by tests
{
const std::lock_guard<std::recursive_mutex> lock(mutex_);

Check warning on line 219 in planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp#L219

Added line #L219 was not covered by tests
if (!pull_over_path_) {
return PullOverPlannerType::NONE;
}

return pull_over_path_->type;

Check warning on line 224 in planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp#L224

Added line #L224 was not covered by tests
};

// pull over path
void reset()
{
const std::lock_guard<std::recursive_mutex> lock(mutex_);
pull_over_path_ = nullptr;
pull_over_path_candidates_.clear();
goal_candidates_.clear();
modified_goal_pose_ = std::nullopt;
last_path_update_time_ = std::nullopt;
last_path_idx_increment_time_ = std::nullopt;
closest_start_pose_ = std::nullopt;
}

DEFINE_GETTER_WITH_MUTEX(std::shared_ptr<PullOverPath>, pull_over_path)
DEFINE_GETTER_WITH_MUTEX(std::optional<rclcpp::Time>, last_path_update_time)
DEFINE_GETTER_WITH_MUTEX(std::optional<rclcpp::Time>, last_path_idx_increment_time)

Check warning on line 241 in planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp#L239-L241

Added lines #L239 - L241 were not covered by tests

DEFINE_SETTER_GETTER_WITH_MUTEX(std::vector<PullOverPath>, pull_over_path_candidates)
DEFINE_SETTER_GETTER_WITH_MUTEX(GoalCandidates, goal_candidates)
DEFINE_SETTER_GETTER_WITH_MUTEX(std::optional<GoalCandidate>, modified_goal_pose)
DEFINE_SETTER_GETTER_WITH_MUTEX(std::optional<Pose>, closest_start_pose)

private:
std::shared_ptr<PullOverPath> pull_over_path_{nullptr};
std::vector<PullOverPath> pull_over_path_candidates_;
std::optional<Pose> closest_start_pose_;
GoalCandidates goal_candidates_{};
std::optional<GoalCandidate> modified_goal_pose_;
std::optional<rclcpp::Time> last_path_update_time_;
std::optional<rclcpp::Time> last_path_idx_increment_time_;
std::optional<Pose> closest_start_pose_{};

std::recursive_mutex & mutex_;
rclcpp::Clock::SharedPtr clock_;
};

#undef DEFINE_SETTER_GETTER
#undef DEFINE_SETTER_WITH_MUTEX
#undef DEFINE_GETTER_WITH_MUTEX
#undef DEFINE_SETTER_GETTER_WITH_MUTEX

struct FreespacePlannerDebugData
{
Expand Down Expand Up @@ -276,6 +356,7 @@

std::recursive_mutex mutex_;
PullOverStatus status_;
ThreadSafeData thread_safe_data_;

std::unique_ptr<LastApprovalData> last_approval_data_{nullptr};

Expand Down Expand Up @@ -329,6 +410,7 @@
bool isStuck();
bool hasDecidedPath() const;
void decideVelocity();
bool foundPullOverPath() const;

// validation
bool hasEnoughDistance(const PullOverPath & pull_over_path) const;
Expand All @@ -352,8 +434,6 @@
const GoalCandidates & goal_candidates) const;

// deal with pull over partial paths
PathWithLaneId getCurrentPath() const;
bool incrementPathIndex();
void transitionToNextPathIfFinishingCurrentPath();

// lanes and drivable area
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@
{
PullOverPlannerType type{PullOverPlannerType::NONE};
std::vector<PathWithLaneId> partial_paths{};
size_t path_idx{0};
// accelerate with constant acceleration to the target velocity
std::vector<std::pair<double, double>> pairs_terminal_velocity_and_accel{};
Pose start_pose{};
Expand Down Expand Up @@ -84,6 +85,27 @@

return parking_path;
}

PathWithLaneId getCurrentPath() const
{
if (partial_paths.empty()) {
return PathWithLaneId{};
} else if (partial_paths.size() <= path_idx) {
return partial_paths.back();

Check warning on line 94 in planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp#L94

Added line #L94 was not covered by tests
}
return partial_paths.at(path_idx);

Check warning on line 96 in planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp#L96

Added line #L96 was not covered by tests
}

bool incrementPathIndex()
{
if (partial_paths.size() - 1 <= path_idx) {
return false;
}
path_idx += 1;
return true;
}

bool isValidPath() const { return type != PullOverPlannerType::NONE; }

Check warning on line 108 in planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/utils/goal_planner/pull_over_planner_base.hpp#L108

Added line #L108 was not covered by tests
};

class PullOverPlannerBase
Expand Down
Loading
Loading