Skip to content

Commit

Permalink
fix conflict
Browse files Browse the repository at this point in the history
Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>
  • Loading branch information
zulfaqar-azmi-t4 committed Nov 7, 2023
1 parent 6852936 commit 64a80d8
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 9 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -136,8 +136,7 @@ class NormalLaneChange : public LaneChangeBase
const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes) const;

bool hasEnoughLengthToTrafficLight(
const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes,
lanelet::Id & traffic_light_id) const;
const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes) const;

bool getLaneChangePaths(
const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include "behavior_path_planner/utils/path_safety_checker/objects_filtering.hpp"
#include "behavior_path_planner/utils/path_safety_checker/safety_check.hpp"
#include "behavior_path_planner/utils/path_utils.hpp"
#include "behavior_path_planner/utils/traffic_light_utils.hpp"
#include "behavior_path_planner/utils/utils.hpp"

#include <lanelet2_extension/utility/message_conversion.hpp>
Expand All @@ -38,6 +39,7 @@
namespace behavior_path_planner
{
using motion_utils::calcSignedArcLength;
using utils::traffic_light::getDistanceToNextTrafficLight;

NormalLaneChange::NormalLaneChange(
const std::shared_ptr<LaneChangeParameters> & parameters, LaneChangeModuleType type,
Expand Down Expand Up @@ -1082,13 +1084,11 @@ bool NormalLaneChange::hasEnoughLengthToIntersection(
}

bool NormalLaneChange::hasEnoughLengthToTrafficLight(
const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes,
lanelet::Id & traffic_light_id) const
const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes) const
{
const auto current_pose = getEgoPose();
const auto [next_traffic_light_id, dist_to_next_traffic_light] =
utils::getDistanceToNextTrafficLight(current_pose, current_lanes);
traffic_light_id = next_traffic_light_id;
const auto dist_to_next_traffic_light =
getDistanceToNextTrafficLight(current_pose, current_lanes);
const auto dist_to_next_traffic_light_from_lc_start_pose =
dist_to_next_traffic_light - path.info.length.prepare;

Expand Down Expand Up @@ -1355,10 +1355,9 @@ bool NormalLaneChange::getLaneChangePaths(
logger_, "Stop time is over threshold. Allow lane change in intersection.");
}

auto traffic_light_id = lanelet::InvalId;
if (
lane_change_parameters_->regulate_on_traffic_light &&
!hasEnoughLengthToTrafficLight(*candidate_path, current_lanes, traffic_light_id)) {
!hasEnoughLengthToTrafficLight(*candidate_path, current_lanes)) {
continue;
}

Expand Down

0 comments on commit 64a80d8

Please sign in to comment.