开发环境:Ubuntu 18.04 LTS + ROS Melodic + ViSP 3.3.1
文章内容主要参考ViSP官方教学文档:https://visp-doc.inria.fr/doxygen/visp-daily/tutorial_mainpage.html
本文主要介绍了如何使用ViSP实现基于图像的视觉伺服(IBVS),关于视觉伺服原理的介绍这里就不再展开了,可以参看这篇博客。本文主要参考了visual-servo/ibvs中的tutorial-ibvs-4pts-image-tracking.cpp.例程。首先要获取这个例程文件并编译它
svn export https://github.com/lagadic/visp.git/trunk/tutorial/visual-servo/ibvs
cd ibvs/
mkdir build
cd build
cmake .. -DCMAKE_BUILD_TYPE=Release -DVISP_DIR=$VISP_WS/visp-build
make
执行例程,查看效果
./tutorial-ibvs-4pts-image-tracking
由上到下顺时针选取四个特征点作为图像特征
选择完成后,物体会在视觉伺服计算得到的控制律作用下逐渐向期望位置靠近。图像中的四个红色十字符号表示期望位置,绿色十字符号表示当前位置,绿色线条表示运动轨迹
最终物体运动到期望位置,绿色十字符号和红色符号重叠。
下面介绍一下代码实现过程
#include <visp3/gui/vpDisplayGDI.h>
#include <visp3/gui/vpDisplayOpenCV.h>
#include <visp3/gui/vpDisplayX.h>
#include <visp3/io/vpImageIo.h>
#include <visp3/robot/vpImageSimulator.h>
#include <visp3/robot/vpSimulatorCamera.h>
#include <visp3/visual_features/vpFeatureBuilder.h>
#include <visp3/vs/vpServo.h>
#include <visp3/vs/vpServoDisplay.h>
void display_trajectory(const vpImage<unsigned char> &I, const std::vector<vpDot2> &dot);
class vpVirtualGrabber//用于计算在不同位置处目标物体在相机坐标系下的成像,
//具体过程可以参见博客:[ViSP学习笔记(七):平面图像投影](https://blog.csdn.net/qq_36104364/article/details/113881985)
{
public:
vpVirtualGrabber(const std::string &filename, const vpCameraParameters &cam) : sim_(), target_(), cam_()
{
// The target is a square 20cm by 2cm square
// Initialise the 3D coordinates of the target corners
for (int i = 0; i < 4; i++)
X_[i].resize(3);
// Top left Top right Bottom right Bottom left
X_[0][0] = -0.1;
X_[1][0] = 0.1;
X_[2][0] = 0.1;
X_[3][0] = -0.1;
X_[0][1] = -0.1;
X_[1][1] = -0.1;
X_[2][1] = 0.1;
X_[3][1] = 0.1;
X_[0][2] = 0;
X_[1][2] = 0;
X_[2][2] = 0;
X_[3][2] = 0;
vpImageIo::read(target_, filename);
// Initialize the image simulator
cam_ = cam;
sim_.setInterpolationType(vpImageSimulator::BILINEAR_INTERPOLATION);
sim_.init(target_, X_);
}
void acquire(vpImage<unsigned char> &I, const vpHomogeneousMatrix &cMo)
{
sim_.setCleanPreviousImage(true);
sim_.setCameraPosition(cMo);
sim_.getImage(I, cam_);
}
private:
vpColVector X_[4]; // 3D coordinates of the target corners
vpImageSimulator sim_;
vpImage<unsigned char> target_; // image of the target
vpCameraParameters cam_;
};
//用于显示目标物体的运动轨迹
void display_trajectory(const vpImage<unsigned char> &I, const std::vector<vpDot2> &dot)
{
static std::vector<vpImagePoint> traj[4];
for (unsigned int i = 0; i < 4; i++) {
traj[i].push_back(dot[i].getCog());
}
for (unsigned int i = 0; i < 4; i++) {
for (unsigned int j = 1; j < traj[i].size(); j++) {
vpDisplay::displayLine(I, traj[i][j - 1], traj[i][j], vpColor::green);
}
}
}
int main()
{
#if defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV)
try {
vpHomogeneousMatrix cdMo(0, 0, 0.75, 0, 0, 0);//相机的期望位置和物体之间位置关系
vpHomogeneousMatrix cMo(0.15, -0.1, 1., vpMath::rad(10), vpMath::rad(-10), vpMath::rad(50));//相机的初始位置和物体之间的位置关系
vpImage<unsigned char> I(480, 640, 255);
vpCameraParameters cam(840, 840, I.getWidth() / 2, I.getHeight() / 2);//设置相机内部参数
std::vector<vpPoint> point;//目标物体特征点的空间坐标容器
point.push_back(vpPoint(-0.1, -0.1, 0));
point.push_back(vpPoint(0.1, -0.1, 0));
point.push_back(vpPoint(0.1, 0.1, 0));
point.push_back(vpPoint(-0.1, 0.1, 0));
vpServo task;
task.setServo(vpServo::EYEINHAND_CAMERA);//设置为eye in hand的视觉伺服模式
task.setInteractionMatrixType(vpServo::CURRENT);//交互矩阵的计算方法是根据当前图像进行计算
task.setLambda(0.5);//增益参数lambda设为0.5
vpVirtualGrabber g("./target_square.pgm", cam);//获取目标图像
g.acquire(I, cMo);//根据相机当前位置将物体的成像保存到I中
#if defined(VISP_HAVE_X11)
vpDisplayX d(I, 0, 0, "Current camera view");
#elif defined(VISP_HAVE_GDI)
vpDisplayGDI d(I, 0, 0, "Current camera view");
#elif defined(VISP_HAVE_OPENCV)
vpDisplayOpenCV d(I, 0, 0, "Current camera view");
#else
std::cout << "No image viewer is available..." << std::endl;
#endif
vpDisplay::display(I);
vpDisplay::displayText(I, 10, 10, "Click in the 4 dots to initialise the tracking and start the servo",
vpColor::red);
vpDisplay::flush(I);
vpFeaturePoint p[4], pd[4];//新建特征点容器,p表示当前位置,pd表示期望位置
std::vector<vpDot2> dot(4);
for (unsigned int i = 0; i < 4; i++) {
point[i].track(cdMo);//将目标特征点在期望位置处的空间坐标投影到相机坐标系中
vpFeatureBuilder::create(pd[i], point[i]);//生成期望位置处的特征
dot[i].setGraphics(true);
dot[i].initTracking(I);//根据鼠标点击获取连通区域blob(四个圆点)作为跟踪的目标
vpDisplay::flush(I);
vpFeatureBuilder::create(p[i], cam, dot[i].getCog());//计算连通区域blob的重心作为当前位置处的特征
task.addFeature(p[i], pd[i]);//把期望位置特征和当前位置特征添加到视觉伺服任务中
}
vpHomogeneousMatrix wMc, wMo;//新建相机和目标物体在世界坐标系下的坐标容器
vpSimulatorCamera robot;//新建仿真相机
robot.setSamplingTime(0.040);//设置采样时间
robot.getPosition(wMc);//获取相机初始位置
wMo = wMc * cMo;//根据相机初始位置和目标物体在相机坐标系下的位置计算目标物体在世界坐标系下的坐标
for (;;) {
robot.getPosition(wMc);//更新相机当前位置
cMo = wMc.inverse() * wMo;//更新目标物体在相机坐标系下的坐标
g.acquire(I, cMo);//更新图像
vpDisplay::display(I);
for (unsigned int i = 0; i < 4; i++) {
dot[i].track(I);
vpFeatureBuilder::create(p[i], cam, dot[i].getCog());
vpColVector cP;
point[i].changeFrame(cMo, cP);//根据当前目标物体在相机坐标系下的坐标和初始位置坐标计算当前目标物体在世界坐标系下的坐标
p[i].set_Z(cP[2]);//获取深度距离信息用于视觉伺服计算
}
vpColVector v = task.computeControlLaw();//视觉伺服控制律计算
display_trajectory(I, dot);//显示运动轨迹
vpServoDisplay::display(task, cam, I, vpColor::green, vpColor::red);
robot.setVelocity(vpRobot::CAMERA_FRAME, v);//设置相机运动速度
vpDisplay::flush(I);
if (vpDisplay::getClick(I, false))
break;
vpTime::wait(robot.getSamplingTime() * 1000);
}
} catch (const vpException &e) {
std::cout << "Catch an exception: " << e << std::endl;
}
#endif
}```
如果大家对于深度学习与计算机视觉领域感兴趣,希望获得更多的知识分享与最新的论文解读,欢迎关注我的个人公众号“**深视**”。