Failed to find match for field 'rgb'

原因:版本不一致

从pcl-1.9以后,保存的pcd文件中rgb字段是以uint来存储,而之前的版本都是用float形式来存储

原因验证

分别在pcl-1.7.2版本和pcl-1.9版本环境下执行如下代码生成pcd文件

#include <pcl/point_types.h>
#include <pcl/io/pcd_io.h>

using PointT = pcl::PointXYZRGB;

int main(int argc, char** argv)
{
    pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>);
    for (int i=0; i<10; i++)
    {
        PointT p;
        p.x = i;
        p.y = i;
        p.z = i;
        p.r = i;
        p.g = i;
        p.b = i;
        cloud->points.push_back(p);
    }

    cloud->width = cloud->points.size();
    cloud->height = 1;
    pcl::io::savePCDFile("/home/cn/temp_1_7.pcd", *cloud);
    //pcl::io::savePCDFile("/home/cn/temp_1_9.pcd", *cloud);

    return 0;
}

结果如下

cat temp_1_9.pcd 
# .PCD v0.7 - Point Cloud Data file format
VERSION 0.7
FIELDS x y z rgb
SIZE 4 4 4 4
TYPE F F F U
COUNT 1 1 1 1
WIDTH 10
HEIGHT 1
VIEWPOINT 0 0 0 1 0 0 0
POINTS 10
DATA ascii
0 0 0 4278190080
1 1 1 4278255873
2 2 2 4278321666
3 3 3 4278387459
4 4 4 4278453252
5 5 5 4278519045
6 6 6 4278584838
7 7 7 4278650631
8 8 8 4278716424
9 9 9 4278782217
cat temp_1_7.pcd 
# .PCD v0.7 - Point Cloud Data file format
VERSION 0.7
FIELDS x y z rgb
SIZE 4 4 4 4
TYPE F F F F
COUNT 1 1 1 1
WIDTH 10
HEIGHT 1
VIEWPOINT 0 0 0 1 0 0 0
POINTS 10
DATA ascii
0 0 0 0
1 1 1 9.219563e-41
2 2 2 1.8439126e-40
3 3 3 2.7658689e-40
4 4 4 3.6878252e-40
5 5 5 4.6097815e-40
6 6 6 5.5317378e-40
7 7 7 6.4536941e-40
8 8 8 7.3756504e-40
9 9 9 8.2976067e-40

从上述结果可以看出pcl-1.7.2保存的pcd类型为TYPE F F F F,而pcl-1.9保存的pcd类型为TYPE F F F U,因此可得pcl的新版本对保存的pcd文件的rgb字段使用的是uint类型,而不再是传统的float类型.为何要更改保存的类型?原因如下:

pcl::PointXYZRGB结构使用注意事项:
* Due to historical reasons (PCL was first developed as a ROS package), the
* RGB information is packed into an integer and casted to a float. This is
* something we wish to remove in the near future
由于pcl库一开始是作为一个ros库,因此需要将以整形封装的rgb信息强转成float类型(ros的点云信息都是以float32类型保存的)

pcl::savePCDFile()接口使用注意事项:
* Caution: PointCloud structures containing an RGB field have
* traditionally used packed float values to store RGB data. Storing a
* float as ASCII can introduce variations to the smallest bits, and
* thus significantly alter the data. This is a known issue, and the fix
* involves switching RGB data to be stored as a packed integer in
* future versions of PCL.
如果直接保存为float类型,将会使最小的几位数据发生变化

更改保存的类型的原因:在进行uint与float之间的转换时,会引起数据的微小变化,改为uint之后将不再需要进行这两种类型之间的转换

问题解决

方案一:

直接根据点云保存的类型切换系统的pcl环境,如果点云rgb字段保存为float类型,则直接将pcl版本切换成pcl-1.9之前的版本,否则将pcl版本切换成pcl-1.9版本

方案二(推荐):

系统的pcl版本一旦确定就很少去改动它,因为有很多先前的项目都是基于这个版本开发的,一旦改动版本,可能会出现"牵一发而动全身"问题,因此推荐直接对pcd文件进行更改,以适应系统的pcl版本.
将rgb字段uint类型转换为float类型:

#include <iostream>
#include <fstream>
#include <pcl/point_types.h>
#include <pcl/io/pcd_io.h>
#include <sstream>

using PointT = pcl::PointXYZRGB;
using namespace std;

int main(int argc, char** argv)
{
    ifstream in_file("temp_1_9.pcd");
    if (!in_file){
        cout<<"couldnt open file !!!!!!"<<endl;
        return 0;
    }

    string str;
    uint32_t row_num = 0;
    ofstream out_file("1_9_to_1_7.pcd");
    while (getline(in_file, str)){
        row_num++;
        // change rgb type in header
        if (row_num == 5){
            out_file<<"TYPE"<<" "<<"F"<<" "<<"F"<<" "<<"F"<<" "<<"F"<<endl;
            continue;
        }
        // skip header
        if (row_num < 12){
            out_file<<str<<endl;
            continue;
        }
        // read line data
        stringstream ss(str);
        float tmp_value = 0;
        vector<float> line_datas;
        line_datas.clear();
        while (ss >> tmp_value){
            line_datas.push_back(tmp_value);
        }
        
        if (line_datas.size() != 4){
            cout<<"line "<<row_num<<" format has problem"<<endl;
            return 0;
        }
        out_file<<line_datas[0]<<" "<<line_datas[1]<<" "<<line_datas[2]<<" ";
        // change rgb data
        uint32_t raw_rgb = static_cast<uint32_t>(line_datas[3]);
        uint8_t r = (raw_rgb >> 16) & 0x0000ff;
        uint8_t g = (raw_rgb >> 8)  & 0x0000ff;
        uint8_t b = (raw_rgb)     & 0x0000ff;
        uint32_t rgb = ((uint32_t)r << 16 | (uint32_t)g << 8 | (uint32_t)b);
        float cha_rgb = *reinterpret_cast<float*>(&rgb);
        out_file<<cha_rgb<<endl;
    }

    return 0;
}

结果:

cat 1_9_to_1_7.pcd 
# .PCD v0.7 - Point Cloud Data file format
VERSION 0.7
FIELDS x y z rgb
SIZE 4 4 4 4
TYPE F F F F
COUNT 1 1 1 1
WIDTH 10
HEIGHT 1
VIEWPOINT 0 0 0 1 0 0 0
POINTS 10
DATA ascii
0 0 0 0
1 1 1 9.21942e-41
2 2 2 1.84388e-40
3 3 3 2.76583e-40
4 4 4 3.68777e-40
5 5 5 4.60971e-40
6 6 6 5.53165e-40
7 7 7 6.4536e-40
8 8 8 7.37554e-40
9 9 9 8.29748e-40

与temp_1_7.pcd内容一致,转换成功.

将rgb字段float类型转换为uint类型:

#include <iostream>
#include <fstream>
#include <pcl/point_types.h>
#include <pcl/io/pcd_io.h>
#include <sstream>

using PointT = pcl::PointXYZRGB;
using namespace std;

int main(int argc, char** argv)
{
    ifstream in_file("temp_1_7.pcd");
    if (!in_file){
        cout<<"couldnt open file !!!!!!"<<endl;
        return 0;
    }

    string str;
    uint32_t row_num = 0;
    ofstream out_file("1_7_to_1_9.pcd");
    while (getline(in_file, str)){
        row_num++;
        // change rgb type in header
        if (row_num == 5){
            out_file<<"TYPE"<<" "<<"F"<<" "<<"F"<<" "<<"F"<<" "<<"U"<<endl;
            continue;
        }
        // skip header
        if (row_num < 12){
            out_file<<str<<endl;
            continue;
        }
        // read line data
        stringstream ss(str);
        float tmp_value = 0;
        vector<float> line_datas;
        line_datas.clear();
        while (ss >> tmp_value){
            line_datas.push_back(tmp_value);
        }
        
        if (line_datas.size() != 4){
            cout<<"line "<<row_num<<" format has problem"<<endl;
            return 0;
        }
        out_file<<line_datas[0]<<" "<<line_datas[1]<<" "<<line_datas[2]<<" ";
        // change rgb data
        uint32_t raw_rgb = *reinterpret_cast<uint32_t*>(&line_datas[3]);
        uint8_t r = (raw_rgb >> 16) & 0x0000ff;
        uint8_t g = (raw_rgb >> 8)  & 0x0000ff;
        uint8_t b = (raw_rgb)     & 0x0000ff;
        // highest Byte is 0xff
        uint32_t cha_rgb = ((uint32_t)(0xff)) << 24 | ((uint32_t)r) << 16 | ((uint32_t)g) << 8 | ((uint32_t)b);
        out_file<<cha_rgb<<endl;
    }

    return 0;
}

结果

cat 1_7_to_1_9.pcd 
# .PCD v0.7 - Point Cloud Data file format
VERSION 0.7
FIELDS x y z rgb
SIZE 4 4 4 4
TYPE F F F U
COUNT 1 1 1 1
WIDTH 10
HEIGHT 1
VIEWPOINT 0 0 0 1 0 0 0
POINTS 10
DATA ascii
0 0 0 4278190080
1 1 1 4278255873
2 2 2 4278321666
3 3 3 4278387459
4 4 4 4278453252
5 5 5 4278519045
6 6 6 4278584838
7 7 7 4278650631
8 8 8 4278716424
9 9 9 4278782217

与temp_1_9.pcd文件内容一致,转换成功.

  • 10
    点赞
  • 46
    收藏
    觉得还不错? 一键收藏
  • 7
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 7
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值