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(map_based_prediction): improve world to map transform calculation #8413

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 2021 Tier IV, Inc.

Check notice on line 1 in perception/autoware_map_based_prediction/src/map_based_prediction_node.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 1956 to 1950, 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.

Check notice on line 1 in perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Overall Code Complexity

The mean cyclomatic complexity decreases from 6.58 to 6.56, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// 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 @@ -970,67 +970,62 @@
if (!lanelet_map_ptr_) {
return;
}

Check notice on line 973 in perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Complex Conditional

MapBasedPredictionNode::objectsCallback no longer has a complex conditional. A complex conditional is an expression inside a branch (e.g. if, for, while) which consists of multiple, logical operators such as AND/OR. The more logical operators in an expression, the more severe the code smell.
auto world2map_transform = transform_listener_.getTransform(
"map", // target
in_objects->header.frame_id, // src
in_objects->header.stamp, rclcpp::Duration::from_seconds(0.1));
auto map2world_transform = transform_listener_.getTransform(
in_objects->header.frame_id, // target
"map", // src
in_objects->header.stamp, rclcpp::Duration::from_seconds(0.1));
auto debug_map2lidar_transform = transform_listener_.getTransform(
"base_link", // target
"map", // src
rclcpp::Time(), rclcpp::Duration::from_seconds(0.1));

if (!world2map_transform || !map2world_transform || !debug_map2lidar_transform) {
return;
}

// Remove old objects information in object history
const double objects_detected_time = rclcpp::Time(in_objects->header.stamp).seconds();
removeOldObjectsHistory(objects_detected_time, object_buffer_time_length_, road_users_history);
removeStaleTrafficLightInfo(in_objects);

auto invalidated_crosswalk_users = removeOldObjectsHistory(
objects_detected_time, object_buffer_time_length_, crosswalk_users_history_);
// delete matches that point to invalid object
for (auto it = known_matches_.begin(); it != known_matches_.end();) {
if (invalidated_crosswalk_users.count(it->second)) {
it = known_matches_.erase(it);
} else {
++it;
}
}

// result output
PredictedObjects output;
output.header = in_objects->header;
output.header.frame_id = "map";

// result debug
visualization_msgs::msg::MarkerArray debug_markers;

// get current crosswalk users for later prediction
std::unordered_map<std::string, TrackedObject> current_crosswalk_users;
for (const auto & object : in_objects->objects) {
const auto label_for_prediction =
changeLabelForPrediction(object.classification.front().label, object, lanelet_map_ptr_);
if (
label_for_prediction == ObjectClassification::PEDESTRIAN ||
label_for_prediction == ObjectClassification::BICYCLE) {
const std::string object_id = autoware::universe_utils::toHexString(object.object_id);
current_crosswalk_users.emplace(object_id, object);
}
}
std::unordered_set<std::string> predicted_crosswalk_users_ids;

// get world to map transform
geometry_msgs::msg::TransformStamped::ConstSharedPtr world2map_transform;

bool is_object_not_in_map_frame = in_objects->header.frame_id != "map";
if (is_object_not_in_map_frame) {
world2map_transform = transform_listener_.getTransform(
"map", // target
in_objects->header.frame_id, // src
in_objects->header.stamp, rclcpp::Duration::from_seconds(0.1));
if (!world2map_transform) return;
}

for (const auto & object : in_objects->objects) {
TrackedObject transformed_object = object;

// transform object frame if it's based on map frame
if (in_objects->header.frame_id != "map") {
if (is_object_not_in_map_frame) {

Check notice on line 1028 in perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Bumpy Road Ahead

MapBasedPredictionNode::objectsCallback increases from 10 to 11 logical blocks with deeply nested code, threshold is one single 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.

Check notice on line 1028 in perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Complex Method

MapBasedPredictionNode::objectsCallback decreases in cyclomatic complexity from 46 to 45, 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.
geometry_msgs::msg::PoseStamped pose_in_map;
geometry_msgs::msg::PoseStamped pose_orig;
pose_orig.pose = object.kinematics.pose_with_covariance.pose;
Expand Down
Loading