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(lidar_centerpoint, pointpainting): add diag publisher for max voxel size #9720

Merged
merged 7 commits into from
Jan 8, 2025
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
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include <autoware/image_projection_based_fusion/utils/utils.hpp>
#include <autoware/lidar_centerpoint/centerpoint_trt.hpp>
#include <autoware/lidar_centerpoint/detection_class_remapper.hpp>
#include <autoware/universe_utils/ros/diagnostics_interface.hpp>

#include <map>
#include <memory>
Expand Down Expand Up @@ -58,6 +59,7 @@ class PointPaintingFusionNode
void postprocess(sensor_msgs::msg::PointCloud2 & painted_pointcloud_msg) override;

rclcpp::Publisher<DetectedObjects>::SharedPtr obj_pub_ptr_;
std::unique_ptr<autoware::universe_utils::DiagnosticsInterface> diagnostics_interface_ptr_;

int omp_num_threads_{1};
float score_threshold_{0.0};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -186,6 +186,8 @@
// create detector
detector_ptr_ = std::make_unique<image_projection_based_fusion::PointPaintingTRT>(
encoder_param, head_param, densification_param, config);
diagnostics_interface_ptr_ =
std::make_unique<autoware::universe_utils::DiagnosticsInterface>(this, "pointpainting_trt");

Check warning on line 190 in perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp#L190

Added line #L190 was not covered by tests

obj_pub_ptr_ = this->create_publisher<DetectedObjects>("~/output/objects", rclcpp::QoS{1});

Expand Down Expand Up @@ -389,6 +391,7 @@
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
diagnostics_interface_ptr_->clear();

Check warning on line 394 in perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp#L394

Added line #L394 was not covered by tests

const auto objects_sub_count =
obj_pub_ptr_->get_subscription_count() + obj_pub_ptr_->get_intra_process_subscription_count();
Expand All @@ -403,10 +406,21 @@
}

std::vector<autoware::lidar_centerpoint::Box3D> det_boxes3d;
bool is_success = detector_ptr_->detect(painted_pointcloud_msg, tf_buffer_, det_boxes3d);
bool is_num_pillars_within_range = true;
bool is_success = detector_ptr_->detect(
painted_pointcloud_msg, tf_buffer_, det_boxes3d, is_num_pillars_within_range);

Check warning on line 411 in perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp#L409-L411

Added lines #L409 - L411 were not covered by tests
if (!is_success) {
return;
}
diagnostics_interface_ptr_->add_key_value(

Check warning on line 415 in perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp#L415

Added line #L415 was not covered by tests
"is_num_pillars_within_range", is_num_pillars_within_range);
if (!is_num_pillars_within_range) {
std::stringstream message;

Check warning on line 418 in perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp#L418

Added line #L418 was not covered by tests
message << "PointPaintingTRT::detect: The actual number of pillars exceeds its maximum value, "
<< "which may limit the detection performance.";
diagnostics_interface_ptr_->update_level_and_message(
diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str());
}

Check warning on line 423 in perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp#L420-L423

Added lines #L420 - L423 were not covered by tests

std::vector<autoware_perception_msgs::msg::DetectedObject> raw_objects;
raw_objects.reserve(det_boxes3d.size());
Expand All @@ -425,6 +439,7 @@
if (objects_sub_count > 0) {
obj_pub_ptr_->publish(output_msg);
}
diagnostics_interface_ptr_->publish(painted_pointcloud_msg.header.stamp);

Check notice on line 442 in perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ New issue: Complex Method

PointPaintingFusionNode::postprocess 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 442 in perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp#L442

Added line #L442 was not covered by tests
}

bool PointPaintingFusionNode::out_of_scope(__attribute__((unused)) const DetectedObjects & obj)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ class CenterPointTRT

bool detect(
const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer,
std::vector<Box3D> & det_boxes3d);
std::vector<Box3D> & det_boxes3d, bool & is_num_pillars_within_range);

protected:
void initPtr();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include "autoware/lidar_centerpoint/postprocess/non_maximum_suppression.hpp"

#include <autoware/universe_utils/ros/debug_publisher.hpp>
#include <autoware/universe_utils/ros/diagnostics_interface.hpp>
#include <autoware/universe_utils/ros/published_time_publisher.hpp>
#include <autoware/universe_utils/system/stop_watch.hpp>
#include <rclcpp/rclcpp.hpp>
Expand Down Expand Up @@ -59,6 +60,7 @@ class LidarCenterPointNode : public rclcpp::Node
DetectionClassRemapper detection_class_remapper_;

std::unique_ptr<CenterPointTRT> detector_ptr_{nullptr};
std::unique_ptr<autoware::universe_utils::DiagnosticsInterface> diagnostics_interface_ptr_;

// debugger
std::unique_ptr<autoware::universe_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include "autoware/lidar_centerpoint/preprocess/preprocess_kernel.hpp"

#include <autoware/universe_utils/math/constants.hpp>
#include <autoware/universe_utils/ros/diagnostics_interface.hpp>

#include <algorithm>
#include <cstdlib>
Expand Down Expand Up @@ -127,8 +128,10 @@

bool CenterPointTRT::detect(
const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer,
std::vector<Box3D> & det_boxes3d)
std::vector<Box3D> & det_boxes3d, bool & is_num_pillars_within_range)
{
is_num_pillars_within_range = true;

Check warning on line 133 in perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp#L133

Added line #L133 was not covered by tests

CHECK_CUDA_ERROR(cudaMemsetAsync(
encoder_in_features_d_.get(), 0, encoder_in_feature_size_ * sizeof(float), stream_));
CHECK_CUDA_ERROR(
Expand All @@ -155,6 +158,7 @@
"The actual number of pillars (%u) exceeds its maximum value (%zu). "
"Please considering increasing it since it may limit the detection performance.",
num_pillars, config_.max_voxel_size_);
is_num_pillars_within_range = false;

Check warning on line 161 in perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp#L161

Added line #L161 was not covered by tests
}

return true;
Expand Down
17 changes: 16 additions & 1 deletion perception/autoware_lidar_centerpoint/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,8 @@
circle_nms_dist_threshold, yaw_norm_thresholds, has_variance_);
detector_ptr_ =
std::make_unique<CenterPointTRT>(encoder_param, head_param, densification_param, config);
diagnostics_interface_ptr_ =
std::make_unique<autoware::universe_utils::DiagnosticsInterface>(this, "centerpoint_trt");

Check warning on line 111 in perception/autoware_lidar_centerpoint/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

LidarCenterPointNode::LidarCenterPointNode increases from 87 to 89 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 111 in perception/autoware_lidar_centerpoint/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_lidar_centerpoint/src/node.cpp#L111

Added line #L111 was not covered by tests

pointcloud_sub_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
"~/input/pointcloud", rclcpp::SensorDataQoS{}.keep_last(1),
Expand Down Expand Up @@ -144,12 +146,24 @@
if (stop_watch_ptr_) {
stop_watch_ptr_->toc("processing_time", true);
}
diagnostics_interface_ptr_->clear();

Check warning on line 149 in perception/autoware_lidar_centerpoint/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_lidar_centerpoint/src/node.cpp#L149

Added line #L149 was not covered by tests

std::vector<Box3D> det_boxes3d;
bool is_success = detector_ptr_->detect(*input_pointcloud_msg, tf_buffer_, det_boxes3d);
bool is_num_pillars_within_range = true;
bool is_success = detector_ptr_->detect(
*input_pointcloud_msg, tf_buffer_, det_boxes3d, is_num_pillars_within_range);

Check warning on line 154 in perception/autoware_lidar_centerpoint/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_lidar_centerpoint/src/node.cpp#L152-L154

Added lines #L152 - L154 were not covered by tests
if (!is_success) {
return;
}
diagnostics_interface_ptr_->add_key_value(

Check warning on line 158 in perception/autoware_lidar_centerpoint/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_lidar_centerpoint/src/node.cpp#L158

Added line #L158 was not covered by tests
"is_num_pillars_within_range", is_num_pillars_within_range);
if (!is_num_pillars_within_range) {
std::stringstream message;

Check warning on line 161 in perception/autoware_lidar_centerpoint/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_lidar_centerpoint/src/node.cpp#L161

Added line #L161 was not covered by tests
message << "CenterPointTRT::detect: The actual number of pillars exceeds its maximum value, "
<< "which may limit the detection performance.";
diagnostics_interface_ptr_->update_level_and_message(
diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str());
}

Check warning on line 166 in perception/autoware_lidar_centerpoint/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_lidar_centerpoint/src/node.cpp#L163-L166

Added lines #L163 - L166 were not covered by tests

std::vector<autoware_perception_msgs::msg::DetectedObject> raw_objects;
raw_objects.reserve(det_boxes3d.size());
Expand All @@ -169,6 +183,7 @@
objects_pub_->publish(output_msg);
published_time_publisher_->publish_if_subscribed(objects_pub_, output_msg.header.stamp);
}
diagnostics_interface_ptr_->publish(input_pointcloud_msg->header.stamp);

Check warning on line 186 in perception/autoware_lidar_centerpoint/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

LidarCenterPointNode::pointCloudCallback 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 186 in perception/autoware_lidar_centerpoint/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_lidar_centerpoint/src/node.cpp#L186

Added line #L186 was not covered by tests

// add processing time for debug
if (debug_publisher_ptr_ && stop_watch_ptr_) {
Expand Down
Loading