开发环境:Ubuntu 18.04 LTS + ROS Melodic + ViSP 3.3.1
文章内容主要参考ViSP官方教学文档:https://visp-doc.inria.fr/doxygen/visp-daily/tutorial_mainpage.html

  本文主要介绍了如何使用ViSP实现基于CAD模型的目标跟踪,需要提供目标物体的CAD模型文件(cao格式或者vrml格式),目标物体的初始位置(init文件),视频文件,并且需要手动在视频文件的第一帧中选择出目标物体的初始位置(至少提供四个点)。本文主要参考了 generic中的 tutorial-mb-generic-tracker.cpp 例程。首先要获取这个例程文件并编译它

svn export https://github.com/lagadic/visp.git/trunk/tutorial/tracking/model-based/generic
cd generic/
mkdir build
cd build 
cmake .. -DCMAKE_BUILD_TYPE=Release -DVISP_DIR=$VISP_WS/visp-build
make 

  执行例程,查看效果

./tutorial-mb-generic-tracker

  按照图像中给定点的顺序,在视频第一帧中依次点击图像中对应的点
在这里插入图片描述
  选择完成后获得物体初始位置
在这里插入图片描述
  点击左键开始跟踪,点击右键重新选取
在这里插入图片描述
  下面介绍一下代码实现过程

#include <visp3/core/vpIoTools.h>
#include <visp3/gui/vpDisplayGDI.h>
#include <visp3/gui/vpDisplayOpenCV.h>
#include <visp3/gui/vpDisplayX.h>
#include <visp3/io/vpImageIo.h>
#include <visp3/mbt/vpMbGenericTracker.h>
#include <visp3/io/vpVideoReader.h>
int main(int argc, char **argv)
{
#if defined(VISP_HAVE_OPENCV) && (VISP_HAVE_OPENCV_VERSION >= 0x020100)
  try {
    std::string opt_videoname = "model/teabox/teabox.mp4"; //视频文件
    std::string opt_modelname = "model/teabox/teabox.cao"; //模型文件
    int opt_tracker = 1;
    for (int i = 0; i < argc; i++) {
      if (std::string(argv[i]) == "--video")
        opt_videoname = std::string(argv[i + 1]);
      else if (std::string(argv[i]) == "--model")
        opt_modelname = std::string(argv[i + 1]);
      else if (std::string(argv[i]) == "--tracker")
        opt_tracker = atoi(argv[i + 1]);
      else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
        std::cout << "\nUsage: " << argv[0]
                  << " [--video <video name>] [--model <model name>]"
                     " [--tracker <0=egde|1=keypoint|2=hybrid>] [--help] [-h]\n"
                  << std::endl;
        return 0;
      }
    }
    std::string parentname = vpIoTools::getParent(opt_modelname);
    std::string objectname = vpIoTools::getNameWE(opt_modelname);
    if (!parentname.empty())
      objectname = parentname + "/" + objectname;
    std::cout << "Video name: " << opt_videoname << std::endl;
    std::cout << "Tracker requested config files: " << objectname << ".[init, cao]" << std::endl;
    std::cout << "Tracker optional config files: " << objectname << ".[ppm]" << std::endl;
    vpImage<unsigned char> I; //新建图像容器
    vpCameraParameters cam;  //新建相机参数容器
    vpHomogeneousMatrix cMo;  //新建变换矩阵
    vpVideoReader g; //新建视频容器
    g.setFileName(opt_videoname); //读取视频文件
    g.open(I); //打开视频第一帧
    vpDisplay *display = NULL;
#if defined(VISP_HAVE_X11)
    display = new vpDisplayX;
#elif defined(VISP_HAVE_GDI)
    display = new vpDisplayGDI;
#else
    display = new vpDisplayOpenCV;
#endif
    display->init(I, 100, 100, "Model-based tracker");
    vpMbGenericTracker tracker;
    if (opt_tracker == 0)
      tracker.setTrackerType(vpMbGenericTracker::EDGE_TRACKER);//选择边缘跟踪模式
#ifdef VISP_HAVE_MODULE_KLT
    else if (opt_tracker == 1)
      tracker.setTrackerType(vpMbGenericTracker::KLT_TRACKER);//选择关键点跟踪模式
    else
      tracker.setTrackerType(vpMbGenericTracker::EDGE_TRACKER | vpMbGenericTracker::KLT_TRACKER);//选择混合跟踪模式(鲁棒性更强)
#else
    else {
      std::cout << "klt and hybrid model-based tracker are not available since visp_klt module is not available. "
                   "In CMakeGUI turn visp_klt module ON, configure and build ViSP again."
                << std::endl;
      return 0;
    }
#endif
    if (opt_tracker == 0 || opt_tracker == 2) {
      vpMe me;
      //设置边缘跟踪参数
      me.setMaskSize(5);//定义用于检测边缘的卷积掩码的大小。
      me.setMaskNumber(180);//用于确定物体轮廓的掩模数目。掩模的数量决定了每个样本边缘的精度。
      						//如果精度是2度,那么有360/2 = 180掩码。
      me.setRange(8);//用于跟踪移动边缘的轮廓法线的两侧的范围。
      				//如果被跟踪对象在连续两幅图像中的位移较大,则必须增加该参数。
      me.setThreshold(10000);//用于确定移动边缘是否有效的似然阈值。
      me.setMu1(0.5);//允许检测轮廓的最小图像对比度。
      me.setMu2(0.5);//允许检测轮廓的最大图像对比度。
      me.setSampleStep(4);//两个离散化的移动边缘之间的最小像素距离。
      					  //若要增加移动边缘的数量,必须减少此参数。
      tracker.setMovingEdge(me);
    }
#ifdef VISP_HAVE_MODULE_KLT
    if (opt_tracker == 1 || opt_tracker == 2) {
      vpKltOpencv klt_settings;
      //设置关键点跟踪的参数
      klt_settings.setMaxFeatures(300);//在图像中跟踪关键点的最大数目
      klt_settings.setWindowSize(5);//用于细化角点位置的窗口尺寸
      klt_settings.setQuality(0.015);//描述图像角点的最小可接受质量的参数。
      klt_settings.setMinDistance(8);//在关键点检测阶段,用于初始化关键点位置的被检测角点之间的最小欧氏距离。
      klt_settings.setHarrisFreeParameter(0.01);//Harris检测器的自由参数
      klt_settings.setBlockSize(3);//用于跟踪关键特征的平均块的大小。
      klt_settings.setPyramidLevels(3);//特征金字塔的最大层级。如果层级为零,则没有计算光流的金字塔。
      tracker.setKltOpencv(klt_settings);
      tracker.setKltMaskBorder(5);
    }
#endif
    cam.initPersProjWithoutDistortion(839, 839, 325, 243);//初始化相机内部参数
    tracker.setCameraParameters(cam);//设置相机参数
    tracker.loadModel(objectname + ".cao");//加载模型文件,cao格式是ViSP专用的格式
    tracker.setDisplayFeatures(true);//是否显示特征
    tracker.initClick(I, objectname + ".init", true);//根据点击初始化目标物体位置
    while (!g.end()) {
      g.acquire(I);
      vpDisplay::display(I);
      tracker.track(I);//跟踪木比奥
      tracker.getPose(cMo);//获得变换矩阵
      tracker.getCameraParameters(cam);//获得相机参数
      tracker.display(I, cMo, cam, vpColor::red, 2);//显示跟踪结果
      vpDisplay::displayFrame(I, cMo, cam, 0.025, vpColor::none, 3);//显示坐标轴
      vpDisplay::displayText(I, 10, 10, "A click to exit...", vpColor::red);
      vpDisplay::flush(I);
      if (vpDisplay::getClick(I, false))
        break;
    }
    vpDisplay::getClick(I);
    delete display;
  } catch (const vpException &e) {
    std::cout << "Catch a ViSP exception: " << e << std::endl;
  }
#else
  (void)argc;
  (void)argv;
  std::cout << "Install OpenCV and rebuild ViSP to use this example." << std::endl;
#endif
}

如果大家对于深度学习与计算机视觉领域感兴趣,希望获得更多的知识分享与最新的论文解读,欢迎关注我的个人公众号“深视”。在这里插入图片描述