OpenCV  4.10.0
开源计算机视觉
正在加载...
正在搜索...
无匹配项
纹理物体的实时姿态估计

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

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

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

目标

本教程介绍如何构建一个实时应用程序,以估计相机姿态,从而使用 2D 图像及其 3D 纹理模型跟踪具有六个自由度的纹理物体。

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

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

理论

在计算机视觉中,根据 *n* 个 3D 到 2D 点对应关系估计相机姿态是一个基本且理解良好的问题。该问题最通用的版本需要估计姿态的六个自由度和五个校准参数:焦距、主点、纵横比和倾斜度。可以使用众所周知的直接线性变换 (DLT) 算法,根据至少 6 个对应关系进行确定。然而,该问题存在一些简化,转化为一系列不同的算法,这些算法可以提高 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 ]\]

有关如何处理这些方程式的完整文档位于 相机校准和 3D 重建 中。

源代码

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

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

  1. 模型注册

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

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

    应用程序启动后将从输入图像中提取 ORB 特征和描述符,然后使用网格和 Möller–Trumbore 交点算法 计算所找到特征的 3D 坐标。最后,3D 点和描述符存储在 YAML 格式的文件中不同的列表中,每行代表一个不同的点。有关如何存储文件的技术背景,请参阅 使用 XML 和 YAML 文件进行文件输入和输出 教程。

  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 (值:2000)
    要检测的关键点数量
    --mesh
    ply 网格路径
    --method, --pnp (值:0)
    PnP 方法: (0) ITERATIVE - (1) EPNP - (2) P3P - (3) DLS
    --model
    yml 模型路径
    -r, --ratio (值: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:304
    @ READ
    值,以读取模式打开文件
    定义 persistence.hpp:309
    n 维密集数组类
    定义 mat.hpp:812
    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 中找到模型网格的示例。

    /* 加载 CSV 文件,格式为 *.ply */
    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 << "Could not open the camera device" << std::endl;
    return -1;
    }
    用于从视频文件、图像序列或相机捕获视频的类。
    定义 videoio.hpp:731
    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); // 设置描述符提取器
    2D 图像特征检测器和描述符提取器的抽象基类。
    定义 features2d.hpp:139

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

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

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

    首先,我们必须设置要使用的匹配器。在本例中,使用 cv::FlannBasedMatcher 匹配器,就计算成本而言,它比 cv::BFMatcher 匹配器快,因为我们增加了训练的特征集。然后,对于 FlannBased 匹配器,创建的索引是 Multi-Probe LSH: Efficient Indexing for High-Dimensional Similarity Search,因为 ORB 描述符是二进制的。

    您可以调整 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

    其次,我们必须使用 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。此具有 4 个属性:给定的校准矩阵、旋转矩阵、平移矩阵和旋转-平移矩阵。您用于估计姿态的摄像头的内在校准参数是必要的。要获取参数,您可以查看 使用方形棋盘进行相机校准使用 OpenCV 进行相机校准 教程。

    以下代码是在主程序中声明 PnPProblem 类 的方法

    // 摄像头的内在参数:UVC 网络摄像头
    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 成功置信度。

    以下代码对应于estimatePoseRANSAC() 函数,该函数属于PnPProblem 类。此函数根据一组 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; // 如果为 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 错误,函数 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 投影,方法是使用理论中显示的公式。

    以下代码对应于backproject3DPoint() 函数,该函数属于PnPProblem 类。该函数将给定以世界参考系表示的 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. 用于错误姿态拒绝的线性卡尔曼滤波器

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

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

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

    \[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)
    返回一个所有元素都设置为 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())
    计算预测状态。

    第六步是设置估计的旋转平移矩阵

    // -- 第六步:设置估计的投影矩阵
    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 上观看实时姿态估计