ArUco: a minimal library for Augmented Reality applications based on OpenCV




News: MarkerMapper android application released in PlayStore 

News: Aruco 3.0.6 released:  Its all about speed


IMPORTANT: see the related project markermapper

The main features of ArUco are:

  • Detect markers with a single line of C++ code.
  • Detect varios dictionaries: ARUCO, AprilTag,ArToolKit+,ARTAG,CHILITAGS.
  • Faster than any other library for detection of markers
  • Few dependencies  OpenCV (>=2.4.9) and eigen3 (included in the library).
  • Detection of  Marker Maps (several markers).
  • Trivial integration with OpenGL and OGRE.
  • Fast, reliable and cross-platform because relies on OpenCV.
  • Examples that will help you to get running your AR application in less than 5 minutes.
  • Calibrate you camera using Aruco ChessBoard
  • BSD licence.


Highlights features of version 3.x

  • Faster than previous approach: at least an order of magnitude (see below for details).
  • Easier to use: only two parameters are required to configure the behaviour of the detection.
  • Able to automatically detect markers of any dictionary (automatic dictionary discovery)
  • Tracking methods to alleviate the ambiguity problem in planar pose estimation.
  • Calibration tool using Aruco Boards added (see below)


Download ArUco

Download ArUco Test Data

Download ArUco+OGRE example  (UNDER ADAPTATION TO VERSION 2.x)



Please cite the following papers if you use aruco:

1. Main ArUco paper:
"Automatic generation and detection of highly reliable fiducial markers under occlusion"
2. Generation of marker dictionaries:
"Generation of fiducial marker dictionaries using mixed integer linear programming"


Videos in YouTube:

Video 1: Aruco and Ogre

Video 2: Single marker detection

Video 3: Board of markers detection

Examples of Projects using ArUco :

In Opencv

Augmented Reality Chess

Vision Based Navigation  and Fuzzy Vision Based Navigation

Soldamatic Project (Augmented Reality Welder) 


JavaScript port : watch demonstration video

ROS (Robot Operative System) port:#1 #2

Panoramic camera calibratio

Contact info:

Rafael Muñoz-Salinas:  rmsalinas at uco dot es

Sergio Garrido-Jurado:   sgarrido2011 at gmail dot com

Fast Code sample

Take a look:



First, read this page, it will give you a general idea of the library. Then, download the library and the tests, and run the tests to better understand what the library is capable of. If you are a windows user, there is a binary version already created so you can tests without compiling. Then, read the README file of the library. Afterwards, read the many examples in the utils directories of the library. Finally, you can have a more in-depth knowledge by reading the above mentioned papers.


ArUco is a library for detecting squared fiducial markers in images. Additionally, if the camera taking the pictures is calibrated (see below), you can estimate the pose of the camera with respect to the markers.

There are several type of markers, each of them belonging to a so called dictionary. Each library has proposed its own set of markers. So, we have ArToolKit+, Chilitags, AprilTags, and of course, ArUco dictionary.

The design of a dictionary is important since the idea is that their markers should be as different as possible to avoid confusions. We propose to use the dictionary ARUCO_MIP_36h12 which we developed in a research paper.

So, the first step is to download our dictionary . Print one of two markers in a piece of paper and take a picture of it with your camera. Alternatively, you can just show them in your screen and take a picture at your screen.

The library is written in C++ and requires OpenCv. Let us see the most simple example in which the camera is not calibrated:

#include "aruco.h"
#include <iostream>
#include <opencv2/highgui/highgui.hpp>
  int main(int argc,char **argv){
    if (argc != 2 ){ std::cerr<<"Usage: inimage"<<std::endl;return -1;}
    cv::Mat image=cv::imread(argv[1]);
    aruco::MarkerDetector MDetector;
    std::vector<aruco::Marker> markers=MDetector.detect(image);
    //print info to console
    for(size_t i=0;i<markers.size();i++)
    //draw in the image
    for(size_t i=0;i<markers.size();i++)
In the above example, you can see that the task of detecting the markers is the class MarkerDetector. The class is prepared to detect markers of any of the Dictionaries allowed. By default, the MarkerDetector will look for squares and then will analyze the binary code inside. For the code extracted, it will compare against all the markers in all the available dictionaries. This is however not the best approach. Ideally, you should explicitly indicate the type of dictionary you are using. The list of possible dictionaries is in Dictionary::DICT_TYPES. 
As previously indicated, we rather that you use the ARUCO_MIP_36h12  dictionary.  So, if you explicitly indicate the dictinoary you are using, you avoid undesired errors and confusions with other Dictionaries. So, before calling detect, you only have to call:

Speeding up the detection

ArUco version 3 main changes are related to speed and to ease of usage. To do so, we define two main concepts:  Minimum Marker Size and Detection Mode.

Minimum Marker Size

In most cases when detecting markers, we are interested in markers of a minumum size. Either we know that markers will have a minimum size in the image, or we are not interested in very small markers because they are not reliable for camera pose estimation. Thus, ArUco 3 defines a method to increase the speed by using images of smaller size for the sake of detection. However, please notice that the precision is not affected by this fact, only computing time is reduced. In order to be general and to adapt to any image size, the minimum marker size is expressed as a normalized value (0,1) indicating the minimum area that a marker must occupy in the image to consider it valid. The value 0 indicates that all markers are considered as valid. As the minimum size increases towards 1, only big markers will be detected.
Which value should I use? Well, you should try in your own video sequences to get the best results. However, we have found that setting this value to 0.02 (2% of the image area) has a tremendous impact in the speed.
If you are processing video and you want maximum speed, you can use the Detection mode DM_VIDEO_FAST (see below) and it will automatically compute the minimum marker by considering the information in the previous frame.

Detection Mode

(See MarkerDetector::DetectionMode in markerdetector.h) refers to three basic use cases that we can normally find among the ArUco users:
  1. DM_NORMAL: this is the case of requiring to detect markers in images, and not taking much care about the computing time. This is normally the case of a batch processing in which  computing time is not a problem. In this case, we apply a local adaptive threshold approach which is very robust. This is the approach used in ArUco version 2.
  2. DM_FAST: in this case, you are concern about speed. Then, a global threshold approach is employed, that randomly searches the best threshold. It works fine in most cases.
  3. DM_VIDEO_FAST: this is specially designed for processing video sequences. In this mode, a global threshold is automatically determined at each frame, and the minimum marker size is also automatically determined in order achieve the maximum speed. If the marker is seen very big in one image, in the next frame, only markers of similar size are searched.


By default, the MarkerDetector is configured to be conservative, i.e., with minimum marker size to zero, and in DM_NORMAL mode. If you want to change this behaviour, you need to call

  void MarkerDetector::setDetectionMode( DetectionMode dm,float minMarkerSize=0);  

before detecting markers.

Camera Calibration


Camera calibration is the process of obtaning the fundamental parameters of a camera. These parameter allows us to determine where a 3D point in the space projects in the camera sensor. The camera parameters can be divided into intrinsics and extrinsics.

Intrinsic parameters are

  • fx,fy: Focal lenght of the camera lens in both axes. These are normally expressed in pixels
  • cx,cy:  Optical center of the sensor(expressed in pixels)
  • k1,k2,p1,p2: distorsion coefficients.

In a ideal camera, a 3D point (X,Y,Z) in the space would project in the pixel:

x= (X fx /Z) +cx ; y= (Y fy/Z)+cy.

However camera lenses normally distorts the scene making the points far from the center to be even farther. Thus, the vertical stripes near the image borders appears slightly bended. As a consequence, if we want to know a pixel's projection, then we must consider the distorsion components. Merely to say that are two type of distorsions (radial and tangential) and these are represented by the paremeters p1,p2,k1,k2.


The  above assumes that you know the 3D location of the point with relation to the camera reference system. If you want to know the projection of a point referred to an arbitrary reference system, then you must use th extrinsic parameters. The extrinsic parameters are basically the 3D rotations (Rvec={Rx,Ry,Rz})and 3D translations (Tvec={Tx,Ty,Tz}) required to translate the camera reference system to the arbitrary one. The rotation elements are expressed in Rodrigues formula, so you can obtain the equivalen 3x3 rotation matrix using the opencv function cv::Rodrigues()

A very popular alternative to manage both rotation and translation is using Homogenoeus coordinates. You can easily create a 4x4 matrix than comprises both rotation and translation (use the following piece of code to create the 4x4 matrix from rvec and tvec).

This matrix allows you to transform a point from one reference system to the other. You can also invert the 4x4 matrix to obtain the opposite transform.

Calibration with Aruco


Aruco has its own calibration board that has an advantage over the classical opencv chessboard: since it is composed by several markers, you do not need to see it completely in order to obtain calibration points. Instead, you can see if partially and still works. This is a very convenient feature in many applications. You have programs in utils_calibration to use calibrate using our chessboard.


To calibrate you should do the following. First, download the calibration board and print it in a piece of paper. Use a tape to measure the size of the markers. Please, be very precise. Annotate the size in meters or in your prefered metric. Please notice that when you compute the distance of your camera to the markers, it will be in the metric you use. So, if you measure the size of the markers in meters, then, you camera position will be expressed in meters too.


Once printed and measured, take photos of the board from different locations and perspectives. Take at least 15 photos, and try to see the whole board in all of them. Here are some examples


Then, use the program in utils_calibration/aruco_calibration_fromimages as

aruco_calibration_fromimages mycalibrationfile.yml pathToDirWithImage -size 0.03

the parameter mycalibrationfile.yml will be the output of the process.. pathToDirWithImage is the directory containing the images used for calibration. The parameter 0.036 is the size of each marker (you measured earlier), and then the images used for calibration.

Alternatively, you can calibrate a camera connected to your computer using the program aruco_calibration, which is an interactive calibration program.

How to Augment Reality?

Augmenting the reality is the process of adding virtual information to images. To do so, we need to know where to paint the virtual information (normally using OpenGL or another 3D engine). Here is where the markers will help you.

An AR Marker, like the one used in ArUco, is a very distintive element that can be easily detected. The marker will be used to calculate the extrinsics of the camera in relation to the marker so that you'll be able to render in 3D knowing where is the (0,0,0) of the world reference system. Since the AR marker is very easy to detect, you can process images and do rendering in real time.

Detection Process in ArUco

The marker detection process of ArUco is as follows:

  • Apply an Adaptive Thresholding so as to obtain borders (Figure 1)
  • Find contours. After that, not only the real markers are detected but also a lot of undesired borders. The rest of the process aims to filter out unwanted borders.
    • Remove borders with an small number of points (Figure 2)
    • Polygonal approximation of contour and keep the concave contours with exactily 4 corners (i.e., rectangles) (Figure 3)
  • Sort corners in anti-clockwise direction.
  • Remove too close rectangles. This is required because the adaptive threshold normally detects the internal an external part of the marker's border. At this stage, we keep the most external border. (Figure 4)
  • Marker Identification
    • Remove the proyection perspective so as to obtain a frontal view of the rectangle area using an homography (Figure 5)
    • Threshold the area using Otsu. Otsu's algorithms assumes a bimodal distribution and finds the threshold that maximizes the extra-class variance while keeping a low intra-class variance.
    • Identification of the internal code. If it is a marker, then it has an internal code. The marker is divided in a 6x6 grid, of which the internal 5x5 cells contains id information. The rest correspond to the external black border. Here, we first check that the external black border is present. Afterwards, we read the internal 5x5 cells and check if they provide a valid code (it might be required to rotate the code to get the valid one).
  • For the valid markers, refine corners using subpixel interpolation
  • Finally, if camera parameters are provided, it is computed the extrinsics of the markers to the camera.

Marker coding

Each marker has an internal code given by 5 words of 5 bits each. The codification employed is a slight modification of the Hamming Code. In total, each word has only 2 bits of information out of the 5 bits employed. The other 3 are employed for error detection. As a consequence, we can have up to 1024 diferent ids.

The main difference with the Hamming Code is that the first bit (parity of bits 3 and 5) is inverted. So, the id 0 (which in hamming code is 00000) becomes 10000 in our codification. The idea is to prevent a completely black rectangle from being a valid marker id with the goal of reducing the likelihood of false positives with objects of the environment.


Benefits of using Marker Maps

Detecting  a single marker might fail for different reasons such as poor lightning conditions,  fast camera  movement, occlusions, etc. To overcome that problem, ArUco allows the use of boards. An Augmented Reality board is a marker composed by several markers arranged in a grid. Markermaps present two main advantages. First, since there have more than one markers, it is less likely to lose them all at the same time. Second, the more markers are detected, the more points are available for computing the camera extrinsics. As a consecuence, the accuracy obtained increases.


Managing the output of ArUco

When you know the camera intrinsics (camera matrix and distortion coefficients obtained by calibration), and you specify the size of the marker, the library can tell you the relative position of the markers and the camera.

ArUco uses the a class named Marker which represents a marker observed in the image. Each marker is a vector of 4 2d points (representing the corners in the image), an unique id, its size (in meters), and the translation and rotation  that relates the center of the marker and the camera location.

The 3D information is represented by the class variables Rvec and Tvec. The latter, reprents a 3D translation. The first, is a rotation transform expressed as given by the Rodrigues formula. To obtatin the full 3x3 rotation matrix, you can use cv::Rodrigues(Rvec,R33).

Then, you can compose a full 4x4 transform matrix by adding the 3x3 matrix to the translation vector. You get a matrix like

T=[ R00 R01 R01 T0;R10 R11 R11 T1;R20 R21 R21 T2; 0 0 0 1]

So, if you want to project a 3D point in the space (measured wrt the marker ref system), you first must transform it to the camera ref system (multiplying the point in homogeneous corrdinates by T). The resulting 3d point is projected using the camera matrix, and finally you need to apply the distortion model.


All these steps are done by cv::projectPoints, which uses as input the CameraMatrix the Distortion Coefficients, and Rvec,Tvec.


Tracking the position of a marker 

Inevitably, the pose of a single marker is subject to the ambiguity problem, i.e., two valid solutions can explain the observed projection of the marker. It generally happens when the marker is small in relation to the image, or in very inclined positions. When tracking a marker, you see this effect as a strange change flip of the z-axis  of the marker.  To alleviate that problem, the library has the possibility of tracking the marker position. If you start from a good position, for the next frame, you can fo an optimization looking for the best pose near from the last one. Then, the abiguity problem can be solved. To do so, use the MarkerPoseTracker and MarkerMapPoseTracker classes.

Using ArUco in your project

Here we show how to create your own project using ArUco and cmake. This example can be downloaded at SourceForge.

First, create a dir for your dir with the project (e.g. aruco_testproject). Go in and create the CMakeLists.txt as

cmake_minimum_required(VERSION 2.8)
find_package(aruco REQUIRED )
add_executable(aruco_simple aruco_simple.cpp)
target_link_libraries(aruco_simple  ${aruco_LIBS})
cmake_minimum_required(VERSION 2.8)
find_package(aruco REQUIRED )
add_executable(aruco_simple aruco_simple.cpp)
target_link_libraries(aruco_simple  ${aruco_LIBS})

Then, create the program file aruco_simple.cpp :

#include <iostream>
#include <aruco/aruco.h>
#include <opencv2/highgui/highgui.hpp>
using namespace cv;
using namespace aruco;
int main(int argc,char **argv)
        if (argc!=2) {
            cerr<<"Usage: in.jpg "<<endl;
            return -1;
        MarkerDetector MDetector;
        vector<Marker> Markers;
        //read the input image
        cv::Mat InImage;
    //Ok, let's detect
        //for each marker, draw info and its boundaries in the image
        for (unsigned int i=0;i<Markers.size();i++) {
        cv::waitKey(0);//wait for key to be pressed
    } catch (std::exception &ex)
        cout<<"Exception :"<<ex.what()<<endl;
Finally, create a directory for building (e.g. build), go in, compile and execute
mkdir build
cd build
cmake ..
./aruco_simple image_withmarkers.jpg

Custom Dictionaries

Aruco allows to use your own dictionaries. To do so, first write the definition of your dictionary. Imagine you want to create a dictionary of 3 markers with size 3x3 bits each shown in the image. (The red lines are just set for the sake of clearly see the bits of the markers.)
 You must create then the following file (A copy of this file is in utils/myown.dict )
name MYOWN
nbits  9
Please notice that the bits are expressed from topleft corner to bottomright corner.
Then, you might want to print your dictionary. So, use the aplication utils/aruco_print_dictionary as:
./utilts/aruco_print_dictionary <pathToSaveAllImages>  <pathto/myown.dict>
In the directory indicated as first parameter, the images will be saved. Then, print them and take a picture. To test if it works, use utils/aruco_test. In that case, pass the parameter -d  <pathto/myown.dict>. It will automatically load your dict and use it.
Note: this feature is not supported for MarkerMaps.