Skip to content

Commit

Permalink
fix(lane_change): orientation check when constructing path
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 Feb 6, 2024
1 parent bd4b5ca commit 3043812
Showing 1 changed file with 16 additions and 0 deletions.
16 changes: 16 additions & 0 deletions planning/behavior_path_lane_change_module/src/utils/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include "behavior_path_planner_common/utils/path_utils.hpp"
#include "behavior_path_planner_common/utils/utils.hpp"
#include "object_recognition_utils/predicted_path_utils.hpp"
#include "tier4_autoware_utils/math/unit_conversion.hpp"

#include <lanelet2_extension/utility/query.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
Expand All @@ -40,7 +41,9 @@
#include <tf2_ros/transform_listener.h>

#include <algorithm>
#include <iterator>
#include <limits>
#include <optional>
#include <string>
#include <vector>

Expand Down Expand Up @@ -385,6 +388,19 @@ std::optional<LaneChangePath> constructCandidatePath(
return std::nullopt;
}

if (prepare_segment.points.size() > 1 && shifted_path.path.points.size() > 1) {
const auto & prepare_segment_second_last_point =
std::prev(prepare_segment.points.end() - 1)->point.pose;
const auto & lane_change_start_from_shifted =
std::next(shifted_path.path.points.begin())->point.pose;
const auto yaw_diff2 = std::abs(tier4_autoware_utils::normalizeRadian(
tf2::getYaw(prepare_segment_second_last_point.orientation) -
tf2::getYaw(lane_change_start_from_shifted.orientation)));
if (yaw_diff2 > tier4_autoware_utils::deg2rad(5.0)) {
return std::nullopt;
}
}

candidate_path.path = utils::combinePath(prepare_segment, shifted_path.path);
candidate_path.shifted_path = shifted_path;

Expand Down

0 comments on commit 3043812

Please sign in to comment.