pcl Leaf size is too small for the input dataset 警告

pcl的体素下采样:
 

void VoxelDownsample( pcl::PointCloud<pcl::PointXYZRGBL>::Ptr& cloud_in, pcl::PointCloud<pcl::PointXYZRGBL>::Ptr& cloud_out,
                      float leaf_size ) {

    if ( cloud_in->size() >= 1000 * 10000 ) {
        return OctreeVoxelDownsample( cloud_in, cloud_out, leaf_size );
    }

    pcl::VoxelGrid<pcl::PointXYZRGBL> sor;
    sor.setInputCloud( cloud_in );
    sor.setLeafSize( leaf_size, leaf_size, leaf_size );
    sor.filter( *cloud_out );
}

如果点云的包围盒的长宽高除以leaf size后生成的小方格数量太多,就会造成整数溢出,然后就会有这个警告。

可以用八叉树做体素下采样:


void OctreeVoxelDownsample( pcl::PointCloud<pcl::PointXYZRGBL>::Ptr& cloud_in, pcl::PointCloud<pcl::PointXYZRGBL>::Ptr& cloud_out,
                            float leaf_size ) {
    using namespace pcl;

    // 创建八叉树
    pcl::octree::OctreePointCloud<pcl::PointXYZRGBL> octree( leaf_size );
    octree.setInputCloud( cloud_in );
    octree.addPointsFromInputCloud();

    // 清空输出点云
    cloud_out->clear();

    // 遍历八叉树的每个叶子节点
    for ( auto leaf_depth_begin = octree.leaf_depth_begin(); leaf_depth_begin != octree.leaf_depth_end(); ++leaf_depth_begin ) {
        octree::OctreeContainerPointIndices& container = leaf_depth_begin.getLeafContainer();
        Indices&                             indices   = container.getPointIndicesVector();

        if ( indices.empty() )
            continue;  // 如果这个体素没有点,跳过

        // 计算xyz的平均值
        Eigen::Vector3f                        centroid_xyz = Eigen::Vector3f::Zero();
        Eigen::Vector3f                        centroid_rgb = Eigen::Vector3f::Zero();
        std::unordered_map<std::uint32_t, int> label_counts;

        for ( auto index : indices ) {
            const auto& point = cloud_in->points[ index ];
            centroid_xyz += Eigen::Vector3f( point.x, point.y, point.z );
            centroid_rgb +=
                Eigen::Vector3f( static_cast<float>( point.r ), static_cast<float>( point.g ), static_cast<float>( point.b ) );

            // 统计每个标签出现的次数
            label_counts[ point.label ]++;
        }

        // 计算平均值
        int num_points = indices.size();
        centroid_xyz /= static_cast<float>( num_points );
        centroid_rgb /= static_cast<float>( num_points );

        // 找到出现次数最多的标签
        std::uint32_t most_common_label = 0;
        int           max_count         = 0;
        for ( const auto& label_count : label_counts ) {
            if ( label_count.second > max_count ) {
                max_count         = label_count.second;
                most_common_label = label_count.first;
            }
        }

        // 创建新的点
        pcl::PointXYZRGBL point;
        point.x     = centroid_xyz[ 0 ];
        point.y     = centroid_xyz[ 1 ];
        point.z     = centroid_xyz[ 2 ];
        point.r     = static_cast<std::uint8_t>( centroid_rgb[ 0 ] );
        point.g     = static_cast<std::uint8_t>( centroid_rgb[ 1 ] );
        point.b     = static_cast<std::uint8_t>( centroid_rgb[ 2 ] );
        point.label = most_common_label;

        // 添加到输出点云
        cloud_out->points.emplace_back( point );
    }

    // 设置输出点云的属性
    cloud_out->width    = cloud_out->points.size();
    cloud_out->height   = 1;     // 非有组织点云
    cloud_out->is_dense = true;  // 假定点云是稠密的
}

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值