23 #include "modules/drivers/proto/pointcloud.pb.h" 27 #include "modules/perception/onboard/proto/lidar_component_config.pb.h" 31 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::atomic<uint32_t> seq_num_;
50 std::string sensor_name_;
51 std::string detector_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::BaseLidarObstacleDetection> detector_;
59 std::shared_ptr<apollo::cyber::Writer<LidarFrameMessage>> writer_;
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
bool Proc(const std::shared_ptr< drivers::PointCloud > &message) override
Definition: detection_component.h:34
virtual ~DetectionComponent()=default
Definition: sensor_meta.h:57
DetectionComponent()=default
The Component can process up to four channels of messages. The message type is specified when the com...
Definition: component.h:58
CYBER_REGISTER_COMPONENT(CameraObstacleDetectionComponent)