Skip to content

Commit c7d8f2c

Browse files
committed
resolve merge conflict
1 parent 2c765a9 commit c7d8f2c

File tree

2 files changed

+2
-23
lines changed

2 files changed

+2
-23
lines changed

planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -456,7 +456,8 @@ class GoalPlannerModule : public SceneModuleInterface
456456

457457
// output setter
458458
void setOutput(BehaviorModuleOutput & output);
459-
void updatePreviousData();
459+
void setStopPath(BehaviorModuleOutput & output) const;
460+
void updatePreviousData(const BehaviorModuleOutput & output);
460461

461462
/**
462463
* @brief Sets a stop path in the current path based on safety conditions and previous paths.

planning/behavior_path_lane_change_module/src/scene.cpp

-22
Original file line numberDiff line numberDiff line change
@@ -1451,28 +1451,6 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const
14511451
return safety_status;
14521452
}
14531453

1454-
PathSafetyStatus NormalLaneChange::evaluateApprovedPathWithUnsafeHysteresis(
1455-
PathSafetyStatus approved_path_safety_status)
1456-
{
1457-
if (!approved_path_safety_status.is_safe) {
1458-
++unsafe_hysteresis_count_;
1459-
RCLCPP_DEBUG(
1460-
logger_, "%s: Increasing hysteresis count to %d.", __func__, unsafe_hysteresis_count_);
1461-
} else {
1462-
if (unsafe_hysteresis_count_ > 0) {
1463-
RCLCPP_DEBUG(logger_, "%s: Lane change is now SAFE. Resetting hysteresis count.", __func__);
1464-
}
1465-
unsafe_hysteresis_count_ = 0;
1466-
}
1467-
if (unsafe_hysteresis_count_ > lane_change_parameters_->cancel.unsafe_hysteresis_threshold) {
1468-
RCLCPP_DEBUG(
1469-
logger_, "%s: hysteresis count exceed threshold. lane change is now %s", __func__,
1470-
(approved_path_safety_status.is_safe ? "safe" : "UNSAFE"));
1471-
return approved_path_safety_status;
1472-
}
1473-
return {};
1474-
}
1475-
14761454
bool NormalLaneChange::isValidPath(const PathWithLaneId & path) const
14771455
{
14781456
const auto & route_handler = planner_data_->route_handler;

0 commit comments

Comments
 (0)