66 using DvCallback = std::function<bool(
const std::string &
string)>;
82 void RegisterMessageHandlers();
84 void UpdatePointCloud(
85 const std::shared_ptr<drivers::PointCloud> &point_cloud);
87 void FilterPointCloud(pcl::PointCloud<pcl::PointXYZ>::Ptr pcl_ptr);
89 void UpdateLocalizationTime(
90 const std::shared_ptr<apollo::localization::LocalizationEstimate>
92 pcl::PointCloud<pcl::PointXYZ>::Ptr ConvertPCLPointCloud(
93 const std::shared_ptr<drivers::PointCloud> &point_cloud);
95 void GetChannelMsg(std::vector<std::string> *channels);
96 bool ChangeChannel(
const std::string &channel);
97 constexpr static float kDefaultLidarHeight = 1.91f;
99 std::unique_ptr<cyber::Node> node_;
103 std::vector<std::string> channels_;
105 bool enabled_ =
false;
108 std::string point_cloud_str_;
110 std::future<void> async_future_;
111 std::atomic<bool> future_ready_;
114 std::shared_ptr<cyber::Reader<apollo::localization::LocalizationEstimate>>
115 localization_reader_;
116 std::shared_ptr<cyber::Reader<drivers::PointCloud>> point_cloud_reader_;
117 double last_point_cloud_time_ = 0.0;
118 double last_localization_time_ = 0.0;
120 bool enable_voxel_filter_ =
false;
121 std::string curr_channel_name =
"";