Skip to content

Commit

Permalink
refactor(lane_change): update filtered objects only once (autowarefou…
Browse files Browse the repository at this point in the history
…ndation#8489)

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>
  • Loading branch information
zulfaqar-azmi-t4 committed Dec 18, 2024
1 parent d7cc786 commit 175ecbc
Show file tree
Hide file tree
Showing 4 changed files with 15 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,8 @@ class NormalLaneChange : public LaneChangeBase

void update_lanes(const bool is_approved) final;

void update_filtered_objects() final;

void updateLaneChangeStatus() override;

std::pair<bool, bool> getSafePath(LaneChangePath & safe_path) const override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,8 @@ class LaneChangeBase

virtual void update_lanes(const bool is_approved) = 0;

virtual void update_filtered_objects() = 0;

virtual void updateLaneChangeStatus() = 0;

virtual std::pair<bool, bool> getSafePath(LaneChangePath & safe_path) const = 0;
Expand Down Expand Up @@ -258,6 +260,7 @@ class LaneChangeBase
std::shared_ptr<LaneChangePath> abort_path_{};
std::shared_ptr<const PlannerData> planner_data_{};
lane_change::CommonDataPtr common_data_ptr_{};
FilteredByLanesExtendedObjects filtered_objects_{};
BehaviorModuleOutput prev_module_output_{};
std::optional<Pose> lane_change_stop_pose_{std::nullopt};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,7 @@ void LaneChangeInterface::updateData()
universe_utils::ScopedTimeTrack st(__func__, *getTimeKeeper());
module_type_->setPreviousModuleOutput(getPreviousModuleOutput());
module_type_->update_lanes(getCurrentStatus() == ModuleStatus::RUNNING);
module_type_->update_filtered_objects();
module_type_->updateSpecialData();

if (isWaitingApproval() || module_type_->isAbortState()) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,11 @@ void NormalLaneChange::update_lanes(const bool is_approved)
*common_data_ptr_->lanes_polygon_ptr = create_lanes_polygon(common_data_ptr_);
}

void NormalLaneChange::update_filtered_objects()
{
filtered_objects_ = filterObjects();
}

void NormalLaneChange::updateLaneChangeStatus()
{
universe_utils::ScopedTimeTrack st(__func__, *time_keeper_);
Expand Down Expand Up @@ -1430,8 +1435,7 @@ bool NormalLaneChange::getLaneChangePaths(
return false;
}

const auto filtered_objects = filterObjects();
const auto target_objects = getTargetObjects(filtered_objects, current_lanes);
const auto target_objects = getTargetObjects(filtered_objects_, current_lanes);

const auto prepare_durations = calcPrepareDuration(current_lanes, target_lanes);

Expand Down Expand Up @@ -1679,7 +1683,7 @@ bool NormalLaneChange::getLaneChangePaths(

if (
!is_stuck && !utils::lane_change::passed_parked_objects(
common_data_ptr_, *candidate_path, filtered_objects.target_lane_leading,
common_data_ptr_, *candidate_path, filtered_objects_.target_lane_leading,
lane_change_buffer, lane_change_debug_.collision_check_objects)) {
debug_print_lat(
"Reject: parking vehicle exists in the target lane, and the ego is not in stuck. Skip "
Expand Down Expand Up @@ -1860,8 +1864,7 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const
return {true, true};
}

const auto filtered_objects = filterObjects();
const auto target_objects = getTargetObjects(filtered_objects, current_lanes);
const auto target_objects = getTargetObjects(filtered_objects_, current_lanes);

CollisionCheckDebugMap debug_data;

Expand All @@ -1870,7 +1873,7 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const
common_data_ptr_->route_handler_ptr->getLateralIntervalsToPreferredLane(current_lanes.back()));

const auto has_passed_parked_objects = utils::lane_change::passed_parked_objects(
common_data_ptr_, path, filtered_objects.target_lane_leading, min_lc_length, debug_data);
common_data_ptr_, path, filtered_objects_.target_lane_leading, min_lc_length, debug_data);

if (!has_passed_parked_objects) {
RCLCPP_DEBUG(logger_, "Lane change has been delayed.");
Expand Down

0 comments on commit 175ecbc

Please sign in to comment.