Commit 91b8c62 1 parent 7bb9128 commit 91b8c62 Copy full SHA for 91b8c62
File tree 1 file changed +16
-0
lines changed
planning/behavior_path_lane_change_module/src/utils
1 file changed +16
-0
lines changed Original file line number Diff line number Diff line change 23
23
#include " behavior_path_planner_common/utils/path_utils.hpp"
24
24
#include " behavior_path_planner_common/utils/utils.hpp"
25
25
#include " object_recognition_utils/predicted_path_utils.hpp"
26
+ #include " tier4_autoware_utils/math/unit_conversion.hpp"
26
27
27
28
#include < lanelet2_extension/utility/query.hpp>
28
29
#include < lanelet2_extension/utility/utilities.hpp>
40
41
#include < tf2_ros/transform_listener.h>
41
42
42
43
#include < algorithm>
44
+ #include < iterator>
43
45
#include < limits>
46
+ #include < optional>
44
47
#include < string>
45
48
#include < vector>
46
49
@@ -385,6 +388,19 @@ std::optional<LaneChangePath> constructCandidatePath(
385
388
return std::nullopt;
386
389
}
387
390
391
+ if (prepare_segment.points .size () > 1 && shifted_path.path .points .size () > 1 ) {
392
+ const auto & prepare_segment_second_last_point =
393
+ std::prev (prepare_segment.points .end () - 1 )->point .pose ;
394
+ const auto & lane_change_start_from_shifted =
395
+ std::next (shifted_path.path .points .begin ())->point .pose ;
396
+ const auto yaw_diff2 = std::abs (tier4_autoware_utils::normalizeRadian (
397
+ tf2::getYaw (prepare_segment_second_last_point.orientation ) -
398
+ tf2::getYaw (lane_change_start_from_shifted.orientation )));
399
+ if (yaw_diff2 > tier4_autoware_utils::deg2rad (5.0 )) {
400
+ return std::nullopt;
401
+ }
402
+ }
403
+
388
404
candidate_path.path = utils::combinePath (prepare_segment, shifted_path.path );
389
405
candidate_path.shifted_path = shifted_path;
390
406
You can’t perform that action at this time.
0 commit comments