一、项目简介

项目结合了 Qt、Intel RealSense 相机以及 AprilTag 标签检测技术,实现了一个实时的视觉检测系统。该系统不仅能够实时捕获彩色和深度图像,还能检测 AprilTag 标签,并计算其在不同坐标系下的位置信息。

二、项目功能概述

  1. 图像捕获:利用 Intel RealSense 相机实时捕获 640x480 分辨率的彩色和深度图像。

  2. AprilTag 检测:使用 AprilTag 库对捕获的图像进行标签检测,并在图像上绘制标签的轮廓、ID 和中心点。

  3. 深度信息获取:获取检测到的 AprilTag 标签中心点的深度信息,并在 LCD 控件上显示。

  4. 坐标转换:支持加载相机内参和手眼标定矩阵,将标签在相机坐标系下的坐标转换到末端执行器坐标系下。

三、项目代码结构

1. main.cpp

这是项目的入口文件,主要负责初始化 Qt 应用程序并显示主窗口。

#include "QtWidgetsApplication1.h"
#include <QtWidgets/QApplication>

int main(int argc, char *argv[])
{
    QApplication a(argc, argv);
    QtWidgetsApplication1 w;
    w.show();
    return a.exec();
}

2. QtWidgetsApplication1.h

该头文件定义了主窗口类QtWidgetsApplication1,包含了类的成员变量和成员函数的声明。

#pragma once

#pragma warning(disable: 4996)

#ifndef QTWIDGETSAPPLICATION1_H
#define QTWIDGETSAPPLICATION1_H

#include <QtWidgets/QMainWindow>
#include "ui_QtWidgetsApplication1.h"

#include <QLabel>
#include <QTimer>
#include <opencv2/opencv.hpp>
#include <librealsense2/rs.hpp>
#include <apriltag.h>
#include <tag36h11.h>
#include <yaml-cpp/yaml.h>
#include <Eigen/Dense>
#include <QFileDialog>

class QtWidgetsApplication1 : public QMainWindow
{
    Q_OBJECT

public:
    QtWidgetsApplication1(QWidget *parent = nullptr);
    ~QtWidgetsApplication1();

private slots:
    void updateFrame();
    void loadCameraIntrinsics();
    void loadHandEyeCalibration();

private:
    Ui::QtWidgetsApplication1Class ui;
    QLabel* label;
    QTimer* timer;
    rs2::pipeline pipe;
    rs2::config cfg;
    rs2::align align_to_color = rs2::align(RS2_STREAM_COLOR);
    cv::Mat frame;
    apriltag_detector_t* td;
    apriltag_family_t* tf;
    Eigen::Matrix3d cameraMatrix;
    bool intrinsicsLoaded;
    Eigen::Matrix4d handEyeMatrix;
    bool handEyeLoaded;
};

#endif

3. QtWidgetsApplication1.cpp

这是主窗口类的实现文件,包含了类的构造函数、析构函数以及各个成员函数的具体实现。

#pragma warning(disable: 4996)

#include "QtWidgetsApplication1.h"

#include <QImage>
#include <QPixmap>
#include <QMessageBox>

QtWidgetsApplication1::QtWidgetsApplication1(QWidget* parent)
	: QMainWindow(parent), intrinsicsLoaded(false), handEyeLoaded(false)
{
	ui.setupUi(this);

	// 初始化 QLabel
	label = ui.label;
	label->setFixedSize(640, 480);
	label->setScaledContents(true);

	// 配置 RealSense 管道
	cfg.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGB8, 30);
	cfg.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
	try {
		pipe.start(cfg);
	}
	catch (const rs2::error& e) {
		QMessageBox::critical(this, "Error", "Failed to start RealSense camera!");
		exit(1);
	}

	// 初始化 AprilTag 检测器
	tf = tag36h11_create();
	td = apriltag_detector_create();
	apriltag_detector_add_family(td, tf);
	td->quad_decimate = 2.0;
	td->quad_sigma = 0.0;
	td->nthreads = 4;
	td->debug = 0;
	td->refine_edges = 1;

	// 初始化 QTimer 用于定时更新画面
	timer = new QTimer(this);

	// 连接定时器的超时信号到 updateFrame 槽
	connect(timer, &QTimer::timeout, this, &QtWidgetsApplication1::updateFrame);

	// 设置定时器间隔为 33 毫秒(约 30 FPS)
	timer->start(33);

	// 连接 pushButton 的点击信号到 loadCameraIntrinsics 槽
	connect(ui.pushButton, &QPushButton::clicked, this, &QtWidgetsApplication1::loadCameraIntrinsics);

	// 连接 pushButton_2 的点击信号到 loadHandEyeCalibration 槽
	connect(ui.pushButton_2, &QPushButton::clicked, this, &QtWidgetsApplication1::loadHandEyeCalibration);

	// 设置窗口大小
	resize(640, 480);
}

QtWidgetsApplication1::~QtWidgetsApplication1()
{
	// 清理 AprilTag 资源
	apriltag_detector_destroy(td);
	tag36h11_destroy(tf);

	// 清理 RealSense 资源
	pipe.stop();

	// 清理 Qt 资源
	delete label;
	delete timer;
}

void QtWidgetsApplication1::updateFrame()
{
	try {
		// 等待帧并进行对齐(将深度对齐到彩色图像)
		rs2::frameset frames = pipe.wait_for_frames();
		frames = align_to_color.process(frames);

		rs2::video_frame color_frame = frames.get_color_frame();
		rs2::depth_frame depth_frame = frames.get_depth_frame();
		if (!color_frame || !depth_frame) {
			return;
		}

		// 转换为 OpenCV Mat
		frame = cv::Mat(cv::Size(640, 480), CV_8UC3, (void*)color_frame.get_data(), cv::Mat::AUTO_STEP);
		if (frame.empty()) {
			return;
		}

		// 转换为灰度图像用于 AprilTag 检测
		cv::Mat gray;
		cv::cvtColor(frame, gray, cv::COLOR_RGB2GRAY);
		if (gray.empty()) {
			return;
		}

		// 使用 AprilTag 提供的函数创建 image_u8_t
		image_u8_t* img = image_u8_create(gray.cols, gray.rows);
		if (!img) {
			return;
		}

		// 逐行拷贝灰度数据到 image_u8_t 的缓冲区
		for (int y = 0; y < gray.rows; y++) {
			memcpy(img->buf + y * img->stride, gray.ptr(y), gray.cols * sizeof(uint8_t));
		}

		// AprilTag 检测
		zarray_t* detections = apriltag_detector_detect(td, img);

		// 在原始帧上绘制检测结果
		for (int i = 0; i < zarray_size(detections); i++) {
			apriltag_detection_t* det;
			zarray_get(detections, i, &det);

			// 绘制边框
			cv::Point2f p0(det->p[0][0], det->p[0][1]);
			cv::Point2f p1(det->p[1][0], det->p[1][1]);
			cv::Point2f p2(det->p[2][0], det->p[2][1]);
			cv::Point2f p3(det->p[3][0], det->p[3][1]);
			cv::line(frame, p0, p1, cv::Scalar(0, 255, 0), 2);
			cv::line(frame, p1, p2, cv::Scalar(0, 255, 0), 2);
			cv::line(frame, p2, p3, cv::Scalar(0, 255, 0), 2);
			cv::line(frame, p3, p0, cv::Scalar(0, 255, 0), 2);

			// 绘制标签 ID
			std::string id_text = "ID: " + std::to_string(det->id);
			cv::putText(frame, id_text, p0, cv::FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(0, 0, 255), 2);

			// 绘制中心点
			cv::Point center(det->c[0], det->c[1]);
			cv::circle(frame, center, 5, cv::Scalar(255, 0, 0), -1);

			// 获取深度(单位:米)
			float depth_in_meters = depth_frame.get_distance(center.x, center.y);

			// 显示到 LCD 控件
			ui.lcdNumber->display(static_cast<int>(center.x));
			ui.lcdNumber_2->display(static_cast<int>(center.y));
			ui.lcdNumber_3->display(static_cast<int>(depth_in_meters * 1000));

			// 像素坐标到相机坐标系转换
			if (intrinsicsLoaded) {
				// 像素坐标 (u, v) 和深度 z(米)
				double u = det->c[0];
				double v = det->c[1];
				double z = depth_in_meters;

				// 内参矩阵元素
				double fx = cameraMatrix(0, 0);
				double fy = cameraMatrix(1, 1);
				double cx = cameraMatrix(0, 2);
				double cy = cameraMatrix(1, 2);

				// 像素坐标到相机坐标(单位:米)
				double x = (u - cx) * z / fx;
				double y = (v - cy) * z / fy;

				// 显示相机坐标(x, y, z,单位:毫米)
				ui.lcdNumber_4->display(static_cast<int>(x * 1000));
				ui.lcdNumber_5->display(static_cast<int>(y * 1000));
				ui.lcdNumber_6->display(static_cast<int>(z * 1000));

				// 相机坐标系到机械臂末端坐标系转换
				if (handEyeLoaded) {
					// 相机坐标(单位:毫米),转换为米以匹配手眼矩阵的单位
					Eigen::Vector4d cameraPoint(x, y, z, 1.0);

					// 应用手眼变换矩阵
					Eigen::Vector4d endEffectorPoint = handEyeMatrix * cameraPoint;

					// 显示机械臂末端坐标(x, y, z,单位:毫米)
					ui.lcdNumber_7->display(static_cast<int>(endEffectorPoint(0) * 1000));
					ui.lcdNumber_8->display(static_cast<int>(endEffectorPoint(1) * 1000));
					ui.lcdNumber_9->display(static_cast<int>(endEffectorPoint(2) * 1000));
				}
			}
		}

		// 释放检测结果
		apriltag_detections_destroy(detections);

		// 释放 image_u8_t
		image_u8_destroy(img);

		// 转换为 QImage
		QImage qImage(frame.data, frame.cols, frame.rows, frame.step, QImage::Format_RGB888);
		if (!qImage.isNull()) {
			// 显示到 QLabel
			label->setPixmap(QPixmap::fromImage(qImage));
			label->update();
		}
	}
	catch (const rs2::error& e) {
		return;
	}
}

void QtWidgetsApplication1::loadCameraIntrinsics()
{
	// 打开文件对话框,选择YAML文件
	QString fileName = QFileDialog::getOpenFileName(this, "Select Camera Intrinsics File", "", "YAML Files (*.yaml *.yml)");
	if (fileName.isEmpty()) {
		return;
	}

	try {
		// 使用 yaml-cpp 解析文件
		YAML::Node config = YAML::LoadFile(fileName.toStdString());

		// 读取 cameraMatrix
		if (!config["cameraMatrix"] || !config["cameraMatrix"]["data"]) {
			QMessageBox::warning(this, "Error", "Invalid camera matrix format! Expected 'cameraMatrix' field.");
			return;
		}

		// 读取 cameraMatrix 的行列数
		YAML::Node cameraMatrixNode = config["cameraMatrix"];
		int rows = cameraMatrixNode["rows"].as<int>();
		int cols = cameraMatrixNode["cols"].as<int>();
		if (rows != 3 || cols != 3) {
			QMessageBox::warning(this, "Error", "Camera matrix must be 3x3!");
			return;
		}

		// 读取 cameraMatrix 的数据
		std::vector<double> cameraMatrixData = cameraMatrixNode["data"].as<std::vector<double>>();
		if (cameraMatrixData.size() != 9) {
			QMessageBox::warning(this, "Error", "Camera matrix must contain 9 elements!");
			return;
		}

		// 填充 Eigen 矩阵
		cameraMatrix << cameraMatrixData[0], cameraMatrixData[1], cameraMatrixData[2],
			            cameraMatrixData[3], cameraMatrixData[4], cameraMatrixData[5],
			            cameraMatrixData[6], cameraMatrixData[7], cameraMatrixData[8];

		intrinsicsLoaded = true;
		QMessageBox::information(this, "Success", "Camera intrinsics loaded successfully!");
	}
	catch (const YAML::Exception& e) {
		QMessageBox::warning(this, "Error", QString("Failed to parse YAML file:%1").arg(QString::fromStdString(e.what())));
	}
}

void QtWidgetsApplication1::loadHandEyeCalibration()
{
	// 打开文件对话框,选择YAML文件
	QString fileName = QFileDialog::getOpenFileName(this, "Select Hand-Eye Calibration File", "", "YAML Files (*.yaml *.yml)");
	if (fileName.isEmpty()) {
		return;
	}

	try {
		// 使用 yaml-cpp 解析文件
		YAML::Node config = YAML::LoadFile(fileName.toStdString());

		// 读取 poseMatrix
		if (!config["poseMatrix"] || !config["poseMatrix"]["data"]) {
			QMessageBox::warning(this, "Error", "Invalid hand-eye calibration matrix format! Expected 'poseMatrix' field.");
			return;
		}

		// 读取 poseMatrix 的行列数
		YAML::Node poseMatrixNode = config["poseMatrix"];
		int rows = poseMatrixNode["rows"].as<int>();
		int cols = poseMatrixNode["cols"].as<int>();
		if (rows != 4 || cols != 4) {
			QMessageBox::warning(this, "Error", "Hand-eye calibration matrix must be 4x4!");
			return;
		}

		// 读取 poseMatrix 的数据
		std::vector<double> poseMatrixData = poseMatrixNode["data"].as<std::vector<double>>();
		if (poseMatrixData.size() != 16) {
			QMessageBox::warning(this, "Error", "Hand-eye calibration matrix must contain 16 elements!");
			return;
		}

		// 填充手眼变换矩阵
		handEyeMatrix << poseMatrixData[0], poseMatrixData[1], poseMatrixData[2], poseMatrixData[3],
			             poseMatrixData[4], poseMatrixData[5], poseMatrixData[6], poseMatrixData[7],
			             poseMatrixData[8], poseMatrixData[9], poseMatrixData[10], poseMatrixData[11],
			             poseMatrixData[12], poseMatrixData[13], poseMatrixData[14], poseMatrixData[15];

		handEyeLoaded = true;
		QMessageBox::information(this, "Success", "Hand-eye calibration loaded successfully!");
	}
	catch (const YAML::Exception& e) {
		QMessageBox::warning(this, "Error", QString("Failed to parse YAML file: %1").arg(QString::fromStdString(e.what())));
	}
}

四、项目依赖

  • Qt:用于创建用户界面和处理事件。

  • Intel RealSense SDK:用于与 RealSense 相机进行交互,捕获彩色和深度图像。

  • OpenCV:用于图像处理和计算机视觉任务,如灰度转换和图像绘制。

  • AprilTag 库:用于 AprilTag 标签的检测。

  • yaml-cpp:用于解析 YAML 格式的配置文件。

  • Eigen:用于矩阵运算和坐标转换。

五、总结

通过本次项目,我们实现了一个基于 Qt、RealSense 和 AprilTag 的实时视觉检测系统。该系统不仅展示了计算机视觉技术在实际应用中的强大功能,还提供了一个可扩展的框架,可以根据具体需求进行进一步的开发和优化。希望本文能对大家在相关领域的学习和实践有所帮助。

本来准备上传到github上,可是github上传限制100MB大小,主要是opencv的dll文件太大了,无法上传github。虽然有解决方案,但我觉得麻烦,就算了吧,哈哈哈,原谅我的懒做。

往事堪堪亦澜澜,前路漫漫亦灿灿。