OpenCV 4.13.0
开源计算机视觉库 (Open Source Computer Vision)
正在加载...
正在搜索...
未找到匹配项
有纹理对象的实时姿态估计

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

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

如今,增强现实(AR)是计算机视觉和机器人领域最热门的研究课题之一。在增强现实中,最基础的问题是估计相机相对于物体的姿态。在计算机视觉领域,这是为了进行后续的 3D 渲染;在机器人领域,则是为了获取物体姿态以便进行抓取和操作。然而,这并不是一个容易解决的问题,因为图像处理中最常见的问题是:为了解决一个对人类来说基本且直观的问题,需要应用大量的算法或数学运算,从而产生巨大的计算开销。

目标

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

该程序将包含以下部分:

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

理论

在计算机视觉中,通过 n 个 3D 到 2D 的点对应关系来估计相机姿态是一个基础且已被充分理解的问题。该问题最通用的版本需要估计姿态的六个自由度和五个标定参数:焦距、主点、纵横比和倾斜。使用著名的直接线性变换(DLT)算法,最少需要 6 组对应关系即可建立。不过,该问题存在多种简化形式,从而产生了一系列不同的算法来提高 DLT 的精度。

最常见的简化是假设标定参数已知,即所谓的 Perspective-n-Point(PnP)问题。

问题阐述: 给定一组在世界参考坐标系中表达的 3D 点 \(p_i\),及其在图像上的 2D 投影 \(u_i\),我们寻求找回相机相对于世界的姿态(\(R\) 和 \(t\))以及焦距 \(f\)。

OpenCV 提供了四种不同的方法来解决 PnP 问题并返回 \(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 ]\]

关于如何处理这些方程的完整文档位于 相机标定与 3D 重建

源代码

您可以在 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::flann::GenericIndexcv::FlannBasedMatcher 在场景描述符和模型描述符之间进行匹配。利用找到的匹配项结合 cv::solvePnPRansac 函数计算相机的 Rt。最后,应用卡尔曼滤波(KalmanFilter)以剔除不良姿态。

    如果您在编译 OpenCV 时包含了示例(samples),可以在 opencv/build/bin/cpp-tutorial-pnp_detection 中找到它。然后您可以运行该应用程序并修改一些参数:

    此程序展示了如何根据给定的 3D 纹理模型检测 物体。您可以选择使用录制的视频或摄像头。
    用法
    ./cpp-tutorial-pnp_detection -help
    按键
    'esc' - 退出。
    -------------------------------------------------------------------------
    用法: cpp-tutorial-pnp_detection [params]
    -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 (默认值:2000)
    检测的关键点数量
    --mesh
    ply 网格文件的路径
    --method, --pnp (默认值:0)
    PnP 方法: (0) ITERATIVE - (1) EPNP - (2) P3P - (3) DLS
    --model
    yml 模型文件的路径
    -r, --ratio (默认值:0.7)
    比例测试(ratio test)的阈值
    -v, --video
    录制视频的路径

    例如,您可以通过更改 pnp 方法来运行应用程序:

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

原理解释

下面详细解释实时应用程序的代码:

  1. 读取 3D 纹理对象模型和对象网格(mesh)。

    为了加载纹理模型,我实现了一个 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:840
    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=/你的网格绝对路径.ply --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:786
    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=/你的视频绝对路径.mp4
  3. 从场景中提取 ORB 特征和描述符

    下一步是检测场景特征并提取其描述符。为此,我实现了一个 RobustMatcher 类,它具有关键点检测和特征提取功能。您可以在 samples/cpp/tutorial_code/calib3d/real_time_pose_estimation/src/RobusMatcher.cpp 中找到它。在您的 RobustMatcher 对象中,可以使用 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); // 设置描述符提取器
    2D 图像特征检测器和描述符提取器的抽象基类。
    定义 features2d.hpp:139

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

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

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

    首先,我们必须设置要使用的匹配器。在这种情况下,使用 cv::FlannBasedMatcher 匹配器,随着训练特征集的增加,其计算开销比 cv::BFMatcher 匹配器更低。然后,对于 FlannBased 匹配器,由于 ORB 描述符是二进制的,创建的索引是 Multi-Probe LSH: Efficient Indexing for High-Dimensional Similarity Search

    您可以调整 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:1004
    基于 Flann 的描述符匹配器。
    定义 features2d.hpp:1303
    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. 移除最近邻比例 > 阈值的匹配
    // 清理图像 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 的原因在于,匹配后的对应关系并不全是正确的,很可能存在错误的对应关系(即离群点 outliers)。随机采样一致性 (Ransac) 是一种非确定性的迭代方法,它从观测数据中估计数学模型的参数,随着迭代次数的增加产生近似结果。应用 Ransac 后,所有 outliers 将被剔除,从而以一定的概率估计出相机姿态的一个良好解。

    对于相机姿态估计,我实现了一个 PnPProblem 类。该类有 4 个属性:给定的标定矩阵、旋转矩阵、平移矩阵和旋转-平移矩阵。用于估计姿态的相机的内参是必需的。为了获取参数,您可以参考 使用正方形棋盘格进行相机标定使用 OpenCV 进行相机标定 教程。

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

    // 相机内参: UVC WEBCAM
    double f = 55; // 焦距 (mm)
    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)
    返回一个指定大小和类型的全 0 数组。
    #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 参数的情况下估计旋转和平移矩阵。

    // 在给定 2D/3D 对应关系列表的情况下,使用 RANSAC 和指定方法估计姿态
    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; // 如果为真,函数将使用提供的 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 的某些 bug,函数 cv::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 个内点的 2D 坐标
    list_points2d_inliers.push_back(point2d); // 添加第 i 个内点到列表
    }

    最后,一旦相机姿态被估计出来,我们就可以使用 \(R\) 和 \(t\),结合“理论”部分展示的公式,计算在世界参考系中表达的给定 3D 点在图像上的 2D 投影。

    以下代码对应于 PnPProblem 类中的 backproject3DPoint() 函数。该函数将世界参考系中表达的给定 3D 点反投影到 2D 图像上:

    // 使用估计的姿态参数将 3D 点反投影到 2D
    cv::Point2f PnPProblem::backproject3DPoint(const cv::Point3f &point3d)
    {
    // 3D 点向量 [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;
    // 2D 点向量 [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
    3D 点的 x 坐标
    定义于 types.hpp:284
    _Tp y
    点的 y 坐标
    定义 types.hpp:202
    _Tp x
    点的 x 坐标
    定义 types.hpp:201

    上述函数用于计算对象 Mesh 的所有 3D 点,以显示物体的姿态。

    您还可以修改 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:435

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

    您可以调整过程噪声和测量噪声以提高 卡尔曼滤波器 的性能。测量噪声越小,收敛速度越快,但算法对错误测量也会变得敏感。

    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:469
    Mat measurementMatrix
    测量矩阵 (H)
    定义 tracking.hpp:471
    Mat errorCovPost
    后验误差估计协方差矩阵 (P(k)): P(k)=(I-K(k)*H)*P'(k)
    定义 tracking.hpp:476
    void init(int dynamParams, int measureParams, int controlParams=0, int type=CV_32F)
    重新初始化卡尔曼滤波器。之前的内容将被销毁。
    Mat measurementNoiseCov
    测量噪声协方差矩阵 (R)
    定义 tracking.hpp:473
    Mat processNoiseCov
    过程噪声协方差矩阵 (Q)
    定义 tracking.hpp:472
    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

结果

以下视频是使用所述检测算法进行实时姿态估计的结果,使用了以下参数:

// Robust Matcher 参数
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 上观看实时姿态估计展示。