centerpoint_trt.hpp 4.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143
  1. // Copyright 2021 TIER IV, Inc.
  2. //
  3. // Licensed under the Apache License, Version 2.0 (the "License");
  4. // you may not use this file except in compliance with the License.
  5. // You may obtain a copy of the License at
  6. //
  7. // http://www.apache.org/licenses/LICENSE-2.0
  8. //
  9. // Unless required by applicable law or agreed to in writing, software
  10. // distributed under the License is distributed on an "AS IS" BASIS,
  11. // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  12. // See the License for the specific language governing permissions and
  13. // limitations under the License.
  14. #ifndef LIDAR_CENTERPOINT__CENTERPOINT_TRT_HPP_
  15. #define LIDAR_CENTERPOINT__CENTERPOINT_TRT_HPP_
  16. #include <lidar_centerpoint/cuda_utils.hpp>
  17. #include <lidar_centerpoint/network/network_trt.hpp>
  18. #include <lidar_centerpoint/postprocess/postprocess_kernel.hpp>
  19. #include <lidar_centerpoint/preprocess/voxel_generator.hpp>
  20. //#include <sensor_msgs/msg/point_cloud2.hpp>
  21. #include <pcl/point_cloud.h>
  22. #include <pcl/point_types.h>
  23. #include <memory>
  24. #include <string>
  25. #include <utility>
  26. #include <vector>
  27. namespace centerpoint
  28. {
  29. static constexpr size_t CAPACITY_POINT = 1000000;
  30. class NetworkParam
  31. {
  32. public:
  33. NetworkParam(std::string onnx_path, std::string engine_path, std::string trt_precision)
  34. : onnx_path_(std::move(onnx_path)),
  35. engine_path_(std::move(engine_path)),
  36. trt_precision_(std::move(trt_precision))
  37. {
  38. }
  39. std::string onnx_path() const { return onnx_path_; }
  40. std::string engine_path() const { return engine_path_; }
  41. std::string trt_precision() const { return trt_precision_; }
  42. private:
  43. std::string onnx_path_;
  44. std::string engine_path_;
  45. std::string trt_precision_;
  46. };
  47. class CenterPointTRT
  48. {
  49. public:
  50. explicit CenterPointTRT(
  51. const NetworkParam & encoder_param, const NetworkParam & head_param,
  52. const DensificationParam & densification_param, const CenterPointConfig & config);
  53. ~CenterPointTRT();
  54. // bool detect(
  55. // const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer,
  56. // std::vector<Box3D> & det_boxes3d);
  57. bool detect(
  58. const pcl::PointCloud<pcl::PointXYZI>::Ptr & pc_ptr,
  59. std::vector<Box3D> & det_boxes3d);
  60. protected:
  61. void initPtr();
  62. // virtual bool preprocess(
  63. // const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer);
  64. virtual bool preprocess(
  65. const pcl::PointCloud<pcl::PointXYZI>::Ptr & pc_ptr);
  66. void inference();
  67. void postProcess(std::vector<Box3D> & det_boxes3d);
  68. std::unique_ptr<VoxelGeneratorTemplate> vg_ptr_{nullptr};
  69. std::unique_ptr<VoxelEncoderTRT> encoder_trt_ptr_{nullptr};
  70. std::unique_ptr<HeadTRT> head_trt_ptr_{nullptr};
  71. std::unique_ptr<PostProcessCUDA> post_proc_ptr_{nullptr};
  72. cudaStream_t stream_{nullptr};
  73. std::size_t class_size_{0};
  74. CenterPointConfig config_;
  75. std::size_t encoder_in_feature_size_{0};
  76. std::size_t spatial_features_size_{0};
  77. std::size_t voxels_buffer_size_{0};
  78. std::size_t mask_size_{0};
  79. std::size_t voxels_size_{0};
  80. std::size_t coordinates_size_{0};
  81. std::vector<float> points_;
  82. cuda::unique_ptr<float[]> voxels_d_{nullptr};
  83. cuda::unique_ptr<int[]> coordinates_d_{nullptr};
  84. cuda::unique_ptr<float[]> num_points_per_voxel_d_{nullptr};
  85. cuda::unique_ptr<float[]> encoder_in_features_d_{nullptr};
  86. cuda::unique_ptr<float[]> pillar_features_d_{nullptr};
  87. cuda::unique_ptr<float[]> spatial_features_d_{nullptr};
  88. cuda::unique_ptr<float[]> head_out_heatmap_d_{nullptr};
  89. cuda::unique_ptr<float[]> head_out_offset_d_{nullptr};
  90. cuda::unique_ptr<float[]> head_out_z_d_{nullptr};
  91. cuda::unique_ptr<float[]> head_out_dim_d_{nullptr};
  92. cuda::unique_ptr<float[]> head_out_rot_d_{nullptr};
  93. cuda::unique_ptr<float[]> head_out_vel_d_{nullptr};
  94. cuda::unique_ptr<float[]> points_d_{nullptr};
  95. cuda::unique_ptr<float[]> voxels_buffer_d_{nullptr};
  96. cuda::unique_ptr<unsigned int[]> mask_d_{nullptr};
  97. cuda::unique_ptr<unsigned int[]> num_voxels_d_{nullptr};
  98. // std::size_t class_size_{0};
  99. // CenterPointConfig config_;
  100. // std::size_t num_voxels_{0};
  101. // std::size_t encoder_in_feature_size_{0};
  102. // std::size_t spatial_features_size_{0};
  103. // std::vector<float> voxels_;
  104. // std::vector<int> coordinates_;
  105. // std::vector<float> num_points_per_voxel_;
  106. // cuda::unique_ptr<float[]> voxels_d_{nullptr};
  107. // cuda::unique_ptr<int[]> coordinates_d_{nullptr};
  108. // cuda::unique_ptr<float[]> num_points_per_voxel_d_{nullptr};
  109. // cuda::unique_ptr<float[]> encoder_in_features_d_{nullptr};
  110. // cuda::unique_ptr<float[]> pillar_features_d_{nullptr};
  111. // cuda::unique_ptr<float[]> spatial_features_d_{nullptr};
  112. // cuda::unique_ptr<float[]> head_out_heatmap_d_{nullptr};
  113. // cuda::unique_ptr<float[]> head_out_offset_d_{nullptr};
  114. // cuda::unique_ptr<float[]> head_out_z_d_{nullptr};
  115. // cuda::unique_ptr<float[]> head_out_dim_d_{nullptr};
  116. // cuda::unique_ptr<float[]> head_out_rot_d_{nullptr};
  117. // cuda::unique_ptr<float[]> head_out_vel_d_{nullptr};
  118. };
  119. } // namespace centerpoint
  120. #endif // LIDAR_CENTERPOINT__CENTERPOINT_TRT_HPP_