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): add static collision check end polygon marker #5955

Merged
merged 1 commit into from
Dec 26, 2023
Merged
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
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 worse: Lines of Code in a Single File

The lines of code increases from 1052 to 1080, 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 @@ -1283,22 +1283,52 @@
using tier4_autoware_utils::createDefaultMarker;
using tier4_autoware_utils::createMarkerColor;
using tier4_autoware_utils::createMarkerScale;
using visualization_msgs::msg::Marker;

const auto life_time = rclcpp::Duration::from_seconds(1.5);
auto add = [&](MarkerArray added) {
for (auto & marker : added.markers) {
marker.lifetime = life_time;
}
tier4_autoware_utils::appendMarkerArray(added, &debug_marker_);
};

debug_marker_.markers.clear();
add(createPoseMarkerArray(status_.pull_out_start_pose, "back_end_pose", 0, 0.9, 0.3, 0.3));
add(createPoseMarkerArray(status_.pull_out_path.start_pose, "start_pose", 0, 0.3, 0.9, 0.3));
add(createPoseMarkerArray(status_.pull_out_path.end_pose, "end_pose", 0, 0.9, 0.9, 0.3));
add(createPathMarkerArray(getFullPath(), "full_path", 0, 0.0, 0.5, 0.9));
add(createPathMarkerArray(status_.backward_path, "backward_driving_path", 0, 0.0, 0.9, 0.0));

// visualize collision_check_end_pose and footprint
{
const auto local_footprint = createVehicleFootprint(vehicle_info_);
const auto collision_check_end_pose = motion_utils::calcLongitudinalOffsetPose(
getFullPath().points, status_.pull_out_path.end_pose.position,

Check warning on line 1307 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#L1305-L1307

Added lines #L1305 - L1307 were not covered by tests
parameters_->collision_check_distance_from_end);
if (collision_check_end_pose) {
add(createPoseMarkerArray(
*collision_check_end_pose, "static_collision_check_end_pose", 0, 1.0, 0.0, 0.0));

Check warning on line 1311 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#L1309-L1311

Added lines #L1309 - L1311 were not covered by tests
auto marker = tier4_autoware_utils::createDefaultMarker(
"map", rclcpp::Clock{RCL_ROS_TIME}.now(), "static_collision_check_end_polygon", 0,
Marker::LINE_LIST, tier4_autoware_utils::createMarkerScale(0.1, 0.1, 0.1),
tier4_autoware_utils::createMarkerColor(1.0, 0.0, 0.0, 0.999));

Check warning on line 1315 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#L1313-L1315

Added lines #L1313 - L1315 were not covered by tests
const auto footprint = transformVector(
local_footprint, tier4_autoware_utils::pose2transform(*collision_check_end_pose));
const double ego_z = planner_data_->self_odometry->pose.pose.position.z;
for (size_t i = 0; i < footprint.size(); i++) {

Check warning on line 1319 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#L1317-L1319

Added lines #L1317 - L1319 were not covered by tests
const auto & current_point = footprint.at(i);
const auto & next_point = footprint.at((i + 1) % footprint.size());

Check warning on line 1321 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#L1321

Added line #L1321 was not covered by tests
marker.points.push_back(
tier4_autoware_utils::createPoint(current_point.x(), current_point.y(), ego_z));

Check warning on line 1323 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#L1323

Added line #L1323 was not covered by tests
marker.points.push_back(
tier4_autoware_utils::createPoint(next_point.x(), next_point.y(), ego_z));

Check warning on line 1325 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#L1325

Added line #L1325 was not covered by tests
}
marker.lifetime = life_time;
debug_marker_.markers.push_back(marker);
}

Check warning on line 1329 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#L1327-L1329

Added lines #L1327 - L1329 were not covered by tests
}

Check warning on line 1331 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)

❌ New issue: Complex Method

StartPlannerModule::setDebugData has a cyclomatic complexity of 9, 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.

Check warning on line 1331 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)

❌ New issue: Bumpy Road Ahead

StartPlannerModule::setDebugData has 2 blocks with nested conditional logic. Any nesting of 2 or deeper is considered. Threshold is one single, nested block per function. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.
// safety check
if (parameters_->safety_check_params.enable_safety_check) {
if (start_planner_data_.ego_predicted_path.size() > 0) {
Expand Down
Loading