Skip to content

Commit

Permalink
fix(bpp_start_planner): nouse pointer
Browse files Browse the repository at this point in the history
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
  • Loading branch information
satoshi-ota committed Dec 18, 2023
1 parent 572d863 commit 67dac3f
Showing 1 changed file with 7 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -402,11 +402,11 @@ BehaviorModuleOutput StartPlannerModule::plan()
path = status_.backward_path;
}

output.path = std::make_shared<PathWithLaneId>(path);
output.path = path;

Check warning on line 405 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#L405

Added line #L405 was not covered by tests
output.reference_path = getPreviousModuleOutput().reference_path;
output.turn_signal_info = calcTurnSignalInfo();
path_candidate_ = std::make_shared<PathWithLaneId>(getFullPath());
path_reference_ = getPreviousModuleOutput().reference_path;
path_reference_ = std::make_shared<PathWithLaneId>(getPreviousModuleOutput().reference_path);

Check warning on line 409 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#L409

Added line #L409 was not covered by tests

setDrivableAreaInfo(output);

Expand Down Expand Up @@ -512,11 +512,11 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval()
p.point.longitudinal_velocity_mps = 0.0;
}

output.path = std::make_shared<PathWithLaneId>(stop_path);
output.path = stop_path;

Check warning on line 515 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#L515

Added line #L515 was not covered by tests
output.reference_path = getPreviousModuleOutput().reference_path;
output.turn_signal_info = calcTurnSignalInfo();
path_candidate_ = std::make_shared<PathWithLaneId>(getFullPath());
path_reference_ = getPreviousModuleOutput().reference_path;
path_reference_ = std::make_unique<PathWithLaneId>(getPreviousModuleOutput().reference_path);

Check warning on line 519 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#L519

Added line #L519 was not covered by tests

setDrivableAreaInfo(output);

Expand Down Expand Up @@ -1182,7 +1182,7 @@ BehaviorModuleOutput StartPlannerModule::generateStopOutput()
{
BehaviorModuleOutput output;
const PathWithLaneId stop_path = generateStopPath();
output.path = std::make_shared<PathWithLaneId>(stop_path);
output.path = stop_path;

Check warning on line 1185 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#L1185

Added line #L1185 was not covered by tests

setDrivableAreaInfo(output);

Expand All @@ -1201,7 +1201,7 @@ BehaviorModuleOutput StartPlannerModule::generateStopOutput()
}

path_candidate_ = std::make_shared<PathWithLaneId>(stop_path);
path_reference_ = getPreviousModuleOutput().reference_path;
path_reference_ = std::make_shared<PathWithLaneId>(getPreviousModuleOutput().reference_path);

Check warning on line 1204 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#L1204

Added line #L1204 was not covered by tests

return output;
}
Expand Down Expand Up @@ -1258,7 +1258,7 @@ void StartPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) cons
planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin;
} else {
const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes(
*output.path, generateDrivableLanes(*output.path),
output.path, generateDrivableLanes(output.path),

Check warning on line 1261 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#L1261

Added line #L1261 was not covered by tests
planner_data_->drivable_area_expansion_parameters);

DrivableAreaInfo current_drivable_area_info;
Expand Down

0 comments on commit 67dac3f

Please sign in to comment.