Skip to content

Commit

Permalink
refactor(cuda_utils): prefix package and namespace with autoware
Browse files Browse the repository at this point in the history
Signed-off-by: Esteve Fernandez <[email protected]>
  • Loading branch information
esteve committed Oct 30, 2024
1 parent 94b9ad0 commit 3721e94
Show file tree
Hide file tree
Showing 25 changed files with 119 additions and 117 deletions.
2 changes: 1 addition & 1 deletion .github/CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
Expand Up @@ -199,6 +199,7 @@ planning/sampling_based_planner/autoware_bezier_sampler/** maxime.clement@tier4.
planning/sampling_based_planner/autoware_frenet_planner/** [email protected]
planning/sampling_based_planner/autoware_path_sampler/** [email protected]
planning/sampling_based_planner/autoware_sampler_common/** [email protected]
sensing/autoware_cuda_utils/** [email protected] [email protected] [email protected]
sensing/autoware_gnss_poser/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
sensing/autoware_image_diagnostics/** [email protected] [email protected]
sensing/autoware_image_transport_decompressor/** [email protected] [email protected]
Expand All @@ -209,7 +210,6 @@ sensing/autoware_radar_scan_to_pointcloud2/** [email protected] shunsuke.m
sensing/autoware_radar_static_pointcloud_filter/** [email protected] [email protected] [email protected] [email protected]
sensing/autoware_radar_threshold_filter/** [email protected] [email protected] [email protected] [email protected]
sensing/autoware_radar_tracks_noise_filter/** [email protected] [email protected] [email protected] [email protected]
sensing/cuda_utils/** [email protected] [email protected] [email protected]
sensing/livox/autoware_livox_tag_filter/** [email protected] [email protected]
sensing/vehicle_velocity_converter/** [email protected]
simulator/autoware_carla_interface/** [email protected] [email protected]
Expand Down
2 changes: 1 addition & 1 deletion perception/autoware_bytetrack/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,10 @@
<buildtool_export_depend>cudnn_cmake_module</buildtool_export_depend>
<buildtool_export_depend>tensorrt_cmake_module</buildtool_export_depend>

<depend>autoware_cuda_utils</depend>
<depend>autoware_kalman_filter</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_tensorrt_common</depend>
<depend>cuda_utils</depend>
<depend>cv_bridge</depend>
<depend>eigen</depend>
<depend>image_transport</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ if(NOT ${autoware_tensorrt_common_FOUND})
)
return()
endif()
find_package(cuda_utils REQUIRED)
find_package(autoware_cuda_utils REQUIRED)

add_library(${PROJECT_NAME} SHARED
src/node.cpp
Expand All @@ -38,7 +38,7 @@ add_library(${PROJECT_NAME} SHARED
target_include_directories(${PROJECT_NAME} PRIVATE
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
${cuda_utils_INCLUDE_DIRS}
${autoware_cuda_utils_INCLUDE_DIRS}
${pcl_conversions_INCLUDE_DIRS}
${autoware_universe_utils_INCLUDE_DIRS}
${autoware_perception_msgs_INCLUDE_DIRS}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,10 @@
#include "autoware/lidar_apollo_instance_segmentation/feature_generator.hpp"
#include "autoware/lidar_apollo_instance_segmentation/node.hpp"

#include <autoware/cuda_utils/cuda_unique_ptr.hpp>
#include <autoware/cuda_utils/stream_unique_ptr.hpp>
#include <autoware/tensorrt_common/tensorrt_common.hpp>
#include <autoware/universe_utils/transform/transforms.hpp>
#include <cuda_utils/cuda_unique_ptr.hpp>
#include <cuda_utils/stream_unique_ptr.hpp>
#include <tf2_eigen/tf2_eigen.hpp>

#include <tf2_ros/buffer_interface.h>
Expand All @@ -35,10 +35,10 @@ namespace autoware
{
namespace lidar_apollo_instance_segmentation
{
using cuda_utils::CudaUniquePtr;
using cuda_utils::CudaUniquePtrHost;
using cuda_utils::makeCudaStream;
using cuda_utils::StreamUniquePtr;
using autoware::cuda_utils::CudaUniquePtr;
using autoware::cuda_utils::CudaUniquePtrHost;
using autoware::cuda_utils::makeCudaStream;
using autoware::cuda_utils::StreamUniquePtr;

class LidarApolloInstanceSegmentation : public LidarInstanceSegmentationInterface
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,10 +13,10 @@

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>autoware_cuda_utils</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_tensorrt_common</depend>
<depend>autoware_universe_utils</depend>
<depend>cuda_utils</depend>
<depend>libpcl-all-dev</depend>
<depend>pcl_conversions</depend>
<depend>rclcpp</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,12 +65,12 @@ LidarApolloInstanceSegmentation::LidarApolloInstanceSegmentation(rclcpp::Node *
const auto input_dims = trt_common_->getBindingDimensions(0);
const auto input_size =
std::accumulate(input_dims.d + 1, input_dims.d + input_dims.nbDims, 1, std::multiplies<int>());
input_d_ = cuda_utils::make_unique<float[]>(input_size);
input_d_ = autoware::cuda_utils::make_unique<float[]>(input_size);
const auto output_dims = trt_common_->getBindingDimensions(1);
output_size_ = std::accumulate(
output_dims.d + 1, output_dims.d + output_dims.nbDims, 1, std::multiplies<int>());
output_d_ = cuda_utils::make_unique<float[]>(output_size_);
output_h_ = cuda_utils::make_unique_host<float[]>(output_size_, cudaHostAllocPortable);
output_d_ = autoware::cuda_utils::make_unique<float[]>(output_size_);
output_h_ = autoware::cuda_utils::make_unique_host<float[]>(output_size_, cudaHostAllocPortable);

// feature map generator: pre process
feature_generator_ = std::make_shared<FeatureGenerator>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,10 @@
#ifndef AUTOWARE__SHAPE_ESTIMATION__TENSORRT_SHAPE_ESTIMATOR_HPP_
#define AUTOWARE__SHAPE_ESTIMATION__TENSORRT_SHAPE_ESTIMATOR_HPP_

#include <autoware/cuda_utils/cuda_check_error.hpp>
#include <autoware/cuda_utils/cuda_unique_ptr.hpp>
#include <autoware/cuda_utils/stream_unique_ptr.hpp>
#include <autoware/tensorrt_common/tensorrt_common.hpp>
#include <cuda_utils/cuda_check_error.hpp>
#include <cuda_utils/cuda_unique_ptr.hpp>
#include <cuda_utils/stream_unique_ptr.hpp>
#include <pcl_ros/transforms.hpp>

#include <autoware_perception_msgs/msg/detected_objects.hpp>
Expand All @@ -34,10 +34,10 @@

namespace autoware::shape_estimation
{
using cuda_utils::CudaUniquePtr;
using cuda_utils::CudaUniquePtrHost;
using cuda_utils::makeCudaStream;
using cuda_utils::StreamUniquePtr;
using autoware::cuda_utils::CudaUniquePtr;
using autoware::cuda_utils::CudaUniquePtrHost;
using autoware::cuda_utils::makeCudaStream;
using autoware::cuda_utils::StreamUniquePtr;

using autoware_perception_msgs::msg::DetectedObject;
using autoware_perception_msgs::msg::DetectedObjects;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,32 +41,33 @@ TrtShapeEstimator::TrtShapeEstimator(
const auto pc_input_dims = trt_common_->getBindingDimensions(0);
const auto pc_input_size = std::accumulate(
pc_input_dims.d + 1, pc_input_dims.d + pc_input_dims.nbDims, 1, std::multiplies<int>());
input_pc_d_ = cuda_utils::make_unique<float[]>(pc_input_size * batch_config[2]);
input_pc_d_ = autoware::cuda_utils::make_unique<float[]>(pc_input_size * batch_config[2]);
batch_size_ = batch_config[2];
const auto one_hot_input_dims = trt_common_->getBindingDimensions(1);
const auto one_hot_input_size = std::accumulate(
one_hot_input_dims.d + 1, one_hot_input_dims.d + one_hot_input_dims.nbDims, 1,
std::multiplies<int>());
input_one_hot_d_ = cuda_utils::make_unique<float[]>(one_hot_input_size * batch_config[2]);
input_one_hot_d_ =
autoware::cuda_utils::make_unique<float[]>(one_hot_input_size * batch_config[2]);

const auto stage1_center_out_dims = trt_common_->getBindingDimensions(2);
out_s1center_elem_num_ = std::accumulate(
stage1_center_out_dims.d + 1, stage1_center_out_dims.d + stage1_center_out_dims.nbDims, 1,
std::multiplies<int>());
out_s1center_elem_num_ = out_s1center_elem_num_ * batch_config[2];
out_s1center_elem_num_per_batch_ = static_cast<size_t>(out_s1center_elem_num_ / batch_config[2]);
out_s1center_prob_d_ = cuda_utils::make_unique<float[]>(out_s1center_elem_num_);
out_s1center_prob_d_ = autoware::cuda_utils::make_unique<float[]>(out_s1center_elem_num_);
out_s1center_prob_h_ =
cuda_utils::make_unique_host<float[]>(out_s1center_elem_num_, cudaHostAllocPortable);
autoware::cuda_utils::make_unique_host<float[]>(out_s1center_elem_num_, cudaHostAllocPortable);

const auto pred_out_dims = trt_common_->getBindingDimensions(3);
out_pred_elem_num_ = std::accumulate(
pred_out_dims.d + 1, pred_out_dims.d + pred_out_dims.nbDims, 1, std::multiplies<int>());
out_pred_elem_num_ = out_pred_elem_num_ * batch_config[2];
out_pred_elem_num_per_batch_ = static_cast<size_t>(out_pred_elem_num_ / batch_config[2]);
out_pred_prob_d_ = cuda_utils::make_unique<float[]>(out_pred_elem_num_);
out_pred_prob_d_ = autoware::cuda_utils::make_unique<float[]>(out_pred_elem_num_);
out_pred_prob_h_ =
cuda_utils::make_unique_host<float[]>(out_pred_elem_num_, cudaHostAllocPortable);
autoware::cuda_utils::make_unique_host<float[]>(out_pred_elem_num_, cudaHostAllocPortable);

g_type_mean_size_ = {{4.6344314, 1.9600292, 1.7375569}, {6.936331, 2.5178623, 2.8506238},
{11.194943, 2.9501154, 3.4918275}, {12.275775, 2.9231303, 3.87086},
Expand Down
2 changes: 1 addition & 1 deletion perception/autoware_shape_estimation/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,10 @@
<buildtool_export_depend>cudnn_cmake_module</buildtool_export_depend>
<buildtool_export_depend>tensorrt_cmake_module</buildtool_export_depend>

<depend>autoware_cuda_utils</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_tensorrt_common</depend>
<depend>autoware_universe_utils</depend>
<depend>cuda_utils</depend>
<depend>eigen</depend>
<depend>libopencv-dev</depend>
<depend>libpcl-all-dev</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,8 @@

#ifndef AUTOWARE__TENSORRT_CLASSIFIER__CALIBRATOR_HPP_
#define AUTOWARE__TENSORRT_CLASSIFIER__CALIBRATOR_HPP_
#include "cuda_utils/cuda_check_error.hpp"
#include "cuda_utils/cuda_unique_ptr.hpp"
#include "autoware/cuda_utils/cuda_check_error.hpp"
#include "autoware/cuda_utils/cuda_unique_ptr.hpp"

#include <opencv2/core/core.hpp>
#include <opencv2/highgui/highgui.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,10 @@
#ifndef AUTOWARE__TENSORRT_CLASSIFIER__TENSORRT_CLASSIFIER_HPP_
#define AUTOWARE__TENSORRT_CLASSIFIER__TENSORRT_CLASSIFIER_HPP_

#include <autoware/cuda_utils/cuda_check_error.hpp>
#include <autoware/cuda_utils/cuda_unique_ptr.hpp>
#include <autoware/cuda_utils/stream_unique_ptr.hpp>
#include <autoware/tensorrt_common/tensorrt_common.hpp>
#include <cuda_utils/cuda_check_error.hpp>
#include <cuda_utils/cuda_unique_ptr.hpp>
#include <cuda_utils/stream_unique_ptr.hpp>
#include <opencv2/opencv.hpp>

#include <memory>
Expand All @@ -27,10 +27,10 @@

namespace autoware::tensorrt_classifier
{
using cuda_utils::CudaUniquePtr;
using cuda_utils::CudaUniquePtrHost;
using cuda_utils::makeCudaStream;
using cuda_utils::StreamUniquePtr;
using autoware::cuda_utils::CudaUniquePtr;
using autoware::cuda_utils::CudaUniquePtrHost;
using autoware::cuda_utils::makeCudaStream;
using autoware::cuda_utils::StreamUniquePtr;

/**
* @class TrtClassifier
Expand Down
2 changes: 1 addition & 1 deletion perception/autoware_tensorrt_classifier/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@

<build_depend>autoware_cmake</build_depend>

<depend>autoware_cuda_utils</depend>
<depend>autoware_tensorrt_common</depend>
<depend>cuda_utils</depend>
<depend>libopencv-dev</depend>
<depend>rclcpp</depend>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -170,13 +170,14 @@ TrtClassifier::TrtClassifier(
std::accumulate(input_dims.d + 1, input_dims.d + input_dims.nbDims, 1, std::multiplies<int>());

const auto output_dims = trt_common_->getBindingDimensions(1);
input_d_ = cuda_utils::make_unique<float[]>(batch_config[2] * input_size);
input_d_ = autoware::cuda_utils::make_unique<float[]>(batch_config[2] * input_size);
out_elem_num_ = std::accumulate(
output_dims.d + 1, output_dims.d + output_dims.nbDims, 1, std::multiplies<int>());
out_elem_num_ = out_elem_num_ * batch_config[2];
out_elem_num_per_batch_ = static_cast<int>(out_elem_num_ / batch_config[2]);
out_prob_d_ = cuda_utils::make_unique<float[]>(out_elem_num_);
out_prob_h_ = cuda_utils::make_unique_host<float[]>(out_elem_num_, cudaHostAllocPortable);
out_prob_d_ = autoware::cuda_utils::make_unique<float[]>(out_elem_num_);
out_prob_h_ =
autoware::cuda_utils::make_unique_host<float[]>(out_elem_num_, cudaHostAllocPortable);

Check warning on line 180 in perception/autoware_tensorrt_classifier/src/tensorrt_classifier.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

TrtClassifier::TrtClassifier already has high cyclomatic complexity, and now it increases in Lines of Code from 83 to 84. 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.

if (cuda) {
m_cuda = true;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,8 @@
#ifndef AUTOWARE__TENSORRT_YOLOX__CALIBRATOR_HPP_
#define AUTOWARE__TENSORRT_YOLOX__CALIBRATOR_HPP_

#include "cuda_utils/cuda_check_error.hpp"
#include "cuda_utils/cuda_unique_ptr.hpp"
#include "autoware/cuda_utils/cuda_check_error.hpp"
#include "autoware/cuda_utils/cuda_unique_ptr.hpp"

#include <opencv2/core/core.hpp>
#include <opencv2/highgui/highgui.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,10 @@
#ifndef AUTOWARE__TENSORRT_YOLOX__TENSORRT_YOLOX_HPP_
#define AUTOWARE__TENSORRT_YOLOX__TENSORRT_YOLOX_HPP_

#include <autoware/cuda_utils/cuda_unique_ptr.hpp>
#include <autoware/cuda_utils/stream_unique_ptr.hpp>
#include <autoware/tensorrt_common/tensorrt_common.hpp>
#include <autoware/tensorrt_yolox/preprocess.hpp>
#include <cuda_utils/cuda_unique_ptr.hpp>
#include <cuda_utils/stream_unique_ptr.hpp>
#include <opencv2/opencv.hpp>

#include <memory>
Expand All @@ -27,10 +27,10 @@

namespace autoware::tensorrt_yolox
{
using cuda_utils::CudaUniquePtr;
using cuda_utils::CudaUniquePtrHost;
using cuda_utils::makeCudaStream;
using cuda_utils::StreamUniquePtr;
using autoware::cuda_utils::CudaUniquePtr;
using autoware::cuda_utils::CudaUniquePtrHost;
using autoware::cuda_utils::makeCudaStream;
using autoware::cuda_utils::StreamUniquePtr;

struct Object
{
Expand Down
2 changes: 1 addition & 1 deletion perception/autoware_tensorrt_yolox/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,10 @@
<buildtool_export_depend>cudnn_cmake_module</buildtool_export_depend>
<buildtool_export_depend>tensorrt_cmake_module</buildtool_export_depend>

<depend>autoware_cuda_utils</depend>
<depend>autoware_object_recognition_utils</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_tensorrt_common</depend>
<depend>cuda_utils</depend>
<depend>cv_bridge</depend>
<depend>image_transport</depend>
<depend>libopencv-dev</depend>
Expand Down
Loading

0 comments on commit 3721e94

Please sign in to comment.