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

feat(start_planner): allow lane departure check override #6512

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
21 changes: 11 additions & 10 deletions planning/behavior_path_start_planner_module/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -433,16 +433,17 @@ Pull out distance is calculated by the speed, lateral deviation, and the lateral

#### parameters for shift pull out

| Name | Unit | Type | Description | Default value |
| :------------------------------ | :----- | :----- | :------------------------------------------------------------------------------------------------------------------- | :------------ |
| enable_shift_pull_out | [-] | bool | flag whether to enable shift pull out | true |
| check_shift_path_lane_departure | [-] | bool | flag whether to check if shift path footprints are out of lane | false |
| shift_pull_out_velocity | [m/s] | double | velocity of shift pull out | 2.0 |
| pull_out_sampling_num | [-] | int | Number of samplings in the minimum to maximum range of lateral_jerk | 4 |
| maximum_lateral_jerk | [m/s3] | double | maximum lateral jerk | 2.0 |
| minimum_lateral_jerk | [m/s3] | double | minimum lateral jerk | 0.1 |
| minimum_shift_pull_out_distance | [m] | double | minimum shift pull out distance. if calculated pull out distance is shorter than this, use this for path generation. | 0.0 |
| maximum_curvature | [m] | double | maximum curvature. The pull out distance is calculated so that the curvature is smaller than this value. | 0.07 |
| Name | Unit | Type | Description | Default value |
| :--------------------------------------------- | :----- | :----- | :------------------------------------------------------------------------------------------------------------------- | :------------ |
| enable_shift_pull_out | [-] | bool | flag whether to enable shift pull out | true |
| check_shift_path_lane_departure | [-] | bool | flag whether to check if shift path footprints are out of lane | true |
| allow_check_shift_path_lane_departure_override | [-] | bool | flag to override/cancel lane departure check if the ego vehicle's starting pose is already out of lane | false |
| shift_pull_out_velocity | [m/s] | double | velocity of shift pull out | 2.0 |
| pull_out_sampling_num | [-] | int | Number of samplings in the minimum to maximum range of lateral_jerk | 4 |
| maximum_lateral_jerk | [m/s3] | double | maximum lateral jerk | 2.0 |
| minimum_lateral_jerk | [m/s3] | double | minimum lateral jerk | 0.1 |
| minimum_shift_pull_out_distance | [m] | double | minimum shift pull out distance. if calculated pull out distance is shorter than this, use this for path generation. | 0.0 |
| maximum_curvature | [m] | double | maximum curvature. The pull out distance is calculated so that the curvature is smaller than this value. | 0.07 |

### **geometric pull out**

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
# shift pull out
enable_shift_pull_out: true
check_shift_path_lane_departure: true
allow_check_shift_path_lane_departure_override: false
shift_collision_check_distance_from_end: -10.0
minimum_shift_pull_out_distance: 0.0
deceleration_interval: 15.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,7 @@ struct StartPlannerParameters
// shift pull out
bool enable_shift_pull_out{false};
bool check_shift_path_lane_departure{false};
bool allow_check_shift_path_lane_departure_override{false};
double shift_collision_check_distance_from_end{0.0};
double minimum_shift_pull_out_distance{0.0};
int lateral_acceleration_sampling_num{0};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -178,6 +178,21 @@

bool requiresDynamicObjectsCollisionDetection() const;

uint16_t getSteeringFactorDirection(
const behavior_path_planner::BehaviorModuleOutput & output) const
{
switch (output.turn_signal_info.turn_signal.command) {

Check warning on line 184 in planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp#L184

Added line #L184 was not covered by tests
case TurnIndicatorsCommand::ENABLE_LEFT:
return SteeringFactor::LEFT;

case TurnIndicatorsCommand::ENABLE_RIGHT:
return SteeringFactor::RIGHT;

Check warning on line 189 in planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp#L188-L189

Added lines #L188 - L189 were not covered by tests

default:
return SteeringFactor::STRAIGHT;

Check warning on line 192 in planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp#L191-L192

Added lines #L191 - L192 were not covered by tests
}
};

/**
* @brief Check if there are no moving objects around within a certain radius.
*
Expand Down
5 changes: 5 additions & 0 deletions planning/behavior_path_start_planner_module/src/manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,8 @@
p.enable_shift_pull_out = node->declare_parameter<bool>(ns + "enable_shift_pull_out");
p.check_shift_path_lane_departure =
node->declare_parameter<bool>(ns + "check_shift_path_lane_departure");
p.allow_check_shift_path_lane_departure_override =
node->declare_parameter<bool>(ns + "allow_check_shift_path_lane_departure_override");

Check warning on line 58 in planning/behavior_path_start_planner_module/src/manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

StartPlannerModuleManager::init increases from 267 to 269 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.

Check warning on line 58 in planning/behavior_path_start_planner_module/src/manager.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/manager.cpp#L57-L58

Added lines #L57 - L58 were not covered by tests
p.shift_collision_check_distance_from_end =
node->declare_parameter<double>(ns + "shift_collision_check_distance_from_end");
p.minimum_shift_pull_out_distance =
Expand Down Expand Up @@ -390,6 +392,9 @@
p->geometric_collision_check_distance_from_end);
updateParam<bool>(
parameters, ns + "check_shift_path_lane_departure", p->check_shift_path_lane_departure);
updateParam<bool>(
parameters, ns + "allow_check_shift_path_lane_departure_override",
p->allow_check_shift_path_lane_departure_override);

Check warning on line 397 in planning/behavior_path_start_planner_module/src/manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

StartPlannerModuleManager::updateModuleParams increases from 322 to 325 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.

Check warning on line 397 in planning/behavior_path_start_planner_module/src/manager.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/manager.cpp#L395-L397

Added lines #L395 - L397 were not covered by tests
updateParam<std::string>(parameters, ns + "search_priority", p->search_priority);
updateParam<double>(parameters, ns + "max_back_distance", p->max_back_distance);
updateParam<double>(
Expand Down
24 changes: 19 additions & 5 deletions planning/behavior_path_start_planner_module/src/shift_pull_out.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,13 +74,27 @@
shift_path.points.begin() + pull_out_end_idx + 1);
}

// check lane departure
// The method for lane departure checking verifies if the footprint of each point on the path is
// contained within a lanelet using `boost::geometry::within`, which incurs a high computational
// cost.
const auto lanelet_map_ptr = planner_data_->route_handler->getLaneletMapPtr();

// if lane departure check override is true, and if the initial pose is not fully within a lane,
// cancel lane departure check
const bool is_lane_departure_check_required = std::invoke([&]() -> bool {
if (!parameters_.allow_check_shift_path_lane_departure_override)
return parameters_.check_shift_path_lane_departure;

Check warning on line 83 in planning/behavior_path_start_planner_module/src/shift_pull_out.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/shift_pull_out.cpp#L81-L83

Added lines #L81 - L83 were not covered by tests

PathWithLaneId path_with_only_first_pose{};
path_with_only_first_pose.points.push_back(path_shift_start_to_end.points.at(0));
return !lane_departure_checker_->checkPathWillLeaveLane(
lanelet_map_ptr, path_with_only_first_pose);
});

Check warning on line 89 in planning/behavior_path_start_planner_module/src/shift_pull_out.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/shift_pull_out.cpp#L86-L89

Added lines #L86 - L89 were not covered by tests

// check lane departure
// The method for lane departure checking verifies if the footprint of each point on the path
// is contained within a lanelet using `boost::geometry::within`, which incurs a high
// computational cost.

if (
parameters_.check_shift_path_lane_departure &&
is_lane_departure_check_required &&

Check warning on line 97 in planning/behavior_path_start_planner_module/src/shift_pull_out.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/shift_pull_out.cpp#L97

Added line #L97 was not covered by tests
lane_departure_checker_->checkPathWillLeaveLane(lanelet_map_ptr, path_shift_start_to_end)) {
continue;
}
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2022 TIER IV, Inc.

Check notice on line 1 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Lines of Code in a Single File

The lines of code decreases from 1301 to 1282, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -182,18 +182,14 @@
status_.first_engaged_time = clock_->now();
}

if (hasFinishedBackwardDriving()) {
status_.backward_driving_complete = hasFinishedBackwardDriving();
if (status_.backward_driving_complete) {

Check warning on line 186 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L185-L186

Added lines #L185 - L186 were not covered by tests
updateStatusAfterBackwardDriving();
DEBUG_PRINT("StartPlannerModule::updateData() completed backward driving");
} else {
status_.backward_driving_complete = false;
}

if (requiresDynamicObjectsCollisionDetection()) {
status_.is_safe_dynamic_objects = !hasCollisionWithDynamicObjects();
} else {
status_.is_safe_dynamic_objects = true;
}
status_.is_safe_dynamic_objects =
(!requiresDynamicObjectsCollisionDetection()) ? true : !hasCollisionWithDynamicObjects();

Check warning on line 192 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L191-L192

Added lines #L191 - L192 were not covered by tests
}

bool StartPlannerModule::hasFinishedBackwardDriving() const
Expand Down Expand Up @@ -364,20 +360,17 @@

bool StartPlannerModule::isExecutionReady() const
{
bool is_safe = true;
// Evaluate safety. The situation is not safe if any of the following conditions are met:
// 1. pull out path has not been found
// 2. there is a moving objects around ego
// 3. waiting for approval and there is a collision with dynamic objects
if (!status_.found_pull_out_path) {
is_safe = false;
} else if (isWaitingApproval()) {
if (!noMovingObjectsAround()) {
is_safe = false;
} else if (requiresDynamicObjectsCollisionDetection() && hasCollisionWithDynamicObjects()) {
is_safe = false;
}
}

const bool is_safe = [&]() -> bool {
if (!status_.found_pull_out_path) return false;

Check warning on line 369 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L368-L369

Added lines #L368 - L369 were not covered by tests
if (!isWaitingApproval()) return true;
if (!noMovingObjectsAround()) return false;
return !(requiresDynamicObjectsCollisionDetection() && hasCollisionWithDynamicObjects());
}();

Check warning on line 373 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L371-L373

Added lines #L371 - L373 were not covered by tests

if (!is_safe) {
stop_pose_ = planner_data_->self_odometry->pose.pose;
Expand Down Expand Up @@ -459,36 +452,30 @@

setDrivableAreaInfo(output);

const uint16_t steering_factor_direction = std::invoke([&output]() {
if (output.turn_signal_info.turn_signal.command == TurnIndicatorsCommand::ENABLE_LEFT) {
return SteeringFactor::LEFT;
} else if (output.turn_signal_info.turn_signal.command == TurnIndicatorsCommand::ENABLE_RIGHT) {
return SteeringFactor::RIGHT;
}
return SteeringFactor::STRAIGHT;
});
const auto steering_factor_direction = getSteeringFactorDirection(output);

if (status_.driving_forward) {
const double start_distance = motion_utils::calcSignedArcLength(
path.points, planner_data_->self_odometry->pose.pose.position,
status_.pull_out_path.start_pose.position);
const double finish_distance = motion_utils::calcSignedArcLength(
path.points, planner_data_->self_odometry->pose.pose.position,
status_.pull_out_path.end_pose.position);
updateRTCStatus(start_distance, finish_distance);
steering_factor_interface_ptr_->updateSteeringFactor(
{status_.pull_out_path.start_pose, status_.pull_out_path.end_pose},
{start_distance, finish_distance}, PlanningBehavior::START_PLANNER, steering_factor_direction,
SteeringFactor::TURNING, "");
} else {
const double distance = motion_utils::calcSignedArcLength(
path.points, planner_data_->self_odometry->pose.pose.position,
status_.pull_out_path.start_pose.position);
updateRTCStatus(0.0, distance);
steering_factor_interface_ptr_->updateSteeringFactor(
{status_.pull_out_path.start_pose, status_.pull_out_path.end_pose}, {0.0, distance},
PlanningBehavior::START_PLANNER, steering_factor_direction, SteeringFactor::TURNING, "");
setDebugData();
return output;

Check warning on line 470 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L469-L470

Added lines #L469 - L470 were not covered by tests
}
const double distance = motion_utils::calcSignedArcLength(
path.points, planner_data_->self_odometry->pose.pose.position,
status_.pull_out_path.start_pose.position);
updateRTCStatus(0.0, distance);
steering_factor_interface_ptr_->updateSteeringFactor(

Check warning on line 476 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L472-L476

Added lines #L472 - L476 were not covered by tests
{status_.pull_out_path.start_pose, status_.pull_out_path.end_pose}, {0.0, distance},
PlanningBehavior::START_PLANNER, steering_factor_direction, SteeringFactor::TURNING, "");

Check notice on line 478 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Complex Method

StartPlannerModule::plan decreases in cyclomatic complexity from 17 to 15, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

setDebugData();

Expand Down Expand Up @@ -569,14 +556,7 @@

setDrivableAreaInfo(output);

const uint16_t steering_factor_direction = std::invoke([&output]() {
if (output.turn_signal_info.turn_signal.command == TurnIndicatorsCommand::ENABLE_LEFT) {
return SteeringFactor::LEFT;
} else if (output.turn_signal_info.turn_signal.command == TurnIndicatorsCommand::ENABLE_RIGHT) {
return SteeringFactor::RIGHT;
}
return SteeringFactor::STRAIGHT;
});
const auto steering_factor_direction = getSteeringFactorDirection(output);

if (status_.driving_forward) {
const double start_distance = motion_utils::calcSignedArcLength(
Expand All @@ -590,15 +570,17 @@
{status_.pull_out_path.start_pose, status_.pull_out_path.end_pose},
{start_distance, finish_distance}, PlanningBehavior::START_PLANNER, steering_factor_direction,
SteeringFactor::APPROACHING, "");
} else {
const double distance = motion_utils::calcSignedArcLength(
stop_path.points, planner_data_->self_odometry->pose.pose.position,
status_.pull_out_path.start_pose.position);
updateRTCStatus(0.0, distance);
steering_factor_interface_ptr_->updateSteeringFactor(
{status_.pull_out_path.start_pose, status_.pull_out_path.end_pose}, {0.0, distance},
PlanningBehavior::START_PLANNER, steering_factor_direction, SteeringFactor::APPROACHING, "");
setDebugData();

Check warning on line 573 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L573

Added line #L573 was not covered by tests

return output;

Check warning on line 575 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L575

Added line #L575 was not covered by tests
}
const double distance = motion_utils::calcSignedArcLength(
stop_path.points, planner_data_->self_odometry->pose.pose.position,
status_.pull_out_path.start_pose.position);
updateRTCStatus(0.0, distance);
steering_factor_interface_ptr_->updateSteeringFactor(

Check warning on line 581 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L577-L581

Added lines #L577 - L581 were not covered by tests
{status_.pull_out_path.start_pose, status_.pull_out_path.end_pose}, {0.0, distance},
PlanningBehavior::START_PLANNER, steering_factor_direction, SteeringFactor::APPROACHING, "");

setDebugData();

Expand Down Expand Up @@ -658,16 +640,20 @@
order_priority.emplace_back(i, planner);
}
}
} else if (search_priority == "short_back_distance") {
return order_priority;
}

if (search_priority == "short_back_distance") {

Check warning on line 646 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L646

Added line #L646 was not covered by tests
for (size_t i = 0; i < start_pose_candidates_num; i++) {
for (const auto & planner : start_planners_) {
order_priority.emplace_back(i, planner);
}
}
} else {
RCLCPP_ERROR(getLogger(), "Invalid search_priority: %s", search_priority.c_str());
throw std::domain_error("[start_planner] invalid search_priority");
return order_priority;

Check warning on line 652 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L652

Added line #L652 was not covered by tests
}

RCLCPP_ERROR(getLogger(), "Invalid search_priority: %s", search_priority.c_str());
throw std::domain_error("[start_planner] invalid search_priority");

Check warning on line 656 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L655-L656

Added lines #L655 - L656 were not covered by tests
return order_priority;
}

Expand Down Expand Up @@ -1099,12 +1085,7 @@
return false;
}

if (status_.planner_type == PlannerType::STOP) {
return true;
}

// not found safe path
if (!status_.found_pull_out_path) {
if (status_.planner_type == PlannerType::STOP || !status_.found_pull_out_path) {

Check warning on line 1088 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L1088

Added line #L1088 was not covered by tests
return true;
}

Expand Down Expand Up @@ -1197,30 +1178,26 @@
return false;
});

if (is_near_intersection) {
// offset required end pose with ration to activate turn signal for intersection
turn_signal.required_end_point = std::invoke([&]() {
const double length_start_to_end =
motion_utils::calcSignedArcLength(path.points, start_pose.position, end_pose.position);
const auto ratio = std::clamp(
parameters_->length_ratio_for_turn_signal_deactivation_near_intersection, 0.0, 1.0);

const double required_end_length = length_start_to_end * ratio;
double accumulated_length = 0.0;
const size_t start_idx = motion_utils::findNearestIndex(path.points, start_pose.position);
for (size_t i = start_idx; i < path.points.size() - 1; ++i) {
accumulated_length +=
tier4_autoware_utils::calcDistance2d(path.points.at(i), path.points.at(i + 1));
if (accumulated_length > required_end_length) {
return path.points.at(i).point.pose;
}
turn_signal.required_end_point = std::invoke([&]() {
if (is_near_intersection) return end_pose;

Check warning on line 1182 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L1181-L1182

Added lines #L1181 - L1182 were not covered by tests
const double length_start_to_end =
motion_utils::calcSignedArcLength(path.points, start_pose.position, end_pose.position);

Check warning on line 1184 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L1184

Added line #L1184 was not covered by tests
const auto ratio = std::clamp(
parameters_->length_ratio_for_turn_signal_deactivation_near_intersection, 0.0, 1.0);

Check warning on line 1186 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L1186

Added line #L1186 was not covered by tests

const double required_end_length = length_start_to_end * ratio;

Check warning on line 1188 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L1188

Added line #L1188 was not covered by tests
double accumulated_length = 0.0;
const size_t start_idx = motion_utils::findNearestIndex(path.points, start_pose.position);
for (size_t i = start_idx; i < path.points.size() - 1; ++i) {
accumulated_length +=
tier4_autoware_utils::calcDistance2d(path.points.at(i), path.points.at(i + 1));
if (accumulated_length > required_end_length) {
return path.points.at(i).point.pose;

Check warning on line 1195 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L1190-L1195

Added lines #L1190 - L1195 were not covered by tests
}
// not found required end point
return end_pose;
});
} else {
turn_signal.required_end_point = end_pose;
}
}
// not found required end point
return end_pose;

Check warning on line 1199 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L1199

Added line #L1199 was not covered by tests
});

return turn_signal;
}
Expand Down Expand Up @@ -1389,22 +1366,27 @@

void StartPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) const
{
if (status_.planner_type == PlannerType::FREESPACE) {
const double drivable_area_margin = planner_data_->parameters.vehicle_width;
output.drivable_area_info.drivable_margin =
planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin;
} else {
const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes(
output.path, generateDrivableLanes(output.path),
planner_data_->drivable_area_expansion_parameters);

DrivableAreaInfo current_drivable_area_info;
current_drivable_area_info.drivable_lanes = target_drivable_lanes;
output.drivable_area_info =
status_.driving_forward
? utils::combineDrivableAreaInfo(
current_drivable_area_info, getPreviousModuleOutput().drivable_area_info)
: current_drivable_area_info;
switch (status_.planner_type) {
case PlannerType::FREESPACE: {
const double drivable_area_margin = planner_data_->parameters.vehicle_width;
output.drivable_area_info.drivable_margin =
planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin;
break;

Check warning on line 1374 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L1369-L1374

Added lines #L1369 - L1374 were not covered by tests
}
default: {

Check warning on line 1376 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L1376

Added line #L1376 was not covered by tests
const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes(
output.path, generateDrivableLanes(output.path),
planner_data_->drivable_area_expansion_parameters);

Check warning on line 1379 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L1378-L1379

Added lines #L1378 - L1379 were not covered by tests

DrivableAreaInfo current_drivable_area_info;
current_drivable_area_info.drivable_lanes = target_drivable_lanes;

Check warning on line 1382 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L1382

Added line #L1382 was not covered by tests
output.drivable_area_info =
status_.driving_forward
? utils::combineDrivableAreaInfo(
current_drivable_area_info, getPreviousModuleOutput().drivable_area_info)
: current_drivable_area_info;

Check warning on line 1387 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L1384-L1387

Added lines #L1384 - L1387 were not covered by tests
break;
}

Check warning on line 1389 in planning/behavior_path_start_planner_module/src/start_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/start_planner_module.cpp#L1389

Added line #L1389 was not covered by tests
}
}

Expand Down
Loading