hku-mars / FAST-LIVO

A Fast and Tightly-coupled Sparse-Direct LiDAR-Inertial-Visual Odometry (LIVO).
GNU General Public License v2.0
1.26k stars 202 forks source link

How can I save it as pcd? when I finished the process of mapping? #94

Closed kilimization closed 5 months ago

xuankuzcr commented 5 months ago
PointCloudXYZRGB::Ptr pcl_wait_save(new PointCloudXYZRGB());
PointCloudXYZI::Ptr pcl_wait_pub(new PointCloudXYZI());
void publish_frame_world_rgb(const ros::Publisher &pubLaserCloudFullRes, lidar_selection::LidarSelectorPtr lidar_selector)
{
    uint size = pcl_wait_pub->points.size();
    PointCloudXYZRGB::Ptr laserCloudWorldRGB(new PointCloudXYZRGB(size, 1));
    if (img_en)
    {
        laserCloudWorldRGB->clear();
        for (int i = 0; i < size; i++)
        {
            PointTypeRGB pointRGB;
            pointRGB.x = pcl_wait_pub->points[i].x;
            pointRGB.y = pcl_wait_pub->points[i].y;
            pointRGB.z = pcl_wait_pub->points[i].z;
            V3D p_w(pcl_wait_pub->points[i].x, pcl_wait_pub->points[i].y, pcl_wait_pub->points[i].z);
            V3D pf(lidar_selector->new_frame_->w2f(p_w));
            if (pf[2] < 0)  continue;
            V2D pc(lidar_selector->new_frame_->w2c(p_w));
            if (lidar_selector->new_frame_->cam_->isInFrame(pc.cast<int>(), 0))
            {
                cv::Mat img_rgb = lidar_selector->img_rgb;
                V3F pixel = lidar_selector->getpixel(img_rgb, pc);
                pointRGB.r = pixel[2];
                pointRGB.g = pixel[1];
                pointRGB.b = pixel[0];
                laserCloudWorldRGB->push_back(pointRGB);
            }
        }
    }
    if (1) // if(publish_count >= PUBFRAME_PERIOD)
    {
        sensor_msgs::PointCloud2 laserCloudmsg;
        if (img_en)
        {
            // cout<<"RGB pointcloud size: "<<laserCloudWorldRGB->size()<<endl;
            pcl::toROSMsg(*laserCloudWorldRGB, laserCloudmsg);
        }
        else
        {
            pcl::toROSMsg(*pcl_wait_pub, laserCloudmsg);
        }
        laserCloudmsg.header.stamp = ros::Time::now(); //.fromSec(last_timestamp_lidar);
        laserCloudmsg.header.frame_id = "camera_init";
        pubLaserCloudFullRes.publish(laserCloudmsg);
        publish_count -= PUBFRAME_PERIOD;
    }

    /**************** save map ****************/
    /* 1. make sure you have enough memories
    /* 2. noted that pcd save will influence the real-time performences **/
    if (1)
    {
        *pcl_wait_save += *laserCloudWorldRGB;
    }
}
if (pcl_wait_save->size() > 0 && pcd_save_en)
{
    string all_points_dir = string(ROOT_DIR + "PCD/" + "scans.pcd");
    pcl::PCDWriter pcd_writer;
    pcd_writer.writeBinary(all_points_dir, *pcl_wait_save);
}

把这两段代码替换进去就可以了