点云3D目标检测理论实战

3D目标检测系列的前4篇已经把训练的方法介绍完整了,接下来会一步一步准备训练数据,也就是点云的处理。

我们知道,目前点云的公开数据集主要是自动驾驶领域,模型的设计及训练都是集中在此类数据,同时标注工具也都是为此设计。该类数据的特点是有道路平面但无顶部(为避免引起误解,这里举个例子说明,比如室内的点云是有天花板的)、同时lidar视角基本是与地面平行的,无旋转。因此我们标注的时候基本都是先从俯视图开始定位bounding box的中心位置,读者可以自行体会有旋转时标注的困难程度。

学习资源地址 https://gitee.com/studywangke/zdjs

本节通过一个室内点云的变换来介绍上述处理过程。

点云的原始状态

如上图,原始的点云图是延Y轴(绿色)倾斜的,而且是带有屋顶的。

点云旋转

这里我们想人为调整旋转角度,因此使用欧拉角(RPY:对应的旋转顺序为ZYX)比较方便。观察上图可知,点云需要延Y轴逆时针旋转20几度。详见代码:

#include <ros/ros.h>
#include <pcl_ros/point_cloud.h>
#include <sensor_msgs/PointCloud2.h>
#include <rosbag/bag.h>
#include <rosbag/view.h>

#include <pcl/common/transforms.h>
#include <pcl_conversions/pcl_conversions.h>

int main(int argc, char **argv)
{
    ros::init(argc, argv, "rosbag_transfer_node");
    ros::NodeHandle nh;
    double trans_roll_ = 0.0;
    double trans_pitch_ = 0.0;
    double trans_yaw_ = 0.0;
    double trans_tx_ = 0.0;
    double trans_ty_ = 0.0;
    double trans_tz_ = 0.0;
    Eigen::Affine3f transform_matrix_ = Eigen::Affine3f::Identity();
    nh.getParam("roll", trans_roll_);
    nh.getParam("pitch", trans_pitch_);
    nh.getParam("yaw", trans_yaw_);

    //Building the transformation matrix
    transform_matrix_.translation() << trans_tx_, trans_ty_, trans_tz_;
    transform_matrix_.rotate(Eigen::AngleAxisf(trans_yaw_ * M_PI / 180, Eigen::Vector3f::UnitZ()));
    transform_matrix_.rotate(Eigen::AngleAxisf(trans_pitch_ * M_PI / 180, Eigen::Vector3f::UnitY()));
    transform_matrix_.rotate(Eigen::AngleAxisf(trans_roll_ * M_PI / 180, Eigen::Vector3f::UnitX()));

    // read bag
    std::string bag_file;
    nh.getParam("bag_file", bag_file);

    rosbag::Bag bag_original;
    bag_original.open(bag_file, rosbag::bagmode::Read);
    std::string topic = "/livox/lidar";

    // write bag
    rosbag::Bag bag_output;
    std::string out_file = bag_file.replace(bag_file.find(".bag"), 4, "_t.bag");
    bag_output.open(out_file, rosbag::bagmode::Write);

    for (rosbag::MessageInstance const m : rosbag::View(bag_original))
    {
        sensor_msgs::PointCloud2::ConstPtr lidar = m.instantiate<sensor_msgs::PointCloud2>();
        if (lidar != NULL)
        {
            pcl::PointCloud<pcl::PointXYZI> lidar_cloud;
            pcl::fromROSMsg(*lidar, lidar_cloud);

            //Transformation
            pcl::PointCloud<pcl::PointXYZI>::Ptr trans_cloud_ptr(new pcl::PointCloud<pcl::PointXYZI>);
            pcl::transformPointCloud(lidar_cloud, *trans_cloud_ptr, transform_matrix_);
            // crop
            for (auto it = trans_cloud_ptr->begin(); it != trans_cloud_ptr->end();)
            {
                if (it->z >0)
                {
                    it=trans_cloud_ptr->erase(it);
                }
                else
                {
                     it++;
                }

            }

            // new msg
            sensor_msgs::PointCloud2 msg;
            pcl::toROSMsg(*trans_cloud_ptr, msg);
            bag_output.write(topic, lidar->header.stamp, msg);
        }
    }

    bag_original.close();
    bag_output.close();

    return 0;
}

简单简释一下:

原始点云文件是通过rosbag录制的bag文件,转换后最终还写为bag格式。因此需要几个步骤:

  • 读取bag
  • 坐标系转换
  • 裁剪屋顶
  • 重新写回bag

重点为Building the transformation matrix部分,构建一个转换矩阵transform_matrix_,之后通过pcl::transformPointCloud直接转换pcl::PointCloud<pcl::PointXYZI>,最后做了一点点裁剪把 𝑍>0

处理后

小结

pcl_ros库为我们提供了非常方便的接口用来处理pointcloud格式的msg,本文是对相关常用接口的用法示例,当然也可以直接拿去使用。下一节会介绍常用点云格式(pcd、bin、npy等)的转换方法。

  • 4
    点赞
  • 4
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

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

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

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值