55 const std::shared_ptr<VelodyneScan>& scan_msg) {
56 std::shared_ptr<PointCloud> point_cloud_out = point_cloud_pool_->GetObject();
57 if (point_cloud_out ==
nullptr) {
58 AWARN <<
"poin cloud pool return nullptr, will be create new.";
59 point_cloud_out = std::make_shared<PointCloud>();
60 point_cloud_out->mutable_point()->Reserve(140000);
62 if (point_cloud_out ==
nullptr) {
63 AWARN <<
"point cloud out is nullptr";
66 point_cloud_out->Clear();
67 conv_->ConvertPacketsToPointcloud(scan_msg, point_cloud_out);
69 if (point_cloud_out ==
nullptr || point_cloud_out->point().empty()) {
70 AWARN <<
"point_cloud_out convert is empty.";
73 writer_->Write(point_cloud_out);