当前位置:   article > 正文

SLAM本质剖析-Open3D

rgbd slam open3d

点击上方“3D视觉工坊”,选择“星标”

干货第一时间送达

3c0e162a382d6091eb42d0eab8c49a4f.png

作者丨lovely_yoshino

来源丨古月居

099720a31f8da48f8f332850ac4277cf.png

e9b9f42b467987bce9ec38820088650f.png

0. 前言

在深入剖析了Ceres、Eigen、Sophus、G2O后,以V-SLAM为代表的计算方式基本已经全部讲完。就L-SLAM而言,本系列也讲述了PCL、与GTSAM点云计算部分。

之前的系列部分作者本以为已经基本讲完,但是近期突然发现还有关于Open3D的部分还没有写。趁着这次不全来形成一整个系列,方便自己回顾以及后面的人一起学习。

dd6d44259522ed07f6a8f3fabadccc46.png

f118f748885747bcb117a15836203b6e.png

1. Open3D环境安装

这里将Open3D的环境安装分为两个部分:非ROS和ROS环境

非ROS环境

  1. //下载源码
  2. git clone git@github.com:intel-isl/Open3D.git
  3. git submodule update --init --recursive
  4. //安装依赖
  5. cd open3d
  6. util/scripts/install-deps-ubuntu.sh
  7. //编译安装
  8. mkdir build
  9. cd build
  10. sudo cmake -DCMAKE_INSTALL_PREFIX=/opt/Open3D/ -DBUILD_EIGEN3=ON -DBUILD_GLEW=ON -DBUILD_GLFW=ON -DBUILD_JSONCPP=ON -DBUILD_PNG=ON -DPYTHON_EXECUTABLE=/usr/bin/python ..
  11. sudo make -j8
  12. sudo make install

ROS环境

  1. //更新cmake
  2. sudo apt-add-repository 'deb https://apt.kitware.com/ubuntu/ bionic main'
  3. sudo apt-get update
  4. sudo apt-get install cmake
  5. //安装Open3D
  6. git clone --recursive https://github.com/intel-isl/Open3D
  7. cd Open3D && source util/scripts/install-deps-ubuntu.sh
  8. mkdir build && cd build
  9. cmake -DBUILD_EIGEN3=ON -DBUILD_GLEW=ON -DBUILD_GLFW=ON -DBUILD_JSONCPP=ON -DBUILD_PNG=ON -DGLIBCXX_USE_CXX11_ABI=ON -DPYTHON_EXECUTABLE=/usr/bin/python -DBUILD_UNIT_TESTS=ON ..
  10. make -j4
  11. sudo make install
  12. //基于Open3D的ros程序
  13. mkdir -p catkin_ws/src
  14. cd catkin_ws/src
  15. git clone git@github.com:unr-arl/open3d_ros.git
  16. cd ..
  17. catkin config -DCMAKE_BUILD_TYPE=Release
  18. catkin build open3d_ros

ef7cb761aa9dc32bfe7148688245fe68.png

ff39123922189c7c374fb86868b6255c.png

2. Open3D示例

Open3D的操作和PCL类似,都是利用源码读取ply点云后, 并做ransec平面分割的操作。

  1. //Open3D
  2. #include "Open3D/Open3D.h"
  3. //Eigen
  4. #include "Eigen/Dense"
  5. /* RANSAC平面分割 */
  6. void testOpen3D::pcPlaneRANSAC(const QString &pcPath)
  7. {
  8.    int width = 700, height = 500;
  9.    auto cloud_ptr = std::make_shared<open3d::geometry::PointCloud>();
  10.    if (!open3d::io::ReadPointCloud(pcPath.toStdString(), *cloud_ptr)) { return; }
  11.    open3d::visualization::DrawGeometries({ cloud_ptr }, "Point Cloud 1", width, height);
  12.    /***** 距离阈值,平面最小点数,最大迭代次数。返回平面参数和内点 *****/
  13.    double tDis = 0.05;
  14.    int minNum = 3;
  15.    int numIter = 100;
  16.    std::tuple<Eigen::Vector4d, std::vector<size_t>> vRes = cloud_ptr->SegmentPlane(tDis, minNum, numIter);
  17.    //ABCD
  18.    Eigen::Vector4d para = std::get<0>(vRes);
  19.    //内点索引
  20.    std::vector<size_t> selectedIndex = std::get<1>(vRes);
  21.    //内点赋红色
  22.    std::shared_ptr<open3d::geometry::PointCloud> inPC = cloud_ptr->SelectByIndex(selectedIndex, false);
  23.    const Eigen::Vector3d colorIn = { 255,0,0 };
  24.    inPC->PaintUniformColor(colorIn);
  25.    //外点赋黑色
  26.    std::shared_ptr<open3d::geometry::PointCloud> outPC = cloud_ptr->SelectByIndex(selectedIndex, true);
  27.    const Eigen::Vector3d colorOut = { 0,0,0 };
  28.    outPC->PaintUniformColor(colorOut);
  29.    //显示
  30.    open3d::visualization::DrawGeometries({ inPC,outPC }, "RANSAC平面分割", width, height);
  31. }

87fe2f1b4e98ad131aedd72082f0c4ae.png

对于Open3D而言,PCL可以做到的,其自身也可以做到,下面部分代码为Open3D的ICP匹配

  1. #include <opencv2/opencv.hpp>
  2. #include <iostream>
  3. #include <Eigen/Dense>
  4. #include <iostream>
  5. #include <memory>
  6. #include "Open3D/Registration/GlobalOptimization.h"
  7. #include "Open3D/Registration/PoseGraph.h"
  8. #include "Open3D/Registration/ColoredICP.h"
  9. #include "Open3D/Open3D.h"
  10. #include "Open3D/Registration/FastGlobalRegistration.h"
  11. using namespace open3d;
  12. using namespace std;
  13. using namespace registration;
  14. using namespace geometry;
  15. using namespace cv;
  16. void main()
  17. {
  18.    open3d::geometry::PointCloud source, target;
  19.    open3d::io::ReadPointCloud("C:/Users/chili1080/Desktop/Augmented ICL-NUIM Dataset-jyx/livingroom1-fragments-ply/cloud_bin_0.ply", source);
  20.    open3d::io::ReadPointCloud("C:/Users/chili1080/Desktop/Augmented ICL-NUIM Dataset-jyx/livingroom1-fragments-ply/cloud_bin_1.ply", target);
  21.    Eigen::Vector3d color_source(1, 0.706, 0);
  22.    Eigen::Vector3d color_target(0, 0.651, 0.929);
  23.    source.PaintUniformColor(color_source);
  24.    target.PaintUniformColor(color_target);
  25.    double th = 0.02;
  26.    open3d::registration::RegistrationResult res = open3d::registration::RegistrationICP(source, target, th, Eigen::Matrix4d::Identity(),
  27.        TransformationEstimationPointToPoint(false), ICPConvergenceCriteria(1e-6, 1e-6, 300));
  28.    //显示配准结果  fitness 算法对这次配准的打分
  29.    //inlier_rmse 表示的是 root of covariance, 也就是所有匹配点之间的距离的总和除以所有点的数量的平方根
  30.    //correspondence_size 代表配准后吻合的点云的数量
  31.    cout << "fitness: "<<res.fitness_<<" inlier rmse:"<<res.inlier_rmse_<<" correspondence_set size:"<<res.correspondence_set_.size()<<endl;
  32.    cout << "done here";
  33. }

079610aa8e9d58178de65a027ee5383b.gif

61f40d2bda7d3bf83c8d6e7aab8ae659.png

deff252b1c0321b7a114c89fa390c567.png

3. Open3D在SLAM当中的应用

由于open3D相较于pcl而言对Python的兼容性会更好,所以在使用python做slam时候,大多数会使用open3d。这里也不例外。提供了一份基于Open3D的点云映射匹配。

  1. import open3d as o3d
  2. import numpy as np
  3. import copy
  4. def visualize(pcd):
  5.    vis = o3d.visualization.Visualizer()
  6.    vis.create_window()
  7.    vis.add_geometry(pcd)
  8.    opt = vis.get_render_option()
  9.    opt.background_color = np.asarray([0, 0, 0])
  10.    opt.light_on = False
  11.    opt.point_size = 2
  12.    vis.run()
  13.    vis.destroy_window()
  14. def draw_registration_result(source, target, transformation):
  15.    source_temp = copy.deepcopy(source)
  16.    target_temp = copy.deepcopy(target)
  17.    # source_temp.paint_uniform_color([1, 0.706, 0])
  18.    # target_temp.paint_uniform_color([0, 0.651, 0.929])
  19.    source_temp.transform(transformation)
  20.    o3d.visualization.draw_geometries([source_temp, target_temp])
  21. def feature_extraction(pcd, voxel_size, gamma=False):
  22.    if gamma:
  23.        color = np.asarray(pcd.colors)
  24.        color = np.minimum(np.power(color, 0.6), 1)
  25.        pcd.colors = o3d.utility.Vector3dVector(color)
  26.        # pcd_down, _ = pcd_down.remove_statistical_outlier(nb_neighbors=20, std_ratio=2.0)
  27.    print(":: Estimate normal with search radius %.3f." % voxel_size)
  28.    pcd.estimate_normals(
  29.        o3d.geometry.KDTreeSearchParamHybrid(radius=voxel_size, max_nn=30))
  30.    print(":: Downsample with a voxel size %.3f." % voxel_size)
  31.    pcd_down = pcd.voxel_down_sample(voxel_size)
  32.    radius_normal = voxel_size * 2
  33.    print(":: Estimate normal with search radius %.3f." % radius_normal)
  34.    pcd_down.estimate_normals(
  35.        o3d.geometry.KDTreeSearchParamHybrid(radius=radius_normal, max_nn=30))
  36.    radius_feature = voxel_size * 5
  37.    print(":: Compute FPFH feature with search radius %.3f." % radius_feature)
  38.    pcd_fpfh = o3d.registration.compute_fpfh_feature(
  39.        pcd_down,
  40.        o3d.geometry.KDTreeSearchParamHybrid(radius=radius_feature, max_nn=100))
  41.    return pcd_down, pcd_fpfh
  42. def prepare_dataset(voxel_size):
  43.    print(":: Load two point clouds and disturb initial pose.")
  44.    source = o3d.io.read_point_cloud('/home/hermit/Code/ACSC/experiments/RGBMAP_v2/RGBMap_avia1.pcd')
  45.    # target = o3d.io.read_point_cloud('/home/hermit/Code/ACSC/experiments/RGBMAP_v2/RGBMap_avia2.pcd')
  46.    target = o3d.io.read_point_cloud('/home/hermit/Code/ACSC/experiments/RGBMAP_v2/RGBMap_avia3.pcd')
  47.    # trans_init = np.asarray([[0.0, 0.0, 1.0, 0.0], [1.0, 0.0, 0.0, 0.0],
  48.    #                          [0.0, 1.0, 0.0, 0.0], [0.0, 0.0, 0.0, 1.0]])
  49.    # source.transform(trans_init)
  50.    draw_registration_result(source, target, np.identity(4))
  51.    source_down, source_fpfh = feature_extraction(source, voxel_size)
  52.    target_down, target_fpfh = feature_extraction(target, voxel_size)
  53.    return source, target, source_down, target_down, source_fpfh, target_fpfh
  54. def execute_global_registration(source_down, target_down, source_fpfh,
  55.                                target_fpfh, voxel_size):
  56.    distance_threshold = voxel_size * 1.5
  57.    print(":: RANSAC registration on downsampled point clouds.")
  58.    print("   Since the downsampling voxel size is %.3f," % voxel_size)
  59.    print("   we use a liberal distance threshold %.3f." % distance_threshold)
  60.    result = o3d.registration.registration_ransac_based_on_feature_matching(
  61.        source_down, target_down, source_fpfh, target_fpfh, distance_threshold,
  62.        o3d.registration.TransformationEstimationPointToPoint(False), 4, [
  63.            o3d.registration.CorrespondenceCheckerBasedOnEdgeLength(0.9),
  64.            o3d.registration.CorrespondenceCheckerBasedOnDistance(
  65.                distance_threshold)
  66.        ], o3d.registration.RANSACConvergenceCriteria(4000000, 500))
  67.    return result
  68. def refine_registration(source, target, source_fpfh, target_fpfh, voxel_size, initial_guess):
  69.    distance_threshold = voxel_size * 0.4
  70.    print(":: Point-to-plane ICP registration is applied on original point")
  71.    print("   clouds to refine the alignment. This time we use a strict")
  72.    print("   distance threshold %.3f." % distance_threshold)
  73.    result = o3d.registration.registration_icp(
  74.        source, target, distance_threshold, initial_guess,
  75.        o3d.registration.TransformationEstimationPointToPlane())
  76.    return result
  77. def mapping(pcd_list, voxel_size):
  78.    for frame_idx in range(len(pcd_list) - 1):
  79.        # 读取数据
  80.        if frame_idx == 0:
  81.            map_pcd = pcd_list[frame_idx]
  82.            map_down, map_fpfh = feature_extraction(map_pcd, voxel_size=voxel_size, gamma=True)
  83.        source_pcd = pcd_list[frame_idx + 1]
  84.        source_down, source_fpfh = feature_extraction(source_pcd, voxel_size=voxel_size, gamma=True)
  85.        # 全局ICP
  86.        result_ransac = execute_global_registration(source_down, map_down,
  87.                                                    source_fpfh, map_fpfh,
  88.                                                    voxel_size)
  89.        print(result_ransac)
  90.        # refine结果
  91.        result_icp = refine_registration(source_pcd, map_pcd, source_fpfh, map_fpfh,
  92.                                         voxel_size, initial_guess=result_ransac.transformation)
  93.        print(result_icp)
  94.        # draw_registration_result(source_pcd, map_pcd,
  95.        #                          result_icp.transformation)
  96.        # 更新map
  97.        map_pcd += source_pcd.transform(result_icp.transformation)
  98.        map_down, map_fpfh = feature_extraction(map_pcd, voxel_size=voxel_size)
  99.    return map_pcd
  100. if __name__ == "__main__":
  101.    voxel_size = 0.3  # means 5cm for the dataset
  102.    # 点云数据路径
  103.    # 每帧之间需要有相互
  104.    data_list = [
  105.        '/home/hermit/Code/ACSC/experiments/RGBMAP_v2/RGBMap_avia1.pcd',
  106.        '/home/hermit/Code/ACSC/experiments/RGBMAP_v2/RGBMap_avia2.pcd',
  107.        '/home/hermit/Code/ACSC/experiments/RGBMAP_v2/RGBMap_avia3.pcd',
  108.    ]
  109.    # 读取点云数据集
  110.    pcds = [o3d.io.read_point_cloud(path) for path in data_list]
  111.    map_pcd = mapping(pcd_list=pcds, voxel_size=voxel_size)
  112.    # 绘制地图
  113.    visualize(map_pcd)
  114.    o3d.io.write_point_cloud("mapping.pcd", map_pcd)

cbb40111a6624af95516ac075b0f37a8.png

b33650e5a348a958ca0293db8ac55a6d.png

参考链接

  • https://bleepcoder.com/cn/open3d/335891727/examples-for-how-to-use-open3d-with-pcl-library-and-ros

  • https://blog.csdn.net/hjwang1/article/details/108889798

本文仅做学术分享,如有侵权,请联系删文。

3D视觉精品课程推荐:

1.面向自动驾驶领域的多传感器数据融合技术

2.面向自动驾驶领域的3D点云目标检测全栈学习路线!(单模态+多模态/数据+代码)
3.彻底搞透视觉三维重建:原理剖析、代码讲解、及优化改进
4.国内首个面向工业级实战的点云处理课程
5.激光-视觉-IMU-GPS融合SLAM算法梳理和代码讲解
6.彻底搞懂视觉-惯性SLAM:基于VINS-Fusion正式开课啦
7.彻底搞懂基于LOAM框架的3D激光SLAM: 源码剖析到算法优化
8.彻底剖析室内、室外激光SLAM关键算法原理、代码和实战(cartographer+LOAM +LIO-SAM)

9.从零搭建一套结构光3D重建系统[理论+源码+实践]

10.单目深度估计方法:算法梳理与代码实现

11.自动驾驶中的深度学习模型部署实战

12.相机模型与标定(单目+双目+鱼眼)

13.重磅!四旋翼飞行器:算法与实战

重磅!3DCVer-学术论文写作投稿 交流群已成立

扫码添加小助手微信,可申请加入3D视觉工坊-学术论文写作与投稿 微信交流群,旨在交流顶会、顶刊、SCI、EI等写作与投稿事宜。

同时也可申请加入我们的细分方向交流群,目前主要有3D视觉CV&深度学习SLAM三维重建点云后处理自动驾驶、多传感器融合、CV入门、三维测量、VR/AR、3D人脸识别、医疗影像、缺陷检测、行人重识别、目标跟踪、视觉产品落地、视觉竞赛、车牌识别、硬件选型、学术交流、求职交流、ORB-SLAM系列源码交流、深度估计等微信群。

一定要备注:研究方向+学校/公司+昵称,例如:”3D视觉 + 上海交大 + 静静“。请按照格式备注,可快速被通过且邀请进群。原创投稿也请联系。

5076bd8fc1395d469cedd5091fcf3fbe.png

▲长按加微信群或投稿

71993489d3f2bdf0935ddce4bbd573cd.png

▲长按关注公众号

3D视觉从入门到精通知识星球:针对3D视觉领域的视频课程(三维重建系列三维点云系列结构光系列手眼标定相机标定激光/视觉SLAM自动驾驶等)、知识点汇总、入门进阶学习路线、最新paper分享、疑问解答五个方面进行深耕,更有各类大厂的算法工程人员进行技术指导。与此同时,星球将联合知名企业发布3D视觉相关算法开发岗位以及项目对接信息,打造成集技术与就业为一体的铁杆粉丝聚集区,近4000星球成员为创造更好的AI世界共同进步,知识星球入口:

学习3D视觉核心技术,扫描查看介绍,3天内无条件退款

9b03297adc213fceb6e1b34a7534ca36.png

 圈里有高质量教程资料、答疑解惑、助你高效解决问题

觉得有用,麻烦给个赞和在看~  

声明:本文内容由网友自发贡献,不代表【wpsshop博客】立场,版权归原作者所有,本站不承担相应法律责任。如您发现有侵权的内容,请联系我们。转载请注明出处:https://www.wpsshop.cn/w/weixin_40725706/article/detail/863585
推荐阅读
  

闽ICP备14008679号