Skip to content

Commit

Permalink
feat(lidar_centerpoint, pointpainting): add diag publisher for max vo…
Browse files Browse the repository at this point in the history
…xel size

Signed-off-by: kminoda <[email protected]>
  • Loading branch information
kminoda committed Dec 23, 2024
1 parent 40ff6d3 commit d13ae2c
Show file tree
Hide file tree
Showing 6 changed files with 42 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,8 @@
#include <autoware/lidar_centerpoint/centerpoint_trt.hpp>
#include <autoware/lidar_centerpoint/detection_class_remapper.hpp>

#include <autoware/universe_utils/ros/diagnostics_module.hpp>

#include <map>
#include <memory>
#include <string>
Expand All @@ -44,6 +46,8 @@ inline bool isInsideBbox(
class PointPaintingFusionNode
: public FusionNode<sensor_msgs::msg::PointCloud2, DetectedObjects, DetectedObjectsWithFeature>
{
using DiagnosticsModule = autoware::universe_utils::DiagnosticsModule;

public:
explicit PointPaintingFusionNode(const rclcpp::NodeOptions & options);

Expand Down Expand Up @@ -75,6 +79,7 @@ class PointPaintingFusionNode
autoware::lidar_centerpoint::DetectionClassRemapper detection_class_remapper_;

std::unique_ptr<image_projection_based_fusion::PointPaintingTRT> detector_ptr_{nullptr};
std::unique_ptr<DiagnosticsModule> diagnostics_module_ptr_;

bool out_of_scope(const DetectedObjects & obj) override;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -193,6 +193,7 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt
// create detector
detector_ptr_ = std::make_unique<image_projection_based_fusion::PointPaintingTRT>(
encoder_param, head_param, densification_param, config);
diagnostics_module_ptr_ = std::make_unique<DiagnosticsModule>(this, "pointpainting_trt");

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

Expand Down Expand Up @@ -401,17 +402,28 @@ void PointPaintingFusionNode::postprocess(sensor_msgs::msg::PointCloud2 & painte
return;
}

diagnostics_module_ptr_->clear();

if (painted_pointcloud_msg.data.empty() || painted_pointcloud_msg.fields.empty()) {
RCLCPP_WARN_STREAM_THROTTLE(
this->get_logger(), *this->get_clock(), 1000, "Empty sensor points!");
return;
}

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);
if (!is_success) {
return;
}
diagnostics_module_ptr_->add_key_value("is_num_pillars_within_range", is_num_pillars_within_range);
if (!is_num_pillars_within_range) {
std::stringstream message;
message << "PointPaintingTRT::detect: The actual number of pillars exceeds its maximum value, "
<< "which may limit the detection performance.";
diagnostics_module_ptr_->update_level_and_message(
diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str());
}

Check notice on line 426 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.

std::vector<autoware_perception_msgs::msg::DetectedObject> raw_objects;
raw_objects.reserve(det_boxes3d.size());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
#include "autoware/lidar_centerpoint/preprocess/voxel_generator.hpp"
#include "pcl/point_cloud.h"
#include "pcl/point_types.h"

#include "sensor_msgs/msg/point_cloud2.hpp"

#include <memory>
Expand Down Expand Up @@ -62,7 +61,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 @@ -19,6 +19,7 @@
#include "autoware/lidar_centerpoint/detection_class_remapper.hpp"
#include "autoware/lidar_centerpoint/postprocess/non_maximum_suppression.hpp"

#include <autoware/universe_utils/ros/diagnostics_module.hpp>
#include <autoware/universe_utils/ros/debug_publisher.hpp>
#include <autoware/universe_utils/ros/published_time_publisher.hpp>
#include <autoware/universe_utils/system/stop_watch.hpp>
Expand All @@ -39,6 +40,8 @@ namespace autoware::lidar_centerpoint

class LidarCenterPointNode : public rclcpp::Node
{
using DiagnosticsModule = autoware::universe_utils::DiagnosticsModule;

public:
explicit LidarCenterPointNode(const rclcpp::NodeOptions & node_options);

Expand All @@ -59,6 +62,7 @@ class LidarCenterPointNode : public rclcpp::Node
DetectionClassRemapper detection_class_remapper_;

std::unique_ptr<CenterPointTRT> detector_ptr_{nullptr};
std::unique_ptr<DiagnosticsModule> diagnostics_module_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 @@ -127,8 +127,10 @@ void CenterPointTRT::initPtr()

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_CUDA_ERROR(cudaMemsetAsync(
encoder_in_features_d_.get(), 0, encoder_in_feature_size_ * sizeof(float), stream_));
CHECK_CUDA_ERROR(
Expand All @@ -155,6 +157,7 @@ bool CenterPointTRT::detect(
"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;
}

return true;
Expand Down
16 changes: 15 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,7 @@ LidarCenterPointNode::LidarCenterPointNode(const rclcpp::NodeOptions & node_opti
circle_nms_dist_threshold, yaw_norm_thresholds, has_variance_);
detector_ptr_ =
std::make_unique<CenterPointTRT>(encoder_param, head_param, densification_param, config);
diagnostics_module_ptr_ = std::make_unique<DiagnosticsModule>(this, "centerpoint_trt");

Check warning on line 110 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 88 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.

pointcloud_sub_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
"~/input/pointcloud", rclcpp::SensorDataQoS{}.keep_last(1),
Expand Down Expand Up @@ -145,11 +146,22 @@ void LidarCenterPointNode::pointCloudCallback(
stop_watch_ptr_->toc("processing_time", true);
}

diagnostics_module_ptr_->clear();

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);
if (!is_success) {
return;
}
diagnostics_module_ptr_->add_key_value("is_num_pillars_within_range", is_num_pillars_within_range);
if (!is_num_pillars_within_range) {
std::stringstream message;
message << "CenterPointTRT::detect: The actual number of pillars exceeds its maximum value, "
<< "which may limit the detection performance.";
diagnostics_module_ptr_->update_level_and_message(
diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str());
}

std::vector<autoware_perception_msgs::msg::DetectedObject> raw_objects;
raw_objects.reserve(det_boxes3d.size());
Expand All @@ -170,6 +182,8 @@ void LidarCenterPointNode::pointCloudCallback(
published_time_publisher_->publish_if_subscribed(objects_pub_, output_msg.header.stamp);
}

diagnostics_module_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.
// add processing time for debug
if (debug_publisher_ptr_ && stop_watch_ptr_) {
const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
Expand Down

0 comments on commit d13ae2c

Please sign in to comment.