先附上资料链接:
软件源码:
https://github.com/AprilRobotics/apriltags
c++:
https://github.com/swatbotics/apriltags-cpp
ros版的网上很多,就不附链接了。
下面主要针对源码方面记录下自己的使用记录。
环境主要是opencv。
build时候就按照readme里面的步骤来。
$cmake ..
$make
$sudo make install
在example/opencv_demo.c文件中,默认的只是识别二维码,但是并没有计算对应的pose,所以这里我稍加修改,添加对应的pose计算功能。
...
...
#include "apriltag_pose.h" //添加该头文件,用来计算对应的pose
...
main(){
...
apriltag_detection_info_t info;
info.tagsize = 0.02; //打印的qrcode尺寸大小
info.fx = 611.963;
info.fy = 611.963;
info.cx = 309.007;
info.cy = 242.101; //初始化对应的相机参数
...
while(true){
...
for (int i = 0; i < zarray_size(detections); i++) {
apriltag_detection_t *det;
zarray_get(detections, i, &det);
info.det = det; //将det赋给info用于计算
apriltag_pose_t pose;
double err = estimate_tag_pose(&info, &pose);
cout<<pose.t->data[0]<<" "<<pose.t->data[1]<<" "<<pose.t->data[2]<<endl; //输出t
cout<<pose.R->nrows<<" "<<pose.R->ncols<<endl; //输出R,3*3
...
...
}
}
其中 apriltag_detection_info_t ,apriltag_pose_t和 matd_t的结构为
typedef struct {
apriltag_detection_t* det;
double tagsize;
double fx;
double fy;
double cx;
double cy;
} apriltag_detection_info_t;
typedef struct {
matd_t* R;
matd_t* t;
} apriltag_pose_t;
typedef struct
{
unsigned int nrows, ncols;
double data[];
// double *data;
} matd_t;
嗯,大致先记录到这,后续再更新。。
下面附上我的完整demo代码:
/* Copyright (C) 2013-2016, The Regents of The University of Michigan.
All rights reserved.
This software was developed in the APRIL Robotics Lab under the
direction of Edwin Olson, ebolson@umich.edu. This software may be
available under alternative licensing terms; contact the address above.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright notice, this
list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR
ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
The views and conclusions contained in the software and documentation are those
of the authors and should not be interpreted as representing official policies,
either expressed or implied, of the Regents of The University of Michigan.
*/
#include <iostream>
#include "opencv2/opencv.hpp"
extern "C" {
#include "apriltag.h"
#include "tag36h11.h"
#include "tag25h9.h"
#include "tag16h5.h"
#include "tagCircle21h7.h"
#include "tagCircle49h12.h"
#include "tagCustom48h12.h"
#include "tagStandard41h12.h"
#include "tagStandard52h13.h"
#include "common/getopt.h"
#include "apriltag_pose.h"
}
using namespace std;
using namespace cv;
int main(int argc, char *argv[])
{
getopt_t *getopt = getopt_create();
getopt_add_bool(getopt, 'h', "help", 0, "Show this help");
getopt_add_bool(getopt, 'd', "debug", 1, "Enable debugging output (slow)");
getopt_add_bool(getopt, 'q', "quiet", 0, "Reduce output");
getopt_add_string(getopt, 'f', "family", "tag36h11", "Tag family to use");
getopt_add_int(getopt, 't', "threads", "1", "Use this many CPU threads");
getopt_add_double(getopt, 'x', "decimate", "1.0", "Decimate input image by this factor");
getopt_add_double(getopt, 'b', "blur", "0.0", "Apply low-pass blur to input");
getopt_add_bool(getopt, '0', "refine-edges", 1, "Spend more time trying to align edges of tags");
if (!getopt_parse(getopt, argc, argv, 1) ||
getopt_get_bool(getopt, "help")) {
printf("Usage: %s [options]\n", argv[0]);
getopt_do_usage(getopt);
exit(0);
}
// Initialize camera
VideoCapture cap(1);
if (!cap.isOpened()) {
cerr << "Couldn't open video capture device" << endl;
return -1;
}
// Initialize tag detector with options
apriltag_family_t *tf = NULL;
const char *famname = getopt_get_string(getopt, "family");
if (!strcmp(famname, "tag36h11")) {
tf = tag36h11_create();
} else if (!strcmp(famname, "tag25h9")) {
tf = tag25h9_create();
} else if (!strcmp(famname, "tag16h5")) {
tf = tag16h5_create();
} else if (!strcmp(famname, "tagCircle21h7")) {
tf = tagCircle21h7_create();
} else if (!strcmp(famname, "tagCircle49h12")) {
tf = tagCircle49h12_create();
} else if (!strcmp(famname, "tagStandard41h12")) {
tf = tagStandard41h12_create();
} else if (!strcmp(famname, "tagStandard52h13")) {
tf = tagStandard52h13_create();
} else {
printf("Unrecognized tag family name. Use e.g. \"tag36h11\".\n");
exit(-1);
}
apriltag_detector_t *td = apriltag_detector_create();
apriltag_detector_add_family(td, tf);
td->quad_decimate = getopt_get_double(getopt, "decimate");
td->quad_sigma = getopt_get_double(getopt, "blur");
td->nthreads = getopt_get_int(getopt, "threads");
td->debug = getopt_get_bool(getopt, "debug");
td->refine_edges = getopt_get_bool(getopt, "refine-edges");
Mat frame, gray;
apriltag_detection_info_t info;
info.tagsize = 0.02;
info.fx = 611.963;
info.fy = 611.963;
info.cx = 309.007;
info.cy = 242.101;
while (true) {
cap >> frame;
//frame = imread("test.jpg");
cvtColor(frame, gray, COLOR_BGR2GRAY);
// Make an image_u8_t header for the Mat data
image_u8_t im = { .width = gray.cols,
.height = gray.rows,
.stride = gray.cols,
.buf = gray.data
};
zarray_t *detections = apriltag_detector_detect(td, &im);
cout << zarray_size(detections) << " tags detected" << endl;
// Draw detection outlines
for (int i = 0; i < zarray_size(detections); i++) {
apriltag_detection_t *det;
zarray_get(detections, i, &det);
info.det = det;
apriltag_pose_t pose;
double err = estimate_tag_pose(&info, &pose);
cout<<pose.t->data[0]<<" "<<pose.t->data[1]<<" "<<pose.t->data[2]<<endl;
cout<<pose.R->nrows<<" "<<pose.R->ncols<<endl; //3*3
line(frame, Point(det->p[0][0], det->p[0][1]),
Point(det->p[1][0], det->p[1][1]),
Scalar(0, 0xff, 0), 2);
line(frame, Point(det->p[0][0], det->p[0][1]),
Point(det->p[3][0], det->p[3][1]),
Scalar(0, 0, 0xff), 2);
line(frame, Point(det->p[1][0], det->p[1][1]),
Point(det->p[2][0], det->p[2][1]),
Scalar(0xff, 0, 0), 2);
line(frame, Point(det->p[2][0], det->p[2][1]),
Point(det->p[3][0], det->p[3][1]),
Scalar(0xff, 0, 0), 2);
stringstream ss;
ss << det->id;
String text = ss.str();
int fontface = FONT_HERSHEY_SCRIPT_SIMPLEX;
double fontscale = 1.0;
int baseline;
Size textsize = getTextSize(text, fontface, fontscale, 2,
&baseline);
putText(frame, text, Point(det->c[0]-textsize.width/2,
det->c[1]+textsize.height/2),
fontface, fontscale, Scalar(0xff, 0x99, 0), 2);
}
zarray_destroy(detections);
imshow("Tag Detections", frame);
if (waitKey(30) == 'q'){
//printf("save!");
//imwrite("test.jpg",frame);
break;
}
}
apriltag_detector_destroy(td);
if (!strcmp(famname, "tag36h11")) {
tag36h11_destroy(tf);
} else if (!strcmp(famname, "tag25h9")) {
tag25h9_destroy(tf);
} else if (!strcmp(famname, "tag16h5")) {
tag16h5_destroy(tf);
} else if (!strcmp(famname, "tagCircle21h7")) {
tagCircle21h7_destroy(tf);
} else if (!strcmp(famname, "tagCircle49h12")) {
tagCircle49h12_destroy(tf);
} else if (!strcmp(famname, "tagStandard41h12")) {
tagStandard41h12_destroy(tf);
} else if (!strcmp(famname, "tagStandard52h13")) {
tagStandard52h13_destroy(tf);
}
getopt_destroy(getopt);
return 0;
}
版权声明:本文为hehehetanchaow原创文章,遵循 CC 4.0 BY-SA 版权协议,转载请附上原文出处链接和本声明。