centerpoint_trt.hpp 3.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109
  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. class NetworkParam
  30. {
  31. public:
  32. NetworkParam(std::string onnx_path, std::string engine_path, std::string trt_precision)
  33. : onnx_path_(std::move(onnx_path)),
  34. engine_path_(std::move(engine_path)),
  35. trt_precision_(std::move(trt_precision))
  36. {
  37. }
  38. std::string onnx_path() const { return onnx_path_; }
  39. std::string engine_path() const { return engine_path_; }
  40. std::string trt_precision() const { return trt_precision_; }
  41. private:
  42. std::string onnx_path_;
  43. std::string engine_path_;
  44. std::string trt_precision_;
  45. };
  46. class CenterPointTRT
  47. {
  48. public:
  49. explicit CenterPointTRT(
  50. const NetworkParam & encoder_param, const NetworkParam & head_param,
  51. const DensificationParam & densification_param, const CenterPointConfig & config);
  52. ~CenterPointTRT();
  53. bool detect(
  54. const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer,
  55. std::vector<Box3D> & det_boxes3d);
  56. protected:
  57. void initPtr();
  58. virtual bool preprocess(
  59. const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer);
  60. void inference();
  61. void postProcess(std::vector<Box3D> & det_boxes3d);
  62. std::unique_ptr<VoxelGeneratorTemplate> vg_ptr_{nullptr};
  63. std::unique_ptr<VoxelEncoderTRT> encoder_trt_ptr_{nullptr};
  64. std::unique_ptr<HeadTRT> head_trt_ptr_{nullptr};
  65. std::unique_ptr<PostProcessCUDA> post_proc_ptr_{nullptr};
  66. cudaStream_t stream_{nullptr};
  67. bool verbose_{false};
  68. std::size_t class_size_{0};
  69. CenterPointConfig config_;
  70. std::size_t num_voxels_{0};
  71. std::size_t encoder_in_feature_size_{0};
  72. std::size_t spatial_features_size_{0};
  73. std::vector<float> voxels_;
  74. std::vector<int> coordinates_;
  75. std::vector<float> num_points_per_voxel_;
  76. cuda::unique_ptr<float[]> voxels_d_{nullptr};
  77. cuda::unique_ptr<int[]> coordinates_d_{nullptr};
  78. cuda::unique_ptr<float[]> num_points_per_voxel_d_{nullptr};
  79. cuda::unique_ptr<float[]> encoder_in_features_d_{nullptr};
  80. cuda::unique_ptr<float[]> pillar_features_d_{nullptr};
  81. cuda::unique_ptr<float[]> spatial_features_d_{nullptr};
  82. cuda::unique_ptr<float[]> head_out_heatmap_d_{nullptr};
  83. cuda::unique_ptr<float[]> head_out_offset_d_{nullptr};
  84. cuda::unique_ptr<float[]> head_out_z_d_{nullptr};
  85. cuda::unique_ptr<float[]> head_out_dim_d_{nullptr};
  86. cuda::unique_ptr<float[]> head_out_rot_d_{nullptr};
  87. cuda::unique_ptr<float[]> head_out_vel_d_{nullptr};
  88. };
  89. } // namespace centerpoint
  90. #endif // LIDAR_CENTERPOINT__CENTERPOINT_TRT_HPP_