Skip to content

Commit

Permalink
fix
Browse files Browse the repository at this point in the history
style(pre-commit): autofix
  • Loading branch information
kosuke55 committed Nov 9, 2023
1 parent f0988a5 commit 9018b21
Show file tree
Hide file tree
Showing 2 changed files with 14 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -101,12 +101,10 @@ class PullOverStatus
pull_over_lanes_.clear();
lanes_.clear();
has_decided_path_ = false;
is_safe_static_objects_ = false;
is_safe_dynamic_objects_ = false;
prev_found_path_ = false;
prev_is_safe_dynamic_objects_ = false;
has_decided_velocity_ = false;
has_requested_approval_ = false;
}

DEFINE_SETTER_GETTER(std::shared_ptr<PullOverPath>, lane_parking_pull_over_path)
Expand All @@ -118,12 +116,10 @@ class PullOverStatus
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_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(Pose, refined_goal_pose)
DEFINE_SETTER_GETTER(Pose, closest_goal_candidate_pose)

Expand All @@ -137,12 +133,10 @@ class PullOverStatus
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_found_path_{false};
bool prev_is_safe_dynamic_objects_{false};
bool has_decided_velocity_{false};
bool has_requested_approval_{false};

Pose refined_goal_pose_{};
Pose closest_goal_candidate_pose_{};
Expand Down Expand Up @@ -220,6 +214,16 @@ class ThreadSafeData
return pull_over_path_->isValidPath();
}

PullOverPlannerType getPullOverPlannerType() const
{
const std::lock_guard<std::recursive_mutex> lock(mutex_);
if (!pull_over_path_) {
return PullOverPlannerType::NONE;
}

return pull_over_path_->type;
};

void reset()
{
const std::lock_guard<std::recursive_mutex> lock(mutex_);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -802,7 +802,7 @@ void GoalPlannerModule::setStopPathFromCurrentPath(BehaviorModuleOutput & output

void GoalPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) const
{
if (thread_safe_data_.get_pull_over_path()->type == PullOverPlannerType::FREESPACE) {
if (thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE) {
const double drivable_area_margin = planner_data_->parameters.vehicle_width;
output.drivable_area_info.drivable_margin =
planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin;
Expand Down Expand Up @@ -953,7 +953,7 @@ BehaviorModuleOutput GoalPlannerModule::planWithGoalModification()
path_reference_ = getPreviousModuleOutput().reference_path;

// return to lane parking if it is possible
if (thread_safe_data_.get_pull_over_path()->type == PullOverPlannerType::FREESPACE) {
if (thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE) {
returnToLaneParking();
}

Expand Down Expand Up @@ -1010,7 +1010,7 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApprovalWithGoalModification(
const auto distance_to_path_change = calcDistanceToPathChange();

// generate drivable area info for new architecture
if (thread_safe_data_.get_pull_over_path()->type == PullOverPlannerType::FREESPACE) {
if (thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE) {
const double drivable_area_margin = planner_data_->parameters.vehicle_width;
out.drivable_area_info.drivable_margin =
planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin;
Expand Down Expand Up @@ -1811,7 +1811,7 @@ void GoalPlannerModule::setDebugData()
marker.pose = thread_safe_data_.get_modified_goal_pose()
? thread_safe_data_.get_modified_goal_pose()->goal_pose
: planner_data_->self_odometry->pose.pose;
marker.text = magic_enum::enum_name(thread_safe_data_.get_pull_over_path()->type);
marker.text = magic_enum::enum_name(thread_safe_data_.getPullOverPlannerType());
marker.text += " " + std::to_string(status_.get_current_path_idx()) + "/" +
std::to_string(thread_safe_data_.get_pull_over_path()->partial_paths.size() - 1);
if (isStuck()) {
Expand Down

0 comments on commit 9018b21

Please sign in to comment.