Skip to content

Commit

Permalink
feat: add has_variance to config
Browse files Browse the repository at this point in the history
Signed-off-by: tzhong518 <[email protected]>
  • Loading branch information
tzhong518 committed Mar 8, 2024
1 parent 6444125 commit 356be27
Show file tree
Hide file tree
Showing 10 changed files with 258 additions and 35 deletions.
1 change: 1 addition & 0 deletions perception/lidar_centerpoint/config/centerpoint.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
iou_nms_threshold: 0.1
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
score_threshold: 0.35
has_variance: false
has_twist: false
trt_precision: fp16
densification_num_past_frames: 1
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
iou_nms_threshold: 0.1
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
score_threshold: 0.35
has_variance: true
has_twist: true
trt_precision: fp16
densification_num_past_frames: 1
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
iou_nms_threshold: 0.1
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
score_threshold: 0.35
has_variance: false
has_twist: false
trt_precision: fp16
densification_num_past_frames: 1
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ class CenterPointConfig
const std::vector<double> & point_cloud_range, const std::vector<double> & voxel_size,
const std::size_t downsample_factor, const std::size_t encoder_in_feature_size,
const float score_threshold, const float circle_nms_dist_threshold,
const std::vector<double> yaw_norm_thresholds)
const std::vector<double> yaw_norm_thresholds, const bool has_variance)
{
class_size_ = class_size;
point_feature_size_ = point_feature_size;
Expand All @@ -49,6 +49,15 @@ class CenterPointConfig
downsample_factor_ = downsample_factor;
encoder_in_feature_size_ = encoder_in_feature_size;

if (has_variance) {
has_variance_ = true;
head_out_offset_size_ = 4;
head_out_z_size_ = 2;
head_out_dim_size_ = 6;
head_out_rot_size_ = 4;
head_out_vel_size_ = 4;
}

if (score_threshold > 0 && score_threshold < 1) {
score_threshold_ = score_threshold;
}
Expand Down Expand Up @@ -97,11 +106,12 @@ class CenterPointConfig
std::size_t encoder_in_feature_size_{9};
const std::size_t encoder_out_feature_size_{32};
const std::size_t head_out_size_{6};
const std::size_t head_out_offset_size_{4};
const std::size_t head_out_z_size_{2};
const std::size_t head_out_dim_size_{6};
const std::size_t head_out_rot_size_{4};
const std::size_t head_out_vel_size_{4};
bool has_variance_{false};
std::size_t head_out_offset_size_{2};
std::size_t head_out_z_size_{1};
std::size_t head_out_dim_size_{3};
std::size_t head_out_rot_size_{2};
std::size_t head_out_vel_size_{2};

// post-process params
float score_threshold_{0.35f};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@ class LidarCenterPointNode : public rclcpp::Node

float score_threshold_{0.0};
std::vector<std::string> class_names_;
bool has_variance_{false};
bool has_twist_{false};

NonMaximumSuppression iou_bev_nms_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ namespace centerpoint

void box3DToDetectedObject(
const Box3D & box3d, const std::vector<std::string> & class_names, const bool has_twist,
autoware_auto_perception_msgs::msg::DetectedObject & obj);
const bool has_variance, autoware_auto_perception_msgs::msg::DetectedObject & obj);

uint8_t getSemanticType(const std::string & class_name);

Expand Down
48 changes: 25 additions & 23 deletions perception/lidar_centerpoint/lib/postprocess/postprocess_kernel.cu
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ __global__ void generateBoxes3D_kernel(
const float * out_rot, const float * out_vel, const float voxel_size_x, const float voxel_size_y,
const float range_min_x, const float range_min_y, const std::size_t down_grid_size_x,
const std::size_t down_grid_size_y, const std::size_t downsample_factor, const int class_size,
const float * yaw_norm_thresholds, Box3D * det_boxes3d)
const bool has_variance, const float * yaw_norm_thresholds, Box3D * det_boxes3d)
{
// generate boxes3d from the outputs of the network.
// shape of out_*: (N, DOWN_GRID_SIZE_Y, DOWN_GRID_SIZE_X)
Expand Down Expand Up @@ -96,17 +96,6 @@ __global__ void generateBoxes3D_kernel(
const float vel_x = out_vel[down_grid_size * 0 + idx];
const float vel_y = out_vel[down_grid_size * 1 + idx];

const float offset_x_variance = out_offset[down_grid_size * 2 + idx];
const float offset_y_variance = out_offset[down_grid_size * 3 + idx];
const float z_variance = out_z[down_grid_size * 1 + idx];
const float w_variance = out_dim[down_grid_size * 3 + idx];
const float l_variance = out_dim[down_grid_size * 4 + idx];
const float h_variance = out_dim[down_grid_size * 5 + idx];
const float yaw_sin_log_variance = out_rot[down_grid_size * 2 + idx];
const float yaw_cos_log_variance = out_rot[down_grid_size * 3 + idx];
const float vel_x_variance = out_vel[down_grid_size * 2 + idx];
const float vel_y_variance = out_vel[down_grid_size * 3 + idx];

det_boxes3d[idx].label = label;
det_boxes3d[idx].score = yaw_norm >= yaw_norm_thresholds[label] ? max_score : 0.f;
det_boxes3d[idx].x = x;
Expand All @@ -119,16 +108,29 @@ __global__ void generateBoxes3D_kernel(
det_boxes3d[idx].vel_x = vel_x;
det_boxes3d[idx].vel_y = vel_y;

det_boxes3d[idx].x_variance = expf(offset_x_variance);
det_boxes3d[idx].y_variance = expf(offset_y_variance);
det_boxes3d[idx].z_variance = expf(z_variance);
det_boxes3d[idx].length_variance = expf(l_variance);
det_boxes3d[idx].width_variance = expf(w_variance);
det_boxes3d[idx].height_variance = expf(h_variance);
det_boxes3d[idx].yaw_variance = (powf(yaw_cos,2) * expf(yaw_sin_log_variance) + powf(yaw_sin,2) * expf(yaw_cos_log_variance)) /
(powf((powf(yaw_sin,2) + powf(yaw_cos,2)),2));
det_boxes3d[idx].vel_x_variance = expf(vel_x_variance);
det_boxes3d[idx].vel_y_variance = expf(vel_y_variance);
if (has_variance) {
const float offset_x_variance = out_offset[down_grid_size * 2 + idx];
const float offset_y_variance = out_offset[down_grid_size * 3 + idx];
const float z_variance = out_z[down_grid_size * 1 + idx];
const float w_variance = out_dim[down_grid_size * 3 + idx];
const float l_variance = out_dim[down_grid_size * 4 + idx];
const float h_variance = out_dim[down_grid_size * 5 + idx];
const float yaw_sin_log_variance = out_rot[down_grid_size * 2 + idx];
const float yaw_cos_log_variance = out_rot[down_grid_size * 3 + idx];
const float vel_x_variance = out_vel[down_grid_size * 2 + idx];
const float vel_y_variance = out_vel[down_grid_size * 3 + idx];

det_boxes3d[idx].x_variance = expf(offset_x_variance);
det_boxes3d[idx].y_variance = expf(offset_y_variance);
det_boxes3d[idx].z_variance = expf(z_variance);
det_boxes3d[idx].length_variance = expf(l_variance);
det_boxes3d[idx].width_variance = expf(w_variance);
det_boxes3d[idx].height_variance = expf(h_variance);
det_boxes3d[idx].yaw_variance = (powf(yaw_cos,2) * expf(yaw_sin_log_variance) + powf(yaw_sin,2) * expf(yaw_cos_log_variance)) /
(powf((powf(yaw_sin,2) + powf(yaw_cos,2)),2));
det_boxes3d[idx].vel_x_variance = expf(vel_x_variance);
det_boxes3d[idx].vel_y_variance = expf(vel_y_variance);
}
}

PostProcessCUDA::PostProcessCUDA(const CenterPointConfig & config) : config_(config)
Expand All @@ -152,7 +154,7 @@ cudaError_t PostProcessCUDA::generateDetectedBoxes3D_launch(
generateBoxes3D_kernel<<<blocks, threads, 0, stream>>>(
out_heatmap, out_offset, out_z, out_dim, out_rot, out_vel, config_.voxel_size_x_,
config_.voxel_size_y_, config_.range_min_x_, config_.range_min_y_, config_.down_grid_size_x_,
config_.down_grid_size_y_, config_.downsample_factor_, config_.class_size_,
config_.down_grid_size_y_, config_.downsample_factor_, config_.class_size_, config_.has_variance_,
thrust::raw_pointer_cast(yaw_norm_thresholds_d_.data()),
thrust::raw_pointer_cast(boxes3d_d_.data()));

Expand Down
12 changes: 9 additions & 3 deletions perception/lidar_centerpoint/lib/ros_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ using Label = autoware_auto_perception_msgs::msg::ObjectClassification;

void box3DToDetectedObject(
const Box3D & box3d, const std::vector<std::string> & class_names, const bool has_twist,
autoware_auto_perception_msgs::msg::DetectedObject & obj)
const bool has_variance, autoware_auto_perception_msgs::msg::DetectedObject & obj)
{
// TODO(yukke42): the value of classification confidence of DNN, not probability.
obj.existence_probability = box3d.score;
Expand Down Expand Up @@ -55,10 +55,13 @@ void box3DToDetectedObject(
tier4_autoware_utils::createPoint(box3d.x, box3d.y, box3d.z);
obj.kinematics.pose_with_covariance.pose.orientation =
tier4_autoware_utils::createQuaternionFromYaw(yaw);
obj.kinematics.pose_with_covariance.covariance = convertPoseCovarianceMatrix(box3d);
obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX;
obj.shape.dimensions =
tier4_autoware_utils::createTranslation(box3d.length, box3d.width, box3d.height);
if (has_variance) {
obj.kinematics.has_position_covariance = has_variance;
obj.kinematics.pose_with_covariance.covariance = convertPoseCovarianceMatrix(box3d);
}

// twist
if (has_twist) {
Expand All @@ -69,7 +72,10 @@ void box3DToDetectedObject(
twist.angular.z = 2 * (std::atan2(vel_y, vel_x) - yaw);
obj.kinematics.twist_with_covariance.twist = twist;
obj.kinematics.has_twist = has_twist;
obj.kinematics.twist_with_covariance.covariance = convertTwistCovarianceMatrix(box3d);
if (has_variance) {
obj.kinematics.has_twist_covariance = has_variance;
obj.kinematics.twist_with_covariance.covariance = convertTwistCovarianceMatrix(box3d);
}

Check warning on line 78 in perception/lidar_centerpoint/lib/ros_utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Excess Number of Function Arguments

box3DToDetectedObject has 5 arguments, threshold = 4. This function has too many arguments, indicating a lack of encapsulation. Avoid adding more arguments.
}
}

Expand Down
200 changes: 200 additions & 0 deletions perception/lidar_centerpoint/src/node copy.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,200 @@
// Copyright 2021 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "lidar_centerpoint/node.hpp"

#include <lidar_centerpoint/centerpoint_config.hpp>
#include <lidar_centerpoint/preprocess/pointcloud_densification.hpp>
#include <lidar_centerpoint/ros_utils.hpp>
#include <lidar_centerpoint/utils.hpp>
#include <pcl_ros/transforms.hpp>

#ifdef ROS_DISTRO_GALACTIC
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#else
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#endif

#include <Eigen/Dense>
#include <Eigen/Geometry>

#include <memory>
#include <string>
#include <vector>

namespace centerpoint
{
LidarCenterPointNode::LidarCenterPointNode(const rclcpp::NodeOptions & node_options)
: Node("lidar_center_point", node_options), tf_buffer_(this->get_clock())
{
const float score_threshold =
static_cast<float>(this->declare_parameter<double>("score_threshold", 0.35));
const float circle_nms_dist_threshold =
static_cast<float>(this->declare_parameter<double>("circle_nms_dist_threshold"));
const auto yaw_norm_thresholds =
this->declare_parameter<std::vector<double>>("yaw_norm_thresholds");
const std::string densification_world_frame_id =
this->declare_parameter("densification_world_frame_id", "map");
const int densification_num_past_frames =
this->declare_parameter("densification_num_past_frames", 1);
const std::string trt_precision = this->declare_parameter("trt_precision", "fp16");
const std::string encoder_onnx_path = this->declare_parameter<std::string>("encoder_onnx_path");
const std::string encoder_engine_path =
this->declare_parameter<std::string>("encoder_engine_path");
const std::string head_onnx_path = this->declare_parameter<std::string>("head_onnx_path");
const std::string head_engine_path = this->declare_parameter<std::string>("head_engine_path");
class_names_ = this->declare_parameter<std::vector<std::string>>("class_names");
has_twist_ = this->declare_parameter("has_twist", false);
const std::size_t point_feature_size =
static_cast<std::size_t>(this->declare_parameter<std::int64_t>("point_feature_size"));
const std::size_t max_voxel_size =
static_cast<std::size_t>(this->declare_parameter<std::int64_t>("max_voxel_size"));
const auto point_cloud_range = this->declare_parameter<std::vector<double>>("point_cloud_range");
const auto voxel_size = this->declare_parameter<std::vector<double>>("voxel_size");
const std::size_t downsample_factor =
static_cast<std::size_t>(this->declare_parameter<std::int64_t>("downsample_factor"));
const std::size_t encoder_in_feature_size =
static_cast<std::size_t>(this->declare_parameter<std::int64_t>("encoder_in_feature_size"));
const auto allow_remapping_by_area_matrix =
this->declare_parameter<std::vector<int64_t>>("allow_remapping_by_area_matrix");
const auto min_area_matrix = this->declare_parameter<std::vector<double>>("min_area_matrix");
const auto max_area_matrix = this->declare_parameter<std::vector<double>>("max_area_matrix");

detection_class_remapper_.setParameters(
allow_remapping_by_area_matrix, min_area_matrix, max_area_matrix);

{
NMSParams p;
p.nms_type_ = NMS_TYPE::IoU_BEV;
p.target_class_names_ =
this->declare_parameter<std::vector<std::string>>("iou_nms_target_class_names");
p.search_distance_2d_ = this->declare_parameter<double>("iou_nms_search_distance_2d");
p.iou_threshold_ = this->declare_parameter<double>("iou_nms_threshold");
iou_bev_nms_.setParameters(p);
}

NetworkParam encoder_param(encoder_onnx_path, encoder_engine_path, trt_precision);
NetworkParam head_param(head_onnx_path, head_engine_path, trt_precision);
DensificationParam densification_param(
densification_world_frame_id, densification_num_past_frames);

if (point_cloud_range.size() != 6) {
RCLCPP_WARN_STREAM(
rclcpp::get_logger("lidar_centerpoint"),
"The size of point_cloud_range != 6: use the default parameters.");
}
if (voxel_size.size() != 3) {
RCLCPP_WARN_STREAM(
rclcpp::get_logger("lidar_centerpoint"),
"The size of voxel_size != 3: use the default parameters.");
}
CenterPointConfig config(
class_names_.size(), point_feature_size, max_voxel_size, point_cloud_range, voxel_size,
downsample_factor, encoder_in_feature_size, score_threshold, circle_nms_dist_threshold,
yaw_norm_thresholds);
detector_ptr_ =
std::make_unique<CenterPointTRT>(encoder_param, head_param, densification_param, config);

pointcloud_sub_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
"~/input/pointcloud", rclcpp::SensorDataQoS{}.keep_last(1),
std::bind(&LidarCenterPointNode::pointCloudCallback, this, std::placeholders::_1));
objects_pub_ = this->create_publisher<autoware_auto_perception_msgs::msg::DetectedObjects>(
"~/output/objects", rclcpp::QoS{1});

// initialize debug tool
{
using tier4_autoware_utils::DebugPublisher;
using tier4_autoware_utils::StopWatch;
stop_watch_ptr_ = std::make_unique<StopWatch<std::chrono::milliseconds>>();
debug_publisher_ptr_ = std::make_unique<DebugPublisher>(this, "lidar_centerpoint");
stop_watch_ptr_->tic("cyclic_time");
stop_watch_ptr_->tic("processing_time");
}

if (this->declare_parameter("build_only", false)) {
RCLCPP_INFO(this->get_logger(), "TensorRT engine is built and shutdown node.");
rclcpp::shutdown();
}
}

Check warning on line 129 in perception/lidar_centerpoint/src/node copy.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Large Method

LidarCenterPointNode::LidarCenterPointNode has 84 lines, 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.

void LidarCenterPointNode::pointCloudCallback(
const sensor_msgs::msg::PointCloud2::ConstSharedPtr input_pointcloud_msg)
{
const auto objects_sub_count =
objects_pub_->get_subscription_count() + objects_pub_->get_intra_process_subscription_count();
if (objects_sub_count < 1) {
return;
}

if (stop_watch_ptr_) {
stop_watch_ptr_->toc("processing_time", true);
}

std::vector<Box3D> det_boxes3d;
std::vector<Variance> det_variance;
bool is_success =
detector_ptr_->detect(*input_pointcloud_msg, tf_buffer_, det_boxes3d, det_variance);
if (!is_success) {
return;
}

std::cout << "-------------------------det_variance:" << det_variance.size() << std::endl;
// << det_variance[0] << std::endl;

std::vector<autoware_auto_perception_msgs::msg::DetectedObject> raw_objects;
raw_objects.reserve(det_boxes3d.size());
// for (const auto & box3d : det_boxes3d) {
// autoware_auto_perception_msgs::msg::DetectedObject obj;
// box3DToDetectedObject(box3d, class_names_, has_twist_, obj);
// raw_objects.emplace_back(obj);
// }
for (size_t i = 0; i < det_boxes3d.size(); ++i) {
autoware_auto_perception_msgs::msg::DetectedObject obj;
box3DToDetectedObject(det_boxes3d[i], class_names_, has_twist_, obj);
raw_objects.emplace_back(obj);
std::cout << i << " /// x_variance:" << det_variance[i].x_variance << std::endl;
}

autoware_auto_perception_msgs::msg::DetectedObjects output_msg;
output_msg.header = input_pointcloud_msg->header;
output_msg.objects = iou_bev_nms_.apply(raw_objects);

detection_class_remapper_.mapClasses(output_msg);

if (objects_sub_count > 0) {
objects_pub_->publish(output_msg);
}

// add processing time for debug
if (debug_publisher_ptr_ && stop_watch_ptr_) {
const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true);
const double pipeline_latency_ms =
std::chrono::duration<double, std::milli>(
std::chrono::nanoseconds(
(this->get_clock()->now() - output_msg.header.stamp).nanoseconds()))
.count();
debug_publisher_ptr_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/cyclic_time_ms", cyclic_time_ms);
debug_publisher_ptr_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);
debug_publisher_ptr_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/pipeline_latency_ms", pipeline_latency_ms);
}
}

} // namespace centerpoint

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(centerpoint::LidarCenterPointNode)
Loading

0 comments on commit 356be27

Please sign in to comment.