【ArUco boards】标定板检测

  之前定位用的Charuco标定板做的(https://blog.csdn.net/qq_45445740/article/details/143897238),因为实际工况中对标定板的尺寸有要求,大概是3cm*2cm这个尺寸,加上选用的是ChAruco标定板,导致每一个aruco码都做的很小大概是一两个毫米,且只能选择是4x4字典的图案,再大一点如6x6字典都放不下,会造成精度方面的下降。

  基于以上问题,想试下ArucoBoard标定板,和Charuco标定板一样的尺寸下,图像可以做到6x6的字典,并且每个aruco标记会比原来ChAruco上的aruco更大,理论上应该会提高些精度。

OpenCV:4.10.0

https://docs.opencv.org/4.10.0/db/da9/tutorial_aruco_board_detection.html

1.ArUco boards介绍

ArUco板是一组标记,其作用类似于单个标记,因为它为相机提供了一个单一的姿势。

最受欢迎的板是所有标记都在同一平面上的板,因为它很容易打印:

在这里插入图片描述
然而,棋盘不限于这种排列方式,并且可以表示任何二维或三维布局。

一个板和一组独立标记的区别在于,板中标记之间的相对位置是先验已知的。这使得所有标记的角点都可以用来估计相机相对于整个板的姿态。

当你使用一组独立的标记时,你可以单独估计每个标记的姿态,因为你不知道环境中标记的相对位置。

使用板子的主要好处有:

  • 1.姿态估计更加通用。只需要一些标记就可以进行姿态估计。因此,即使存在遮挡或部分视图,也可以计算姿态。
  • 2.获得的姿态通常更准确,因为使用了更多的点对应关系(标记角点)。

2.标定板检测

标定检测与标准标记检测类似,唯一的区别在于姿态估计步骤。事实上,要使用标记板,应该在估计板姿态之前先进行标准的标记检测。

要对ArucoBoard标定板进行姿态估计,应该使用 solvePnP() 函数,官方示例: samples/cpp/tutorial_code/objectDetection/detect_board.cpp

在这里插入图片描述

  • detect_board.cpp
#include <iostream>
#include <vector>
#include <opencv2/highgui.hpp>
#include <opencv2/objdetect/aruco_detector.hpp>
#include "aruco_samples_utility.hpp"

using namespace std;
using namespace cv;

namespace {
const char* about = "Pose estimation using a ArUco Planar Grid board";

//! [aruco_detect_board_keys]
const char* keys  =
        "{w        |       | Number of squares in X direction }"
        "{h        |       | Number of squares in Y direction }"
        "{l        |       | Marker side length (in pixels) }"
        "{s        |       | Separation between two consecutive markers in the grid (in pixels)}"
        "{d        |       | dictionary: DICT_4X4_50=0, DICT_4X4_100=1, DICT_4X4_250=2,"
        "DICT_4X4_1000=3, DICT_5X5_50=4, DICT_5X5_100=5, DICT_5X5_250=6, DICT_5X5_1000=7, "
        "DICT_6X6_50=8, DICT_6X6_100=9, DICT_6X6_250=10, DICT_6X6_1000=11, DICT_7X7_50=12,"
        "DICT_7X7_100=13, DICT_7X7_250=14, DICT_7X7_1000=15, DICT_ARUCO_ORIGINAL = 16}"
        "{cd       |       | Input file with custom dictionary }"
        "{c        |       | Output file with calibrated camera parameters }"
        "{v        |       | Input from video or image file, if omitted, input comes from camera }"
        "{ci       | 0     | Camera id if input doesnt come from video (-v) }"
        "{dp       |       | File of marker detector parameters }"
        "{rs       |       | Apply refind strategy }"
        "{r        |       | show rejected candidates too }";
}
//! [aruco_detect_board_keys]

int main(int argc, char *argv[]) {
    CommandLineParser parser(argc, argv, keys);
    parser.about(about);

    if(argc < 7) {
        parser.printMessage();
        return 0;
    }

    //! [aruco_detect_board_full_sample]
    int markersX = parser.get<int>("w");
    int markersY = parser.get<int>("h");
    float markerLength = parser.get<float>("l");
    float markerSeparation = parser.get<float>("s");
    bool showRejected = parser.has("r");
    bool refindStrategy = parser.has("rs");
    int camId = parser.get<int>("ci");


    Mat camMatrix, distCoeffs;
    readCameraParamsFromCommandLine(parser, camMatrix, distCoeffs);
    aruco::Dictionary dictionary = readDictionatyFromCommandLine(parser);
    aruco::DetectorParameters detectorParams = readDetectorParamsFromCommandLine(parser);

    String video;
    if(parser.has("v")) {
        video = parser.get<String>("v");
    }

    if(!parser.check()) {
        parser.printErrors();
        return 0;
    }

    aruco::ArucoDetector detector(dictionary, detectorParams);
    VideoCapture inputVideo;
    int waitTime;
    if(!video.empty()) {
        inputVideo.open(video);
        waitTime = 0;
    } else {
        inputVideo.open(camId);
        waitTime = 10;
    }

    float axisLength = 0.5f * ((float)min(markersX, markersY) * (markerLength + markerSeparation) +
                               markerSeparation);

    // Create GridBoard object
    //! [aruco_create_board]
    aruco::GridBoard board(Size(markersX, markersY), markerLength, markerSeparation, dictionary);
    //! [aruco_create_board]

    // Also you could create Board object
    //vector<vector<Point3f> > objPoints; // array of object points of all the marker corners in the board
    //vector<int> ids; // vector of the identifiers of the markers in the board
    //aruco::Board board(objPoints, dictionary, ids);

    double totalTime = 0;
    int totalIterations = 0;

    while(inputVideo.grab()) {
        Mat image, imageCopy;
        inputVideo.retrieve(image);

        double tick = (double)getTickCount();

        vector<int> ids;
        vector<vector<Point2f>> corners, rejected;
        Vec3d rvec, tvec;

        //! [aruco_detect_and_refine]

        // Detect markers
        detector.detectMarkers(image, corners, ids, rejected);

        // Refind strategy to detect more markers
        if(refindStrategy)
            detector.refineDetectedMarkers(image, board, corners, ids, rejected, camMatrix,
                                           distCoeffs);

        //! [aruco_detect_and_refine]

        // Estimate board pose
        int markersOfBoardDetected = 0;
        if(!ids.empty()) {
            // Get object and image points for the solvePnP function
            cv::Mat objPoints, imgPoints;
            board.matchImagePoints(corners, ids, objPoints, imgPoints);

            // Find pose
            cv::solvePnP(objPoints, imgPoints, camMatrix, distCoeffs, rvec, tvec);

            markersOfBoardDetected = (int)objPoints.total() / 4;
        }

        double currentTime = ((double)getTickCount() - tick) / getTickFrequency();
        totalTime += currentTime;
        totalIterations++;
        if(totalIterations % 30 == 0) {
            cout << "Detection Time = " << currentTime * 1000 << " ms "
                 << "(Mean = " << 1000 * totalTime / double(totalIterations) << " ms)" << endl;
        }

        // Draw results
        image.copyTo(imageCopy);
        if(!ids.empty())
            aruco::drawDetectedMarkers(imageCopy, corners, ids);

        if(showRejected && !rejected.empty())
            aruco::drawDetectedMarkers(imageCopy, rejected, noArray(), Scalar(100, 0, 255));

        if(markersOfBoardDetected > 0)
            cv::drawFrameAxes(imageCopy, camMatrix, distCoeffs, rvec, tvec, axisLength);

        imshow("out", imageCopy);
        char key = (char)waitKey(waitTime);
        if(key == 27) break;
    //! [aruco_detect_board_full_sample]
    }

    return 0;
}

参数说明:

  • objPoints, imgPoints:对象点和图像点,与**cv::aruco::GridBoard::matchImagePoints()匹配,后者又将来自cv::aruco::ArucoDetector::detectMarkers()**函数检测到的标记的markerCorners和markerIds结构作为输入。
  • board:定义棋盘布局及其ID的cv::aruco::Board对象。
  • cameraMatrixdistCoeffs:用于姿态估计的必要相机校准参数。
  • rvectvec:棋盘估计的姿态。如果非空,则将其视为初始猜测。
  • 该函数返回用于估计棋盘姿态的标记总数。

drawFrameAxes()函数可用于检查获得的姿态。例如:
在这里插入图片描述
这是一张棋盘部分被遮挡的例子:
在这里插入图片描述
正如所观察到的,尽管一些标记未被检测到,但仍然可以从其余标记估计板位姿。

在这里插入图片描述
这些示例现在通过 cv::CommandLineParser 经由命令行获取输入,示例参数如下所示:

-w=5 -h=7 -l=100 -s=10
-v=/path_to_opencv/opencv/doc/tutorials/objdetect/aruco_board_detection/gboriginal.jpg
-c=/path_to_opencv/opencv/samples/cpp/tutorial_code/objectDetection/tutorial_camera_params.yml
-cd=/path_to_opencv/opencv/samples/cpp/tutorial_code/objectDetection/tutorial_dict.yml

Q1.为什么自己实际生成的DICT_6X6_250的aruco图案和文档中的不同?

在这里插入图片描述
在这里插入图片描述
我发现我生成的arucoboard和官方文档中的图案始终对应不上,原因是作者用的自定义的图案:
在这里插入图片描述

Q2.为什么自己按照示例实现的位姿估计和官方文档中的识别的位姿估计原点不一样?

  • 官方的图:坐标原点是在id30的aruco码上面,id30、id31、id32、id33、id34是红色的X轴,id30、id25、id20、id15、id10、id5、id0是绿色的Y轴。
    在这里插入图片描述
  • 自己识别的:坐标原点是在id0的aruco码上面,id0、id1、id2、id3、id4是红色的X轴,id0、id5、id10、id15、id20、id25、id30是绿色的Y轴。
    在这里插入图片描述
    在这里插入图片描述

没明白。。。

3.网格板

创建 cv::aruco::Board 对象需要指定环境中每个标记的角点位置。 然而在许多情况下,板仅仅是同一平面上且呈网格布局的一组标记,因此可以很容易地打印和使用。

幸运的是,aruco模块提供了基本的功能来轻松创建和打印这些类型的标记。

cv::aruco::GridBoard类是一个专门的类,它继承自cv::aruco::Board类,表示一个所有标记位于同一平面且以网格布局排列的Board,如下图所示:
在这里插入图片描述

具体来说,网格板上的坐标系位于板平面内,以板的左下角为中心,Z轴指向外,如下图所示(X:红色,Y:绿色,Z:蓝色):
在这里插入图片描述
可以使用以下参数定义 cv::aruco::GridBoard 对象:

  • X 方向的标记数量。
  • Y 方向的标记数量。
  • 标记边的长度。
  • 标记间距的长度。
  • 标记的字典。
  • 所有标记的 ID (X*Y 个标记)。

可以使用 cv::aruco::GridBoard 构造函数从这些参数轻松创建此对象:

aruco::GridBoard board(Size(markersX, markersY), markerLength, markerSeparation, dictionary);

// 参数说明:
// markersX和markersY:分别是X和Y方向上的标记数量。
//markerLength和markerSeparation:分别是标记长度和标记间距,它们可以以任何单位提供,但请记住,此板的估计姿势将以相同的单位测量(通常使用米)。
// dictionary:提供了标记的字典。

所以,这个板子将由5x7=35个标记组成。每个标记的ID默认按升序分配,从0开始,所以它们将是0, 1, 2, …, 34。

在创建网格板之后,我们可能需要打印并使用它。有两种方法可以做到这一点:

  • 1.通过使用脚本 doc/patter_tools/gen_pattern.py,请参阅创建校准图案。
    在这里插入图片描述
  • gen_pattern.py
#!/usr/bin/env python

"""gen_pattern.py
Usage example:
python gen_pattern.py -o out.svg -r 11 -c 8 -T circles -s 20.0 -R 5.0 -u mm -w 216 -h 279
-o, --output - output file (default out.svg)
-r, --rows - pattern rows (default 11)
-c, --columns - pattern columns (default 8)
-T, --type - type of pattern: circles, acircles, checkerboard, radon_checkerboard, charuco_board. default circles.
-s, --square_size - size of squares in pattern (default 20.0)
-R, --radius_rate - circles_radius = square_size/radius_rate (default 5.0)
-u, --units - mm, inches, px, m (default mm)
-w, --page_width - page width in units (default 216)
-h, --page_height - page height in units (default 279)
-a, --page_size - page size (default A4), supersedes -h -w arguments
-m, --markers - list of cells with markers for the radon checkerboard
-p, --aruco_marker_size - aruco markers size for ChAruco pattern (default 10.0)
-f, --dict_file - file name of custom aruco dictionary for ChAruco pattern
-H, --help - show help
"""

import argparse
import numpy as np
import json
import gzip
from svgfig import *


class PatternMaker:
    def __init__(self, cols, rows, output, units, square_size, radius_rate, page_width, page_height, markers, aruco_marker_size, dict_file):
        self.cols = cols
        self.rows = rows
        self.output = output
        self.units = units
        self.square_size = square_size
        self.radius_rate = radius_rate
        self.width = page_width
        self.height = page_height
        self.markers = markers
        self.aruco_marker_size = aruco_marker_size #for charuco boards only
        self.dict_file = dict_file

        self.g = SVG("g")  # the svg group container

    def make_circles_pattern(self):
        spacing = self.square_size
        r = spacing / self.radius_rate
        pattern_width = ((self.cols - 1.0) * spacing) + (2.0 * r)
        pattern_height = ((self.rows - 1.0) * spacing) + (2.0 * r)
        x_spacing = (self.width - pattern_width) / 2.0
        y_spacing = (self.height - pattern_height) / 2.0
        for x in range(0, self.cols):
            for y in range(0, self.rows):
                dot = SVG("circle", cx=(x * spacing) + x_spacing + r,
                          cy=(y * spacing) + y_spacing + r, r=r, fill="black", stroke="none")
                self.g.append(dot)

    def make_acircles_pattern(self):
        spacing = self.square_size
        r = spacing / self.radius_rate
        pattern_width = ((self.cols-1.0) * 2 * spacing) + spacing + (2.0 * r)
        pattern_height = ((self.rows-1.0) * spacing) + (2.0 * r)
        x_spacing = (self.width - pattern_width) / 2.0
        y_spacing = (self.height - pattern_height) / 2.0
        for x in range(0, self.cols):
            for y in range(0, self.rows):
                dot = SVG("circle", cx=(2 * x * spacing) + (y % 2)*spacing + x_spacing + r,
                          cy=(y * spacing) + y_spacing + r, r=r, fill="black", stroke="none")
                self.g.append(dot)

    def make_checkerboard_pattern(self):
        spacing = self.square_size
        xspacing = (self.width - self.cols * self.square_size) / 2.0
        yspacing = (self.height - self.rows * self.square_size) / 2.0
        for x in range(0, self.cols):
            for y in range(0, self.rows):
                if x % 2 == y % 2:
                    square = SVG("rect", x=x * spacing + xspacing, y=y * spacing + yspacing, width=spacing,
                                 height=spacing, fill="black", stroke="none")
                    self.g.append(square)

    @staticmethod
    def _make_round_rect(x, y, diam, corners=("right", "right", "right", "right")):
        rad = diam / 2
        cw_point = ((0, 0), (diam, 0), (diam, diam), (0, diam))
        mid_cw_point = ((0, rad), (rad, 0), (diam, rad), (rad, diam))
        res_str = "M{},{} ".format(x + mid_cw_point[0][0], y + mid_cw_point[0][1])
        n = len(cw_point)
        for i in range(n):
            if corners[i] == "right":
                res_str += "L{},{} L{},{} ".format(x + cw_point[i][0], y + cw_point[i][1],
                                                   x + mid_cw_point[(i + 1) % n][0], y + mid_cw_point[(i + 1) % n][1])
            elif corners[i] == "round":
                res_str += "A{},{} 0,0,1 {},{} ".format(rad, rad, x + mid_cw_point[(i + 1) % n][0],
                                                        y + mid_cw_point[(i + 1) % n][1])
            else:
                raise TypeError("unknown corner type")
        return res_str

    def _get_type(self, x, y):
        corners = ["right", "right", "right", "right"]
        is_inside = True
        if x == 0:
            corners[0] = "round"
            corners[3] = "round"
            is_inside = False
        if y == 0:
            corners[0] = "round"
            corners[1] = "round"
            is_inside = False
        if x == self.cols - 1:
            corners[1] = "round"
            corners[2] = "round"
            is_inside = False
        if y == self.rows - 1:
            corners[2] = "round"
            corners[3] = "round"
            is_inside = False
        return corners, is_inside

    def make_radon_checkerboard_pattern(self):
        spacing = self.square_size
        xspacing = (self.width - self.cols * self.square_size) / 2.0
        yspacing = (self.height - self.rows * self.square_size) / 2.0
        for x in range(0, self.cols):
            for y in range(0, self.rows):
                if x % 2 == y % 2:
                    corner_types, is_inside = self._get_type(x, y)
                    if is_inside:
                        square = SVG("rect", x=x * spacing + xspacing, y=y * spacing + yspacing, width=spacing,
                                     height=spacing, fill="black", stroke="none")
                    else:
                        square = SVG("path", d=self._make_round_rect(x * spacing + xspacing, y * spacing + yspacing,
                                      spacing, corner_types), fill="black", stroke="none")
                    self.g.append(square)
        if self.markers is not None:
            r = self.square_size * 0.17
            pattern_width = ((self.cols - 1.0) * spacing) + (2.0 * r)
            pattern_height = ((self.rows - 1.0) * spacing) + (2.0 * r)
            x_spacing = (self.width - pattern_width) / 2.0
            y_spacing = (self.height - pattern_height) / 2.0
            for x, y in self.markers:
                color = "black"
                if x % 2 == y % 2:
                    color = "white"
                dot = SVG("circle", cx=(x * spacing) + x_spacing + r,
                          cy=(y * spacing) + y_spacing + r, r=r, fill=color, stroke="none")
                self.g.append(dot)

    @staticmethod
    def _create_marker_bits(markerSize_bits, byteList):

        marker = np.zeros((markerSize_bits+2, markerSize_bits+2))
        bits = marker[1:markerSize_bits+1, 1:markerSize_bits+1]

        for i in range(markerSize_bits):
            for j in range(markerSize_bits):
                bits[i][j] = int(byteList[i*markerSize_bits+j])

        return marker

    def make_charuco_board(self):
        if (self.aruco_marker_size>self.square_size):
            print("Error: Aruco marker cannot be lager than chessboard square!")
            return

        if (self.dict_file.split(".")[-1] == "gz"):
            with gzip.open(self.dict_file, 'r') as fin:
                json_bytes = fin.read()
                json_str = json_bytes.decode('utf-8')
                dictionary = json.loads(json_str)

        else:
            f = open(self.dict_file)
            dictionary = json.load(f)

        if (dictionary["nmarkers"] < int(self.cols*self.rows/2)):
            print("Error: Aruco dictionary contains less markers than it needs for chosen board. Please choose another dictionary or use smaller board than required for chosen board")
            return

        markerSize_bits = dictionary["markersize"]

        side = self.aruco_marker_size / (markerSize_bits+2)
        spacing = self.square_size
        xspacing = (self.width - self.cols * self.square_size) / 2.0
        yspacing = (self.height - self.rows * self.square_size) / 2.0

        ch_ar_border = (self.square_size - self.aruco_marker_size)/2
        if ch_ar_border < side*0.7:
            print("Marker border {} is less than 70% of ArUco pin size {}. Please increase --square_size or decrease --marker_size for stable board detection".format(ch_ar_border, int(side)))
        marker_id = 0
        for y in range(0, self.rows):
            for x in range(0, self.cols):

                if x % 2 == y % 2:
                    square = SVG("rect", x=x * spacing + xspacing, y=y * spacing + yspacing, width=spacing,
                                 height=spacing, fill="black", stroke="none")
                    self.g.append(square)
                else:
                    img_mark = self._create_marker_bits(markerSize_bits, dictionary["marker_"+str(marker_id)])
                    marker_id +=1
                    x_pos = x * spacing + xspacing
                    y_pos = y * spacing + yspacing

                    square = SVG("rect", x=x_pos+ch_ar_border, y=y_pos+ch_ar_border, width=self.aruco_marker_size,
                                             height=self.aruco_marker_size, fill="black", stroke="none")
                    self.g.append(square)
                    for x_ in range(len(img_mark[0])):
                        for y_ in range(len(img_mark)):
                            if (img_mark[y_][x_] != 0):
                                square = SVG("rect", x=x_pos+ch_ar_border+(x_)*side, y=y_pos+ch_ar_border+(y_)*side, width=side,
                                             height=side, fill="white", stroke="white", stroke_width = spacing*0.01)
                                self.g.append(square)

    def save(self):
        c = canvas(self.g, width="%d%s" % (self.width, self.units), height="%d%s" % (self.height, self.units),
                   viewBox="0 0 %d %d" % (self.width, self.height))
        c.save(self.output)


def main():
    # parse command line options
    parser = argparse.ArgumentParser(description="generate camera-calibration pattern", add_help=False)
    parser.add_argument("-H", "--help", help="show help", action="store_true", dest="show_help")
    parser.add_argument("-o", "--output", help="output file", default="out.svg", action="store", dest="output")
    parser.add_argument("-c", "--columns", help="pattern columns", default="8", action="store", dest="columns",
                        type=int)
    parser.add_argument("-r", "--rows", help="pattern rows", default="11", action="store", dest="rows", type=int)
    parser.add_argument("-T", "--type", help="type of pattern", default="circles", action="store", dest="p_type",
                        choices=["circles", "acircles", "checkerboard", "radon_checkerboard", "charuco_board"])
    parser.add_argument("-u", "--units", help="length unit", default="mm", action="store", dest="units",
                        choices=["mm", "inches", "px", "m"])
    parser.add_argument("-s", "--square_size", help="size of squares in pattern", default="20.0", action="store",
                        dest="square_size", type=float)
    parser.add_argument("-R", "--radius_rate", help="circles_radius = square_size/radius_rate", default="5.0",
                        action="store", dest="radius_rate", type=float)
    parser.add_argument("-w", "--page_width", help="page width in units", default=argparse.SUPPRESS, action="store",
                        dest="page_width", type=float)
    parser.add_argument("-h", "--page_height", help="page height in units", default=argparse.SUPPRESS, action="store",
                        dest="page_height", type=float)
    parser.add_argument("-a", "--page_size", help="page size, superseded if -h and -w are set", default="A4",
                        action="store", dest="page_size", choices=["A0", "A1", "A2", "A3", "A4", "A5"])
    parser.add_argument("-m", "--markers", help="list of cells with markers for the radon checkerboard. Marker "
                                                "coordinates as list of numbers: -m 1 2 3 4 means markers in cells "
                                                "[1, 2] and [3, 4]",
                        default=argparse.SUPPRESS, action="store", dest="markers", nargs="+", type=int)
    parser.add_argument("-p", "--marker_size", help="aruco markers size for ChAruco pattern (default 10.0)", default="10.0",
                        action="store", dest="aruco_marker_size", type=float)
    parser.add_argument("-f", "--dict_file", help="file name of custom aruco dictionary for ChAruco pattern", default="DICT_ARUCO_ORIGINAL.json",
                        action="store", dest="dict_file", type=str)
    args = parser.parse_args()

    show_help = args.show_help
    if show_help:
        parser.print_help()
        return
    output = args.output
    columns = args.columns
    rows = args.rows
    p_type = args.p_type
    units = args.units
    square_size = args.square_size
    radius_rate = args.radius_rate
    aruco_marker_size = args.aruco_marker_size
    dict_file = args.dict_file

    if 'page_width' and 'page_height' in args:
        page_width = args.page_width
        page_height = args.page_height
    else:
        page_size = args.page_size
        # page size dict (ISO standard, mm) for easy lookup. format - size: [width, height]
        page_sizes = {"A0": [840, 1188], "A1": [594, 840], "A2": [420, 594], "A3": [297, 420], "A4": [210, 297],
                      "A5": [148, 210]}
        page_width = page_sizes[page_size][0]
        page_height = page_sizes[page_size][1]
    markers = None
    if p_type == "radon_checkerboard" and "markers" in args:
        if len(args.markers) % 2 == 1:
            raise ValueError("The length of the markers array={} must be even".format(len(args.markers)))
        markers = set()
        for x, y in zip(args.markers[::2], args.markers[1::2]):
            if x in range(0, columns) and y in range(0, rows):
                markers.add((x, y))
            else:
                raise ValueError("The marker {},{} is outside the checkerboard".format(x, y))

    if p_type == "charuco_board" and aruco_marker_size >= square_size:
        raise ValueError("ArUco markers size must be smaller than square size")

    pm = PatternMaker(columns, rows, output, units, square_size, radius_rate, page_width, page_height, markers, aruco_marker_size, dict_file)
    # dict for easy lookup of pattern type
    mp = {"circles": pm.make_circles_pattern, "acircles": pm.make_acircles_pattern,
          "checkerboard": pm.make_checkerboard_pattern, "radon_checkerboard": pm.make_radon_checkerboard_pattern,
         "charuco_board": pm.make_charuco_board}
    mp[p_type]()
    # this should save pattern to output
    pm.save()


if __name__ == "__main__":
    main()
  • 2.通过使用函数 cv::aruco::GridBoard::generateImage()

cv::aruco::GridBoard类的generateImage()函数可以通过以下代码调用:

Mat boardImage;
board.generateImage(imageSize, boardImage, margins, borderBits);

// 参数说明:
// imageSize:表示输出图像的尺寸,以像素为单位。在本例中为 600x500 像素。如果这与棋盘尺寸不成比例,它将居中显示在图像上。
// boardImage:包含棋盘的输出图像。
// margins:表示(可选的)边距,以像素为单位,因此没有任何标记接触图像边界。在本例中,边距为 10。
// borderBits:标记边框的大小,类似于 generateImageMarker() 函数。默认值为 1。

samples/cpp/tutorial_code/objectDetection/create_board.cpp 中包含了一个完整的棋盘创建工作示例。
在这里插入图片描述
输出图像将类似于这样:
在这里插入图片描述
这些示例现在通过cv::CommandLineParser经由命令行获取输入,对于上面的示例,输入参数如下所示:

"_output_path_/aboard.png" -w=5 -h=7 -l=100 -s=10 -d=10

4.优化标记检测

4.1 官方文档说明

ArUco板也可用于提高标记的检测率。如果我们检测到属于该板的一部分标记,我们可以使用这些标记和板的布局信息,尝试找到之前未检测到的标记。

这可以通过cv::aruco::refineDetectedMarkers()函数来实现,该函数应在调用cv::aruco::ArucoDetector::detectMarkers()之后调用。

此函数的主要参数是检测到标记的原始图像、棋盘对象、检测到的标记角点、检测到的标记 ID 和拒绝的标记角点。

被拒绝的角点可以从cv::aruco::ArucoDetector::detectMarkers()函数中获得,也被称为marker候选点。这些候选点是在原始图像中发现的方形形状,但未能通过识别步骤(即它们的内部编码存在太多错误),因此它们未被识别为marker。

然而,由于图像中存在高噪声、分辨率极低或其他影响二进制码提取的相关问题,这些候选者有时实际上是未被正确识别的实际标记。cv::aruco::ArucoDetector::refineDetectedMarkers()函数会查找这些候选者与板上缺失标记之间的对应关系。此搜索基于两个参数:

  • 候选者与缺失标记投影之间的距离。为了获得这些投影,至少需要检测到棋盘上的一个标记。如果提供了相机参数(相机矩阵和畸变系数),则使用这些参数获得投影。如果没有提供,则从局部单应性获得投影,并且只允许使用平面棋盘(即,所有标记角点的 Z 坐标应该相同)。 refineDetectedMarkers() 中的 minRepDistance 参数确定候选角点与投影标记角点之间的最小欧几里德距离(默认值为 10)。
  • 二进制编码。如果候选者超过最小距离条件,则再次分析其内部位,以确定它是否实际上是投影标记。但是,在这种情况下,条件不是那么严格,并且允许的错误位数可以更高。这在 errorCorrectionRate 参数中指示(默认值为 3.0)。如果提供负值,则根本不分析内部位,而仅评估角点距离。

示例

这是一个使用 cv::aruco::ArucoDetector::refineDetectedMarkers() 函数的例子:

// Detect markers
detector.detectMarkers(image, corners, ids, rejected);
 
// Refind strategy to detect more markers
if(refindStrategy)
  detector.refineDetectedMarkers(image, board, corners, ids, rejected, camMatrix, distCoeffs);

还需注意的是,在某些情况下,如果最初检测到的标记数量太少(例如,只有 1 或 2 个标记),则缺失标记的投影质量可能较差,从而产生错误的对应关系。

4.2 关于refineDetectedMarkers()函数

4.2.1 refineDetectedMarkers()函数说明

    /** @brief Refine not detected markers based on the already detected and the board layout
     *
     * @param image input image
     * @param board layout of markers in the board.
     * @param detectedCorners vector of already detected marker corners.
     * @param detectedIds vector of already detected marker identifiers.
     * @param rejectedCorners vector of rejected candidates during the marker detection process.
     * @param cameraMatrix optional input 3x3 floating-point camera matrix
     * \f$A = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$
     * @param distCoeffs optional vector of distortion coefficients
     * \f$(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6],[s_1, s_2, s_3, s_4]])\f$ of 4, 5, 8 or 12 elements
     * @param recoveredIdxs Optional array to returns the indexes of the recovered candidates in the
     * original rejectedCorners array.
     *
     * This function tries to find markers that were not detected in the basic detecMarkers function.
     * First, based on the current detected marker and the board layout, the function interpolates
     * the position of the missing markers. Then it tries to find correspondence between the reprojected
     * markers and the rejected candidates based on the minRepDistance and errorCorrectionRate parameters.
     * If camera parameters and distortion coefficients are provided, missing markers are reprojected
     * using projectPoint function. If not, missing marker projections are interpolated using global
     * homography, and all the marker corners in the board must have the same Z coordinate.
     */
    CV_WRAP void refineDetectedMarkers(InputArray image, const Board &board,
                                       InputOutputArrayOfArrays detectedCorners,
                                       InputOutputArray detectedIds, InputOutputArrayOfArrays rejectedCorners,
                                       InputArray cameraMatrix = noArray(), InputArray distCoeffs = noArray(),
                                       OutputArray recoveredIdxs = noArray()) const;
  • 函数功能:
    refineDetectedMarkers 是 OpenCV 中 cv::aruco::ArucoDetector 类中的一个成员函数,主要用于改进和修正已检测的标记(markers)。它的作用是基于当前已检测的标记及其布局,进一步细化未被检测到的标记位置。通常,这个函数是在标记检测阶段后调用的,尤其是在某些标记未被正常检测到的情况下。

该函数尝试通过已有的检测结果来推测缺失标记的位置,并通过计算与已拒绝候选标记的匹配关系来进一步确认缺失标记。它还支持根据相机的内参和畸变系数进行误差校正。

  • 输入和输出参数:
    在这里插入图片描述
    在这里插入图片描述

4.2.2 detectMarkers 与 detectMarkers() 的区别和关系

  • detectMarkers 函数:
    detectMarkers 是 OpenCV 中 ArucoDetector 类的一个方法,主要用于检测图像中的标记,并返回标记的角点坐标和标识符。它基于图像中的亮点、边缘等特征来找到标记,并且可以执行基本的检测和识别任务。然而,在一些情况下,某些标记可能由于噪声、遮挡或其他原因未能被检测到,或是误判为不存在。

  • refineDetectedMarkers 函数:

    refineDetectedMarkers 则是在 detectMarkers 之后用来进一步修正和完善标记检测结果的一个函数。它并不重新执行标记的检测,而是通过利用已检测到的标记和标记板的布局信息,推测和修正那些未能正确检测到的标记。这个函数特别适用于在初次检测时漏掉的标记,或者需要提高标记检测精度的情况。

4.2.3 是否需要 refineDetectedMarkers

  • 是否需要调用 refineDetectedMarkers 取决于实际的应用场景:
如果所有标记都已成功检测到,且检测结果较为精确,则通常不需要调用 refineDetectedMarkers。

如果部分标记未被检测到,或者标记的角点有误差,可以通过调用 refineDetectedMarkers 来修正这些问题,特别是在检测不完整或复杂环境下的标记时。

简而言之,refineDetectedMarkers 是在标记检测后进行的额外步骤,旨在通过已知的标记布局和相机参数(如果提供)来进一步细化检测结果。

  • 在调用 detectMarkers 后,始终默认加上 refineDetectedMarkers,即使没有检测到任何标记。这样做的好处是,即使在某些情况下没有检测到标记,refineDetectedMarkers 也会根据已经得到的结果(如果有的话)尽可能修正角点位置,或者提供更精确的检测效果。
    在这里插入图片描述
    在这里插入图片描述

5.opencv4.10.0 代码

5.1 创建 arucoBoard

#include <opencv2/highgui.hpp>
#include <opencv2/objdetect/aruco_detector.hpp>
#include <iostream>
// ref: samples/cpp/tutorial_code/objectDetection/create_board.cpp
TEST(TestDetect_Board, create_aruco_board)
{
    int markersX         = 5;   // X方向aruco标记的数量
    int markersY         = 7;   // Y方向aruco标记的数量
    int markerLength     = 100; // aruco标记边长(以像素为单位)
    int markerSeparation = 10;  // 网格中两个连续aruco标记之间的间距(以像素为单位)
    int margins          = markerSeparation;

    // dictionary: DICT_4X4_50=0, DICT_4X4_100=1, DICT_4X4_250=2, DICT_4X4_1000=3, DICT_5X5_50=4, DICT_5X5_100=5,
    // DICT_5X5_250=6, DICT_5X5_1000=7, DICT_6X6_50=8, DICT_6X6_100=9, DICT_6X6_250=10, DICT_6X6_1000=11,
    // DICT_7X7_50=12,DICT_7X7_100=13, DICT_7X7_250=14, DICT_7X7_1000=15, DICT_ARUCO_ORIGINAL = 16
    int dictionaryId = 10;

    int borderBits = 1; // 标记边框中的位数,默认1
    bool showImage = true;

    cv::Size imageSize;
    imageSize.width  = markersX * (markerLength + markerSeparation) - markerSeparation + 2 * margins;
    imageSize.height = markersY * (markerLength + markerSeparation) - markerSeparation + 2 * margins;

    cv::aruco::Dictionary dictionary = cv::aruco::getPredefinedDictionary(dictionaryId);
    cv::aruco::GridBoard board(cv::Size(markersX, markersY), float(markerLength), float(markerSeparation), dictionary);

    // show created board
    //! [aruco_generate_board_image]
    cv::Mat boardImage;
    board.generateImage(imageSize, boardImage, margins, borderBits);
    //! [aruco_generate_board_image]

    if (showImage) {
        cv::imshow("Aruco boards", boardImage);
        cv::waitKey(0);
    }

    cv::imwrite("arucoBoard.png", boardImage);
}

5.2 arucoBoard 位姿估计

官方代码里面markerLength和markerSeparation的代码注释写的单位是像素,实际验证这里的单位是米。

#include <opencv2/highgui.hpp>
#include <opencv2/objdetect/aruco_detector.hpp>
#include <iostream>
#include <algorithm>

int markersX           = 5;      // X方向aruco标记的数量
int markersY           = 7;      // Y方向aruco标记的数量
float markerLength     = 0.0032; // aruco标记边长(以m素为单位)
float markerSeparation = 0.0008; // 网格中两个连续aruco标记之间的间距(以m为单位)
bool showRejected      = true;
bool refindStrategy    = true; 

// dictionary: DICT_4X4_50=0, DICT_4X4_100=1, DICT_4X4_250=2, DICT_4X4_1000=3, DICT_5X5_50=4, DICT_5X5_100=5,
// DICT_5X5_250=6, DICT_5X5_1000=7, DICT_6X6_50=8, DICT_6X6_100=9, DICT_6X6_250=10, DICT_6X6_1000=11,
// DICT_7X7_50=12,DICT_7X7_100=13, DICT_7X7_250=14, DICT_7X7_1000=15, DICT_ARUCO_ORIGINAL = 16

int dictionaryId = 10;

cv::Mat camMatrix  = (cv::Mat_<double>(3, 3) << 5166.6, 0.0, 1524.46, 0.0, 5165.3, 1118.25, 0.0, 0.0, 1.0);
cv::Mat distCoeffs = (cv::Mat_<double>(5, 1) << 0.0261802, -0.455624, 0.00267969, -0.00287971, -0.877674);

cv::aruco::Dictionary dictionary = cv::aruco::getPredefinedDictionary(dictionaryId);
cv::aruco::DetectorParameters detectorParams;

cv::aruco::ArucoDetector detector(dictionary, detectorParams);

float axisLength = 0.5f * ((float)std::min(markersX, markersY) * (markerLength + markerSeparation) + markerSeparation);

// Create GridBoard object
//! [aruco_create_board]
cv::aruco::GridBoard board(cv::Size(markersX, markersY), markerLength, markerSeparation, dictionary);

//! [aruco_create_board]
// Also you could create Board object
// vector<vector<Point3f> > objPoints; // array of object points of all the marker corners in the board
// vector<int> ids; // vector of the identifiers of the markers in the board
// aruco::Board board(objPoints, dictionary, ids);

cv::Mat image = cv::imread("./data/localization/arucoboards_1.bmp", cv::IMREAD_COLOR);
cv::Mat imageCopy;

std::vector<int> ids;
std::vector<std::vector<cv::Point2f>> corners, rejected;
cv::Vec3d rvec, tvec;

//! [aruco_detect_and_refine]

// Detect markers
detector.detectMarkers(image, corners, ids, rejected);

// Refind strategy to detect more markers
if (refindStrategy) {
    detector.refineDetectedMarkers(image, board, corners, ids, rejected, camMatrix, distCoeffs);
}

//! [aruco_detect_and_refine]

// Estimate board pose
int markersOfBoardDetected = 0;
if (!ids.empty()) {
    // Get object and image points for the solvePnP function
    cv::Mat objPoints, imgPoints;
    board.matchImagePoints(corners, ids, objPoints, imgPoints);

    // Find pose
    cv::solvePnP(objPoints, imgPoints, camMatrix, distCoeffs, rvec, tvec);

    markersOfBoardDetected = (int)objPoints.total() / 4;
}

// Draw results
image.copyTo(imageCopy);
if (!ids.empty())
    cv::aruco::drawDetectedMarkers(imageCopy, corners, ids);

if (showRejected && !rejected.empty())
    cv::aruco::drawDetectedMarkers(imageCopy, rejected, cv::noArray(), cv::Scalar(100, 0, 255));

if (markersOfBoardDetected > 0)
    cv::drawFrameAxes(imageCopy, camMatrix, distCoeffs, rvec, tvec, axisLength);

cv::imshow("out", imageCopy);
cv::waitKey(0);

cv::imwrite("detect_arucoBoard.png", imageCopy);
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

boss-dog

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值