23 #include "Eigen/Eigen" 31 #include "modules/drivers/lidar/proto/velodyne_config.pb.h" 32 #include "modules/drivers/proto/pointcloud.pb.h" 49 bool Proc(
const std::shared_ptr<PointCloud>& point_cloud)
override;
52 bool Fusion(std::shared_ptr<PointCloud> target,
53 std::shared_ptr<PointCloud> source);
54 bool IsExpired(
const std::shared_ptr<PointCloud>& target,
55 const std::shared_ptr<PointCloud>& source);
56 bool QueryPoseAffine(
const std::string& target_frame_id,
57 const std::string& source_frame_id,
59 void AppendPointCloud(std::shared_ptr<PointCloud> point_cloud,
60 std::shared_ptr<PointCloud> point_cloud_add,
65 std::shared_ptr<Writer<PointCloud>> fusion_writer_;
66 std::vector<std::shared_ptr<Reader<PointCloud>>> readers_;
bool Proc(const std::shared_ptr< PointCloud > &point_cloud) override
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: pri_sec_fusion_component.h:46
pcl::PointCloud< Point > PointCloud
Definition: types.h:64
Reader subscribes a channel, it has two main functions:
Definition: reader.h:68
#define CYBER_REGISTER_COMPONENT(name)
Definition: component.h:551
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34
The Component can process up to four channels of messages. The message type is specified when the com...
Definition: component.h:58
apollo::cyber::Writer< T > Writer
Definition: sensor_canbus.h:67