21 #include "cyber/cyber.h" 22 #include "modules/drivers/proto/pointcloud.pb.h" 26 #include "modules/perception/onboard/proto/lidar_component_config.pb.h" 30 namespace perception {
40 bool Proc(
const std::shared_ptr<drivers::PointCloud>& message)
override;
43 bool InitAlgorithmPlugin();
45 const std::shared_ptr<const drivers::PointCloud>& in_message,
46 const std::shared_ptr<LidarFrameMessage>& out_message);
49 static std::mutex s_mutex_;
50 static uint32_t s_seq_num_;
51 std::string sensor_name_;
52 bool enable_hdmap_ =
true;
53 float lidar_query_tf_offset_ = 20.0f;
54 std::string lidar2novatel_tf2_child_frame_id_;
55 std::string output_channel_name_;
58 std::unique_ptr<lidar::LidarObstacleSegmentation> segmentor_;
59 std::shared_ptr<apollo::cyber::Writer<LidarFrameMessage>> writer_;
bool Proc(const std::shared_ptr< drivers::PointCloud > &message) override
~SegmentationComponent()=default
SegmentationComponent()
Definition: segmentation_component.h:35
Definition: segmentation_component.h:33
Definition: sensor_meta.h:57
CYBER_REGISTER_COMPONENT(FusionCameraDetectionComponent)