Skip to content

Commit

Permalink
experiment branch for lane change combined expriment
Browse files Browse the repository at this point in the history
feat(behavior_path_planner): revise lane change module (#1139)

* feat(behavior_path_planner): revise lane change module

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

Refactoring and renaming

Remove some of the unused variables

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

Add longitudinal threshold and modify default param

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

fix error after rebase

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

* refactor and copy predicted if not empty

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

* Include abort parameters and reorganize parameters declaration

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

feat(behavior_path_planner): lane change revised visualization (#1140)

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

change force lane change path color

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

visualize ego polygon with respect to object using same color

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

Add valid path's visualization

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

fix conflicts

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

fix(behavior_path_planner): lane change ego and target polygon pose (autowarefoundation#1786)

* fix(behavior_path_planner): lane change ego and target polygon pose

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

* reduce lane changing duration

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

* refactor(behavior_path_planner): lane change refactoring

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>
Co-authored-by: Fumiya Watanabe <[email protected]>
Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

fix(behavior_path_planner): fix lane change logic on the edge case

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

fix pose init and add failed reasons

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

Ignore prepare distance if object is static

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

revert the lerp by time stamp

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

feat(behavior_path_planner): debug message for lane change

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

with param server

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

with abort

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

Improved abort function

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

fix(behavior_path_planner): minimum distance for lane change

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>

Added keiro seisei

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>
  • Loading branch information
zulfaqar-azmi-t4 committed Dec 14, 2022
1 parent aee2610 commit b6aab81
Show file tree
Hide file tree
Showing 45 changed files with 3,392 additions and 732 deletions.
106 changes: 106 additions & 0 deletions common/motion_utils/include/motion_utils/trajectory/trajectory.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -1012,6 +1012,112 @@ inline boost::optional<size_t> insertStopPoint(

return stop_idx;
}

template <class T>
size_t findFirstNearestIndexWithSoftConstraints(
const T & points, const geometry_msgs::msg::Pose & pose,
const double dist_threshold = std::numeric_limits<double>::max(),
const double yaw_threshold = std::numeric_limits<double>::max())
{
validateNonEmpty(points);

{ // with dist and yaw thresholds
const double squared_dist_threshold = dist_threshold * dist_threshold;
double min_squared_dist = std::numeric_limits<double>::max();
size_t min_idx = 0;
bool is_within_constraints = false;
for (size_t i = 0; i < points.size(); ++i) {
const auto squared_dist =
tier4_autoware_utils::calcSquaredDistance2d(points.at(i), pose.position);
const auto yaw =
tier4_autoware_utils::calcYawDeviation(tier4_autoware_utils::getPose(points.at(i)), pose);

if (squared_dist_threshold < squared_dist || yaw_threshold < std::abs(yaw)) {
if (is_within_constraints) {
break;
} else {
continue;
}
}

if (min_squared_dist <= squared_dist) {
continue;
}

min_squared_dist = squared_dist;
min_idx = i;
is_within_constraints = true;
}

// nearest index is found
if (is_within_constraints) {
return min_idx;
}
}

{ // with dist threshold
const double squared_dist_threshold = dist_threshold * dist_threshold;
double min_squared_dist = std::numeric_limits<double>::max();
size_t min_idx = 0;
bool is_within_constraints = false;
for (size_t i = 0; i < points.size(); ++i) {
const auto squared_dist =
tier4_autoware_utils::calcSquaredDistance2d(points.at(i), pose.position);

if (squared_dist_threshold < squared_dist) {
if (is_within_constraints) {
break;
} else {
continue;
}
}

if (min_squared_dist <= squared_dist) {
continue;
}

min_squared_dist = squared_dist;
min_idx = i;
is_within_constraints = true;
}

// nearest index is found
if (is_within_constraints) {
return min_idx;
}
}

// without any threshold
return findNearestIndex(points, pose.position);
}

template <class T>
size_t findFirstNearestSegmentIndexWithSoftConstraints(
const T & points, const geometry_msgs::msg::Pose & pose,
const double dist_threshold = std::numeric_limits<double>::max(),
const double yaw_threshold = std::numeric_limits<double>::max())
{
// find first nearest index with soft constraints (not segment index)
const size_t nearest_idx =
findFirstNearestIndexWithSoftConstraints(points, pose, dist_threshold, yaw_threshold);

// calculate segment index
if (nearest_idx == 0) {
return 0;
}
if (nearest_idx == points.size() - 1) {
return points.size() - 2;
}

const double signed_length = calcLongitudinalOffsetToSegment(points, nearest_idx, pose.position);

if (signed_length <= 0) {
return nearest_idx - 1;
}

return nearest_idx;
}

} // namespace motion_utils

#endif // MOTION_UTILS__TRAJECTORY__TRAJECTORY_HPP_
2 changes: 2 additions & 0 deletions planning/behavior_path_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,13 +22,15 @@ ament_auto_add_library(behavior_path_planner_node SHARED
src/scene_module/lane_following/lane_following_module.cpp
src/scene_module/lane_change/lane_change_module.cpp
src/scene_module/lane_change/util.cpp
src/scene_module/lane_change/debug.cpp
src/scene_module/pull_over/pull_over_module.cpp
src/scene_module/pull_over/util.cpp
src/scene_module/pull_out/pull_out_module.cpp
src/scene_module/pull_out/util.cpp
src/scene_module/utils/geometric_parallel_parking.cpp
src/scene_module/utils/occupancy_grid_based_collision_detector.cpp
src/scene_module/utils/path_shifter.cpp
src/scene_module/scene_module_visitor.cpp
)

target_include_directories(behavior_path_planner_node SYSTEM PUBLIC
Expand Down
Loading

0 comments on commit b6aab81

Please sign in to comment.