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

feat(behavior_path_planner): remove redundant process (#4077) #622

Merged
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 @@ -83,6 +83,8 @@ class LaneChangeBase

virtual bool hasFinishedAbort() const = 0;

virtual bool isLaneChangeRequired() const = 0;

virtual bool isAbortState() const = 0;

virtual bool isAbleToReturnCurrentLane() const = 0;
Expand Down Expand Up @@ -193,7 +195,7 @@ class LaneChangeBase
virtual bool getLaneChangePaths(
const lanelet::ConstLanelets & original_lanelets,
const lanelet::ConstLanelets & target_lanelets, Direction direction,
LaneChangePaths * candidate_paths) const = 0;
LaneChangePaths * candidate_paths, const bool check_safety) const = 0;

virtual std::vector<DrivableLanes> getDrivableLanes() const = 0;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,8 @@ class NormalLaneChange : public LaneChangeBase

bool isAbortState() const override;

bool isLaneChangeRequired() const override;

protected:
lanelet::ConstLanelets getCurrentLanes() const override;

Expand All @@ -96,7 +98,7 @@ class NormalLaneChange : public LaneChangeBase
bool getLaneChangePaths(
const lanelet::ConstLanelets & original_lanelets,
const lanelet::ConstLanelets & target_lanelets, Direction direction,
LaneChangePaths * candidate_paths) const override;
LaneChangePaths * candidate_paths, const bool check_safety = true) const override;

std::vector<DrivableLanes> getDrivableLanes() const override;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,22 +67,12 @@ bool LaneChangeInterface::isExecutionRequested() const
return true;
}

LaneChangePath selected_path;
module_type_->setPreviousModulePaths(
getPreviousModuleOutput().reference_path, getPreviousModuleOutput().path);
const auto [found_valid_path, found_safe_path] = module_type_->getSafePath(selected_path);

return found_valid_path;
return module_type_->isLaneChangeRequired();
}

bool LaneChangeInterface::isExecutionReady() const
{
LaneChangePath selected_path;
module_type_->setPreviousModulePaths(
getPreviousModuleOutput().reference_path, getPreviousModuleOutput().path);
const auto [found_valid_path, found_safe_path] = module_type_->getSafePath(selected_path);

return found_safe_path;
return module_type_->isSafe();
}

ModuleStatus LaneChangeInterface::updateState()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,28 @@ std::pair<bool, bool> NormalLaneChange::getSafePath(LaneChangePath & safe_path)
return {true, found_safe_path};
}

bool NormalLaneChange::isLaneChangeRequired() const
{
const auto current_lanes = getCurrentLanes();

if (current_lanes.empty()) {
return false;
}

const auto target_lanes = getLaneChangeLanes(current_lanes, direction_);

if (target_lanes.empty()) {
return false;
}

// find candidate paths
LaneChangePaths valid_paths{};
[[maybe_unused]] const auto found_safe_path =
getLaneChangePaths(current_lanes, target_lanes, direction_, &valid_paths, false);

return !valid_paths.empty();
}

LaneChangePath NormalLaneChange::getLaneChangePath() const
{
return isAbortState() ? *abort_path_ : status_.lane_change_path;
Expand Down Expand Up @@ -397,7 +419,7 @@ PathWithLaneId NormalLaneChange::getPrepareSegment(

bool NormalLaneChange::getLaneChangePaths(
const lanelet::ConstLanelets & original_lanelets, const lanelet::ConstLanelets & target_lanelets,
Direction direction, LaneChangePaths * candidate_paths) const
Direction direction, LaneChangePaths * candidate_paths, const bool check_safety) const
{
object_debug_.clear();
if (original_lanelets.empty() || target_lanelets.empty()) {
Expand Down Expand Up @@ -648,6 +670,10 @@ bool NormalLaneChange::getLaneChangePaths(
}
candidate_paths->push_back(*candidate_path);

if (!check_safety) {
return false;
}

const auto [is_safe, is_object_coming_from_rear] = utils::lane_change::isLaneChangePathSafe(
*candidate_path, dynamic_objects, dynamic_object_indices, getEgoPose(), getEgoTwist(),
common_parameter, *lane_change_parameters_, common_parameter.expected_front_deceleration,
Expand Down
Loading