23 #include "pcl/point_cloud.h" 24 #include "pcl/point_types.h" 33 namespace perception {
46 std::string
Name()
const override {
return "PointPillarsDetection"; }
50 float normalizing_factor);
53 const std::deque<base::PointDCloudPtr>& fuse_clouds);
55 std::vector<int> GenerateIndices(
int start_index,
int size,
bool shuffle);
57 void GetObjects(std::vector<std::shared_ptr<base::Object>>* objects,
59 std::vector<int>* labels);
65 std::shared_ptr<base::AttributePointCloud<base::PointF>> original_cloud_;
66 std::shared_ptr<base::AttributePointCloud<base::PointD>>
67 original_world_cloud_;
70 std::unique_ptr<PointPillars> point_pillars_ptr_;
71 std::deque<base::PointDCloudPtr> prev_world_clouds_;
83 double downsample_time_ = 0.0;
84 double fuse_time_ = 0.0;
85 double shuffle_time_ = 0.0;
86 double cloud_to_array_time_ = 0.0;
87 double inference_time_ = 0.0;
88 double collect_time_ = 0.0;
bool Init(const LidarDetectorInitOptions &options=LidarDetectorInitOptions()) override
bool Detect(const LidarDetectorOptions &options, LidarFrame *frame) override
std::string Name() const override
Definition: point_pillars_detection.h:46
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: base_lidar_detector.h:34
virtual ~PointPillarsDetection()=default
Definition: lidar_frame.h:33
std::shared_ptr< PointFCloud > PointFCloudPtr
Definition: point_cloud.h:482
Definition: base_lidar_detector.h:28
Definition: base_lidar_detector.h:32
Algorithm for PointPillars.
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34
ObjectSubType
Definition: object_types.h:63
Definition: point_pillars_detection.h:36