OpenCV 4.11.0
开源计算机视觉
加载中…
搜索中…
无匹配项
纹理物体的实时位姿估计

上一教程: 使用 OpenCV 进行相机标定
下一教程: 交互式相机标定应用程序

原作者Edgar Riba
兼容性OpenCV >= 3.0

如今,增强现实是计算机视觉和机器人领域最热门的研究课题之一。增强现实中最基本的问题是在计算机视觉领域估计相机相对于物体的位姿,以便稍后进行3D渲染;在机器人领域,则是为了抓取物体并进行操作而获取物体的位姿。然而,这并非一个容易解决的问题,因为图像处理中最常见的问题是,为了解决对人类来说简单直接的问题,需要应用大量算法或数学运算,这带来了巨大的计算成本。

目标

本教程解释了如何构建一个实时应用程序,以估计相机位姿,以便根据2D图像及其3D纹理模型跟踪具有六个自由度的纹理物体。

该应用程序将包含以下部分:

  • 读取3D纹理物体模型和物体网格。
  • 从相机或视频获取输入。
  • 从场景中提取ORB特征和描述符。
  • 使用Flann匹配器将场景描述符与模型描述符进行匹配。
  • 使用PnP + Ransac进行位姿估计。
  • 使用线性卡尔曼滤波器去除错误位姿。

理论

在计算机视觉中,根据*n*个3D-to-2D点对应关系估计相机位姿是一个基本且已被充分理解的问题。该问题的最一般形式需要估计位姿的六个自由度和五个校准参数:焦距、主点、纵横比和倾斜度。可以使用至少6个对应关系,使用著名的直接线性变换(DLT)算法来建立。然而,这个问题有几个简化方法,转化为大量的不同算法,这些算法提高了DLT的精度。

最常见的简化是假设已知校准参数,这就是所谓的透视-*n*-点问题。

问题描述: 给定一组在世界参考系中表达的3D点\(p_i\)与其在图像上的2D投影\(u_i\)之间的对应关系,我们寻求检索相机相对于世界的位姿(\(R\)和\(t\))以及焦距\(f\)。

OpenCV提供了四种不同的方法来解决透视-*n*-点问题,这些方法返回\(R\)和\(t\)。然后,使用以下公式可以将3D点投影到图像平面:

\[s\ \left [ \begin{matrix} u \\ v \\ 1 \end{matrix} \right ] = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \left [ \begin{matrix} r_{11} & r_{12} & r_{13} & t_1 \\ r_{21} & r_{22} & r_{23} & t_2 \\ r_{31} & r_{32} & r_{33} & t_3 \end{matrix} \right ] \left [ \begin{matrix} X \\ Y \\ Z\\ 1 \end{matrix} \right ]\]

如何处理这些方程的完整文档可在相机标定和三维重建中找到。

源代码

您可以在OpenCV源代码库的samples/cpp/tutorial_code/calib3d/real_time_pose_estimation/文件夹中找到本教程的源代码。

本教程包含两个主要程序:

  1. 模型配准

    此应用程序仅适用于没有待检测物体的3D纹理模型的用户。您可以使用此程序创建您自己的纹理3D模型。此程序仅适用于平面物体,因此如果您想对形状复杂的物体建模,则应使用更复杂的软件来创建它。

    该应用程序需要待配准物体的输入图像及其3D网格。我们还需要提供拍摄输入图像的相机的内参。所有文件都需要使用绝对路径或应用程序工作目录的相对路径指定。如果没有指定任何文件,程序将尝试打开提供的默认参数。

    应用程序首先从输入图像中提取ORB特征和描述符,然后使用网格以及Möller–Trumbore相交算法来计算找到的特征的3D坐标。最后,3D点和描述符存储在YAML格式文件的不同列表中,每一行代表一个不同的点。关于如何存储文件的技术背景可以在使用XML/YAML/JSON文件进行文件输入和输出教程中找到。

  1. 模型检测

    此应用程序的目标是根据其3D纹理模型实时估计物体的位姿。

    应用程序首先加载YAML文件格式的3D纹理模型,其结构与模型配准程序中解释的结构相同。从场景中检测和提取ORB特征和描述符。然后,使用cv::FlannBasedMatchercv::flann::GenericIndex来匹配场景描述符和模型描述符。使用找到的匹配项以及cv::solvePnPRansac函数计算相机的Rt。最后,应用卡尔曼滤波器以去除错误位姿。

    如果您使用示例编译了OpenCV,则可以在opencv/build/bin/cpp-tutorial-pnp_detection`中找到它。然后您可以运行应用程序并更改一些参数。

    此程序演示了如何根据其3D纹理模型检测物体。您可以选择使用录制的视频或网络摄像头。
    用法
    ./cpp-tutorial-pnp_detection -help
    按键
    'esc' - 退出。
    --------------------------------------------------------------------------
    用法:cpp-tutorial-pnp_detection [参数]
    -c, --confidence (值:0.95)
    RANSAC 置信度
    -e, --error (值:2.0)
    RANSAC 投影误差
    -f, --fast (值:true)
    使用鲁棒快速匹配
    -h, --help (值:true)
    打印此消息
    --in, --inliers (值:30)
    卡尔曼更新的最小内点
    --it, --iterations (值:500)
    RANSAC 最大迭代次数
    -k, --keypoints (value:2000)
    检测关键点的数量
    --mesh
    PLY 网格模型路径
    --method, --pnp (value:0)
    PnP 方法: (0) 迭代法 - (1) EPNP - (2) P3P - (3) DLS
    --model
    YML 模型路径
    -r, --ratio (value:0.7)
    比率测试阈值
    -v, --video
    录制视频路径

    例如,您可以更改 PnP 方法后运行应用程序

    ./cpp-tutorial-pnp_detection --method=2

说明

此处详细解释了实时应用程序的代码

  1. 读取3D纹理物体模型和物体网格。

    为了加载纹理模型,我实现了Model,它具有load()函数,该函数打开一个 YAML 文件并获取存储的 3D 点及其对应的描述符。您可以在samples/cpp/tutorial_code/calib3d/real_time_pose_estimation/Data/cookies_ORB.yml中找到 3D 纹理模型示例。

    /* 使用 OpenCV 加载 YAML 文件 */
    void Model::load(const std::string path)
    {
    cv::Mat points3d_mat;
    storage["points_3d"] >> points3d_mat;
    storage["descriptors"] >> descriptors_;
    points3d_mat.copyTo(list_points3d_in_);
    storage.release();
    }
    XML/YAML/JSON 文件存储类,封装了写入或读取所需的所有信息……
    定义 persistence.hpp:261
    @ READ
    值,以读取模式打开文件
    定义 persistence.hpp:266
    n 维密集数组类
    定义 mat.hpp:829
    void copyTo(OutputArray m) const
    将矩阵复制到另一个矩阵。

    在主程序中,模型加载如下

    Model model; // 实例化 Model 对象
    model.load(yml_read_path); // 加载 3D 纹理对象模型

    为了读取模型网格,我实现了一个Mesh,它具有一个load()函数,该函数打开一个 \(*\).ply 文件并存储对象的 3D 点以及组成的三角形。您可以在samples/cpp/tutorial_code/calib3d/real_time_pose_estimation/Data/box.ply中找到模型网格示例。

    /* 加载具有 *.ply 格式的 CSV 文件 */
    void Mesh::load(const std::string path)
    {
    // 创建读取器
    CsvReader csvReader(path);
    // 清除先前的数据
    list_vertex_.clear();
    list_triangles_.clear();
    // 从 .ply 文件读取
    csvReader.readPLY(list_vertex_, list_triangles_);
    // 更新网格属性
    num_vertexs_ = list_vertex_.size();
    num_triangles_ = list_triangles_.size();
    }

    在主程序中,网格加载如下

    Mesh mesh; // 实例化 Mesh 对象
    mesh.load(ply_read_path); // 加载对象网格

    您还可以加载不同的模型和网格

    ./cpp-tutorial-pnp_detection --mesh=/absolute_path_to_your_mesh.ply --model=/absolute_path_to_your_model.yml
  2. 从摄像头或视频中获取输入

    要进行检测,需要捕获视频。这是通过传递录制视频在您机器上的绝对路径来完成的。为了测试应用程序,您可以在samples/cpp/tutorial_code/calib3d/real_time_pose_estimation/Data/box.mp4中找到一个录制视频。

    cv::VideoCapture cap; // 实例化 VideoCapture
    cap.open(video_read_path); // 打开录制视频
    if(!cap.isOpened()) // 检查是否成功
    {
    std::cout << "无法打开相机设备" << std::endl;
    return -1;
    }
    用于从视频文件、图像序列或摄像头捕获视频的类。
    定义 videoio.hpp:766
    virtual bool open(const String &filename, int apiPreference=CAP_ANY)
    打开视频文件或捕获设备或 IP 视频流以进行视频捕获。
    virtual bool isOpened() const
    如果视频捕获已初始化,则返回 true。

    然后逐帧计算算法

    cv::Mat frame, frame_vis;
    while(cap.read(frame) && cv::waitKey(30) != 27) // 按下 ESC 键之前捕获帧
    {
    frame_vis = frame.clone(); // 刷新可视化帧
    // 主算法
    }
    CV_NODISCARD_STD Mat clone() const
    创建数组和底层数据的完整副本。
    virtual bool read(OutputArray image)
    抓取、解码并返回下一视频帧。
    int waitKey(int delay=0)
    等待按下键。

    您还可以加载不同的录制视频

    ./cpp-tutorial-pnp_detection --video=/absolute_path_to_your_video.mp4
  3. 从场景中提取 ORB 特征和描述符

    下一步是检测场景特征并提取其描述符。为此,我实现了一个RobustMatcher,它具有用于关键点检测和特征提取的函数。您可以在samples/cpp/tutorial_code/calib3d/real_time_pose_estimation/src/RobusMatcher.cpp中找到它。在您的RobusMatch对象中,您可以使用任何 OpenCV 的 2D 特征检测器。在本例中,我使用了cv::ORB 特征,因为它基于cv::FAST 来检测关键点,并使用cv::xfeatures2d::BriefDescriptorExtractor来提取描述符,这意味着它速度快且对旋转具有鲁棒性。您可以在文档中找到关于ORB的更多详细信息。

    以下代码是如何实例化和设置特征检测器和描述符提取器的

    RobustMatcher rmatcher; // 实例化 RobustMatcher
    cv::FeatureDetector * detector = new cv::OrbFeatureDetector(numKeyPoints); // 实例化 ORB 特征检测器
    cv::DescriptorExtractor * extractor = new cv::OrbDescriptorExtractor(); // 实例化 ORB 描述符提取器
    rmatcher.setFeatureDetector(detector); // 设置特征检测器
    rmatcher.setDescriptorExtractor(extractor); // 设置描述符提取器
    二维图像特征检测器和描述符提取器的抽象基类。
    定义 features2d.hpp:139

    特征和描述符将在匹配函数内部由RobustMatcher计算。

  4. 使用 Flann 匹配器将场景描述符与模型描述符进行匹配

    这是我们检测算法的第一步。其主要思想是将场景描述符与我们的模型描述符进行匹配,以便了解当前场景中找到的特征的 3D 坐标。

    首先,我们必须设置要使用的匹配器。在本例中,使用了cv::FlannBasedMatcher 匹配器,就计算成本而言,它比cv::BFMatcher 匹配器更快,因为我们增加了训练特征的集合。然后,对于 FlannBased 匹配器,由于 *ORB* 描述符是二进制的,因此创建的索引为 *多探针 LSH:高效索引用于高维相似性搜索*。

    您可以调整 *LSH* 和搜索参数以提高匹配效率。

    cv::Ptr<cv::flann::IndexParams> indexParams = cv::makePtr<cv::flann::LshIndexParams>(6, 12, 1); // 实例化 LSH 索引参数
    cv::Ptr<cv::flann::SearchParams> searchParams = cv::makePtr<cv::flann::SearchParams>(50); // 实例化 flann 搜索参数
    cv::DescriptorMatcher * matcher = new cv::FlannBasedMatcher(indexParams, searchParams); // 实例化 FlannBased 匹配器
    rmatcher.setDescriptorMatcher(matcher); // 设置匹配器
    关键点描述符匹配的抽象基类。
    定义 features2d.hpp:995
    基于 Flann 的描述符匹配器。
    定义 features2d.hpp:1294
    std::shared_ptr< _Tp > Ptr
    定义 cvstd_wrapper.hpp:23
    static Ptr< _Tp > makePtr(const A1 &... a1)
    定义 cvstd_wrapper.hpp:26

    其次,我们必须使用 *robustMatch()* 或 *fastRobustMatch()* 函数调用匹配器。这两个函数的区别在于它们的计算成本。第一种方法较慢,但在过滤良好匹配方面更稳健,因为它使用了两次比率测试和一次对称性测试。相反,第二种方法更快,但不太稳健,因为它只对匹配应用单比率测试。

    以下代码用于获取模型 3D 点及其描述符,然后在主程序中调用匹配器。

    // 获取模型信息
    std::vector<cv::Point3f> list_points3d_model = model.get_points3d(); // 包含模型 3D 坐标的列表
    cv::Mat descriptors_model = model.get_descriptors(); // 包含每个 3D 坐标描述符的列表
    // -- 步骤 1:模型描述符和场景描述符之间的鲁棒匹配
    std::vector<cv::DMatch> good_matches; // 用于获取场景中的模型 3D 点
    std::vector<cv::KeyPoint> keypoints_scene; // 用于获取场景的 2D 点
    if(fast_match)
    {
    rmatcher.fastRobustMatch(frame, good_matches, keypoints_scene, descriptors_model);
    }
    else
    {
    rmatcher.robustMatch(frame, good_matches, keypoints_scene, descriptors_model);
    }

    以下代码对应于属于 *RobustMatcher* 类的 *robustMatch()* 函数。此函数使用给定的图像来检测关键点并提取描述符,使用 *最近邻* 将提取的描述符与给定的模型描述符进行匹配,反之亦然。然后,将比率测试应用于两个方向的匹配,以去除其第一和第二最佳匹配之间的距离比率大于给定阈值的匹配。最后,应用对称性测试以去除非对称匹配。

    void RobustMatcher::robustMatch( const cv::Mat& frame, std::vector<cv::DMatch>& good_matches,
    std::vector<cv::KeyPoint>& keypoints_frame,
    const std::vector<cv::KeyPoint>& keypoints_model, const cv::Mat& descriptors_model )
    {
    // 1a. ORB 特征检测
    this->computeKeyPoints(frame, keypoints_frame);
    // 1b. ORB 描述符提取
    cv::Mat descriptors_frame;
    this->computeDescriptors(frame, keypoints_frame, descriptors_frame);
    // 2. 匹配两个图像描述符
    std::vector<std::vector<cv::DMatch> > matches12, matches21;
    // 2a. 从图像 1 到图像 2
    matcher_->knnMatch(descriptors_frame, descriptors_model, matches12, 2); // 返回 2 个最近邻
    // 2b. 从图像 2 到图像 1
    matcher_->knnMatch(descriptors_model, descriptors_frame, matches21, 2); // 返回 2 个最近邻
    // 3. 删除 NN 比率 > 阈值的匹配
    // 清理图像 1 -> 图像 2 匹配
    int removed1 = ratioTest(matches12);
    // 清理图像 2 -> 图像 1 匹配
    int removed2 = ratioTest(matches21);
    // 4. 删除非对称匹配
    symmetryTest(matches12, matches21, good_matches);
    }

    匹配过滤后,我们必须使用获得的 *DMatches* 向量从找到的场景关键点和我们的 3D 模型中减去 2D 和 3D 对应关系。有关 cv::DMatch 的更多信息,请查看文档。

    // -- 步骤 2:找出 2D/3D 对应关系
    std::vector<cv::Point3f> list_points3d_model_match; // 场景中找到的模型 3D 坐标容器
    std::vector<cv::Point2f> list_points2d_scene_match; // 场景中找到的模型 2D 坐标容器
    for(unsigned int match_index = 0; match_index < good_matches.size(); ++match_index)
    {
    cv::Point3f point3d_model = list_points3d_model[ good_matches[match_index].trainIdx ]; // 来自模型的 3D 点
    cv::Point2f point2d_scene = keypoints_scene[ good_matches[match_index].queryIdx ].pt; // 来自场景的 2D 点
    list_points3d_model_match.push_back(point3d_model); // 添加 3D 点
    list_points2d_scene_match.push_back(point2d_scene); // 添加 2D 点
    }
    用于由其坐标 x、y 和 z 指定的 3D 点的模板类。
    定义 types.hpp:255

    您还可以更改比率测试阈值、要检测的关键点数以及是否使用鲁棒匹配器。

    ./cpp-tutorial-pnp_detection --ratio=0.8 --keypoints=1000 --fast=false
  5. 使用 PnP + Ransac 进行姿态估计

    一旦有了 2D 和 3D 对应关系,我们就必须应用 PnP 算法来估计相机姿态。我们必须使用 cv::solvePnPRansac 而不是 cv::solvePnP 的原因是,匹配后并非所有找到的对应关系都是正确的,并且很可能存在错误对应关系,也称为 *离群值*。随机抽样一致性 或 *Ransac* 是一种非确定性迭代方法,它根据观察到的数据估计数学模型的参数,随着迭代次数的增加,产生近似结果。应用 *Ransac* 后,所有 *离群值* 都将被消除,然后以一定的概率估计相机姿态以获得良好的解决方案。

    对于相机姿态估计,我实现了一个名为PnPProblem。这个有四个属性:给定的标定矩阵、旋转矩阵、平移矩阵和旋转平移矩阵。你需要使用用于估计姿态的相机的内参标定参数。要获取这些参数,你可以查看使用方格棋盘的相机标定使用OpenCV进行相机标定教程。

    以下代码展示了如何在主程序中声明PnPProblem类

    // 相机内参:UVC WEBCAM
    double f = 55; // 焦距(毫米)
    double sx = 22.3, sy = 14.9; // 传感器尺寸
    double width = 640, height = 480; // 图像尺寸
    double params_WEBCAM[] = { width*f/sx, // fx
    height*f/sy, // fy
    width/2, // cx
    height/2}; // cy
    PnPProblem pnp_detection(params_WEBCAM); // 实例化PnPProblem类

    以下代码展示了PnPProblem类如何初始化其属性

    // 给定相机内参的自定义构造函数
    PnPProblem::PnPProblem(const double params[])
    {
    _A_matrix = cv::Mat::zeros(3, 3, CV_64FC1); // 相机内参矩阵
    _A_matrix.at<double>(0, 0) = params[0]; // [ fx 0 cx ]
    _A_matrix.at<double>(1, 1) = params[1]; // [ 0 fy cy ]
    _A_matrix.at<double>(0, 2) = params[2]; // [ 0 0 1 ]
    _A_matrix.at<double>(1, 2) = params[3];
    _A_matrix.at<double>(2, 2) = 1;
    _R_matrix = cv::Mat::zeros(3, 3, CV_64FC1); // 旋转矩阵
    _t_matrix = cv::Mat::zeros(3, 1, CV_64FC1); // 平移矩阵
    _P_matrix = cv::Mat::zeros(3, 4, CV_64FC1); // 旋转平移矩阵
    }
    static CV_NODISCARD_STD MatExpr zeros(int rows, int cols, int type)
    返回指定大小和类型的零数组。
    #define CV_64FC1
    定义 interface.h:124

    OpenCV 提供四种 PnP 方法:ITERATIVE、EPNP、P3P 和 DLS。根据应用类型,估计方法会有所不同。如果需要构建实时应用,EPNP 和 P3P 更为合适,因为它们比 ITERATIVE 和 DLS 查找最优解的速度更快。但是,EPNP 和 P3P 在平面表面面前并不十分鲁棒,有时姿态估计会出现镜像效应。因此,本教程使用 ITERATIVE 方法,因为待检测物体具有平面表面。

    OpenCV 的 RANSAC 实现需要三个参数:1)算法停止之前的最大迭代次数;2)将观测到的点投影和计算出的点投影之间的最大允许距离(视为内点);3)获得良好结果的置信度。你可以调整这些参数以提高算法性能。增加迭代次数将获得更精确的解,但会花费更多时间。增加重投影误差将减少计算时间,但解的精度会降低。降低置信度将使算法更快,但获得的解的精度会降低。

    以下参数适用于此应用

    // RANSAC 参数
    int iterationsCount = 500; // Ransac 迭代次数。
    float reprojectionError = 2.0; // 视为内点的最大允许距离。
    float confidence = 0.95; // RANSAC 成功置信度。

    以下代码对应于PnPProblem类estimatePoseRANSAC()函数。此函数给定一组 2D/3D 对应点、所需的 PnP 方法、输出内点容器和 RANSAC 参数来估计旋转矩阵和平移矩阵。

    // 使用 RANSAC 和指定方法估计一组 2D/3D 对应点的姿态
    void PnPProblem::estimatePoseRANSAC( const std::vector<cv::Point3f> &list_points3d, // 模型 3D 坐标列表
    const std::vector<cv::Point2f> &list_points2d, // 场景 2D 坐标列表
    int flags, cv::Mat &inliers, int iterationsCount, // PnP 方法;内点容器
    float reprojectionError, float confidence ) // RANSAC 参数
    {
    cv::Mat distCoeffs = cv::Mat::zeros(4, 1, CV_64FC1); // 畸变系数向量
    cv::Mat rvec = cv::Mat::zeros(3, 1, CV_64FC1); // 输出旋转向量
    cv::Mat tvec = cv::Mat::zeros(3, 1, CV_64FC1); // 输出平移向量
    bool useExtrinsicGuess = false; // 如果为 true,则函数使用提供的 rvec 和 tvec 值作为
    // 旋转向量和平移向量的初始近似值
    cv::solvePnPRansac( list_points3d, list_points2d, _A_matrix, distCoeffs, rvec, tvec,
    useExtrinsicGuess, iterationsCount, reprojectionError, confidence,
    inliers, flags );
    Rodrigues(rvec,_R_matrix); // 将旋转向量转换为矩阵
    _t_matrix = tvec; // 设置平移矩阵
    this->set_P_matrix(_R_matrix, _t_matrix); // 设置旋转平移矩阵
    }
    bool solvePnPRansac(InputArray objectPoints, InputArray imagePoints, InputArray cameraMatrix, InputArray distCoeffs, OutputArray rvec, OutputArray tvec, bool useExtrinsicGuess=false, int iterationsCount=100, float reprojectionError=8.0, double confidence=0.99, OutputArray inliers=noArray(), int flags=SOLVEPNP_ITERATIVE)
    使用 RANSAC 方案根据 3D-2D 点对应关系查找物体姿态。

    以下代码是主算法的第 3 步和第 4 步。第一步调用上述函数,第二步获取 RANSAC 的输出内点向量以获取用于绘图的 2D 场景点。如代码所示,如果存在匹配项,则必须应用 RANSAC,否则,由于任何 OpenCV 的bugcv::solvePnPRansac 函数将崩溃。

    if(good_matches.size() > 0) // 没有匹配项,则 RANSAC 会崩溃
    {
    // -- 步骤 3:使用 RANSAC 方法估计姿态
    pnp_detection.estimatePoseRANSAC( list_points3d_model_match, list_points2d_scene_match,
    pnpMethod, inliers_idx, iterationsCount, reprojectionError, confidence );
    // -- 步骤 4:获取内点关键点进行绘制
    for(int inliers_index = 0; inliers_index < inliers_idx.rows; ++inliers_index)
    {
    int n = inliers_idx.at<int>(inliers_index); // 第 i 个内点
    cv::Point2f point2d = list_points2d_scene_match[n]; // 第 i 个内点二维坐标
    list_points2d_inliers.push_back(point2d); // 将第 i 个内点添加到列表中
    }

    最后,一旦估计出相机姿态,我们就可以使用旋转矩阵 \(R\) 和平移向量 \(t\) 来计算给定三维点在世界坐标系下的二维投影,具体公式如理论部分所示。

    下面的代码对应于PnPProblem类中的backproject3DPoint()函数。该函数将世界坐标系中给定的三维点投影到二维图像上。

    // 使用估计的姿态参数将三维点反投影到二维
    cv::Point2f PnPProblem::backproject3DPoint(const cv::Point3f &point3d)
    {
    // 三维点向量 [x y z 1]'
    cv::Mat point3d_vec = cv::Mat(4, 1, CV_64FC1);
    point3d_vec.at<double>(0) = point3d.x;
    point3d_vec.at<double>(1) = point3d.y;
    point3d_vec.at<double>(2) = point3d.z;
    point3d_vec.at<double>(3) = 1;
    // 二维点向量 [u v 1]'
    cv::Mat point2d_vec = cv::Mat(4, 1, CV_64FC1);
    point2d_vec = _A_matrix * _P_matrix * point3d_vec;
    // 对 [u v]' 进行归一化
    cv::Point2f point2d;
    point2d.x = point2d_vec.at<double>(0) / point2d_vec.at<double>(2);
    point2d.y = point2d_vec.at<double>(1) / point2d_vec.at<double>(2);
    return point2d;
    }
    _Tp & at(int i0=0)
    返回对指定数组元素的引用。
    _Tp x
    三维点的 x 坐标
    定义 types.hpp:284
    _Tp y
    点的 y 坐标
    定义 types.hpp:202
    _Tp x
    点的 x 坐标
    定义 types.hpp:201

    上述函数用于计算对象Mesh的所有三维点,以显示对象的姿态。

    您还可以更改RANSAC参数和PnP方法

    ./cpp-tutorial-pnp_detection --error=0.25 --confidence=0.90 --iterations=250 --method=3
  6. 线性卡尔曼滤波器用于剔除错误姿态

    在计算机视觉或机器人领域,应用检测或跟踪技术后,由于一些传感器误差而导致结果错误是很常见的。为了避免本教程中这些错误的检测,解释了如何实现线性卡尔曼滤波器。在检测到一定数量的内点后,将应用卡尔曼滤波器。

    您可以找到更多关于卡尔曼滤波器的信息。在本教程中,使用了基于用于位置和方向跟踪的线性卡尔曼滤波器的OpenCV实现的cv::KalmanFilter来设置动态模型和测量模型。

    首先,我们必须定义状态向量,它将有18个状态:位置数据 (x,y,z)及其一阶和二阶导数(速度和加速度),然后以三个欧拉角 (roll, pitch, yaw) 的形式添加旋转以及它们的一阶和二阶导数(角速度和角加速度)

    \[X = (x,y,z,\dot x,\dot y,\dot z,\ddot x,\ddot y,\ddot z,\psi,\theta,\phi,\dot \psi,\dot \theta,\dot \phi,\ddot \psi,\ddot \theta,\ddot \phi)^T\]

    其次,我们必须定义测量数量,它将为 6:从 \(R\) 和 \(t\) 中我们可以提取 \((x,y,z)\) 和 \((\psi,\theta,\phi)\)。此外,我们必须定义要应用于系统的控制动作的数量,在本例中为。最后,我们必须定义测量之间的微分时间,在本例中为 \(1/T\),其中T是视频的帧率。

    cv::KalmanFilter KF; // 实例化卡尔曼滤波器
    int nStates = 18; // 状态数量
    int nMeasurements = 6; // 测量状态的数量
    int nInputs = 0; // 控制动作的数量
    double dt = 0.125; // 测量之间的时间(1/FPS)
    initKalmanFilter(KF, nStates, nMeasurements, nInputs, dt); // 初始化函数
    卡尔曼滤波器类。
    定义 tracking.hpp:361

    下面的代码对应于卡尔曼滤波器的初始化。首先,设置过程噪声、测量噪声和误差协方差矩阵。其次,设置状态转移矩阵(即动态模型)和测量矩阵(即测量模型)。

    您可以调整过程噪声和测量噪声以提高卡尔曼滤波器的性能。随着测量噪声的减小,算法收敛速度越快,对不良测量的敏感性也越高。

    void initKalmanFilter(cv::KalmanFilter &KF, int nStates, int nMeasurements, int nInputs, double dt)
    {
    KF.init(nStates, nMeasurements, nInputs, CV_64F); // 初始化卡尔曼滤波器
    cv::setIdentity(KF.processNoiseCov, cv::Scalar::all(1e-5)); // 设置过程噪声
    cv::setIdentity(KF.measurementNoiseCov, cv::Scalar::all(1e-4)); // 设置测量噪声
    cv::setIdentity(KF.errorCovPost, cv::Scalar::all(1)); // 后验误差协方差
    /* 动态模型 */
    // [1 0 0 dt 0 0 dt2 0 0 0 0 0 0 0 0 0 0 0]
    // [0 1 0 0 dt 0 0 dt2 0 0 0 0 0 0 0 0 0 0]
    // [0 0 1 0 0 dt 0 0 dt2 0 0 0 0 0 0 0 0 0]
    // [0 0 0 1 0 0 dt 0 0 0 0 0 0 0 0 0 0 0]
    // [0 0 0 0 1 0 0 dt 0 0 0 0 0 0 0 0 0 0]
    // [0 0 0 0 0 1 0 0 dt 0 0 0 0 0 0 0 0 0]
    // [0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0]
    // [0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0]
    // [0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0]
    // [0 0 0 0 0 0 0 0 0 1 0 0 dt 0 0 dt2 0 0]
    // [0 0 0 0 0 0 0 0 0 0 1 0 0 dt 0 0 dt2 0]
    // [0 0 0 0 0 0 0 0 0 0 0 1 0 0 dt 0 0 dt2]
    // [0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 dt 0 0]
    // [0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 dt 0]
    // [0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 dt]
    // [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0]
    // [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0]
    // [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1]
    // 位置
    KF.transitionMatrix.at<double>(0,3) = dt;
    KF.transitionMatrix.at<double>(1,4) = dt;
    KF.transitionMatrix.at<double>(2,5) = dt;
    KF.transitionMatrix.at<double>(3,6) = dt;
    KF.transitionMatrix.at<double>(4,7) = dt;
    KF.transitionMatrix.at<double>(5,8) = dt;
    KF.transitionMatrix.at<double>(0,6) = 0.5*pow(dt,2);
    KF.transitionMatrix.at<double>(1,7) = 0.5*pow(dt,2);
    KF.transitionMatrix.at<double>(2,8) = 0.5*pow(dt,2);
    // 方向
    KF.transitionMatrix.at<double>(9,12) = dt;
    KF.transitionMatrix.at<double>(10,13) = dt;
    KF.transitionMatrix.at<double>(11,14) = dt;
    KF.transitionMatrix.at<double>(12,15) = dt;
    KF.transitionMatrix.at<double>(13,16) = dt;
    KF.transitionMatrix.at<double>(14,17) = dt;
    KF.transitionMatrix.at<double>(9,15) = 0.5*pow(dt,2);
    KF.transitionMatrix.at<double>(10,16) = 0.5*pow(dt,2);
    KF.transitionMatrix.at<double>(11,17) = 0.5*pow(dt,2);
    /* 测量模型 */
    // [1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
    // [0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
    // [0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
    // [0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0]
    // [0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0]
    // [0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0]
    KF.measurementMatrix.at<double>(0,0) = 1; // x
    KF.measurementMatrix.at<double>(1,1) = 1; // y
    KF.measurementMatrix.at<double>(2,2) = 1; // z
    KF.measurementMatrix.at<double>(3,9) = 1; // 横滚角(roll)
    KF.measurementMatrix.at<double>(4,10) = 1; // 俯仰角(pitch)
    KF.measurementMatrix.at<double>(5,11) = 1; // 航向角(yaw)
    }
    Mat transitionMatrix
    状态转移矩阵 (A)
    定义 tracking.hpp:395
    Mat measurementMatrix
    测量矩阵 (H)
    定义 tracking.hpp:397
    Mat errorCovPost
    后验误差估计协方差矩阵 (P(k)): P(k)=(I-K(k)*H)*P'(k)
    定义 tracking.hpp:402
    void init(int dynamParams, int measureParams, int controlParams=0, int type=CV_32F)
    重新初始化卡尔曼滤波器。之前的內容將被销毁。
    Mat measurementNoiseCov
    测量噪声协方差矩阵 (R)
    定义 tracking.hpp:399
    Mat processNoiseCov
    过程噪声协方差矩阵 (Q)
    定义 tracking.hpp:398
    static Scalar_< double > all(double v0)
    void setIdentity(InputOutputArray mtx, const Scalar &s=Scalar(1))
    初始化一个缩放后的单位矩阵。
    #define CV_64F
    定义 interface.h:79

    下面的代码是主算法的第5步。当Ransac之后获得的内点数量超过阈值时,测量矩阵被填充,然后更新卡尔曼滤波器。

    // -- 步骤 5:卡尔曼滤波器
    // 良好测量值
    if( inliers_idx.rows >= minInliersKalman )
    {
    // 获取测量的平移向量
    cv::Mat translation_measured(3, 1, CV_64F);
    translation_measured = pnp_detection.get_t_matrix();
    // 获取测量的旋转矩阵
    cv::Mat rotation_measured(3, 3, CV_64F);
    rotation_measured = pnp_detection.get_R_matrix();
    // 填充测量向量
    fillMeasurements(measurements, translation_measured, rotation_measured);
    }
    // 实例化估计的平移和旋转
    cv::Mat translation_estimated(3, 1, CV_64F);
    cv::Mat rotation_estimated(3, 3, CV_64F);
    // 使用良好测量值更新卡尔曼滤波器
    updateKalmanFilter( KF, measurements,
    translation_estimated, rotation_estimated);

    下面的代码对应于`fillMeasurements()`函数,该函数将测量的旋转矩阵转换为欧拉角,并连同测量的平移向量一起填充测量矩阵。

    void fillMeasurements( cv::Mat &measurements,
    const cv::Mat &translation_measured, const cv::Mat &rotation_measured)
    {
    // 将旋转矩阵转换为欧拉角
    cv::Mat measured_eulers(3, 1, CV_64F);
    measured_eulers = rot2euler(rotation_measured);
    // 设置测量值以进行预测
    measurements.at<double>(0) = translation_measured.at<double>(0); // x
    measurements.at<double>(1) = translation_measured.at<double>(1); // y
    measurements.at<double>(2) = translation_measured.at<double>(2); // z
    measurements.at<double>(3) = measured_eulers.at<double>(0); // roll
    measurements.at<double>(4) = measured_eulers.at<double>(1); // pitch
    measurements.at<double>(5) = measured_eulers.at<double>(2); // yaw
    }

    下面的代码对应于`updateKalmanFilter()`函数,该函数更新卡尔曼滤波器并设置估计的旋转矩阵和平移向量。估计的旋转矩阵来自估计的欧拉角到旋转矩阵

    void updateKalmanFilter( cv::KalmanFilter &KF, cv::Mat &measurement,
    cv::Mat &translation_estimated, cv::Mat &rotation_estimated )
    {
    // 首先预测,以更新内部状态变量statePre
    cv::Mat prediction = KF.predict();
    // 将要使用预测值和我们的测量的“校正”阶段
    cv::Mat estimated = KF.correct(measurement);
    // 估计的平移向量
    translation_estimated.at<double>(0) = estimated.at<double>(0);
    translation_estimated.at<double>(1) = estimated.at<double>(1);
    translation_estimated.at<double>(2) = estimated.at<double>(2);
    // 估计的欧拉角
    cv::Mat eulers_estimated(3, 1, CV_64F);
    eulers_estimated.at<double>(0) = estimated.at<double>(9);
    eulers_estimated.at<double>(1) = estimated.at<double>(10);
    eulers_estimated.at<double>(2) = estimated.at<double>(11);
    // 将估计的欧拉角转换为旋转矩阵
    rotation_estimated = euler2rot(eulers_estimated);
    }
    const Mat & correct(const Mat &measurement)
    根据测量值更新预测状态。
    const Mat & predict(const Mat &control=Mat())
    计算预测状态。

    第6步是设置估计的旋转-平移矩阵。

    // -- 步骤 6:设置估计的投影矩阵
    pnp_detection_est.set_P_matrix(rotation_estimated, translation_estimated);

    最后一步(可选)是绘制找到的姿态。为此,我实现了一个函数来绘制所有网格3D点和一个额外的参考轴。

    // -- 步骤 X:绘制姿态
    drawObjectMesh(frame_vis, &mesh, &pnp_detection, green); // 绘制当前姿态
    drawObjectMesh(frame_vis, &mesh, &pnp_detection_est, yellow); // 绘制估计姿态
    double l = 5;
    std::vector<cv::Point2f> pose_points2d;
    pose_points2d.push_back(pnp_detection_est.backproject3DPoint(cv::Point3f(0,0,0))); // 坐标系中心
    pose_points2d.push_back(pnp_detection_est.backproject3DPoint(cv::Point3f(l,0,0))); // x轴
    pose_points2d.push_back(pnp_detection_est.backproject3DPoint(cv::Point3f(0,l,0))); // y轴
    pose_points2d.push_back(pnp_detection_est.backproject3DPoint(cv::Point3f(0,0,l))); // z轴
    draw3DCoordinateAxes(frame_vis, pose_points2d); // 绘制坐标轴

    您也可以修改最小内点数量来更新卡尔曼滤波器

    ./cpp-tutorial-pnp_detection --inliers=20

结果

以下视频是使用所解释的检测算法和以下参数进行实时位姿估计的结果

// 鲁棒匹配器参数
int numKeyPoints = 2000; // 检测到的关键点数
float ratio = 0.70f; // 比率测试
bool fast_match = true; // fastRobustMatch() 或 robustMatch()
// RANSAC 参数
int iterationsCount = 500; // Ransac 迭代次数。
int reprojectionError = 2.0; // 允许的最大距离,将其视为内点。
float confidence = 0.95; // RANSAC 成功置信度。
// 卡尔曼滤波器参数
int minInliersKalman = 30; // 卡尔曼滤波器更新阈值

您可以在YouTube上观看实时位姿估计视频