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(lane_change): change prev info to non pointer #3659

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 @@ -57,10 +57,6 @@ class LaneChangeBase
Direction direction)
: lane_change_parameters_{std::move(parameters)}, direction_{direction}, type_{type}
{
prev_module_reference_path_ = std::make_shared<PathWithLaneId>();
prev_module_path_ = std::make_shared<PathWithLaneId>();
prev_drivable_area_info_ = std::make_shared<DrivableAreaInfo>();
prev_turn_signal_info_ = std::make_shared<TurnSignalInfo>();
}

LaneChangeBase(const LaneChangeBase &) = delete;
Expand Down Expand Up @@ -94,23 +90,21 @@ class LaneChangeBase
const std::shared_ptr<PathWithLaneId> & prev_module_path)
{
if (prev_module_reference_path) {
*prev_module_reference_path_ = *prev_module_reference_path;
prev_module_reference_path_ = *prev_module_reference_path;
}
if (prev_module_path) {
*prev_module_path_ = *prev_module_path;
prev_module_path_ = *prev_module_path;
}
};

virtual void setPreviousDrivableAreaInfo(const DrivableAreaInfo & prev_drivable_area_info)
{
if (prev_drivable_area_info_) {
*prev_drivable_area_info_ = prev_drivable_area_info;
}
prev_drivable_area_info_ = prev_drivable_area_info;
}

virtual void setPreviousTurnSignalInfo(const TurnSignalInfo & prev_turn_signal_info)
{
*prev_turn_signal_info_ = prev_turn_signal_info;
prev_turn_signal_info_ = prev_turn_signal_info;
}

virtual void updateSpecialData() {}
Expand Down Expand Up @@ -235,10 +229,10 @@ class LaneChangeBase
std::shared_ptr<LaneChangeParameters> lane_change_parameters_{};
std::shared_ptr<LaneChangePath> abort_path_{};
std::shared_ptr<const PlannerData> planner_data_{};
std::shared_ptr<PathWithLaneId> prev_module_reference_path_{};
std::shared_ptr<PathWithLaneId> prev_module_path_{};
std::shared_ptr<DrivableAreaInfo> prev_drivable_area_info_{};
std::shared_ptr<TurnSignalInfo> prev_turn_signal_info_{};
PathWithLaneId prev_module_reference_path_{};
PathWithLaneId prev_module_path_{};
DrivableAreaInfo prev_drivable_area_info_{};
TurnSignalInfo prev_turn_signal_info_{};

PathWithLaneId prev_approved_path_{};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ AvoidancePlanningData AvoidanceByLaneChange::calcAvoidancePlanningData(
// reference pose
data.reference_pose = getEgoPose();

data.reference_path_rough = *prev_module_path_;
data.reference_path_rough = prev_module_path_;

const auto resample_interval =
avoidance_by_lane_change_parameters_->avoidance->resample_interval_for_planning;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -105,13 +105,9 @@ BehaviorModuleOutput NormalLaneChange::generateOutput()
output.reference_path = std::make_shared<PathWithLaneId>(getReferencePath());
output.turn_signal_info = updateOutputTurnSignal();

if (!prev_turn_signal_info_) {
return output;
}

const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path->points);
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
*output.path, getEgoPose(), current_seg_idx, *prev_turn_signal_info_, output.turn_signal_info,
*output.path, getEgoPose(), current_seg_idx, prev_turn_signal_info_, output.turn_signal_info,
planner_data_->parameters.ego_nearest_dist_threshold,
planner_data_->parameters.ego_nearest_yaw_threshold);

Expand All @@ -132,12 +128,8 @@ void NormalLaneChange::extendOutputDrivableArea(BehaviorModuleOutput & output)
// for new architecture
DrivableAreaInfo current_drivable_area_info;
current_drivable_area_info.drivable_lanes = expanded_lanes;
if (prev_drivable_area_info_) {
output.drivable_area_info =
utils::combineDrivableAreaInfo(current_drivable_area_info, *prev_drivable_area_info_);
} else {
output.drivable_area_info = current_drivable_area_info;
}
output.drivable_area_info =
utils::combineDrivableAreaInfo(current_drivable_area_info, prev_drivable_area_info_);

// for old architecture
utils::generateDrivableArea(
Expand Down Expand Up @@ -249,7 +241,7 @@ TurnSignalInfo NormalLaneChange::updateOutputTurnSignal()

lanelet::ConstLanelets NormalLaneChange::getCurrentLanes() const
{
return utils::getCurrentLanesFromPath(*prev_module_reference_path_, planner_data_);
return utils::getCurrentLanesFromPath(prev_module_reference_path_, planner_data_);
}

lanelet::ConstLanelets NormalLaneChange::getLaneChangeLanes(
Expand Down Expand Up @@ -301,7 +293,7 @@ PathWithLaneId NormalLaneChange::getPrepareSegment(
return PathWithLaneId();
}

auto prepare_segment = *prev_module_path_;
auto prepare_segment = prev_module_path_;
const size_t current_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
prepare_segment.points, getEgoPose(), 3.0, 1.0);
utils::clipPathLength(prepare_segment, current_seg_idx, prepare_length, backward_path_length);
Expand Down Expand Up @@ -538,7 +530,7 @@ std::vector<DrivableLanes> NormalLaneChange::getDrivableLanes() const
{
const auto drivable_lanes = utils::lane_change::generateDrivableLanes(
*getRouteHandler(), status_.current_lanes, status_.lane_change_lanes);
return utils::combineDrivableLanes(prev_drivable_area_info_->drivable_lanes, drivable_lanes);
return utils::combineDrivableLanes(prev_drivable_area_info_.drivable_lanes, drivable_lanes);
}

bool NormalLaneChange::isApprovedPathSafe(Pose & ego_pose_before_collision) const
Expand Down