Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

perf(lane_change): path stability and correctness #1720

Merged
merged 29 commits into from
Dec 23, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
29 commits
Select commit Hold shift + click to select a range
bc555c5
feat(lane_change): add checks to ensure the edge of vehicle do not ex…
mkquda Sep 20, 2024
9beabb6
feat(lane_change): ensure LC merging lane stop point is safe (#8369)
mkquda Aug 16, 2024
7cef47d
refactor(lane_change): refactor getLaneChangePaths function (#8909)
mkquda Sep 25, 2024
b62a71f
refactor(lane_change): add TransientData to store commonly used lane …
zulfaqar-azmi-t4 Sep 27, 2024
5c1fa6c
fix(lane_change): fix abort distance enough check (#8979)
zulfaqar-azmi-t4 Sep 27, 2024
4765981
refactor(lane_change): refactor code using transient data (#8997)
mkquda Oct 3, 2024
88352a1
refactor(lane_change): replace any code that can use transient data (…
zulfaqar-azmi-t4 Oct 4, 2024
284525d
refactor(lane_change): refactor get_lane_change_lanes function (#9044)
zulfaqar-azmi-t4 Oct 7, 2024
f76dac0
fix(lane_change): insert stop for current lanes object (RT0-33761) (…
zulfaqar-azmi-t4 Oct 11, 2024
33a2213
refactor(lane_change): reducing clang-tidy warnings (#9085)
zulfaqar-azmi-t4 Oct 17, 2024
983e95e
fix(lane_change): enable cancel when ego in turn direction lane (#9124)
zulfaqar-azmi-t4 Nov 7, 2024
11f21b3
style(pre-commit): autofix
pre-commit-ci[bot] Dec 20, 2024
03d49c5
fix(lane_change): correct computation of maximum lane changing length…
mkquda Nov 11, 2024
39a6625
fix(lane_change): extending lane change path for multiple lane change…
zulfaqar-azmi-t4 Nov 11, 2024
114f8d6
refactor(lane_change): remove std::optional from lanes polygon (#9288)
zulfaqar-azmi-t4 Nov 12, 2024
0b50120
refactor(lane_change): separate target lane leading based on obj beha…
zulfaqar-azmi-t4 Nov 22, 2024
ae4acf2
feat(lane_change): add unit test for normal lane change class (RT1-79…
zulfaqar-azmi-t4 Oct 21, 2024
e60ed8a
refactor(lane_change): refactor longitudinal acceleration sampling (#…
mkquda Oct 23, 2024
6115e7b
feat(lane_change): modify lane change target boundary check to consid…
mkquda Sep 27, 2024
7d080e3
refactor(lane_change): refactor lane change parameters (#9403)
mkquda Nov 26, 2024
fa3b398
fix(autoware_behavior_path_lane_change_module): fix clang-diagnostic-…
kobayu858 Nov 26, 2024
f82e01f
fix(autoware_behavior_path_lane_change_module): fix clang-diagnostic-…
kobayu858 Nov 26, 2024
3bfd52b
fix(autoware_behavior_path_lane_change_module): fix clang-diagnostic-…
kobayu858 Nov 28, 2024
31eec09
feat(lane_change): improve delay lane change logic (#9480)
mkquda Nov 28, 2024
f935b5a
feat(lane_changing): improve computation of lane changing acceleratio…
mkquda Dec 4, 2024
3791695
feat(lane_change): reduce prepare duration when blinker has been acti…
mkquda Dec 5, 2024
ec210a2
fix(lane_change): check obj predicted path when filtering (#9385)
zulfaqar-azmi-t4 Dec 9, 2024
491c3f5
fix(lane_change): remove overlapping preceding lanes (#9526)
zulfaqar-azmi-t4 Dec 12, 2024
066279a
refactor(lane_change): separate structs to different folders (#9625)
zulfaqar-azmi-t4 Dec 12, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -324,6 +324,9 @@ class RouteHandler
lanelet::ConstLanelets getShoulderLaneletsAtPose(const Pose & pose) const;
lanelet::ConstPolygon3d getIntersectionAreaById(const lanelet::Id id) const;

Pose get_pose_from_2d_arc_length(
const lanelet::ConstLanelets & lanelet_sequence, const double s) const;

private:
// MUST
lanelet::routing::RoutingGraphPtr routing_graph_ptr_;
Expand Down
27 changes: 27 additions & 0 deletions planning/autoware_route_handler/src/route_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,8 @@ namespace autoware::route_handler
{
namespace
{
using autoware::universe_utils::createPoint;
using autoware::universe_utils::createQuaternionFromYaw;
using autoware_planning_msgs::msg::LaneletPrimitive;
using autoware_planning_msgs::msg::Path;
using geometry_msgs::msg::Pose;
Expand Down Expand Up @@ -2225,4 +2227,29 @@ std::optional<lanelet::routing::LaneletPath> RouteHandler::findDrivableLanePath(
if (route) return route->shortestPath();
return {};
}

Pose RouteHandler::get_pose_from_2d_arc_length(
const lanelet::ConstLanelets & lanelet_sequence, const double s) const
{
double accumulated_distance2d = 0;
for (const auto & llt : lanelet_sequence) {
const auto & centerline = llt.centerline();
for (auto it = centerline.begin(); std::next(it) != centerline.end(); ++it) {
const auto pt = *it;
const auto next_pt = *std::next(it);
const double distance2d = lanelet::geometry::distance2d(to2D(pt), to2D(next_pt));
if (accumulated_distance2d + distance2d > s) {
const double ratio = (s - accumulated_distance2d) / distance2d;
const auto interpolated_pt = pt.basicPoint() * (1 - ratio) + next_pt.basicPoint() * ratio;
const auto yaw = std::atan2(next_pt.y() - pt.y(), next_pt.x() - pt.x());
Pose pose;
pose.position = createPoint(interpolated_pt.x(), interpolated_pt.y(), interpolated_pt.z());
pose.orientation = createQuaternionFromYaw(yaw);
return pose;
}
accumulated_distance2d += distance2d;
}
}
return Pose{};
}
} // namespace autoware::route_handler
Original file line number Diff line number Diff line change
Expand Up @@ -44,11 +44,14 @@ AvoidanceByLaneChangeInterface::AvoidanceByLaneChangeInterface(
{
}

// cppcheck-suppress unusedFunction
bool AvoidanceByLaneChangeInterface::isExecutionRequested() const
{
return module_type_->isLaneChangeRequired() && module_type_->specialRequiredCheck() &&
module_type_->isValidPath();
}

// cppcheck-suppress unusedFunction
void AvoidanceByLaneChangeInterface::processOnEntry()
{
waitApproval();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -187,8 +187,8 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node)
avoidance_parameters_ = std::make_shared<AvoidanceByLCParameters>(p);
}

std::unique_ptr<SceneModuleInterface>
AvoidanceByLaneChangeModuleManager::createNewSceneModuleInstance()
// cppcheck-suppress unusedFunction
SMIPtr AvoidanceByLaneChangeModuleManager::createNewSceneModuleInstance()
{
return std::make_unique<AvoidanceByLaneChangeInterface>(
name_, *node_, parameters_, avoidance_parameters_, rtc_interface_ptr_map_,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,8 @@ using autoware::behavior_path_planner::LaneChangeModuleManager;
using autoware::behavior_path_planner::LaneChangeModuleType;
using autoware::behavior_path_planner::SceneModuleInterface;

using SMIPtr = std::unique_ptr<SceneModuleInterface>;

class AvoidanceByLaneChangeModuleManager : public LaneChangeModuleManager
{
public:
Expand All @@ -44,7 +46,7 @@ class AvoidanceByLaneChangeModuleManager : public LaneChangeModuleManager

void init(rclcpp::Node * node) override;

std::unique_ptr<SceneModuleInterface> createNewSceneModuleInstance() override;
SMIPtr createNewSceneModuleInstance() override;

private:
std::shared_ptr<AvoidanceByLCParameters> avoidance_parameters_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,14 +34,55 @@
#include <optional>
#include <utility>

namespace
{
geometry_msgs::msg::Point32 create_point32(const geometry_msgs::msg::Pose & pose)
{
geometry_msgs::msg::Point32 p;
p.x = static_cast<float>(pose.position.x);
p.y = static_cast<float>(pose.position.y);
p.z = static_cast<float>(pose.position.z);
return p;
};

geometry_msgs::msg::Polygon create_execution_area(
const autoware::vehicle_info_utils::VehicleInfo & vehicle_info,
const geometry_msgs::msg::Pose & pose, double additional_lon_offset, double additional_lat_offset)
{
const double & base_to_front = vehicle_info.max_longitudinal_offset_m;
const double & width = vehicle_info.vehicle_width_m;
const double & base_to_rear = vehicle_info.rear_overhang_m;

// if stationary object, extend forward and backward by the half of lon length
const double forward_lon_offset = base_to_front + additional_lon_offset;
const double backward_lon_offset = -base_to_rear;
const double lat_offset = width / 2.0 + additional_lat_offset;

const auto p1 =
autoware::universe_utils::calcOffsetPose(pose, forward_lon_offset, lat_offset, 0.0);
const auto p2 =
autoware::universe_utils::calcOffsetPose(pose, forward_lon_offset, -lat_offset, 0.0);
const auto p3 =
autoware::universe_utils::calcOffsetPose(pose, backward_lon_offset, -lat_offset, 0.0);
const auto p4 =
autoware::universe_utils::calcOffsetPose(pose, backward_lon_offset, lat_offset, 0.0);
geometry_msgs::msg::Polygon polygon;

polygon.points.push_back(create_point32(p1));
polygon.points.push_back(create_point32(p2));
polygon.points.push_back(create_point32(p3));
polygon.points.push_back(create_point32(p4));

return polygon;
}
} // namespace

namespace autoware::behavior_path_planner
{
using autoware::behavior_path_planner::Direction;
using autoware::behavior_path_planner::LaneChangeModuleType;
using autoware::behavior_path_planner::ObjectInfo;
using autoware::behavior_path_planner::Point2d;
using autoware::behavior_path_planner::utils::lane_change::debug::createExecutionArea;
namespace utils = autoware::behavior_path_planner::utils;

AvoidanceByLaneChange::AvoidanceByLaneChange(
const std::shared_ptr<LaneChangeParameters> & parameters,
Expand Down Expand Up @@ -83,9 +124,9 @@ bool AvoidanceByLaneChange::specialRequiredCheck() const

const auto & nearest_object = data.target_objects.front();
const auto minimum_avoid_length = calcMinAvoidanceLength(nearest_object);
const auto minimum_lane_change_length = calcMinimumLaneChangeLength();
const auto minimum_lane_change_length = calc_minimum_dist_buffer();

lane_change_debug_.execution_area = createExecutionArea(
lane_change_debug_.execution_area = create_execution_area(
getCommonParam().vehicle_info, getEgoPose(),
std::max(minimum_lane_change_length, minimum_avoid_length), calcLateralOffset());

Expand Down Expand Up @@ -274,16 +315,11 @@ double AvoidanceByLaneChange::calcMinAvoidanceLength(const ObjectData & nearest_
return avoidance_helper_->getMinAvoidanceDistance(shift_length);
}

double AvoidanceByLaneChange::calcMinimumLaneChangeLength() const
double AvoidanceByLaneChange::calc_minimum_dist_buffer() const
{
const auto current_lanes = get_current_lanes();
if (current_lanes.empty()) {
RCLCPP_DEBUG(logger_, "no empty lanes");
return std::numeric_limits<double>::infinity();
}

return utils::lane_change::calculation::calc_minimum_lane_change_length(
getRouteHandler(), current_lanes.back(), *lane_change_parameters_, direction_);
const auto [_, dist_buffer] = utils::lane_change::calculation::calc_lc_length_and_dist_buffer(
common_data_ptr_, get_current_lanes());
return dist_buffer.min;
}

double AvoidanceByLaneChange::calcLateralOffset() const
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ class AvoidanceByLaneChange : public NormalLaneChange
void fillAvoidanceTargetObjects(AvoidancePlanningData & data, AvoidanceDebugData & debug) const;

double calcMinAvoidanceLength(const ObjectData & nearest_object) const;
double calcMinimumLaneChangeLength() const;
double calc_minimum_dist_buffer() const;
double calcLateralOffset() const;
};
} // namespace autoware::behavior_path_planner
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ if(BUILD_TESTING)
ament_add_ros_isolated_gmock(test_${PROJECT_NAME}
test/test_behavior_path_planner_node_interface.cpp
test/test_lane_change_utils.cpp
# test/test_lane_change_scene.cpp
)

target_link_libraries(test_${PROJECT_NAME}
Expand Down
Loading
Loading