├── .gitignore ├── images ├── 1.png ├── 2.png ├── 3.png ├── 1023.png ├── graph.png ├── square.jpg ├── adaptive.png ├── dictionary.png ├── perspective.png ├── results_angle.png └── results_distance.png ├── msg └── Marker.msg ├── launch └── aruco.launch ├── package.xml ├── CMakeLists.txt ├── src ├── math │ ├── Transformations.cpp │ ├── Triangle.cpp │ └── Quadrilateral.cpp ├── SquareFinder.cpp ├── CornerRefinement.cpp ├── ArucoMarkerInfo.cpp ├── ArucoMarker.cpp ├── ArucoDetector.cpp └── ros │ └── ArucoNode.cpp ├── LICENSE ├── README.md └── Doxyfile /.gitignore: -------------------------------------------------------------------------------- 1 | *.db 2 | -------------------------------------------------------------------------------- /images/1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tentone/aruco/HEAD/images/1.png -------------------------------------------------------------------------------- /images/2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tentone/aruco/HEAD/images/2.png -------------------------------------------------------------------------------- /images/3.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tentone/aruco/HEAD/images/3.png -------------------------------------------------------------------------------- /images/1023.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tentone/aruco/HEAD/images/1023.png -------------------------------------------------------------------------------- /images/graph.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tentone/aruco/HEAD/images/graph.png -------------------------------------------------------------------------------- /images/square.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tentone/aruco/HEAD/images/square.jpg -------------------------------------------------------------------------------- /images/adaptive.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tentone/aruco/HEAD/images/adaptive.png -------------------------------------------------------------------------------- /images/dictionary.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tentone/aruco/HEAD/images/dictionary.png -------------------------------------------------------------------------------- /images/perspective.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tentone/aruco/HEAD/images/perspective.png -------------------------------------------------------------------------------- /images/results_angle.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tentone/aruco/HEAD/images/results_angle.png -------------------------------------------------------------------------------- /images/results_distance.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tentone/aruco/HEAD/images/results_distance.png -------------------------------------------------------------------------------- /msg/Marker.msg: -------------------------------------------------------------------------------- 1 | # Position of the marker in meters 2 | float64 posx 3 | float64 posy 4 | float64 posz 5 | 6 | # Euler rotation of the marker 7 | float64 rotx 8 | float64 roty 9 | float64 rotz 10 | 11 | # Marker size in meters 12 | float64 size 13 | 14 | # ID of the aruco marker 15 | int32 id 16 | -------------------------------------------------------------------------------- /launch/aruco.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | aruco 4 | 1.1.0 5 | The aruco package can be used to detect, track and calculate pose from aruco markers. 6 | tentone 7 | MIT 8 | 9 | message_generation 10 | message_runtime 11 | 12 | image_transport 13 | image_transport 14 | 15 | catkin 16 | 17 | roscpp 18 | roscpp 19 | 20 | std_msgs 21 | std_msgs 22 | 23 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(aruco) 3 | 4 | #Enable C++ 11 5 | add_compile_options(-std=c++11) 6 | 7 | #Packages 8 | find_package(catkin REQUIRED COMPONENTS cv_bridge roscpp std_msgs message_generation image_transport) 9 | find_package(OpenCV REQUIRED) 10 | 11 | #Messages 12 | add_message_files(FILES Marker.msg) 13 | generate_messages(DEPENDENCIES std_msgs) 14 | 15 | #Catkin dependencies 16 | catkin_package(CATKIN_DEPENDS message_runtime roscpp std_msgs) 17 | 18 | #Aruco ROS node 19 | add_executable(aruco src/ros/ArucoNode.cpp) 20 | add_dependencies(aruco aruco_generate_messages_cpp ${catkin_EXPORTED_TARGETS}) 21 | target_link_libraries(aruco ${catkin_LIBRARIES} ${OpenCV_LIBS}) 22 | 23 | #Include directories 24 | include_directories(include ${catkin_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS}) 25 | 26 | #Install 27 | install(TARGETS aruco 28 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 29 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 30 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 31 | ) 32 | -------------------------------------------------------------------------------- /src/math/Transformations.cpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | 5 | #include 6 | #include 7 | 8 | using namespace cv; 9 | using namespace std; 10 | 11 | /** 12 | * Transformations class contains method to help create and apply tranformations to points. 13 | */ 14 | class Transformations 15 | { 16 | public: 17 | /** 18 | * Creates a new rotation matrix from euler rotation. 19 | * @return Rotation matrix created from euler rotation. 20 | */ 21 | static Mat rotationMatrix(Point3d euler) 22 | { 23 | //Rotation on x axis 24 | Mat rx = (Mat_(3,3) << 25 | 1, 0, 0, 26 | 0, cos(euler.x), -sin(euler.x), 27 | 0, sin(euler.x), cos(euler.x)); 28 | 29 | //Rotation on y axis 30 | Mat ry = (Mat_(3,3) << 31 | cos(euler.y), 0, sin(euler.y), 32 | 0, 1, 0, 33 | -sin(euler.y), 0, cos(euler.y)); 34 | 35 | //Rotation on z axis 36 | Mat rz = (Mat_(3,3) << 37 | cos(euler.z), -sin(euler.z), 0, 38 | sin(euler.z), cos(euler.z), 0, 39 | 0, 0, 1); 40 | 41 | return rz * ry * rx; 42 | } 43 | }; 44 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2017 Tentone 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /src/math/Triangle.cpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | #include 5 | 6 | #include 7 | 8 | using namespace cv; 9 | 10 | /** 11 | * Class is used to represent and manipulate triangles. 12 | */ 13 | class Triangle 14 | { 15 | public: 16 | /** 17 | * Triangle points. 18 | */ 19 | Point2f points[3]; 20 | 21 | /** 22 | * Default triangle contructor. 23 | */ 24 | Triangle() 25 | { 26 | for(int i = 0; i < 3; i++) 27 | { 28 | points[i] = Point2f(0.0, 0.0); 29 | } 30 | } 31 | 32 | /** 33 | * Triangle contructor from corners. 34 | * @param a Corner a. 35 | * @param b Corner b. 36 | * @param c Corner c. 37 | */ 38 | Triangle(Point2f a, Point2f b, Point2f c) 39 | { 40 | points[0] = a; 41 | points[1] = b; 42 | points[2] = c; 43 | } 44 | 45 | /** 46 | * Calculate the area of this triangle. 47 | * @return Area of this triangle. 48 | */ 49 | float area() 50 | { 51 | return abs(points[0].x*(points[1].y-points[2].y) + points[1].x*(points[2].y-points[0].y) + points[2].x*(points[0].y-points[1].y)) / 2.0; 52 | } 53 | 54 | /** 55 | * Check if this triangle collides with another triangle. 56 | * @return True if triangles are colliding, false otherwise. 57 | */ 58 | bool isColliding(Triangle t) 59 | { 60 | return containsPoint(t.points[0]) || containsPoint(t.points[1]) || containsPoint(t.points[2]) || t.containsPoint(points[0]) || t.containsPoint(points[1]) || t.containsPoint(points[2]); 61 | } 62 | 63 | /** 64 | * Check if the point is inside this triangle. 65 | * @param p Point to check. 66 | * @return True if point is inside triangle, false otherwise. 67 | */ 68 | bool containsPoint(Point2f p) 69 | { 70 | bool b1 = sign(p, points[0], points[1]) <= 0.0; 71 | bool b2 = sign(p, points[1], points[2]) <= 0.0; 72 | bool b3 = sign(p, points[2], points[0]) <= 0.0; 73 | 74 | return ((b1 == b2) && (b2 == b3)); 75 | } 76 | 77 | /** 78 | * Sign operation used to check if point a is before or after the line composed for b and c. 79 | * @param a Point a. 80 | * @param b Point b. 81 | * @param c Point c. 82 | * @return Float value if less than 0 point is before line. 83 | */ 84 | float sign(Point2f a, Point2f b, Point2f c) 85 | { 86 | return (a.x - c.x) * (b.y - c.y) - (b.x - c.x) * (a.y - c.y); 87 | } 88 | }; 89 | -------------------------------------------------------------------------------- /src/math/Quadrilateral.cpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | 5 | #include 6 | #include 7 | 8 | #include "Triangle.cpp" 9 | 10 | using namespace cv; 11 | using namespace std; 12 | 13 | /** 14 | * Used to represent and operate over quads. 15 | */ 16 | class Quadrilateral 17 | { 18 | public: 19 | /** 20 | * Vector of points that compose the quad. 21 | */ 22 | vector points; 23 | 24 | /** 25 | * Quad constructor initializes 4 points. 26 | */ 27 | Quadrilateral() 28 | { 29 | for(int i = 0; i < 4; i++) 30 | { 31 | points.push_back(Point2f(0.0, 0.0)); 32 | } 33 | } 34 | 35 | /** 36 | * Quad contructor from a points. 37 | */ 38 | Quadrilateral(Point2f a, Point2f b, Point2f c, Point2f d) 39 | { 40 | points.push_back(a); 41 | points.push_back(b); 42 | points.push_back(c); 43 | points.push_back(d); 44 | } 45 | 46 | /** 47 | * Calculate Area of this quad. 48 | * 49 | * @return Area of this quad. 50 | */ 51 | float area() 52 | { 53 | return contourArea(points); 54 | } 55 | 56 | /** 57 | * Check if point is inside this quad. 58 | * 59 | * @param p Point to check. 60 | * @return true if point is inside this quad 61 | */ 62 | bool containsPoint(Point2f p) 63 | { 64 | return pointPolygonTest(points, p, false) >= 0.0; 65 | } 66 | 67 | /** 68 | * Draw quad lines to image. 69 | * 70 | * @param image Image where to draw line. 71 | * @param color Color of the lines to be drawn. 72 | * @param weight Weight of the lines. 73 | */ 74 | void draw(Mat image, Scalar color, int weigth = 1) 75 | { 76 | for(int j = 0; j < 3; j++) 77 | { 78 | line(image, points[j], points[j+1], color, weigth, 8); 79 | } 80 | 81 | line(image, points[3], points[0], color, weigth, 8); 82 | } 83 | 84 | /** 85 | * Print quad info to cout. 86 | */ 87 | void print() 88 | { 89 | cout << "[" << this->points[0] << ", " << this->points[1] << ", " << this->points[2] << ", " << this->points[3] << "]" << endl; 90 | } 91 | 92 | /** 93 | * Get bigger square on a vector (caller have to check vector size). 94 | * 95 | * @param quad Vector of quads. 96 | * @return quad Bigger quad in the vector. 97 | */ 98 | static Quadrilateral biggerQuadrilateral(vector quads) 99 | { 100 | Quadrilateral max = quads[0]; 101 | float max_area = quads[0].area(); 102 | 103 | //Search for bigger quad 104 | for(unsigned int i = 1; i < quads.size(); i++) 105 | { 106 | float area = quads[i].area(); 107 | if(area > max_area) 108 | { 109 | max = quads[i]; 110 | max_area = area; 111 | } 112 | } 113 | return max; 114 | } 115 | 116 | /** 117 | * Draw all squares from vector to image. 118 | * 119 | * @param image Image where to draw. 120 | * @param quads Vector of quads to draw. 121 | * @param color Color used to draw the quads. 122 | */ 123 | static void drawVector(Mat image, vector quads, Scalar color) 124 | { 125 | for(unsigned int i = 0; i < quads.size(); i++) 126 | { 127 | quads[i].draw(image, color); 128 | } 129 | } 130 | }; 131 | -------------------------------------------------------------------------------- /src/SquareFinder.cpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "math/Quadrilateral.cpp" 4 | 5 | using namespace cv; 6 | using namespace std; 7 | 8 | /** 9 | * SquareFinder can be used to detect distorted squares in images. 10 | */ 11 | class SquareFinder 12 | { 13 | public: 14 | /** 15 | * Detect quads in grayscale image. 16 | * @param gray Grayscale image. 17 | * @param limitCosine Limit value for cosine in the quad corners, by default its 0.6. 18 | * @param maxError Max error percentage relative to the square perimeter. 19 | * @returns sequence of squares detected on the image the sequence is stored in the specified memory storage 20 | */ 21 | static vector findSquares(Mat gray, double limitCosine = 0.6, int minArea = 100, double maxError = 0.025) 22 | { 23 | //Quads found 24 | vector squares = vector(); 25 | 26 | //Contours 27 | vector> contours; 28 | 29 | //Find contours and store them all as a list 30 | findContours(gray, contours, RETR_LIST, CHAIN_APPROX_SIMPLE); 31 | vector approx; 32 | 33 | for(unsigned int i = 0; i < contours.size(); i++) 34 | { 35 | //Approximate contour with accuracy proportional to the contour perimeter 36 | approxPolyDP(Mat(contours[i]), approx, arcLength(Mat(contours[i]), true) * maxError, true); 37 | 38 | //Square contours have 4 vertices after approximation relatively large area (to filter out noisy contours)and be convex. 39 | if(approx.size() == 4 && fabs(contourArea(Mat(approx))) > minArea && isContourConvex(Mat(approx))) 40 | { 41 | float maxCosine = 0; 42 | 43 | //Find the maximum cosine of the angle between joint edges 44 | for(int j = 2; j < 5; j++) 45 | { 46 | float cosine = fabs(angleCornerPointsCos(approx[j%4], approx[j-2], approx[j-1])); 47 | maxCosine = MAX(maxCosine, cosine); 48 | } 49 | 50 | //Check if all angle corner close to 90 (more than the max cosine) 51 | if(maxCosine < limitCosine) 52 | { 53 | Quadrilateral quad = Quadrilateral(); 54 | 55 | for(int j = 0; !approx.empty() && j < 4; j++) 56 | { 57 | quad.points[j] = approx.back(); 58 | approx.pop_back(); 59 | } 60 | 61 | squares.push_back(quad); 62 | } 63 | } 64 | } 65 | 66 | return squares; 67 | } 68 | 69 | /** 70 | * Draw quads into the matrix. 71 | * 72 | * @param mat Mat to draw quads. 73 | * @param quads Vector of quadrilaterals to draw. 74 | */ 75 | static void drawQuads(Mat mat, vector quads) 76 | { 77 | for(unsigned int i = 0; i < quads.size(); i++) 78 | { 79 | for(unsigned int j = 0; j < 4; j++) 80 | { 81 | line(mat, quads[i].points[j], quads[i].points[(j + 1) % 4], Scalar(255, 0, 255), 2); 82 | } 83 | } 84 | } 85 | 86 | /** 87 | * Finds a cosine of angle between vectors from pt0->pt1 and from pt0->pt2. 88 | * 89 | * @param b Point b. 90 | * @param c Point c. 91 | * @param a Point a. 92 | */ 93 | static float angleCornerPointsCos(Point b, Point c, Point a) 94 | { 95 | float dx1 = b.x - a.x; 96 | float dy1 = b.y - a.y; 97 | float dx2 = c.x - a.x; 98 | float dy2 = c.y - a.y; 99 | 100 | return (dx1*dx2 + dy1*dy2) / sqrt((dx1*dx1 + dy1*dy1)*(dx2*dx2 + dy2*dy2) + 1e-12); 101 | } 102 | }; 103 | -------------------------------------------------------------------------------- /src/CornerRefinement.cpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | /** 4 | * This class contains methods to perform corner refinement on the points found by the SquareFinder. 5 | */ 6 | class CornerRefinement 7 | { 8 | public: 9 | /** 10 | * Refine corner position using a grayscale version of the captured image (without threshold). 11 | * This method uses the sobel operator and assumes that only one corner is visible, if the box size is too large corners from the marker migth be visible. 12 | * @param corner Initial corner position in the image. 13 | * @param gray Grayscale image. 14 | * @param box Box size to refine corner. 15 | */ 16 | static Point2f refineCornerSobel(Mat gray, Point corner, int box = 10) 17 | { 18 | Rect roi = getROI(gray, corner, box); 19 | 20 | Mat sobel; 21 | Sobel(gray(roi), sobel, -1, 2, 2, 3, 5); 22 | 23 | int rows = sobel.rows; 24 | int cols = sobel.cols; 25 | 26 | int x = 0, y = 0; 27 | int max = sobel.data[0]; 28 | 29 | for(int i = 0; i < rows; i++) 30 | { 31 | for(int j = 0; j < cols; j++) 32 | { 33 | int value = sobel.data[rows * i + j]; 34 | if(value > max) 35 | { 36 | x = j; 37 | y = i; 38 | max = value; 39 | } 40 | } 41 | } 42 | 43 | #if DEBUG == true 44 | Mat debug = gray(roi).clone(); 45 | debug.at(x, y) = Vec3b(0, 255, 0); 46 | debug.at(roi.width / 2, roi.height / 2) = Vec3b(0, 0, 255); 47 | imshow("Corner", debug); 48 | #endif 49 | 50 | return Point2f(corner.x + x - box / 2 , corner.y + y - box / 2); 51 | } 52 | 53 | /** 54 | * Corner refiment using harris operator. 55 | * @param corner Initial corner position in the image. 56 | * @param gray Grayscale image. 57 | * @param box Box size to refine corner. 58 | */ 59 | static Point2f refineCornerHarris(Mat frame, Point corner, int box = 10) 60 | { 61 | Rect roi = getROI(frame, corner, box); 62 | Mat dst; 63 | 64 | int thresh = 150; 65 | 66 | Mat area = frame(roi).clone(); 67 | Mat gray; 68 | cvtColor(area, gray, COLOR_BGR2GRAY); 69 | 70 | cornerHarris(gray, dst, 2, 3, 0.02); 71 | normalize(dst, dst, 0, 255, NORM_MINMAX); 72 | 73 | int x = corner.x, y = corner.y; 74 | int min = box; 75 | 76 | for(int j = 0; j < dst.rows ; j++) 77 | { 78 | for(int i = 0; i < dst.cols; i++) 79 | { 80 | if(dst.at(j,i) > thresh) 81 | { 82 | int distance = sqrt(pow(j - box / 2, 2) + pow(i - box / 2, 2)); 83 | if(distance < min) 84 | { 85 | x = j; 86 | y = i; 87 | } 88 | 89 | area.at(j, i) = Vec3b(0, 255, 0); 90 | } 91 | } 92 | } 93 | 94 | area.at(box / 2, box / 2) = Vec3b(0, 0, 255); 95 | imshow("Harris", area); 96 | 97 | return Point2f(corner.x + x - box / 2 , corner.y + y - box / 2); 98 | } 99 | 100 | /** 101 | * Get region of interest of the image from center point and box size. 102 | * @param image Image to apply ROI. 103 | * @param center Center ROI point. 104 | * @param box Box size. 105 | */ 106 | static Rect getROI(Mat image, Point center, int box) 107 | { 108 | Rect roi = Rect(center.x - box / 2, center.y - box / 2, box, box); 109 | 110 | if(roi.x < 0) roi.x = 0; 111 | if(roi.y < 0) roi.y = 0; 112 | if(roi.x + box > image.cols) roi.x = image.cols - box; 113 | if(roi.y + box > image.rows) roi.y = image.rows - box; 114 | 115 | return roi; 116 | } 117 | }; 118 | -------------------------------------------------------------------------------- /src/ArucoMarkerInfo.cpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | #include 5 | #include 6 | 7 | #include 8 | 9 | #include "math/Transformations.cpp" 10 | 11 | using namespace cv; 12 | using namespace std; 13 | 14 | /** 15 | * Class is used to store info about a marker. 16 | * The info present in this class is related with real world information. 17 | * Units are store in meters for positions and dimensions and radians for angles. 18 | */ 19 | class ArucoMarkerInfo 20 | { 21 | public: 22 | /** 23 | * Marker ID. 24 | */ 25 | int id; 26 | 27 | /** 28 | * Size of the marker in real position scale. 29 | */ 30 | double size; 31 | 32 | /** 33 | * Marker position in real world coordinates. 34 | */ 35 | Point3d position; 36 | 37 | /** 38 | * Euler rotation of this marker. 39 | */ 40 | Point3d rotation; 41 | 42 | /** 43 | * World corner points calculated from position and rotation of the marker. 44 | * This vector should have only 4 points. 45 | * But can be used to store extra known points for the marker. 46 | * World points stored in the following order: TopLeft, TopRight, BottomRight, BottomLeft. 47 | */ 48 | vector world; 49 | 50 | /** 51 | * Default constructor with id -1. 52 | */ 53 | ArucoMarkerInfo() 54 | { 55 | id = -1; 56 | size = 1.0; 57 | position = Point3d(0.0, 0.0, 0.0); 58 | rotation = Point3d(0.0, 0.0, 0.0); 59 | world = vector(); 60 | calculateWorldPoints(); 61 | } 62 | 63 | /** 64 | * Aruco marker constructor. 65 | * @param id Marker id. 66 | * @param size Marker size in meters. 67 | * @param position Marker world position. 68 | */ 69 | ArucoMarkerInfo(int _id, double _size, Point3f _position) 70 | { 71 | id = _id; 72 | size = _size; 73 | position = _position; 74 | rotation = Point3f(0.0, 0.0, 0.0); 75 | world = vector(); 76 | calculateWorldPoints(); 77 | } 78 | 79 | /** 80 | * Aruco marker constructor. 81 | * @param id Marker id. 82 | * @param size Marker size in meters. 83 | * @param position Marker world position. 84 | * @param rotation Marker world euler rotation. 85 | */ 86 | ArucoMarkerInfo(int _id, double _size, Point3f _position, Point3f _rotation) 87 | { 88 | id = _id; 89 | size = _size; 90 | position = _position; 91 | rotation = _rotation; 92 | world = vector(); 93 | calculateWorldPoints(); 94 | } 95 | 96 | /** 97 | * Calculate the marker world points, considering the marker center position and rotation. 98 | * First the marker is rotated and is translated after so the rotation is always relative to the marker center. 99 | */ 100 | void calculateWorldPoints() 101 | { 102 | double half = size / 2.0; 103 | 104 | world.clear(); 105 | 106 | world.push_back(Point3f(-half, -half, 0)); 107 | world.push_back(Point3f(-half, +half, 0)); 108 | world.push_back(Point3f(half, +half, 0)); 109 | world.push_back(Point3f(half, -half, 0)); 110 | 111 | Mat rot = Transformations::rotationMatrix(rotation); 112 | 113 | for(unsigned int i = 0; i < world.size(); i++) 114 | { 115 | Mat temp = (Mat_(3, 1) << world[i].x, world[i].y, world[i].z); 116 | Mat transf = rot * temp; 117 | 118 | world[i].x = transf.at(0, 0) + position.x; 119 | world[i].y = transf.at(1, 0) + position.y; 120 | world[i].z = transf.at(2, 0) - position.z; 121 | } 122 | } 123 | 124 | /** 125 | * Print info about this marker to the stdout. 126 | */ 127 | void print() 128 | { 129 | cout << "{" << endl; 130 | cout << " ID: " << id << endl; 131 | cout << " Size: " << size << endl; 132 | cout << " Position: " << position.x << ", " << position.y << ", " << position.z << endl; 133 | cout << " Rotation: " << rotation.x << ", " << rotation.y << ", " << rotation.z << endl; 134 | 135 | for(unsigned int i = 0; i < world.size(); i++) 136 | { 137 | cout << " World: " << world[i].x << ", " << world[i].y << ", " << world[i].z << endl; 138 | } 139 | 140 | cout << "}" << endl; 141 | } 142 | }; 143 | -------------------------------------------------------------------------------- /src/ArucoMarker.cpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | #include 5 | #include 6 | 7 | #include 8 | 9 | #include "ArucoMarkerInfo.cpp" 10 | 11 | using namespace cv; 12 | using namespace std; 13 | 14 | /** 15 | * Class is used to represent aruco markers. 16 | * All markers are assumed to be 5x5 markers capable of 1024 options, after considering rotation and error detection. 17 | */ 18 | class ArucoMarker 19 | { 20 | public: 21 | /** 22 | * Contain all the cells in the marker. 23 | * Cells are encoded as [x][y] from left to right on X and from up to down on Y. 24 | */ 25 | int cells[7][7]; 26 | 27 | /** 28 | * Number of rows used to store data in the marker. 29 | */ 30 | int rows; 31 | 32 | /** 33 | * Number of cols used to store data in the marker. 34 | */ 35 | int cols; 36 | 37 | /** 38 | * Number of 90 degrees turns applied to the marker. 39 | */ 40 | int rotation; 41 | 42 | /** 43 | * Id of this markers. 44 | * Can be calculated after filling up the cells info. 45 | */ 46 | int id; 47 | 48 | /** 49 | * Flag to store if the marker was already validated. 50 | */ 51 | int validated; 52 | 53 | /** 54 | * Store info about the marker real world morphology and location. 55 | */ 56 | ArucoMarkerInfo info; 57 | 58 | /** 59 | * Projected corner points in camera coordinates. 60 | * This vector should have only 4 points. 61 | * But can be used to store extra known points for the marker. 62 | */ 63 | vector projected; 64 | 65 | /** 66 | * Aruco marker constructor. 67 | */ 68 | ArucoMarker() 69 | { 70 | rows = 5; 71 | cols = 5; 72 | id = -1; 73 | rotation = 0; 74 | validated = false; 75 | } 76 | 77 | /** 78 | * Attach info to this marker. 79 | * 80 | * @param info Marker information. 81 | */ 82 | void attachInfo(ArucoMarkerInfo _info) 83 | { 84 | info = _info; 85 | } 86 | 87 | /** 88 | * Get the id of the marker. The ID its a value between 0 and 1024. 89 | * 90 | * @return ID of this aruco marker. 91 | */ 92 | int calculateID() 93 | { 94 | id = 0; 95 | 96 | for(int i = 1; i < 6; ++i) 97 | { 98 | id <<= 1; 99 | id |= cells[i][2]; 100 | id <<= 1; 101 | id |= cells[i][4]; 102 | } 103 | 104 | return id; 105 | } 106 | 107 | /** 108 | * Calculate all parameters and check if its a valid aruco marker. 109 | * Should be called only after projected points and cell info is added. 110 | * @return true if the marker is valid, false otherwise. 111 | */ 112 | bool validate() 113 | { 114 | validated = false; 115 | 116 | //Check if there are points 117 | if(projected.size() == 0) 118 | { 119 | return false; 120 | } 121 | 122 | //Check black border allow up to three white squares for edge light bleed cases 123 | unsigned int bad = 0; 124 | for(unsigned int i = 0; i < 7; i++) 125 | { 126 | if(cells[i][0] != 0 || cells[i][6] != 0 || cells[0][i] != 0 || cells[6][i] != 0) 127 | { 128 | bad++; 129 | if(bad > 3) 130 | { 131 | return false; 132 | } 133 | } 134 | } 135 | 136 | //Check hamming distance of internal data 137 | for(int j = 0; j < 4; j++) 138 | { 139 | if(hammingDistance() == 0) 140 | { 141 | calculateID(); 142 | validated = true; 143 | return true; 144 | } 145 | 146 | rotate(); 147 | } 148 | 149 | return false; 150 | } 151 | 152 | /** 153 | * Used to rotate marker 90 degrees. 154 | * Can be used to rotate the marker data and make sure that it is read properly. 155 | */ 156 | void rotate() 157 | { 158 | int temp[7][7]; 159 | int n = 7; 160 | 161 | for (int i = 0; i < n; i++) 162 | { 163 | for (int j = 0; j < n; j++) 164 | { 165 | temp[i][j] = cells[n - j - 1][i]; 166 | } 167 | } 168 | 169 | for (int i = 0; i < n; i++) 170 | { 171 | for (int j = 0; j < n; j++) 172 | { 173 | cells[i][j] = temp[i][j]; 174 | } 175 | } 176 | 177 | rotation++; 178 | 179 | std::rotate(projected.begin(), projected.begin() + 1, projected.end()); 180 | } 181 | 182 | /** 183 | * Calculates the sum of the hamming distance (number of diferent bits) for this marker relative to the ids matrix used to validate the aruco markers. 184 | */ 185 | int hammingDistance() 186 | { 187 | int ids[4][5] = { 188 | {1, 0, 0, 0, 0}, 189 | {1, 0, 1, 1, 1}, 190 | {0, 1, 0, 0, 1}, 191 | {0, 1, 1, 1, 0} 192 | }; 193 | 194 | int dist = 0; 195 | int sum, minSum; 196 | 197 | for(int i = 1; i < 6; ++i) 198 | { 199 | minSum = 99999; 200 | 201 | for(int j = 1; j < 5; ++j) 202 | { 203 | sum = 0; 204 | 205 | for(int k = 1; k < 6; ++k) 206 | { 207 | sum += cells[i][k] == ids[j - 1][k - 1] ? 0 : 1; 208 | } 209 | 210 | if(sum < minSum) 211 | { 212 | minSum = sum; 213 | } 214 | } 215 | 216 | dist += minSum; 217 | } 218 | 219 | return dist; 220 | } 221 | 222 | /** 223 | * Print marker cells to the stdout. 224 | */ 225 | void print() 226 | { 227 | cout << "{" << endl; 228 | cout << " Valid: " << validated << endl; 229 | cout << " Hamming: " << hammingDistance() << endl; 230 | cout << " ID: " << id << endl; 231 | cout << " Cells: ["; 232 | for(int i = 0; i < 7; i++) 233 | { 234 | for(int j = 0; j < 7; j++) 235 | { 236 | cout << cells[i][j] << ", "; 237 | } 238 | 239 | if(i == 6) 240 | { 241 | cout << "]" << endl; 242 | } 243 | else 244 | { 245 | cout << endl << " "; 246 | } 247 | } 248 | cout << " Rotation: " << rotation << endl; 249 | 250 | for(unsigned int i = 0; i < projected.size(); i++) 251 | { 252 | cout << " Projected: " << projected[i].x << ", " << projected[i].y << endl; 253 | } 254 | 255 | info.print(); 256 | 257 | cout << "}" << endl; 258 | } 259 | }; 260 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Aruco 2 | 3 | - Library for aruco marker detection and pose estimation, compatible with ROS. 4 | - Multi marker pose estimation, use as many markers as possible to improve the performance of the system. 5 | - Detection is not affected by lighting conditions (can be used for low light and high noise tracking). 6 | 7 | 8 | 9 | 10 | 11 | ### Markers 12 | 13 | Aruco markers are geometrically square, they have a black border and an inner grid that is used to store a numeric identifier in binary code. 14 | 15 | A dictionary is used to identify the marker. The dictionary defines a set of rules used to calculate the marker identifier, perform validation and apply error correction. 16 | 17 | We use the original aruco dictionary, that uses bits from the marker 2nd and 4th columns to store the marker identifier in natural binary code, the remaining bits are used for parity checking. 18 | 19 | 20 | 21 | By analyzing the signature matrix, it is possibly to verify that it is not enough to guarantee that there is only one possible rotation for each marker in the we can see the marker 1023 that is horizontally symmetric. 22 | 23 | 24 | 25 | ### Algorithm 26 | 27 | The detection algorithm was implemented using the OpenCV library, since it pro-vides a large set of image processing algorithms. Figure 3 shows the steps applied to detect and identify markers. 28 | 29 | 30 | 31 | The algorithm starts by applying adaptive threshold [4] to the image, this algorithm consists in calculating for each pixel a threshold value using the histogram of its neighborhood. It is of particular interest for situations with multiple lighting conditions. 32 | 33 | 34 | 35 | To determine the threshold block (neighborhood size), one block size is tested on each frame, the block size chosen is the average size from all block sizes were the maximum number of markers were found, the block size is retested when there are no markers visible. 36 | After threshold is applied to the image, we perform square detection contours are detected using a border-following algorithm [5], followed by the Douglas-Peucker contour simplification algorithm [6]. 37 | Based on the detected contours, the Quadrilateral Sum Conjecture is used as a criterion to detect squares. Even under significant perspective distortion a square is al-ways a convex quadrilateral. Our second criteria will be to make sure that the sum of the cosine of all inner angle is below a defined threshold. 38 | To filter noise a third criterion was added: all contours composing a geometry with an area bellow a defined threshold will be discarded. 39 | These three criteria allow to properly filter squares even under heavy distortion from the contour list. Figure 5 represents the obtained result for a maximum sum of cosine of 0.25 and a minimum area of 100px. 40 | 41 | 42 | 43 | Perspective distortion is corrected in the detected squares, then they are resampled into a 7x7 matrix using linear interpolation, threshold is applied using the Otsu’s Binarization algorithm [7], at this point we obtain a matrix with the marker data in it. Fig-ure 6 represents the matrix obtained after the binarization process. 44 | 45 | 46 | 47 | At this stage, the marker data is validated as aruco using the signature matrix. Markers might be detected in any orientation. The algorithm tests the data with different rotations (90º, 180º, 270º), if the marker is not recognized for any rotation it is then discarded. 48 | For pose estimation the method solvePnp from OpenCV was used, in iterative mode using Levenberg-Marquardt optimization [8]. 49 | To obtain the camera position, markers need to be registered into the program, a marker is represented by its identifier and a real-world pose (position and rotation). 50 | Corners obtained from all visible known markers are used to estimate the camera pose. 51 | 52 | ### Results 53 | 54 | We created a testing environment to compare the developed solution with the ones already existing in the literature. Two test markers were printed: one Aruco maker and one ARTag maker. Both markers had exactly 20cm in size and the camera was placed on top of a box with the marker aligned with the camera. The marker was fixed with transparent tape. 55 | A measuring tape with a millimeter scale was used to measure the distance be-tween the camera and the markers. An image was taken for each distance tested and the markers were moved 30cm each time until none of the algorithms was able to detect the marker. Figure 7 represents some samples of the testing images used during the experiments. 56 | To measure the tolerance of the detector to perspective distortion a second testing environment was created. A marker was placed on a box and the camera was positioned 2.0 meters away. The marker was rotated in steps of 10º from 0º to 80º. Table 2 presents the results obtained for marker rotation showing that the proposed method performed better than the other two algorithms used for comparison, obtain-ing lower error. 57 | 58 | 59 | 60 | Camera calibration was performed using a chessboard pattern and the values obtained were stored to be used for the tests. Figure 8 presents the results obtained. It is possible to observe an improvement in the maximum detection distance when using our algorithm. 61 | 62 | 63 | 64 | 65 | ### Documentation 66 | 67 | - API documentation can be generated using Doxygen 68 | - The ROS package is called "maruco" to void collision with the already existing aruco package. 69 | - To install in your ROS project simply copy the aruco folder into your catkin workspace and execute "catkin_make" to build the code. 70 | - To test with a USB camera also install usb-camera and camera-calibration from aptitude to access and calibrate the camera. 71 | 72 | | Parameter | Description | Default | 73 | | ------------------- | ------------------------------------------------------------ | ------- | 74 | | debug | When debug parameter is se to true the node creates a new cv window to show debug information. | false | 75 | | use_opencv_coords | When set opencv coordinates are used, otherwise ros coords are used (X+ depth, Z+ height, Y+ lateral) | false | 76 | | cosine_limit | Cosine limit used during the quad detection phase. The bigger the value more distortion tolerant the square detection will be. | 0.8 | 77 | | theshold_block_size | Adaptive threshold base block size. | 9 | 78 | | min_area | Minimum area considered for aruco markers. Should be a value high enough to filter blobs out but detect the smallest marker necessary. | 100 | 79 | | calibrated | Used to indicate if the camera should be calibrated using external message of use default calib parameters | true | 80 | | calibration | Camera intrinsic calibration matrix as defined by opencv (values by row separated by _ char) Ex "260.3_0_154.6_0_260.5_117_0_0_1" | | 81 | | distortion | Camera distortion matrix as defined by opencv composed of up to 5 parameters (values separated by _ char) Ex "0.007_-0.023_-0.004_-0.0006_-0.16058" | | 82 | | marker### | These parameters are used to pass to the node a list of known markers, these markers will be used to calculate the camera pose in the `world.Markers` are declared in the format `marker###`: "______ Ex marker768 0.156_0_0_0_0_0_0" | | 83 | 84 | 85 | 86 | ### Subscribed Topics 87 | 88 | | Topic | Description | Default | 89 | | --------------------- | ----------------------------------------- | ----------------------- | 90 | | topic_camera | Camera image topic | /camera/rgb/image_raw | 91 | | topic_camera_info | Camera info_expects a Camera Info message | /camera/rgb/camera_info | 92 | | topic_marker_register | Register markers in the node | /marker_register | 93 | | topic_marker_remove | Remove markers registered in the node | /marker_remove | 94 | 95 | 96 | 97 | ### Published Topics 98 | 99 | | Topic | Description | Default | 100 | | -------------- | ------------------------------------------------------------ | --------- | 101 | | topic_visible | Publishes true when a marker is visible_false otherwise | /visible | 102 | | topic_position | Publishes the camera world position relative to the registered markers as a Point message | /position | 103 | | topic_rotation | Publishes the camera world rotation relative to the registered markers | /rotation | 104 | | topic_pose | Publishes camera rotation and position as Pose message | /pose | 105 | 106 | 107 | 108 | ### Dependencies 109 | - OpenCV 2.4.9+ 110 | - Works with OpenCV 3.0+ 111 | - Previous versions of opencv 2 might cause problems. 112 | - CMake 113 | - ROS (indigo and later) 114 | - cv-bridge 115 | 116 | ### License 117 | - MIT license (Available on GitHub page) 118 | -------------------------------------------------------------------------------- /src/ArucoDetector.cpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | #include 5 | #include 6 | 7 | #include 8 | #include 9 | #include 10 | #include 11 | 12 | #include "SquareFinder.cpp" 13 | #include "CornerRefinement.cpp" 14 | #include "ArucoMarker.cpp" 15 | #include "ArucoMarkerInfo.cpp" 16 | 17 | #define DEBUG false 18 | 19 | using namespace cv; 20 | using namespace std; 21 | 22 | /** 23 | * Class is used to detect 5x5 aruco markers. 24 | * It contains method for detection, data reading, previsualization and debugging aruco markers information. 25 | * After detection camera position relative to the aruco markers can be easily calculated using opencv solvePnP. 26 | */ 27 | class ArucoDetector 28 | { 29 | public: 30 | /** 31 | * Process image to identify aruco markers. 32 | * Applies pre-processing over the frame and get list of quads in the frame. 33 | * @param frame Frame to be processed. 34 | * @param limitCosine Higher values allow detection of more distorted markers but performance is slower 35 | */ 36 | static vector getMarkers(Mat frame, float limitCosine = 0.7, int thresholdBlockSize = 7, int minArea = 100, double maxError = 0.025) 37 | { 38 | //Create a grayscale image 39 | Mat gray; 40 | cvtColor(frame, gray, COLOR_BGR2GRAY); 41 | 42 | //Adaptive threshold 43 | Mat thresh; 44 | adaptiveThreshold(gray, thresh, 255, THRESH_BINARY, ADAPTIVE_THRESH_MEAN_C, thresholdBlockSize, 0.0); 45 | 46 | #if DEBUG 47 | imshow("Adaptive", thresh); 48 | #endif 49 | 50 | //Get quads 51 | vector quads = SquareFinder::findSquares(thresh, limitCosine, minArea, maxError); 52 | 53 | #if DEBUG 54 | Mat quad = frame.clone(); 55 | SquareFinder::drawQuads(quad, quads); 56 | imshow("Quads", quad); 57 | #endif 58 | 59 | //List of markers 60 | vector markers = vector(); 61 | 62 | //Transform quads and filter invalid markers 63 | for(unsigned int i = 0; i < quads.size(); i++) 64 | { 65 | 66 | Mat board = deformQuad(frame, Point2i(49, 49), quads[i].points); 67 | Mat binary = processArucoImage(board); 68 | 69 | //Process aruco image and get data 70 | ArucoMarker marker = readArucoData(binary); 71 | marker.projected = quads[i].points; 72 | 73 | //Check if marker is valid 74 | if(marker.validate()) 75 | { 76 | //Show board 77 | #if DEBUG 78 | imshow("Board", board); 79 | #endif 80 | 81 | markers.push_back(marker); 82 | } 83 | } 84 | 85 | return markers; 86 | } 87 | 88 | /** 89 | * Get aruco marker bits data. 90 | * @param image Square image with the aruco marker. 91 | * @return Binary image with the aruco code the image has resolution (cols + 2, rows + 2) 92 | */ 93 | static Mat processArucoImage(Mat image) 94 | { 95 | Mat aruco; 96 | resize(image, aruco, Size(7, 7)); 97 | 98 | Mat gray; 99 | cvtColor(aruco, gray, CV_RGB2GRAY); 100 | 101 | Mat binary; 102 | threshold(gray, binary, 0, 255, CV_THRESH_BINARY | CV_THRESH_OTSU);; 103 | 104 | return binary; 105 | } 106 | 107 | /** 108 | * Read aruco data from binary image with exactly the same size of the aruco marker. 109 | * @param binary Binary image containing aruco info. 110 | * @return ArucoMarker with the information collected. 111 | */ 112 | static ArucoMarker readArucoData(Mat binary) 113 | { 114 | ArucoMarker marker = ArucoMarker(); 115 | 116 | for(unsigned int i = 0; i < binary.cols * binary.rows ; i++) 117 | { 118 | marker.cells[i / binary.cols][i % binary.cols] = (binary.data[i] == 255); 119 | } 120 | 121 | return marker; 122 | } 123 | 124 | /** 125 | * Draw the border and id of all markers found on top of camera image. 126 | * @param frame Image where to write Aruco information. 127 | * @param markers Vector with all aruco markers found. 128 | * @param camera Camera intrinsic calibration matrix. 129 | * @param distortion Camera distortion calibration matrix. 130 | */ 131 | static void drawMarkers(Mat frame, vector markers, Mat camera, Mat distortion) 132 | { 133 | for(unsigned int i = 0; i < markers.size(); i++) 134 | { 135 | Point2f center; 136 | 137 | //Draw countours 138 | for(unsigned int j = 0; j < 4; j++) 139 | { 140 | line(frame, markers[i].projected[j], markers[i].projected[(j + 1) % 4], Scalar(255, 0, 255), 2); 141 | center.x += markers[i].projected[j].x; 142 | center.y += markers[i].projected[j].y; 143 | } 144 | 145 | center.x /= 4; 146 | center.y /= 4; 147 | 148 | //Draw referencial 149 | Mat rotation, position; 150 | 151 | #if CV_MAJOR_VERSION == 2 152 | solvePnP(markers[i].info.world, markers[i].projected, camera, distortion, rotation, position, false, ITERATIVE); 153 | #else 154 | solvePnP(markers[i].info.world, markers[i].projected, camera, distortion, rotation, position, false, SOLVEPNP_ITERATIVE); 155 | #endif 156 | 157 | vector referencial; 158 | referencial.push_back(Point3d(0, 0, 0)); 159 | referencial.push_back(Point3d(markers[i].info.size / 2, 0, 0)); 160 | referencial.push_back(Point3d(0, markers[i].info.size / 2, 0)); 161 | referencial.push_back(Point3d(0, 0, markers[i].info.size / 2)); 162 | 163 | vector projected; 164 | projectPoints(referencial, rotation, position, camera, distortion, projected); 165 | 166 | line(frame, projected[0], projected[1], Scalar(0, 0, 255), 2); 167 | putText(frame, "X", projected[1], FONT_HERSHEY_SIMPLEX, 0.5, Scalar(0, 0, 255), 1); 168 | 169 | line(frame, projected[0], projected[2], Scalar(0, 255, 0), 2); 170 | putText(frame, "Y", projected[2], FONT_HERSHEY_SIMPLEX, 0.5, Scalar(0, 255, 0), 1); 171 | 172 | line(frame, projected[0], projected[3], Scalar(255, 0, 0), 2); 173 | putText(frame, "Z", projected[3], FONT_HERSHEY_SIMPLEX, 0.5, Scalar(255, 0, 0), 1); 174 | 175 | //Draw number 176 | putText(frame, to_string(markers[i].id), center, FONT_HERSHEY_SIMPLEX, 0.5, Scalar(0, 255, 255), 1); 177 | } 178 | } 179 | 180 | /** 181 | * Draw origin of the referencial estimated from all markers found. 182 | * @param frame Image where to write origin referencial. 183 | * @param markers Vector with all aruco markers found. 184 | * @param camera Camera intrinsic calibration matrix. 185 | * @param distortion Camera distortion calibration matrix. 186 | * @param size Size of the referencial. 187 | */ 188 | static void drawOrigin(Mat frame, vector markers, Mat camera, Mat distortion, float size = 1) 189 | { 190 | if(markers.size() == 0) 191 | { 192 | return; 193 | } 194 | 195 | vector world; 196 | vector image; 197 | 198 | for(unsigned int i = 0; i < markers.size(); i++) 199 | { 200 | for(unsigned int k = 0; k < markers[i].projected.size(); k++) 201 | { 202 | world.push_back(markers[i].info.world[k]); 203 | image.push_back(markers[i].projected[k]); 204 | } 205 | 206 | //Draw countours 207 | for(unsigned int j = 0; j < 4; j++) 208 | { 209 | line(frame, markers[i].projected[j], markers[i].projected[(j + 1) % 4], Scalar(0, 150, 0), 2); 210 | } 211 | } 212 | 213 | Mat rotation, position; 214 | 215 | #if CV_MAJOR_VERSION == 2 216 | solvePnP(world, image, camera, distortion, rotation, position, false, ITERATIVE); 217 | #else 218 | solvePnP(world, image, camera, distortion, rotation, position, false, SOLVEPNP_ITERATIVE); 219 | #endif 220 | 221 | vector referencial; 222 | referencial.push_back(Point3d(0, 0, 0)); 223 | referencial.push_back(Point3d(size, 0, 0)); 224 | referencial.push_back(Point3d(0, size, 0)); 225 | referencial.push_back(Point3d(0, 0, size)); 226 | 227 | vector projected; 228 | projectPoints(referencial, rotation, position, camera, distortion, projected); 229 | 230 | line(frame, projected[0], projected[1], Scalar(0, 0, 255), 2); 231 | putText(frame, "X", projected[1], FONT_HERSHEY_SIMPLEX, 0.5, Scalar(0, 0, 255), 1); 232 | 233 | line(frame, projected[0], projected[2], Scalar(0, 255, 0), 2); 234 | putText(frame, "Y", projected[2], FONT_HERSHEY_SIMPLEX, 0.5, Scalar(0, 255, 0), 1); 235 | 236 | line(frame, projected[0], projected[3], Scalar(255, 0, 0), 2); 237 | putText(frame, "Z", projected[3], FONT_HERSHEY_SIMPLEX, 0.5, Scalar(255, 0, 0), 1); 238 | } 239 | 240 | /** 241 | * Preview all quads found in the image. 242 | * Used for debug purpuse only. 243 | * @param frame Original frame to extract color information 244 | * @param quads Vector of quads detected in the frame. 245 | * @return Image only with the found quads. 246 | */ 247 | static Mat previewQuads(Mat frame, vector quads) 248 | { 249 | Mat sum = Mat::zeros(frame.rows, frame.cols, CV_8UC3); 250 | 251 | for(unsigned int i = 0; i < quads.size(); i++) 252 | { 253 | add(sum, filterQuadRegion(frame, quads[i]), sum); 254 | } 255 | 256 | return sum; 257 | } 258 | 259 | /** 260 | * Draw aruco marker to binary image. 261 | * @param marker Marker to be drawn. 262 | * @param size Size of the output image. 263 | * @return Image representing the marker. 264 | */ 265 | static Mat drawArucoMarker(ArucoMarker marker, Size size) 266 | { 267 | Mat out = Mat::zeros(7, 7, CV_8UC1); 268 | 269 | for(unsigned int i = 0; i < 7; i++) 270 | { 271 | for(unsigned int j = 0; j < 7; j++) 272 | { 273 | out.data[i * 7 + j] = marker.cells[i][j] * 255; 274 | } 275 | } 276 | 277 | resize(out, out, size, 0, 0, INTER_NEAREST); 278 | 279 | return out; 280 | } 281 | 282 | /** 283 | * Crop image to quad area. 284 | * Output size has the same size as the input. 285 | * @param image Image to be cropped. 286 | * @param quad Quad to be used to crop the image. 287 | * @return Cropped image. 288 | */ 289 | static Mat filterQuadRegion(Mat image, Quadrilateral quad) 290 | { 291 | Mat out = Mat::zeros(image.rows, image.cols, CV_8UC3); 292 | 293 | Point p[1][4]; 294 | p[0][0] = quad.points[0]; 295 | p[0][1] = quad.points[1]; 296 | p[0][2] = quad.points[2]; 297 | p[0][3] = quad.points[3]; 298 | 299 | const Point* points[1] = {p[0]}; 300 | int points_count[] = {4}; 301 | 302 | //Create Mask 303 | fillPoly(out, points, points_count, 1, Scalar(1, 1, 1)); 304 | 305 | //Apply mask to image 306 | for(unsigned int i = 0; i < out.rows; i++) 307 | { 308 | for(unsigned int j = 0; j < out.cols; j++) 309 | { 310 | int t = (i*out.cols+j)*3; 311 | out.data[t] *= image.data[t]; 312 | out.data[t+1] *= image.data[t+1]; 313 | out.data[t+2] *= image.data[t+2]; 314 | } 315 | } 316 | 317 | return out; 318 | } 319 | 320 | /** 321 | * Apply inverse perspective transformation to image using quad. 322 | * @param image Image to transform. 323 | * @param size Size of the output image. 324 | * @param quad Quad that defines the square area. 325 | * @return Corrected image. 326 | */ 327 | static Mat deformQuad(Mat image, Point2i size, vector quad) 328 | { 329 | Mat out = Mat::zeros(size.x, size.y, CV_8UC3); 330 | 331 | vector points; 332 | points.push_back(Point2f(0, 0)); 333 | points.push_back(Point2f(0, out.rows)); 334 | points.push_back(Point2f(out.cols, out.rows)); 335 | points.push_back(Point2f(out.cols, 0)); 336 | 337 | Mat transformation = getPerspectiveTransform(quad, points); 338 | warpPerspective(image, out, transformation, out.size(), INTER_LINEAR); 339 | 340 | return out; 341 | } 342 | }; 343 | -------------------------------------------------------------------------------- /src/ros/ArucoNode.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | 10 | #include "ros/ros.h" 11 | 12 | #include "std_msgs/String.h" 13 | #include "std_msgs/Bool.h" 14 | #include "std_msgs/Int32.h" 15 | 16 | #include "geometry_msgs/Point.h" 17 | #include "geometry_msgs/PoseStamped.h" 18 | #include "sensor_msgs/image_encodings.h" 19 | #include "nav_msgs/Odometry.h" 20 | 21 | #include "image_transport/image_transport.h" 22 | #include "cv_bridge/cv_bridge.h" 23 | 24 | #include "aruco/Marker.h" 25 | 26 | #include "../ArucoMarker.cpp" 27 | #include "../ArucoMarkerInfo.cpp" 28 | #include "../ArucoDetector.cpp" 29 | 30 | using namespace cv; 31 | using namespace std; 32 | 33 | /** 34 | * Camera calibration matrix pre initialized with calibration values for the test camera. 35 | */ 36 | double data_calibration[9] = {570.3422241210938, 0, 319.5, 0, 570.3422241210938, 239.5, 0, 0, 1}; 37 | Mat calibration; 38 | 39 | /** 40 | * Lenses distortion matrix initialized with values for the test camera. 41 | */ 42 | double data_distortion[5] = {0, 0, 0, 0, 0}; 43 | Mat distortion; 44 | 45 | /** 46 | * List of known of markers, to get the absolute position and rotation of the camera, some of these are required. 47 | */ 48 | vector known = vector(); 49 | 50 | /** 51 | * Node visibility publisher. 52 | * Publishes true when a known marker is visible, publishes false otherwise. 53 | */ 54 | ros::Publisher pub_visible; 55 | 56 | /** 57 | * Node position publisher. 58 | */ 59 | ros::Publisher pub_position; 60 | 61 | /** 62 | * Node rotation publisher. 63 | */ 64 | ros::Publisher pub_rotation; 65 | 66 | /** 67 | * Node pose publisher. 68 | */ 69 | ros::Publisher pub_pose; 70 | 71 | /** 72 | * Node odometry publisher. 73 | * Publishes the odometry of the tf_frame indicated using the pose calculated from marker. 74 | */ 75 | ros::Publisher pub_odom; 76 | 77 | /** 78 | * Name of the transform tf name to indicate on published topics. 79 | */ 80 | string tf_frame_id; 81 | 82 | /** 83 | * Pose publisher sequence counter. 84 | */ 85 | int pub_pose_seq = 0; 86 | 87 | /** 88 | * Flag to check if calibration parameters were received. 89 | * If set to false the camera will be calibrated when a camera info message is received. 90 | */ 91 | bool calibrated; 92 | 93 | /** 94 | * Flag to determine if OpenCV or ROS coordinates are used. 95 | */ 96 | bool use_opencv_coords; 97 | 98 | /** 99 | * When debug parameter is se to true the node creates a new cv window to show debug information. 100 | * By default is set to false. 101 | * If set true the node will open a debug window. 102 | */ 103 | bool debug; 104 | 105 | /** 106 | * Cosine limit used during the quad detection phase. 107 | * Value between 0 and 1. 108 | * By default 0.8 is used. 109 | * The bigger the value more distortion tolerant the square detection will be. 110 | */ 111 | float cosine_limit; 112 | 113 | /** 114 | * Maximum error to be used by geometry poly aproximation method in the quad detection phase. 115 | * By default 0.035 is used. 116 | */ 117 | float max_error_quad; 118 | 119 | /** 120 | * Adaptive theshold pre processing block size. 121 | */ 122 | int theshold_block_size; 123 | 124 | /** 125 | * Minimum threshold block size. 126 | * By default 5 is used. 127 | */ 128 | int theshold_block_size_min; 129 | 130 | /** 131 | * Maximum threshold block size. 132 | * By default 9 is used. 133 | */ 134 | int theshold_block_size_max; 135 | 136 | /** 137 | * Minimum area considered for aruco markers. 138 | * Should be a value high enough to filter blobs out but detect the smallest marker necessary. 139 | * By default 100 is used. 140 | */ 141 | int min_area; 142 | 143 | /** 144 | * Draw yellow text with black outline into a frame. 145 | * @param frame Frame mat. 146 | * @param text Text to be drawn into the frame. 147 | * @param point Position of the text in frame coordinates. 148 | */ 149 | void drawText(Mat frame, string text, Point point) 150 | { 151 | putText(frame, text, point, FONT_HERSHEY_SIMPLEX, 0.5, Scalar(0, 0, 0), 2, CV_AA); 152 | putText(frame, text, point, FONT_HERSHEY_SIMPLEX, 0.5, Scalar(0, 255, 255), 1, CV_AA); 153 | } 154 | 155 | /** 156 | * Callback executed every time a new camera frame is received. 157 | * This callback is used to process received images and publish messages with camera position data if any. 158 | */ 159 | void onFrame(const sensor_msgs::ImageConstPtr& msg) 160 | { 161 | try 162 | { 163 | Mat frame = cv_bridge::toCvShare(msg, "bgr8")->image; 164 | 165 | //Process image and get markers 166 | vector markers = ArucoDetector::getMarkers(frame, cosine_limit, theshold_block_size, min_area, max_error_quad); 167 | 168 | //Visible 169 | vector found; 170 | 171 | //Vector of points 172 | vector projected; 173 | vector world; 174 | 175 | if(markers.size() == 0) 176 | { 177 | theshold_block_size += 2; 178 | 179 | if(theshold_block_size > theshold_block_size_max) 180 | { 181 | theshold_block_size = theshold_block_size_min; 182 | } 183 | } 184 | 185 | //Check known markers and build known of points 186 | for(unsigned int i = 0; i < markers.size(); i++) 187 | { 188 | for(unsigned int j = 0; j < known.size(); j++) 189 | { 190 | if(markers[i].id == known[j].id) 191 | { 192 | markers[i].attachInfo(known[j]); 193 | 194 | for(unsigned int k = 0; k < 4; k++) 195 | { 196 | projected.push_back(markers[i].projected[k]); 197 | world.push_back(known[j].world[k]); 198 | } 199 | 200 | found.push_back(markers[i]); 201 | } 202 | } 203 | } 204 | 205 | //Draw markers 206 | if(debug) 207 | { 208 | ArucoDetector::drawMarkers(frame, markers, calibration, distortion); 209 | } 210 | 211 | //Check if any marker was found 212 | if(world.size() > 0) 213 | { 214 | //Calculate position and rotation 215 | Mat rotation, position; 216 | 217 | #if CV_MAJOR_VERSION == 2 218 | solvePnP(world, projected, calibration, distortion, rotation, position, false, ITERATIVE); 219 | #else 220 | solvePnP(world, projected, calibration, distortion, rotation, position, false, SOLVEPNP_ITERATIVE); 221 | #endif 222 | 223 | //Invert position and rotation to get camera coords 224 | Mat rodrigues; 225 | Rodrigues(rotation, rodrigues); 226 | 227 | Mat camera_rotation; 228 | Rodrigues(rodrigues.t(), camera_rotation); 229 | 230 | Mat camera_position = -rodrigues.t() * position; 231 | 232 | //Publish position and rotation 233 | geometry_msgs::Point message_position, message_rotation; 234 | 235 | //OpenCV coordinates 236 | if(use_opencv_coords) 237 | { 238 | message_position.x = camera_position.at(0, 0); 239 | message_position.y = camera_position.at(1, 0); 240 | message_position.z = camera_position.at(2, 0); 241 | 242 | message_rotation.x = camera_rotation.at(0, 0); 243 | message_rotation.y = camera_rotation.at(1, 0); 244 | message_rotation.z = camera_rotation.at(2, 0); 245 | } 246 | //Robot coordinates 247 | else 248 | { 249 | message_position.x = camera_position.at(2, 0); 250 | message_position.y = -camera_position.at(0, 0); 251 | message_position.z = -camera_position.at(1, 0); 252 | 253 | message_rotation.x = camera_rotation.at(2, 0); 254 | message_rotation.y = -camera_rotation.at(0, 0); 255 | message_rotation.z = -camera_rotation.at(1, 0); 256 | } 257 | 258 | pub_position.publish(message_position); 259 | pub_rotation.publish(message_rotation); 260 | 261 | //Publish pose 262 | geometry_msgs::PoseStamped message_pose; 263 | 264 | //Header 265 | message_pose.header.frame_id = tf_frame_id; 266 | message_pose.header.seq = pub_pose_seq++; 267 | message_pose.header.stamp = ros::Time::now(); 268 | 269 | //Position 270 | message_pose.pose.position.x = message_position.x; 271 | message_pose.pose.position.y = message_position.y; 272 | message_pose.pose.position.z = message_position.z; 273 | 274 | //Convert to quaternion 275 | double x = message_rotation.x; 276 | double y = message_rotation.y; 277 | double z = message_rotation.z; 278 | 279 | //Module of angular velocity 280 | double angle = sqrt(x*x + y*y + z*z); 281 | if(angle > 0.0) 282 | { 283 | message_pose.pose.orientation.x = x * sin(angle/2.0)/angle; 284 | message_pose.pose.orientation.y = y * sin(angle/2.0)/angle; 285 | message_pose.pose.orientation.z = z * sin(angle/2.0)/angle; 286 | message_pose.pose.orientation.w = cos(angle/2.0); 287 | } 288 | //To avoid illegal expressions 289 | else 290 | { 291 | message_pose.pose.orientation.x = 0.0; 292 | message_pose.pose.orientation.y = 0.0; 293 | message_pose.pose.orientation.z = 0.0; 294 | message_pose.pose.orientation.w = 1.0; 295 | } 296 | 297 | pub_pose.publish(message_pose); 298 | 299 | nav_msgs::Odometry message_odometry; 300 | message_odometry.header.frame_id = tf_frame_id; 301 | message_odometry.header.stamp = ros::Time::now(); 302 | message_odometry.pose.pose = message_pose.pose; 303 | pub_odom.publish(message_odometry); 304 | 305 | //Debug 306 | if(debug) 307 | { 308 | ArucoDetector::drawOrigin(frame, found, calibration, distortion, 0.1); 309 | 310 | drawText(frame, "Position: " + to_string(message_position.x) + ", " + to_string(message_position.y) + ", " + to_string(message_position.z), Point2f(10, 180)); 311 | drawText(frame, "Rotation: " + to_string(message_rotation.x) + ", " + to_string(message_rotation.y) + ", " + to_string(message_rotation.z), Point2f(10, 200)); 312 | } 313 | } 314 | else if(debug) 315 | { 316 | drawText(frame, "Position: unknown", Point2f(10, 180)); 317 | drawText(frame, "Rotation: unknown", Point2f(10, 200)); 318 | } 319 | 320 | //Publish visible 321 | std_msgs::Bool message_visible; 322 | message_visible.data = world.size() != 0; 323 | pub_visible.publish(message_visible); 324 | 325 | //Debug info 326 | if(debug) 327 | { 328 | drawText(frame, "Aruco ROS Debug", Point2f(10, 20)); 329 | drawText(frame, "OpenCV V" + to_string(CV_MAJOR_VERSION) + "." + to_string(CV_MINOR_VERSION), Point2f(10, 40)); 330 | drawText(frame, "Cosine Limit (A-Q): " + to_string(cosine_limit), Point2f(10, 60)); 331 | drawText(frame, "Threshold Block (W-S): " + to_string(theshold_block_size), Point2f(10, 80)); 332 | drawText(frame, "Min Area (E-D): " + to_string(min_area), Point2f(10, 100)); 333 | drawText(frame, "MaxError PolyDP (R-F): " + to_string(max_error_quad), Point2f(10, 120)); 334 | drawText(frame, "Visible: " + to_string(message_visible.data), Point2f(10, 140)); 335 | drawText(frame, "Calibrated: " + to_string(calibrated), Point2f(10, 160)); 336 | 337 | imshow("Aruco", frame); 338 | 339 | char key = (char) waitKey(1); 340 | 341 | if(key == 'q') 342 | { 343 | cosine_limit += 0.05; 344 | } 345 | else if(key == 'a') 346 | { 347 | cosine_limit -= 0.05; 348 | } 349 | 350 | if(key == 'w') 351 | { 352 | theshold_block_size += 2; 353 | } 354 | else if(key == 's' && theshold_block_size > 3) 355 | { 356 | theshold_block_size -= 2; 357 | } 358 | 359 | if(key == 'r') 360 | { 361 | max_error_quad += 0.005; 362 | } 363 | else if(key == 'f') 364 | { 365 | max_error_quad -= 0.005; 366 | } 367 | 368 | if(key == 'e') 369 | { 370 | min_area += 50; 371 | } 372 | else if(key == 'd') 373 | { 374 | min_area -= 50; 375 | } 376 | } 377 | } 378 | catch(cv_bridge::Exception& e) 379 | { 380 | ROS_ERROR("Error getting image data"); 381 | } 382 | } 383 | 384 | /** 385 | * On camera info callback. 386 | * Used to receive camera calibration parameters. 387 | */ 388 | void onCameraInfo(const sensor_msgs::CameraInfo &msg) 389 | { 390 | if(!calibrated) 391 | { 392 | calibrated = true; 393 | 394 | for(unsigned int i = 0; i < 9; i++) 395 | { 396 | calibration.at(i / 3, i % 3) = msg.K[i]; 397 | } 398 | 399 | for(unsigned int i = 0; i < 5; i++) 400 | { 401 | distortion.at(0, i) = msg.D[i]; 402 | } 403 | 404 | if(debug) 405 | { 406 | cout << "Camera calibration param received" << endl; 407 | cout << "Camera: " << calibration << endl; 408 | cout << "Distortion: " << distortion << endl; 409 | } 410 | } 411 | } 412 | 413 | /** 414 | * Callback to register markers on the marker list. 415 | * This callback received a custom marker message. 416 | */ 417 | void onMarkerRegister(const aruco::Marker &msg) 418 | { 419 | for(unsigned int i = 0; i < known.size(); i++) 420 | { 421 | if(known[i].id == msg.id) 422 | { 423 | known.erase(known.begin() + i); 424 | cout << "Marker " << to_string(msg.id) << " already exists, was replaced." << endl; 425 | break; 426 | } 427 | } 428 | 429 | known.push_back(ArucoMarkerInfo(msg.id, msg.size, Point3d(msg.posx, msg.posy, msg.posz), Point3d(msg.rotx, msg.roty, msg.rotz))); 430 | cout << "Marker " << to_string(msg.id) << " added." << endl; 431 | } 432 | 433 | /** 434 | * Callback to remove markers from the marker list. 435 | * Markers are removed by publishing the remove ID to the remove topic. 436 | */ 437 | void onMarkerRemove(const std_msgs::Int32 &msg) 438 | { 439 | for(unsigned int i = 0; i < known.size(); i++) 440 | { 441 | if(known[i].id == msg.data) 442 | { 443 | known.erase(known.begin() + i); 444 | cout << "Marker " << to_string(msg.data) << " removed." << endl; 445 | break; 446 | } 447 | } 448 | } 449 | 450 | /** 451 | * Converts a string with numeric values separated by a delimiter to an array of double values. 452 | * If 0_1_2_3 and delimiter is _ array will contain {0, 1, 2, 3}. 453 | * @param data String to be converted 454 | * @param values Array to store values on 455 | * @param cout Number of elements in the string 456 | * @param delimiter Separator element 457 | * @return Array with values. 458 | */ 459 | void stringToDoubleArray(string data, double* values, unsigned int count, string delimiter) 460 | { 461 | unsigned int pos = 0, k = 0; 462 | 463 | while((pos = data.find(delimiter)) != string::npos && k < count) 464 | { 465 | string token = data.substr(0, pos); 466 | values[k] = stod(token); 467 | data.erase(0, pos + delimiter.length()); 468 | k++; 469 | } 470 | } 471 | 472 | /** 473 | * Main method launches aruco ros node, the node gets image and calibration parameters from camera, and publishes position and rotation of the camera relative to the markers. 474 | * Units should be in meters and radians, the markers are described by a position and an euler rotation. 475 | * Position is also available as a pose message that should be easier to consume by other ROS nodes. 476 | * Its possible to pass markers as arugment to this node or register and remove them during runtime using another ROS node. 477 | * The coordinate system used by OpenCV uses Z+ to represent depth, Y- for height and X+ for lateral, but for the node the coordinate system used is diferent X+ for depth, Z+ for height and Y- for lateral movement. 478 | * The coordinates are converted on input and on output, its possible to force the OpenCV coordinate system by setting the use_opencv_coords param to true. 479 | * 480 | * ROS | OpenCV 481 | * Z+ | Y- 482 | * | | | 483 | * | X+ | | Z+ 484 | * | / | | / 485 | * | / | | / 486 | * | / | | / 487 | * | / | | / 488 | * |/ | |/ 489 | * O-------------> Y- | O-------------> X+ 490 | * 491 | * @param argc Number of arguments. 492 | * @param argv Value of the arguments. 493 | */ 494 | int main(int argc, char **argv) 495 | { 496 | ros::init(argc, argv, "aruco"); 497 | 498 | //ROS node instance 499 | ros::NodeHandle node("aruco"); 500 | 501 | //Parameters 502 | node.param("debug", debug, false); 503 | node.param("use_opencv_coords", use_opencv_coords, false); 504 | node.param("cosine_limit", cosine_limit, 0.7); 505 | node.param("theshold_block_size_min", theshold_block_size_min, 3); 506 | node.param("theshold_block_size_max", theshold_block_size_max, 21); 507 | node.param("max_error_quad", max_error_quad, 0.035); 508 | node.param("min_area", min_area, 100); 509 | node.param("calibrated", calibrated, false); 510 | 511 | //Initial threshold block size 512 | theshold_block_size = (theshold_block_size_min + theshold_block_size_max) / 2; 513 | if(theshold_block_size % 2 == 0) 514 | { 515 | theshold_block_size++; 516 | } 517 | 518 | //Initialize calibration matrices 519 | calibration = Mat(3, 3, CV_64F, data_calibration); 520 | distortion = Mat(1, 5, CV_64F, data_distortion); 521 | 522 | //Camera instrinsic calibration parameters 523 | if(node.hasParam("calibration")) 524 | { 525 | string data; 526 | node.param("calibration", data, ""); 527 | 528 | double values[9]; 529 | stringToDoubleArray(data, values, 9, "_"); 530 | 531 | for(unsigned int i = 0; i < 9; i++) 532 | { 533 | calibration.at(i / 3, i % 3) = values[i]; 534 | } 535 | 536 | calibrated = true; 537 | } 538 | 539 | //Camera distortion calibration parameters 540 | if(node.hasParam("distortion")) 541 | { 542 | string data; 543 | node.param("distortion", data, ""); 544 | 545 | double values[5]; 546 | stringToDoubleArray(data, values, 5, "_"); 547 | 548 | for(unsigned int i = 0; i < 5; i++) 549 | { 550 | distortion.at(0, i) = values[i]; 551 | } 552 | 553 | calibrated = true; 554 | } 555 | 556 | //Aruco makers passed as parameters 557 | for(unsigned int i = 0; i < 1024; i++) 558 | { 559 | if(node.hasParam("marker" + to_string(i))) 560 | { 561 | string data; 562 | node.param("marker" + to_string(i), data, "1_0_0_0_0_0_0"); 563 | 564 | double values[7]; 565 | stringToDoubleArray(data, values, 7, "_"); 566 | 567 | //Use OpenCV coordinates 568 | if(use_opencv_coords) 569 | { 570 | known.push_back(ArucoMarkerInfo(i, values[0], Point3d(values[1], values[2], values[3]), Point3d(values[4], values[5], values[6]))); 571 | } 572 | //Convert coordinates (-Y, -Z, +X) 573 | else 574 | { 575 | known.push_back(ArucoMarkerInfo(i, values[0], Point3d(-values[2], -values[3], -values[1]), Point3d(-values[5], -values[6], values[4]))); 576 | } 577 | } 578 | } 579 | 580 | //Print all known markers 581 | if(debug) 582 | { 583 | for(unsigned int i = 0; i < known.size(); i++) 584 | { 585 | known[i].print(); 586 | } 587 | } 588 | 589 | // TF frame 590 | node.param("tf_frame_id", tf_frame_id, "robot"); 591 | 592 | //Subscribed topic names 593 | string topic_camera, topic_camera_info, topic_marker_register, topic_marker_remove; 594 | node.param("topic_camera", topic_camera, "/rgb/image"); 595 | node.param("topic_camera_info", topic_camera_info, "/rgb/camera_info"); 596 | node.param("topic_marker_register", topic_marker_register, "/marker_register"); 597 | node.param("topic_marker_remove", topic_marker_register, "/marker_remove"); 598 | 599 | //Publish topic names 600 | string topic_visible, topic_position, topic_rotation, topic_pose, topic_odom; 601 | node.param("topic_visible", topic_visible, "/visible"); 602 | node.param("topic_position", topic_position, "/position"); 603 | node.param("topic_rotation", topic_rotation, "/rotation"); 604 | node.param("topic_pose", topic_pose, "/pose"); 605 | node.param("topic_odom", topic_odom, "/odom"); 606 | 607 | //Advertise topics 608 | pub_visible = node.advertise(node.getNamespace() + topic_visible, 10); 609 | pub_position = node.advertise(node.getNamespace() + topic_position, 10); 610 | pub_rotation = node.advertise(node.getNamespace() + topic_rotation, 10); 611 | pub_pose = node.advertise(node.getNamespace() + topic_pose, 10); 612 | pub_odom = node.advertise(node.getNamespace() + topic_odom, 10); 613 | 614 | //Subscribe topics 615 | image_transport::ImageTransport it(node); 616 | image_transport::Subscriber sub_camera = it.subscribe(topic_camera, 1, onFrame); 617 | ros::Subscriber sub_camera_info = node.subscribe(topic_camera_info, 1, onCameraInfo); 618 | ros::Subscriber sub_marker_register = node.subscribe(topic_marker_register, 1, onMarkerRegister); 619 | ros::Subscriber sub_marker_remove = node.subscribe(topic_marker_remove, 1, onMarkerRemove); 620 | 621 | ros::spin(); 622 | 623 | return 0; 624 | } 625 | -------------------------------------------------------------------------------- /Doxyfile: -------------------------------------------------------------------------------- 1 | # Doxyfile 1.7.5.1 2 | 3 | # This file describes the settings to be used by the documentation system 4 | # doxygen (www.doxygen.org) for a project. 5 | # 6 | # All text after a hash (#) is considered a comment and will be ignored. 7 | # The format is: 8 | # TAG = value [value, ...] 9 | # For lists items can also be appended using: 10 | # TAG += value [value, ...] 11 | # Values that contain spaces should be placed between quotes (" "). 12 | 13 | #--------------------------------------------------------------------------- 14 | # Project related configuration options 15 | #--------------------------------------------------------------------------- 16 | 17 | # This tag specifies the encoding used for all characters in the config file 18 | # that follow. The default is UTF-8 which is also the encoding used for all 19 | # text before the first occurrence of this tag. Doxygen uses libiconv (or the 20 | # iconv built into libc) for the transcoding. See 21 | # http://www.gnu.org/software/libiconv for the list of possible encodings. 22 | 23 | DOXYFILE_ENCODING = UTF-8 24 | 25 | # The PROJECT_NAME tag is a single word (or sequence of words) that should 26 | # identify the project. Note that if you do not use Doxywizard you need 27 | # to put quotes around the project name if it contains spaces. 28 | 29 | PROJECT_NAME = Aruco 30 | 31 | # The PROJECT_NUMBER tag can be used to enter a project or revision number. 32 | # This could be handy for archiving the generated documentation or 33 | # if some version control system is used. 34 | 35 | PROJECT_NUMBER = 36 | 37 | # Using the PROJECT_BRIEF tag one can provide an optional one line description 38 | # for a project that appears at the top of each page and should give viewer 39 | # a quick idea about the purpose of the project. Keep the description short. 40 | 41 | PROJECT_BRIEF = 42 | 43 | # With the PROJECT_LOGO tag one can specify an logo or icon that is 44 | # included in the documentation. The maximum height of the logo should not 45 | # exceed 55 pixels and the maximum width should not exceed 200 pixels. 46 | # Doxygen will copy the logo to the output directory. 47 | 48 | PROJECT_LOGO = 49 | 50 | # The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) 51 | # base path where the generated documentation will be put. 52 | # If a relative path is entered, it will be relative to the location 53 | # where doxygen was started. If left blank the current directory will be used. 54 | 55 | OUTPUT_DIRECTORY = docs 56 | 57 | # If the CREATE_SUBDIRS tag is set to YES, then doxygen will create 58 | # 4096 sub-directories (in 2 levels) under the output directory of each output 59 | # format and will distribute the generated files over these directories. 60 | # Enabling this option can be useful when feeding doxygen a huge amount of 61 | # source files, where putting all generated files in the same directory would 62 | # otherwise cause performance problems for the file system. 63 | 64 | CREATE_SUBDIRS = NO 65 | 66 | # The OUTPUT_LANGUAGE tag is used to specify the language in which all 67 | # documentation generated by doxygen is written. Doxygen will use this 68 | # information to generate all constant output in the proper language. 69 | # The default language is English, other supported languages are: 70 | # Afrikaans, Arabic, Brazilian, Catalan, Chinese, Chinese-Traditional, 71 | # Croatian, Czech, Danish, Dutch, Esperanto, Farsi, Finnish, French, German, 72 | # Greek, Hungarian, Italian, Japanese, Japanese-en (Japanese with English 73 | # messages), Korean, Korean-en, Lithuanian, Norwegian, Macedonian, Persian, 74 | # Polish, Portuguese, Romanian, Russian, Serbian, Serbian-Cyrillic, Slovak, 75 | # Slovene, Spanish, Swedish, Ukrainian, and Vietnamese. 76 | 77 | OUTPUT_LANGUAGE = English 78 | 79 | # If the BRIEF_MEMBER_DESC tag is set to YES (the default) Doxygen will 80 | # include brief member descriptions after the members that are listed in 81 | # the file and class documentation (similar to JavaDoc). 82 | # Set to NO to disable this. 83 | 84 | BRIEF_MEMBER_DESC = YES 85 | 86 | # If the REPEAT_BRIEF tag is set to YES (the default) Doxygen will prepend 87 | # the brief description of a member or function before the detailed description. 88 | # Note: if both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the 89 | # brief descriptions will be completely suppressed. 90 | 91 | REPEAT_BRIEF = YES 92 | 93 | # This tag implements a quasi-intelligent brief description abbreviator 94 | # that is used to form the text in various listings. Each string 95 | # in this list, if found as the leading text of the brief description, will be 96 | # stripped from the text and the result after processing the whole list, is 97 | # used as the annotated text. Otherwise, the brief description is used as-is. 98 | # If left blank, the following values are used ("$name" is automatically 99 | # replaced with the name of the entity): "The $name class" "The $name widget" 100 | # "The $name file" "is" "provides" "specifies" "contains" 101 | # "represents" "a" "an" "the" 102 | 103 | ABBREVIATE_BRIEF = 104 | 105 | # If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then 106 | # Doxygen will generate a detailed section even if there is only a brief 107 | # description. 108 | 109 | ALWAYS_DETAILED_SEC = NO 110 | 111 | # If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all 112 | # inherited members of a class in the documentation of that class as if those 113 | # members were ordinary class members. Constructors, destructors and assignment 114 | # operators of the base classes will not be shown. 115 | 116 | INLINE_INHERITED_MEMB = NO 117 | 118 | # If the FULL_PATH_NAMES tag is set to YES then Doxygen will prepend the full 119 | # path before files name in the file list and in the header files. If set 120 | # to NO the shortest path that makes the file name unique will be used. 121 | 122 | FULL_PATH_NAMES = YES 123 | 124 | # If the FULL_PATH_NAMES tag is set to YES then the STRIP_FROM_PATH tag 125 | # can be used to strip a user-defined part of the path. Stripping is 126 | # only done if one of the specified strings matches the left-hand part of 127 | # the path. The tag can be used to show relative paths in the file list. 128 | # If left blank the directory from which doxygen is run is used as the 129 | # path to strip. 130 | 131 | STRIP_FROM_PATH = 132 | 133 | # The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of 134 | # the path mentioned in the documentation of a class, which tells 135 | # the reader which header file to include in order to use a class. 136 | # If left blank only the name of the header file containing the class 137 | # definition is used. Otherwise one should specify the include paths that 138 | # are normally passed to the compiler using the -I flag. 139 | 140 | STRIP_FROM_INC_PATH = 141 | 142 | # If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter 143 | # (but less readable) file names. This can be useful if your file system 144 | # doesn't support long names like on DOS, Mac, or CD-ROM. 145 | 146 | SHORT_NAMES = NO 147 | 148 | # If the JAVADOC_AUTOBRIEF tag is set to YES then Doxygen 149 | # will interpret the first line (until the first dot) of a JavaDoc-style 150 | # comment as the brief description. If set to NO, the JavaDoc 151 | # comments will behave just like regular Qt-style comments 152 | # (thus requiring an explicit @brief command for a brief description.) 153 | 154 | JAVADOC_AUTOBRIEF = NO 155 | 156 | # If the QT_AUTOBRIEF tag is set to YES then Doxygen will 157 | # interpret the first line (until the first dot) of a Qt-style 158 | # comment as the brief description. If set to NO, the comments 159 | # will behave just like regular Qt-style comments (thus requiring 160 | # an explicit \brief command for a brief description.) 161 | 162 | QT_AUTOBRIEF = NO 163 | 164 | # The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make Doxygen 165 | # treat a multi-line C++ special comment block (i.e. a block of //! or /// 166 | # comments) as a brief description. This used to be the default behaviour. 167 | # The new default is to treat a multi-line C++ comment block as a detailed 168 | # description. Set this tag to YES if you prefer the old behaviour instead. 169 | 170 | MULTILINE_CPP_IS_BRIEF = NO 171 | 172 | # If the INHERIT_DOCS tag is set to YES (the default) then an undocumented 173 | # member inherits the documentation from any documented member that it 174 | # re-implements. 175 | 176 | INHERIT_DOCS = YES 177 | 178 | # If the SEPARATE_MEMBER_PAGES tag is set to YES, then doxygen will produce 179 | # a new page for each member. If set to NO, the documentation of a member will 180 | # be part of the file/class/namespace that contains it. 181 | 182 | SEPARATE_MEMBER_PAGES = NO 183 | 184 | # The TAB_SIZE tag can be used to set the number of spaces in a tab. 185 | # Doxygen uses this value to replace tabs by spaces in code fragments. 186 | 187 | TAB_SIZE = 8 188 | 189 | # This tag can be used to specify a number of aliases that acts 190 | # as commands in the documentation. An alias has the form "name=value". 191 | # For example adding "sideeffect=\par Side Effects:\n" will allow you to 192 | # put the command \sideeffect (or @sideeffect) in the documentation, which 193 | # will result in a user-defined paragraph with heading "Side Effects:". 194 | # You can put \n's in the value part of an alias to insert newlines. 195 | 196 | ALIASES = 197 | 198 | # Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C 199 | # sources only. Doxygen will then generate output that is more tailored for C. 200 | # For instance, some of the names that are used will be different. The list 201 | # of all members will be omitted, etc. 202 | 203 | OPTIMIZE_OUTPUT_FOR_C = NO 204 | 205 | # Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java 206 | # sources only. Doxygen will then generate output that is more tailored for 207 | # Java. For instance, namespaces will be presented as packages, qualified 208 | # scopes will look different, etc. 209 | 210 | OPTIMIZE_OUTPUT_JAVA = NO 211 | 212 | # Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran 213 | # sources only. Doxygen will then generate output that is more tailored for 214 | # Fortran. 215 | 216 | OPTIMIZE_FOR_FORTRAN = NO 217 | 218 | # Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL 219 | # sources. Doxygen will then generate output that is tailored for 220 | # VHDL. 221 | 222 | OPTIMIZE_OUTPUT_VHDL = NO 223 | 224 | # Doxygen selects the parser to use depending on the extension of the files it 225 | # parses. With this tag you can assign which parser to use for a given extension. 226 | # Doxygen has a built-in mapping, but you can override or extend it using this 227 | # tag. The format is ext=language, where ext is a file extension, and language 228 | # is one of the parsers supported by doxygen: IDL, Java, Javascript, CSharp, C, 229 | # C++, D, PHP, Objective-C, Python, Fortran, VHDL, C, C++. For instance to make 230 | # doxygen treat .inc files as Fortran files (default is PHP), and .f files as C 231 | # (default is Fortran), use: inc=Fortran f=C. Note that for custom extensions 232 | # you also need to set FILE_PATTERNS otherwise the files are not read by doxygen. 233 | 234 | EXTENSION_MAPPING = 235 | 236 | # If you use STL classes (i.e. std::string, std::vector, etc.) but do not want 237 | # to include (a tag file for) the STL sources as input, then you should 238 | # set this tag to YES in order to let doxygen match functions declarations and 239 | # definitions whose arguments contain STL classes (e.g. func(std::string); v.s. 240 | # func(std::string) {}). This also makes the inheritance and collaboration 241 | # diagrams that involve STL classes more complete and accurate. 242 | 243 | BUILTIN_STL_SUPPORT = NO 244 | 245 | # If you use Microsoft's C++/CLI language, you should set this option to YES to 246 | # enable parsing support. 247 | 248 | CPP_CLI_SUPPORT = NO 249 | 250 | # Set the SIP_SUPPORT tag to YES if your project consists of sip sources only. 251 | # Doxygen will parse them like normal C++ but will assume all classes use public 252 | # instead of private inheritance when no explicit protection keyword is present. 253 | 254 | SIP_SUPPORT = NO 255 | 256 | # For Microsoft's IDL there are propget and propput attributes to indicate getter 257 | # and setter methods for a property. Setting this option to YES (the default) 258 | # will make doxygen replace the get and set methods by a property in the 259 | # documentation. This will only work if the methods are indeed getting or 260 | # setting a simple type. If this is not the case, or you want to show the 261 | # methods anyway, you should set this option to NO. 262 | 263 | IDL_PROPERTY_SUPPORT = YES 264 | 265 | # If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC 266 | # tag is set to YES, then doxygen will reuse the documentation of the first 267 | # member in the group (if any) for the other members of the group. By default 268 | # all members of a group must be documented explicitly. 269 | 270 | DISTRIBUTE_GROUP_DOC = NO 271 | 272 | # Set the SUBGROUPING tag to YES (the default) to allow class member groups of 273 | # the same type (for instance a group of public functions) to be put as a 274 | # subgroup of that type (e.g. under the Public Functions section). Set it to 275 | # NO to prevent subgrouping. Alternatively, this can be done per class using 276 | # the \nosubgrouping command. 277 | 278 | SUBGROUPING = YES 279 | 280 | # When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and 281 | # unions are shown inside the group in which they are included (e.g. using 282 | # @ingroup) instead of on a separate page (for HTML and Man pages) or 283 | # section (for LaTeX and RTF). 284 | 285 | INLINE_GROUPED_CLASSES = NO 286 | 287 | # When the INLINE_SIMPLE_STRUCTS tag is set to YES, structs, classes, and 288 | # unions with only public data fields will be shown inline in the documentation 289 | # of the scope in which they are defined (i.e. file, namespace, or group 290 | # documentation), provided this scope is documented. If set to NO (the default), 291 | # structs, classes, and unions are shown on a separate page (for HTML and Man 292 | # pages) or section (for LaTeX and RTF). 293 | 294 | INLINE_SIMPLE_STRUCTS = NO 295 | 296 | # When TYPEDEF_HIDES_STRUCT is enabled, a typedef of a struct, union, or enum 297 | # is documented as struct, union, or enum with the name of the typedef. So 298 | # typedef struct TypeS {} TypeT, will appear in the documentation as a struct 299 | # with name TypeT. When disabled the typedef will appear as a member of a file, 300 | # namespace, or class. And the struct will be named TypeS. This can typically 301 | # be useful for C code in case the coding convention dictates that all compound 302 | # types are typedef'ed and only the typedef is referenced, never the tag name. 303 | 304 | TYPEDEF_HIDES_STRUCT = NO 305 | 306 | # The SYMBOL_CACHE_SIZE determines the size of the internal cache use to 307 | # determine which symbols to keep in memory and which to flush to disk. 308 | # When the cache is full, less often used symbols will be written to disk. 309 | # For small to medium size projects (<1000 input files) the default value is 310 | # probably good enough. For larger projects a too small cache size can cause 311 | # doxygen to be busy swapping symbols to and from disk most of the time 312 | # causing a significant performance penalty. 313 | # If the system has enough physical memory increasing the cache will improve the 314 | # performance by keeping more symbols in memory. Note that the value works on 315 | # a logarithmic scale so increasing the size by one will roughly double the 316 | # memory usage. The cache size is given by this formula: 317 | # 2^(16+SYMBOL_CACHE_SIZE). The valid range is 0..9, the default is 0, 318 | # corresponding to a cache size of 2^16 = 65536 symbols 319 | 320 | SYMBOL_CACHE_SIZE = 0 321 | 322 | #--------------------------------------------------------------------------- 323 | # Build related configuration options 324 | #--------------------------------------------------------------------------- 325 | 326 | # If the EXTRACT_ALL tag is set to YES doxygen will assume all entities in 327 | # documentation are documented, even if no documentation was available. 328 | # Private class members and static file members will be hidden unless 329 | # the EXTRACT_PRIVATE and EXTRACT_STATIC tags are set to YES 330 | 331 | EXTRACT_ALL = YES 332 | 333 | # If the EXTRACT_PRIVATE tag is set to YES all private members of a class 334 | # will be included in the documentation. 335 | 336 | EXTRACT_PRIVATE = NO 337 | 338 | # If the EXTRACT_STATIC tag is set to YES all static members of a file 339 | # will be included in the documentation. 340 | 341 | EXTRACT_STATIC = NO 342 | 343 | # If the EXTRACT_LOCAL_CLASSES tag is set to YES classes (and structs) 344 | # defined locally in source files will be included in the documentation. 345 | # If set to NO only classes defined in header files are included. 346 | 347 | EXTRACT_LOCAL_CLASSES = YES 348 | 349 | # This flag is only useful for Objective-C code. When set to YES local 350 | # methods, which are defined in the implementation section but not in 351 | # the interface are included in the documentation. 352 | # If set to NO (the default) only methods in the interface are included. 353 | 354 | EXTRACT_LOCAL_METHODS = NO 355 | 356 | # If this flag is set to YES, the members of anonymous namespaces will be 357 | # extracted and appear in the documentation as a namespace called 358 | # 'anonymous_namespace{file}', where file will be replaced with the base 359 | # name of the file that contains the anonymous namespace. By default 360 | # anonymous namespaces are hidden. 361 | 362 | EXTRACT_ANON_NSPACES = NO 363 | 364 | # If the HIDE_UNDOC_MEMBERS tag is set to YES, Doxygen will hide all 365 | # undocumented members of documented classes, files or namespaces. 366 | # If set to NO (the default) these members will be included in the 367 | # various overviews, but no documentation section is generated. 368 | # This option has no effect if EXTRACT_ALL is enabled. 369 | 370 | HIDE_UNDOC_MEMBERS = NO 371 | 372 | # If the HIDE_UNDOC_CLASSES tag is set to YES, Doxygen will hide all 373 | # undocumented classes that are normally visible in the class hierarchy. 374 | # If set to NO (the default) these classes will be included in the various 375 | # overviews. This option has no effect if EXTRACT_ALL is enabled. 376 | 377 | HIDE_UNDOC_CLASSES = NO 378 | 379 | # If the HIDE_FRIEND_COMPOUNDS tag is set to YES, Doxygen will hide all 380 | # friend (class|struct|union) declarations. 381 | # If set to NO (the default) these declarations will be included in the 382 | # documentation. 383 | 384 | HIDE_FRIEND_COMPOUNDS = NO 385 | 386 | # If the HIDE_IN_BODY_DOCS tag is set to YES, Doxygen will hide any 387 | # documentation blocks found inside the body of a function. 388 | # If set to NO (the default) these blocks will be appended to the 389 | # function's detailed documentation block. 390 | 391 | HIDE_IN_BODY_DOCS = NO 392 | 393 | # The INTERNAL_DOCS tag determines if documentation 394 | # that is typed after a \internal command is included. If the tag is set 395 | # to NO (the default) then the documentation will be excluded. 396 | # Set it to YES to include the internal documentation. 397 | 398 | INTERNAL_DOCS = NO 399 | 400 | # If the CASE_SENSE_NAMES tag is set to NO then Doxygen will only generate 401 | # file names in lower-case letters. If set to YES upper-case letters are also 402 | # allowed. This is useful if you have classes or files whose names only differ 403 | # in case and if your file system supports case sensitive file names. Windows 404 | # and Mac users are advised to set this option to NO. 405 | 406 | CASE_SENSE_NAMES = NO 407 | 408 | # If the HIDE_SCOPE_NAMES tag is set to NO (the default) then Doxygen 409 | # will show members with their full class and namespace scopes in the 410 | # documentation. If set to YES the scope will be hidden. 411 | 412 | HIDE_SCOPE_NAMES = NO 413 | 414 | # If the SHOW_INCLUDE_FILES tag is set to YES (the default) then Doxygen 415 | # will put a list of the files that are included by a file in the documentation 416 | # of that file. 417 | 418 | SHOW_INCLUDE_FILES = YES 419 | 420 | # If the FORCE_LOCAL_INCLUDES tag is set to YES then Doxygen 421 | # will list include files with double quotes in the documentation 422 | # rather than with sharp brackets. 423 | 424 | FORCE_LOCAL_INCLUDES = NO 425 | 426 | # If the INLINE_INFO tag is set to YES (the default) then a tag [inline] 427 | # is inserted in the documentation for inline members. 428 | 429 | INLINE_INFO = YES 430 | 431 | # If the SORT_MEMBER_DOCS tag is set to YES (the default) then doxygen 432 | # will sort the (detailed) documentation of file and class members 433 | # alphabetically by member name. If set to NO the members will appear in 434 | # declaration order. 435 | 436 | SORT_MEMBER_DOCS = YES 437 | 438 | # If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the 439 | # brief documentation of file, namespace and class members alphabetically 440 | # by member name. If set to NO (the default) the members will appear in 441 | # declaration order. 442 | 443 | SORT_BRIEF_DOCS = NO 444 | 445 | # If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen 446 | # will sort the (brief and detailed) documentation of class members so that 447 | # constructors and destructors are listed first. If set to NO (the default) 448 | # the constructors will appear in the respective orders defined by 449 | # SORT_MEMBER_DOCS and SORT_BRIEF_DOCS. 450 | # This tag will be ignored for brief docs if SORT_BRIEF_DOCS is set to NO 451 | # and ignored for detailed docs if SORT_MEMBER_DOCS is set to NO. 452 | 453 | SORT_MEMBERS_CTORS_1ST = NO 454 | 455 | # If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the 456 | # hierarchy of group names into alphabetical order. If set to NO (the default) 457 | # the group names will appear in their defined order. 458 | 459 | SORT_GROUP_NAMES = NO 460 | 461 | # If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be 462 | # sorted by fully-qualified names, including namespaces. If set to 463 | # NO (the default), the class list will be sorted only by class name, 464 | # not including the namespace part. 465 | # Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES. 466 | # Note: This option applies only to the class list, not to the 467 | # alphabetical list. 468 | 469 | SORT_BY_SCOPE_NAME = NO 470 | 471 | # If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to 472 | # do proper type resolution of all parameters of a function it will reject a 473 | # match between the prototype and the implementation of a member function even 474 | # if there is only one candidate or it is obvious which candidate to choose 475 | # by doing a simple string match. By disabling STRICT_PROTO_MATCHING doxygen 476 | # will still accept a match between prototype and implementation in such cases. 477 | 478 | STRICT_PROTO_MATCHING = NO 479 | 480 | # The GENERATE_TODOLIST tag can be used to enable (YES) or 481 | # disable (NO) the todo list. This list is created by putting \todo 482 | # commands in the documentation. 483 | 484 | GENERATE_TODOLIST = YES 485 | 486 | # The GENERATE_TESTLIST tag can be used to enable (YES) or 487 | # disable (NO) the test list. This list is created by putting \test 488 | # commands in the documentation. 489 | 490 | GENERATE_TESTLIST = YES 491 | 492 | # The GENERATE_BUGLIST tag can be used to enable (YES) or 493 | # disable (NO) the bug list. This list is created by putting \bug 494 | # commands in the documentation. 495 | 496 | GENERATE_BUGLIST = YES 497 | 498 | # The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or 499 | # disable (NO) the deprecated list. This list is created by putting 500 | # \deprecated commands in the documentation. 501 | 502 | GENERATE_DEPRECATEDLIST= YES 503 | 504 | # The ENABLED_SECTIONS tag can be used to enable conditional 505 | # documentation sections, marked by \if sectionname ... \endif. 506 | 507 | ENABLED_SECTIONS = 508 | 509 | # The MAX_INITIALIZER_LINES tag determines the maximum number of lines 510 | # the initial value of a variable or macro consists of for it to appear in 511 | # the documentation. If the initializer consists of more lines than specified 512 | # here it will be hidden. Use a value of 0 to hide initializers completely. 513 | # The appearance of the initializer of individual variables and macros in the 514 | # documentation can be controlled using \showinitializer or \hideinitializer 515 | # command in the documentation regardless of this setting. 516 | 517 | MAX_INITIALIZER_LINES = 30 518 | 519 | # Set the SHOW_USED_FILES tag to NO to disable the list of files generated 520 | # at the bottom of the documentation of classes and structs. If set to YES the 521 | # list will mention the files that were used to generate the documentation. 522 | 523 | SHOW_USED_FILES = YES 524 | 525 | # If the sources in your project are distributed over multiple directories 526 | # then setting the SHOW_DIRECTORIES tag to YES will show the directory hierarchy 527 | # in the documentation. The default is NO. 528 | 529 | SHOW_DIRECTORIES = NO 530 | 531 | # Set the SHOW_FILES tag to NO to disable the generation of the Files page. 532 | # This will remove the Files entry from the Quick Index and from the 533 | # Folder Tree View (if specified). The default is YES. 534 | 535 | SHOW_FILES = YES 536 | 537 | # Set the SHOW_NAMESPACES tag to NO to disable the generation of the 538 | # Namespaces page. 539 | # This will remove the Namespaces entry from the Quick Index 540 | # and from the Folder Tree View (if specified). The default is YES. 541 | 542 | SHOW_NAMESPACES = YES 543 | 544 | # The FILE_VERSION_FILTER tag can be used to specify a program or script that 545 | # doxygen should invoke to get the current version for each file (typically from 546 | # the version control system). Doxygen will invoke the program by executing (via 547 | # popen()) the command , where is the value of 548 | # the FILE_VERSION_FILTER tag, and is the name of an input file 549 | # provided by doxygen. Whatever the program writes to standard output 550 | # is used as the file version. See the manual for examples. 551 | 552 | FILE_VERSION_FILTER = 553 | 554 | # The LAYOUT_FILE tag can be used to specify a layout file which will be parsed 555 | # by doxygen. The layout file controls the global structure of the generated 556 | # output files in an output format independent way. The create the layout file 557 | # that represents doxygen's defaults, run doxygen with the -l option. 558 | # You can optionally specify a file name after the option, if omitted 559 | # DoxygenLayout.xml will be used as the name of the layout file. 560 | 561 | LAYOUT_FILE = 562 | 563 | # The CITE_BIB_FILES tag can be used to specify one or more bib files 564 | # containing the references data. This must be a list of .bib files. The 565 | # .bib extension is automatically appended if omitted. Using this command 566 | # requires the bibtex tool to be installed. See also 567 | # http://en.wikipedia.org/wiki/BibTeX for more info. For LaTeX the style 568 | # of the bibliography can be controlled using LATEX_BIB_STYLE. 569 | 570 | CITE_BIB_FILES = 571 | 572 | #--------------------------------------------------------------------------- 573 | # configuration options related to warning and progress messages 574 | #--------------------------------------------------------------------------- 575 | 576 | # The QUIET tag can be used to turn on/off the messages that are generated 577 | # by doxygen. Possible values are YES and NO. If left blank NO is used. 578 | 579 | QUIET = NO 580 | 581 | # The WARNINGS tag can be used to turn on/off the warning messages that are 582 | # generated by doxygen. Possible values are YES and NO. If left blank 583 | # NO is used. 584 | 585 | WARNINGS = YES 586 | 587 | # If WARN_IF_UNDOCUMENTED is set to YES, then doxygen will generate warnings 588 | # for undocumented members. If EXTRACT_ALL is set to YES then this flag will 589 | # automatically be disabled. 590 | 591 | WARN_IF_UNDOCUMENTED = YES 592 | 593 | # If WARN_IF_DOC_ERROR is set to YES, doxygen will generate warnings for 594 | # potential errors in the documentation, such as not documenting some 595 | # parameters in a documented function, or documenting parameters that 596 | # don't exist or using markup commands wrongly. 597 | 598 | WARN_IF_DOC_ERROR = YES 599 | 600 | # The WARN_NO_PARAMDOC option can be enabled to get warnings for 601 | # functions that are documented, but have no documentation for their parameters 602 | # or return value. If set to NO (the default) doxygen will only warn about 603 | # wrong or incomplete parameter documentation, but not about the absence of 604 | # documentation. 605 | 606 | WARN_NO_PARAMDOC = NO 607 | 608 | # The WARN_FORMAT tag determines the format of the warning messages that 609 | # doxygen can produce. The string should contain the $file, $line, and $text 610 | # tags, which will be replaced by the file and line number from which the 611 | # warning originated and the warning text. Optionally the format may contain 612 | # $version, which will be replaced by the version of the file (if it could 613 | # be obtained via FILE_VERSION_FILTER) 614 | 615 | WARN_FORMAT = "$file:$line: $text" 616 | 617 | # The WARN_LOGFILE tag can be used to specify a file to which warning 618 | # and error messages should be written. If left blank the output is written 619 | # to stderr. 620 | 621 | WARN_LOGFILE = 622 | 623 | #--------------------------------------------------------------------------- 624 | # configuration options related to the input files 625 | #--------------------------------------------------------------------------- 626 | 627 | # The INPUT tag can be used to specify the files and/or directories that contain 628 | # documented source files. You may enter file names like "myfile.cpp" or 629 | # directories like "/usr/src/myproject". Separate the files or directories 630 | # with spaces. 631 | 632 | INPUT = 633 | 634 | # This tag can be used to specify the character encoding of the source files 635 | # that doxygen parses. Internally doxygen uses the UTF-8 encoding, which is 636 | # also the default input encoding. Doxygen uses libiconv (or the iconv built 637 | # into libc) for the transcoding. See http://www.gnu.org/software/libiconv for 638 | # the list of possible encodings. 639 | 640 | INPUT_ENCODING = UTF-8 641 | 642 | # If the value of the INPUT tag contains directories, you can use the 643 | # FILE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp 644 | # and *.h) to filter out the source-files in the directories. If left 645 | # blank the following patterns are tested: 646 | # *.c *.cc *.cxx *.cpp *.c++ *.d *.java *.ii *.ixx *.ipp *.i++ *.inl *.h *.hh 647 | # *.hxx *.hpp *.h++ *.idl *.odl *.cs *.php *.php3 *.inc *.m *.mm *.dox *.py 648 | # *.f90 *.f *.for *.vhd *.vhdl 649 | 650 | FILE_PATTERNS = 651 | 652 | # The RECURSIVE tag can be used to turn specify whether or not subdirectories 653 | # should be searched for input files as well. Possible values are YES and NO. 654 | # If left blank NO is used. 655 | 656 | RECURSIVE = NO 657 | 658 | # The EXCLUDE tag can be used to specify files and/or directories that should 659 | # excluded from the INPUT source files. This way you can easily exclude a 660 | # subdirectory from a directory tree whose root is specified with the INPUT tag. 661 | # Note that relative paths are relative to directory from which doxygen is run. 662 | 663 | EXCLUDE = 664 | 665 | # The EXCLUDE_SYMLINKS tag can be used select whether or not files or 666 | # directories that are symbolic links (a Unix file system feature) are excluded 667 | # from the input. 668 | 669 | EXCLUDE_SYMLINKS = NO 670 | 671 | # If the value of the INPUT tag contains directories, you can use the 672 | # EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude 673 | # certain files from those directories. Note that the wildcards are matched 674 | # against the file with absolute path, so to exclude all test directories 675 | # for example use the pattern */test/* 676 | 677 | EXCLUDE_PATTERNS = 678 | 679 | # The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names 680 | # (namespaces, classes, functions, etc.) that should be excluded from the 681 | # output. The symbol name can be a fully qualified name, a word, or if the 682 | # wildcard * is used, a substring. Examples: ANamespace, AClass, 683 | # AClass::ANamespace, ANamespace::*Test 684 | 685 | EXCLUDE_SYMBOLS = 686 | 687 | # The EXAMPLE_PATH tag can be used to specify one or more files or 688 | # directories that contain example code fragments that are included (see 689 | # the \include command). 690 | 691 | EXAMPLE_PATH = 692 | 693 | # If the value of the EXAMPLE_PATH tag contains directories, you can use the 694 | # EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp 695 | # and *.h) to filter out the source-files in the directories. If left 696 | # blank all files are included. 697 | 698 | EXAMPLE_PATTERNS = 699 | 700 | # If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be 701 | # searched for input files to be used with the \include or \dontinclude 702 | # commands irrespective of the value of the RECURSIVE tag. 703 | # Possible values are YES and NO. If left blank NO is used. 704 | 705 | EXAMPLE_RECURSIVE = NO 706 | 707 | # The IMAGE_PATH tag can be used to specify one or more files or 708 | # directories that contain image that are included in the documentation (see 709 | # the \image command). 710 | 711 | IMAGE_PATH = 712 | 713 | # The INPUT_FILTER tag can be used to specify a program that doxygen should 714 | # invoke to filter for each input file. Doxygen will invoke the filter program 715 | # by executing (via popen()) the command , where 716 | # is the value of the INPUT_FILTER tag, and is the name of an 717 | # input file. Doxygen will then use the output that the filter program writes 718 | # to standard output. 719 | # If FILTER_PATTERNS is specified, this tag will be 720 | # ignored. 721 | 722 | INPUT_FILTER = 723 | 724 | # The FILTER_PATTERNS tag can be used to specify filters on a per file pattern 725 | # basis. 726 | # Doxygen will compare the file name with each pattern and apply the 727 | # filter if there is a match. 728 | # The filters are a list of the form: 729 | # pattern=filter (like *.cpp=my_cpp_filter). See INPUT_FILTER for further 730 | # info on how filters are used. If FILTER_PATTERNS is empty or if 731 | # non of the patterns match the file name, INPUT_FILTER is applied. 732 | 733 | FILTER_PATTERNS = 734 | 735 | # If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using 736 | # INPUT_FILTER) will be used to filter the input files when producing source 737 | # files to browse (i.e. when SOURCE_BROWSER is set to YES). 738 | 739 | FILTER_SOURCE_FILES = NO 740 | 741 | # The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file 742 | # pattern. A pattern will override the setting for FILTER_PATTERN (if any) 743 | # and it is also possible to disable source filtering for a specific pattern 744 | # using *.ext= (so without naming a filter). This option only has effect when 745 | # FILTER_SOURCE_FILES is enabled. 746 | 747 | FILTER_SOURCE_PATTERNS = 748 | 749 | #--------------------------------------------------------------------------- 750 | # configuration options related to source browsing 751 | #--------------------------------------------------------------------------- 752 | 753 | # If the SOURCE_BROWSER tag is set to YES then a list of source files will 754 | # be generated. Documented entities will be cross-referenced with these sources. 755 | # Note: To get rid of all source code in the generated output, make sure also 756 | # VERBATIM_HEADERS is set to NO. 757 | 758 | SOURCE_BROWSER = NO 759 | 760 | # Setting the INLINE_SOURCES tag to YES will include the body 761 | # of functions and classes directly in the documentation. 762 | 763 | INLINE_SOURCES = YES 764 | 765 | # Setting the STRIP_CODE_COMMENTS tag to YES (the default) will instruct 766 | # doxygen to hide any special comment blocks from generated source code 767 | # fragments. Normal C and C++ comments will always remain visible. 768 | 769 | STRIP_CODE_COMMENTS = YES 770 | 771 | # If the REFERENCED_BY_RELATION tag is set to YES 772 | # then for each documented function all documented 773 | # functions referencing it will be listed. 774 | 775 | REFERENCED_BY_RELATION = NO 776 | 777 | # If the REFERENCES_RELATION tag is set to YES 778 | # then for each documented function all documented entities 779 | # called/used by that function will be listed. 780 | 781 | REFERENCES_RELATION = NO 782 | 783 | # If the REFERENCES_LINK_SOURCE tag is set to YES (the default) 784 | # and SOURCE_BROWSER tag is set to YES, then the hyperlinks from 785 | # functions in REFERENCES_RELATION and REFERENCED_BY_RELATION lists will 786 | # link to the source code. 787 | # Otherwise they will link to the documentation. 788 | 789 | REFERENCES_LINK_SOURCE = YES 790 | 791 | # If the USE_HTAGS tag is set to YES then the references to source code 792 | # will point to the HTML generated by the htags(1) tool instead of doxygen 793 | # built-in source browser. The htags tool is part of GNU's global source 794 | # tagging system (see http://www.gnu.org/software/global/global.html). You 795 | # will need version 4.8.6 or higher. 796 | 797 | USE_HTAGS = NO 798 | 799 | # If the VERBATIM_HEADERS tag is set to YES (the default) then Doxygen 800 | # will generate a verbatim copy of the header file for each class for 801 | # which an include is specified. Set to NO to disable this. 802 | 803 | VERBATIM_HEADERS = YES 804 | 805 | #--------------------------------------------------------------------------- 806 | # configuration options related to the alphabetical class index 807 | #--------------------------------------------------------------------------- 808 | 809 | # If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index 810 | # of all compounds will be generated. Enable this if the project 811 | # contains a lot of classes, structs, unions or interfaces. 812 | 813 | ALPHABETICAL_INDEX = YES 814 | 815 | # If the alphabetical index is enabled (see ALPHABETICAL_INDEX) then 816 | # the COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns 817 | # in which this list will be split (can be a number in the range [1..20]) 818 | 819 | COLS_IN_ALPHA_INDEX = 5 820 | 821 | # In case all classes in a project start with a common prefix, all 822 | # classes will be put under the same header in the alphabetical index. 823 | # The IGNORE_PREFIX tag can be used to specify one or more prefixes that 824 | # should be ignored while generating the index headers. 825 | 826 | IGNORE_PREFIX = 827 | 828 | #--------------------------------------------------------------------------- 829 | # configuration options related to the HTML output 830 | #--------------------------------------------------------------------------- 831 | 832 | # If the GENERATE_HTML tag is set to YES (the default) Doxygen will 833 | # generate HTML output. 834 | 835 | GENERATE_HTML = YES 836 | 837 | # The HTML_OUTPUT tag is used to specify where the HTML docs will be put. 838 | # If a relative path is entered the value of OUTPUT_DIRECTORY will be 839 | # put in front of it. If left blank `html' will be used as the default path. 840 | 841 | HTML_OUTPUT = html 842 | 843 | # The HTML_FILE_EXTENSION tag can be used to specify the file extension for 844 | # each generated HTML page (for example: .htm,.php,.asp). If it is left blank 845 | # doxygen will generate files with .html extension. 846 | 847 | HTML_FILE_EXTENSION = .html 848 | 849 | # The HTML_HEADER tag can be used to specify a personal HTML header for 850 | # each generated HTML page. If it is left blank doxygen will generate a 851 | # standard header. Note that when using a custom header you are responsible 852 | # for the proper inclusion of any scripts and style sheets that doxygen 853 | # needs, which is dependent on the configuration options used. 854 | # It is adviced to generate a default header using "doxygen -w html 855 | # header.html footer.html stylesheet.css YourConfigFile" and then modify 856 | # that header. Note that the header is subject to change so you typically 857 | # have to redo this when upgrading to a newer version of doxygen or when 858 | # changing the value of configuration settings such as GENERATE_TREEVIEW! 859 | 860 | HTML_HEADER = 861 | 862 | # The HTML_FOOTER tag can be used to specify a personal HTML footer for 863 | # each generated HTML page. If it is left blank doxygen will generate a 864 | # standard footer. 865 | 866 | HTML_FOOTER = 867 | 868 | # The HTML_STYLESHEET tag can be used to specify a user-defined cascading 869 | # style sheet that is used by each HTML page. It can be used to 870 | # fine-tune the look of the HTML output. If the tag is left blank doxygen 871 | # will generate a default style sheet. Note that doxygen will try to copy 872 | # the style sheet file to the HTML output directory, so don't put your own 873 | # stylesheet in the HTML output directory as well, or it will be erased! 874 | 875 | HTML_STYLESHEET = 876 | 877 | # The HTML_EXTRA_FILES tag can be used to specify one or more extra images or 878 | # other source files which should be copied to the HTML output directory. Note 879 | # that these files will be copied to the base HTML output directory. Use the 880 | # $relpath$ marker in the HTML_HEADER and/or HTML_FOOTER files to load these 881 | # files. In the HTML_STYLESHEET file, use the file name only. Also note that 882 | # the files will be copied as-is; there are no commands or markers available. 883 | 884 | HTML_EXTRA_FILES = 885 | 886 | # The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. 887 | # Doxygen will adjust the colors in the stylesheet and background images 888 | # according to this color. Hue is specified as an angle on a colorwheel, 889 | # see http://en.wikipedia.org/wiki/Hue for more information. 890 | # For instance the value 0 represents red, 60 is yellow, 120 is green, 891 | # 180 is cyan, 240 is blue, 300 purple, and 360 is red again. 892 | # The allowed range is 0 to 359. 893 | 894 | HTML_COLORSTYLE_HUE = 220 895 | 896 | # The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of 897 | # the colors in the HTML output. For a value of 0 the output will use 898 | # grayscales only. A value of 255 will produce the most vivid colors. 899 | 900 | HTML_COLORSTYLE_SAT = 100 901 | 902 | # The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to 903 | # the luminance component of the colors in the HTML output. Values below 904 | # 100 gradually make the output lighter, whereas values above 100 make 905 | # the output darker. The value divided by 100 is the actual gamma applied, 906 | # so 80 represents a gamma of 0.8, The value 220 represents a gamma of 2.2, 907 | # and 100 does not change the gamma. 908 | 909 | HTML_COLORSTYLE_GAMMA = 80 910 | 911 | # If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML 912 | # page will contain the date and time when the page was generated. Setting 913 | # this to NO can help when comparing the output of multiple runs. 914 | 915 | HTML_TIMESTAMP = YES 916 | 917 | # If the HTML_ALIGN_MEMBERS tag is set to YES, the members of classes, 918 | # files or namespaces will be aligned in HTML using tables. If set to 919 | # NO a bullet list will be used. 920 | 921 | HTML_ALIGN_MEMBERS = YES 922 | 923 | # If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML 924 | # documentation will contain sections that can be hidden and shown after the 925 | # page has loaded. For this to work a browser that supports 926 | # JavaScript and DHTML is required (for instance Mozilla 1.0+, Firefox 927 | # Netscape 6.0+, Internet explorer 5.0+, Konqueror, or Safari). 928 | 929 | HTML_DYNAMIC_SECTIONS = NO 930 | 931 | # If the GENERATE_DOCSET tag is set to YES, additional index files 932 | # will be generated that can be used as input for Apple's Xcode 3 933 | # integrated development environment, introduced with OSX 10.5 (Leopard). 934 | # To create a documentation set, doxygen will generate a Makefile in the 935 | # HTML output directory. Running make will produce the docset in that 936 | # directory and running "make install" will install the docset in 937 | # ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find 938 | # it at startup. 939 | # See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html 940 | # for more information. 941 | 942 | GENERATE_DOCSET = NO 943 | 944 | # When GENERATE_DOCSET tag is set to YES, this tag determines the name of the 945 | # feed. A documentation feed provides an umbrella under which multiple 946 | # documentation sets from a single provider (such as a company or product suite) 947 | # can be grouped. 948 | 949 | DOCSET_FEEDNAME = "Doxygen generated docs" 950 | 951 | # When GENERATE_DOCSET tag is set to YES, this tag specifies a string that 952 | # should uniquely identify the documentation set bundle. This should be a 953 | # reverse domain-name style string, e.g. com.mycompany.MyDocSet. Doxygen 954 | # will append .docset to the name. 955 | 956 | DOCSET_BUNDLE_ID = org.doxygen.Project 957 | 958 | # When GENERATE_PUBLISHER_ID tag specifies a string that should uniquely identify 959 | # the documentation publisher. This should be a reverse domain-name style 960 | # string, e.g. com.mycompany.MyDocSet.documentation. 961 | 962 | DOCSET_PUBLISHER_ID = org.doxygen.Publisher 963 | 964 | # The GENERATE_PUBLISHER_NAME tag identifies the documentation publisher. 965 | 966 | DOCSET_PUBLISHER_NAME = Publisher 967 | 968 | # If the GENERATE_HTMLHELP tag is set to YES, additional index files 969 | # will be generated that can be used as input for tools like the 970 | # Microsoft HTML help workshop to generate a compiled HTML help file (.chm) 971 | # of the generated HTML documentation. 972 | 973 | GENERATE_HTMLHELP = NO 974 | 975 | # If the GENERATE_HTMLHELP tag is set to YES, the CHM_FILE tag can 976 | # be used to specify the file name of the resulting .chm file. You 977 | # can add a path in front of the file if the result should not be 978 | # written to the html output directory. 979 | 980 | CHM_FILE = 981 | 982 | # If the GENERATE_HTMLHELP tag is set to YES, the HHC_LOCATION tag can 983 | # be used to specify the location (absolute path including file name) of 984 | # the HTML help compiler (hhc.exe). If non-empty doxygen will try to run 985 | # the HTML help compiler on the generated index.hhp. 986 | 987 | HHC_LOCATION = 988 | 989 | # If the GENERATE_HTMLHELP tag is set to YES, the GENERATE_CHI flag 990 | # controls if a separate .chi index file is generated (YES) or that 991 | # it should be included in the master .chm file (NO). 992 | 993 | GENERATE_CHI = NO 994 | 995 | # If the GENERATE_HTMLHELP tag is set to YES, the CHM_INDEX_ENCODING 996 | # is used to encode HtmlHelp index (hhk), content (hhc) and project file 997 | # content. 998 | 999 | CHM_INDEX_ENCODING = 1000 | 1001 | # If the GENERATE_HTMLHELP tag is set to YES, the BINARY_TOC flag 1002 | # controls whether a binary table of contents is generated (YES) or a 1003 | # normal table of contents (NO) in the .chm file. 1004 | 1005 | BINARY_TOC = NO 1006 | 1007 | # The TOC_EXPAND flag can be set to YES to add extra items for group members 1008 | # to the contents of the HTML help documentation and to the tree view. 1009 | 1010 | TOC_EXPAND = NO 1011 | 1012 | # If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and 1013 | # QHP_VIRTUAL_FOLDER are set, an additional index file will be generated 1014 | # that can be used as input for Qt's qhelpgenerator to generate a 1015 | # Qt Compressed Help (.qch) of the generated HTML documentation. 1016 | 1017 | GENERATE_QHP = NO 1018 | 1019 | # If the QHG_LOCATION tag is specified, the QCH_FILE tag can 1020 | # be used to specify the file name of the resulting .qch file. 1021 | # The path specified is relative to the HTML output folder. 1022 | 1023 | QCH_FILE = 1024 | 1025 | # The QHP_NAMESPACE tag specifies the namespace to use when generating 1026 | # Qt Help Project output. For more information please see 1027 | # http://doc.trolltech.com/qthelpproject.html#namespace 1028 | 1029 | QHP_NAMESPACE = org.doxygen.Project 1030 | 1031 | # The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating 1032 | # Qt Help Project output. For more information please see 1033 | # http://doc.trolltech.com/qthelpproject.html#virtual-folders 1034 | 1035 | QHP_VIRTUAL_FOLDER = doc 1036 | 1037 | # If QHP_CUST_FILTER_NAME is set, it specifies the name of a custom filter to 1038 | # add. For more information please see 1039 | # http://doc.trolltech.com/qthelpproject.html#custom-filters 1040 | 1041 | QHP_CUST_FILTER_NAME = 1042 | 1043 | # The QHP_CUST_FILT_ATTRS tag specifies the list of the attributes of the 1044 | # custom filter to add. For more information please see 1045 | # 1046 | # Qt Help Project / Custom Filters. 1047 | 1048 | QHP_CUST_FILTER_ATTRS = 1049 | 1050 | # The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this 1051 | # project's 1052 | # filter section matches. 1053 | # 1054 | # Qt Help Project / Filter Attributes. 1055 | 1056 | QHP_SECT_FILTER_ATTRS = 1057 | 1058 | # If the GENERATE_QHP tag is set to YES, the QHG_LOCATION tag can 1059 | # be used to specify the location of Qt's qhelpgenerator. 1060 | # If non-empty doxygen will try to run qhelpgenerator on the generated 1061 | # .qhp file. 1062 | 1063 | QHG_LOCATION = 1064 | 1065 | # If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files 1066 | # will be generated, which together with the HTML files, form an Eclipse help 1067 | # plugin. To install this plugin and make it available under the help contents 1068 | # menu in Eclipse, the contents of the directory containing the HTML and XML 1069 | # files needs to be copied into the plugins directory of eclipse. The name of 1070 | # the directory within the plugins directory should be the same as 1071 | # the ECLIPSE_DOC_ID value. After copying Eclipse needs to be restarted before 1072 | # the help appears. 1073 | 1074 | GENERATE_ECLIPSEHELP = NO 1075 | 1076 | # A unique identifier for the eclipse help plugin. When installing the plugin 1077 | # the directory name containing the HTML and XML files should also have 1078 | # this name. 1079 | 1080 | ECLIPSE_DOC_ID = org.doxygen.Project 1081 | 1082 | # The DISABLE_INDEX tag can be used to turn on/off the condensed index at 1083 | # top of each HTML page. The value NO (the default) enables the index and 1084 | # the value YES disables it. 1085 | 1086 | DISABLE_INDEX = NO 1087 | 1088 | # The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values 1089 | # (range [0,1..20]) that doxygen will group on one line in the generated HTML 1090 | # documentation. Note that a value of 0 will completely suppress the enum 1091 | # values from appearing in the overview section. 1092 | 1093 | ENUM_VALUES_PER_LINE = 4 1094 | 1095 | # The GENERATE_TREEVIEW tag is used to specify whether a tree-like index 1096 | # structure should be generated to display hierarchical information. 1097 | # If the tag value is set to YES, a side panel will be generated 1098 | # containing a tree-like index structure (just like the one that 1099 | # is generated for HTML Help). For this to work a browser that supports 1100 | # JavaScript, DHTML, CSS and frames is required (i.e. any modern browser). 1101 | # Windows users are probably better off using the HTML help feature. 1102 | 1103 | GENERATE_TREEVIEW = NO 1104 | 1105 | # By enabling USE_INLINE_TREES, doxygen will generate the Groups, Directories, 1106 | # and Class Hierarchy pages using a tree view instead of an ordered list. 1107 | 1108 | USE_INLINE_TREES = NO 1109 | 1110 | # If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be 1111 | # used to set the initial width (in pixels) of the frame in which the tree 1112 | # is shown. 1113 | 1114 | TREEVIEW_WIDTH = 250 1115 | 1116 | # When the EXT_LINKS_IN_WINDOW option is set to YES doxygen will open 1117 | # links to external symbols imported via tag files in a separate window. 1118 | 1119 | EXT_LINKS_IN_WINDOW = NO 1120 | 1121 | # Use this tag to change the font size of Latex formulas included 1122 | # as images in the HTML documentation. The default is 10. Note that 1123 | # when you change the font size after a successful doxygen run you need 1124 | # to manually remove any form_*.png images from the HTML output directory 1125 | # to force them to be regenerated. 1126 | 1127 | FORMULA_FONTSIZE = 10 1128 | 1129 | # Use the FORMULA_TRANPARENT tag to determine whether or not the images 1130 | # generated for formulas are transparent PNGs. Transparent PNGs are 1131 | # not supported properly for IE 6.0, but are supported on all modern browsers. 1132 | # Note that when changing this option you need to delete any form_*.png files 1133 | # in the HTML output before the changes have effect. 1134 | 1135 | FORMULA_TRANSPARENT = YES 1136 | 1137 | # Enable the USE_MATHJAX option to render LaTeX formulas using MathJax 1138 | # (see http://www.mathjax.org) which uses client side Javascript for the 1139 | # rendering instead of using prerendered bitmaps. Use this if you do not 1140 | # have LaTeX installed or if you want to formulas look prettier in the HTML 1141 | # output. When enabled you also need to install MathJax separately and 1142 | # configure the path to it using the MATHJAX_RELPATH option. 1143 | 1144 | USE_MATHJAX = NO 1145 | 1146 | # When MathJax is enabled you need to specify the location relative to the 1147 | # HTML output directory using the MATHJAX_RELPATH option. The destination 1148 | # directory should contain the MathJax.js script. For instance, if the mathjax 1149 | # directory is located at the same level as the HTML output directory, then 1150 | # MATHJAX_RELPATH should be ../mathjax. The default value points to the 1151 | # mathjax.org site, so you can quickly see the result without installing 1152 | # MathJax, but it is strongly recommended to install a local copy of MathJax 1153 | # before deployment. 1154 | 1155 | MATHJAX_RELPATH = http://www.mathjax.org/mathjax 1156 | 1157 | # The MATHJAX_EXTENSIONS tag can be used to specify one or MathJax extension 1158 | # names that should be enabled during MathJax rendering. 1159 | 1160 | MATHJAX_EXTENSIONS = 1161 | 1162 | # When the SEARCHENGINE tag is enabled doxygen will generate a search box 1163 | # for the HTML output. The underlying search engine uses javascript 1164 | # and DHTML and should work on any modern browser. Note that when using 1165 | # HTML help (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets 1166 | # (GENERATE_DOCSET) there is already a search function so this one should 1167 | # typically be disabled. For large projects the javascript based search engine 1168 | # can be slow, then enabling SERVER_BASED_SEARCH may provide a better solution. 1169 | 1170 | SEARCHENGINE = YES 1171 | 1172 | # When the SERVER_BASED_SEARCH tag is enabled the search engine will be 1173 | # implemented using a PHP enabled web server instead of at the web client 1174 | # using Javascript. Doxygen will generate the search PHP script and index 1175 | # file to put on the web server. The advantage of the server 1176 | # based approach is that it scales better to large projects and allows 1177 | # full text search. The disadvantages are that it is more difficult to setup 1178 | # and does not have live searching capabilities. 1179 | 1180 | SERVER_BASED_SEARCH = NO 1181 | 1182 | #--------------------------------------------------------------------------- 1183 | # configuration options related to the LaTeX output 1184 | #--------------------------------------------------------------------------- 1185 | 1186 | # If the GENERATE_LATEX tag is set to YES (the default) Doxygen will 1187 | # generate Latex output. 1188 | 1189 | GENERATE_LATEX = NO 1190 | 1191 | # The LATEX_OUTPUT tag is used to specify where the LaTeX docs will be put. 1192 | # If a relative path is entered the value of OUTPUT_DIRECTORY will be 1193 | # put in front of it. If left blank `latex' will be used as the default path. 1194 | 1195 | LATEX_OUTPUT = latex 1196 | 1197 | # The LATEX_CMD_NAME tag can be used to specify the LaTeX command name to be 1198 | # invoked. If left blank `latex' will be used as the default command name. 1199 | # Note that when enabling USE_PDFLATEX this option is only used for 1200 | # generating bitmaps for formulas in the HTML output, but not in the 1201 | # Makefile that is written to the output directory. 1202 | 1203 | LATEX_CMD_NAME = latex 1204 | 1205 | # The MAKEINDEX_CMD_NAME tag can be used to specify the command name to 1206 | # generate index for LaTeX. If left blank `makeindex' will be used as the 1207 | # default command name. 1208 | 1209 | MAKEINDEX_CMD_NAME = makeindex 1210 | 1211 | # If the COMPACT_LATEX tag is set to YES Doxygen generates more compact 1212 | # LaTeX documents. This may be useful for small projects and may help to 1213 | # save some trees in general. 1214 | 1215 | COMPACT_LATEX = NO 1216 | 1217 | # The PAPER_TYPE tag can be used to set the paper type that is used 1218 | # by the printer. Possible values are: a4, letter, legal and 1219 | # executive. If left blank a4wide will be used. 1220 | 1221 | PAPER_TYPE = a4 1222 | 1223 | # The EXTRA_PACKAGES tag can be to specify one or more names of LaTeX 1224 | # packages that should be included in the LaTeX output. 1225 | 1226 | EXTRA_PACKAGES = 1227 | 1228 | # The LATEX_HEADER tag can be used to specify a personal LaTeX header for 1229 | # the generated latex document. The header should contain everything until 1230 | # the first chapter. If it is left blank doxygen will generate a 1231 | # standard header. Notice: only use this tag if you know what you are doing! 1232 | 1233 | LATEX_HEADER = 1234 | 1235 | # The LATEX_FOOTER tag can be used to specify a personal LaTeX footer for 1236 | # the generated latex document. The footer should contain everything after 1237 | # the last chapter. If it is left blank doxygen will generate a 1238 | # standard footer. Notice: only use this tag if you know what you are doing! 1239 | 1240 | LATEX_FOOTER = 1241 | 1242 | # If the PDF_HYPERLINKS tag is set to YES, the LaTeX that is generated 1243 | # is prepared for conversion to pdf (using ps2pdf). The pdf file will 1244 | # contain links (just like the HTML output) instead of page references 1245 | # This makes the output suitable for online browsing using a pdf viewer. 1246 | 1247 | PDF_HYPERLINKS = YES 1248 | 1249 | # If the USE_PDFLATEX tag is set to YES, pdflatex will be used instead of 1250 | # plain latex in the generated Makefile. Set this option to YES to get a 1251 | # higher quality PDF documentation. 1252 | 1253 | USE_PDFLATEX = YES 1254 | 1255 | # If the LATEX_BATCHMODE tag is set to YES, doxygen will add the \\batchmode. 1256 | # command to the generated LaTeX files. This will instruct LaTeX to keep 1257 | # running if errors occur, instead of asking the user for help. 1258 | # This option is also used when generating formulas in HTML. 1259 | 1260 | LATEX_BATCHMODE = NO 1261 | 1262 | # If LATEX_HIDE_INDICES is set to YES then doxygen will not 1263 | # include the index chapters (such as File Index, Compound Index, etc.) 1264 | # in the output. 1265 | 1266 | LATEX_HIDE_INDICES = NO 1267 | 1268 | # If LATEX_SOURCE_CODE is set to YES then doxygen will include 1269 | # source code with syntax highlighting in the LaTeX output. 1270 | # Note that which sources are shown also depends on other settings 1271 | # such as SOURCE_BROWSER. 1272 | 1273 | LATEX_SOURCE_CODE = NO 1274 | 1275 | # The LATEX_BIB_STYLE tag can be used to specify the style to use for the 1276 | # bibliography, e.g. plainnat, or ieeetr. The default style is "plain". See 1277 | # http://en.wikipedia.org/wiki/BibTeX for more info. 1278 | 1279 | LATEX_BIB_STYLE = plain 1280 | 1281 | #--------------------------------------------------------------------------- 1282 | # configuration options related to the RTF output 1283 | #--------------------------------------------------------------------------- 1284 | 1285 | # If the GENERATE_RTF tag is set to YES Doxygen will generate RTF output 1286 | # The RTF output is optimized for Word 97 and may not look very pretty with 1287 | # other RTF readers or editors. 1288 | 1289 | GENERATE_RTF = NO 1290 | 1291 | # The RTF_OUTPUT tag is used to specify where the RTF docs will be put. 1292 | # If a relative path is entered the value of OUTPUT_DIRECTORY will be 1293 | # put in front of it. If left blank `rtf' will be used as the default path. 1294 | 1295 | RTF_OUTPUT = rtf 1296 | 1297 | # If the COMPACT_RTF tag is set to YES Doxygen generates more compact 1298 | # RTF documents. This may be useful for small projects and may help to 1299 | # save some trees in general. 1300 | 1301 | COMPACT_RTF = NO 1302 | 1303 | # If the RTF_HYPERLINKS tag is set to YES, the RTF that is generated 1304 | # will contain hyperlink fields. The RTF file will 1305 | # contain links (just like the HTML output) instead of page references. 1306 | # This makes the output suitable for online browsing using WORD or other 1307 | # programs which support those fields. 1308 | # Note: wordpad (write) and others do not support links. 1309 | 1310 | RTF_HYPERLINKS = NO 1311 | 1312 | # Load stylesheet definitions from file. Syntax is similar to doxygen's 1313 | # config file, i.e. a series of assignments. You only have to provide 1314 | # replacements, missing definitions are set to their default value. 1315 | 1316 | RTF_STYLESHEET_FILE = 1317 | 1318 | # Set optional variables used in the generation of an rtf document. 1319 | # Syntax is similar to doxygen's config file. 1320 | 1321 | RTF_EXTENSIONS_FILE = 1322 | 1323 | #--------------------------------------------------------------------------- 1324 | # configuration options related to the man page output 1325 | #--------------------------------------------------------------------------- 1326 | 1327 | # If the GENERATE_MAN tag is set to YES (the default) Doxygen will 1328 | # generate man pages 1329 | 1330 | GENERATE_MAN = NO 1331 | 1332 | # The MAN_OUTPUT tag is used to specify where the man pages will be put. 1333 | # If a relative path is entered the value of OUTPUT_DIRECTORY will be 1334 | # put in front of it. If left blank `man' will be used as the default path. 1335 | 1336 | MAN_OUTPUT = man 1337 | 1338 | # The MAN_EXTENSION tag determines the extension that is added to 1339 | # the generated man pages (default is the subroutine's section .3) 1340 | 1341 | MAN_EXTENSION = .3 1342 | 1343 | # If the MAN_LINKS tag is set to YES and Doxygen generates man output, 1344 | # then it will generate one additional man file for each entity 1345 | # documented in the real man page(s). These additional files 1346 | # only source the real man page, but without them the man command 1347 | # would be unable to find the correct page. The default is NO. 1348 | 1349 | MAN_LINKS = NO 1350 | 1351 | #--------------------------------------------------------------------------- 1352 | # configuration options related to the XML output 1353 | #--------------------------------------------------------------------------- 1354 | 1355 | # If the GENERATE_XML tag is set to YES Doxygen will 1356 | # generate an XML file that captures the structure of 1357 | # the code including all documentation. 1358 | 1359 | GENERATE_XML = NO 1360 | 1361 | # The XML_OUTPUT tag is used to specify where the XML pages will be put. 1362 | # If a relative path is entered the value of OUTPUT_DIRECTORY will be 1363 | # put in front of it. If left blank `xml' will be used as the default path. 1364 | 1365 | XML_OUTPUT = xml 1366 | 1367 | # The XML_SCHEMA tag can be used to specify an XML schema, 1368 | # which can be used by a validating XML parser to check the 1369 | # syntax of the XML files. 1370 | 1371 | XML_SCHEMA = 1372 | 1373 | # The XML_DTD tag can be used to specify an XML DTD, 1374 | # which can be used by a validating XML parser to check the 1375 | # syntax of the XML files. 1376 | 1377 | XML_DTD = 1378 | 1379 | # If the XML_PROGRAMLISTING tag is set to YES Doxygen will 1380 | # dump the program listings (including syntax highlighting 1381 | # and cross-referencing information) to the XML output. Note that 1382 | # enabling this will significantly increase the size of the XML output. 1383 | 1384 | XML_PROGRAMLISTING = YES 1385 | 1386 | #--------------------------------------------------------------------------- 1387 | # configuration options for the AutoGen Definitions output 1388 | #--------------------------------------------------------------------------- 1389 | 1390 | # If the GENERATE_AUTOGEN_DEF tag is set to YES Doxygen will 1391 | # generate an AutoGen Definitions (see autogen.sf.net) file 1392 | # that captures the structure of the code including all 1393 | # documentation. Note that this feature is still experimental 1394 | # and incomplete at the moment. 1395 | 1396 | GENERATE_AUTOGEN_DEF = NO 1397 | 1398 | #--------------------------------------------------------------------------- 1399 | # configuration options related to the Perl module output 1400 | #--------------------------------------------------------------------------- 1401 | 1402 | # If the GENERATE_PERLMOD tag is set to YES Doxygen will 1403 | # generate a Perl module file that captures the structure of 1404 | # the code including all documentation. Note that this 1405 | # feature is still experimental and incomplete at the 1406 | # moment. 1407 | 1408 | GENERATE_PERLMOD = NO 1409 | 1410 | # If the PERLMOD_LATEX tag is set to YES Doxygen will generate 1411 | # the necessary Makefile rules, Perl scripts and LaTeX code to be able 1412 | # to generate PDF and DVI output from the Perl module output. 1413 | 1414 | PERLMOD_LATEX = NO 1415 | 1416 | # If the PERLMOD_PRETTY tag is set to YES the Perl module output will be 1417 | # nicely formatted so it can be parsed by a human reader. 1418 | # This is useful 1419 | # if you want to understand what is going on. 1420 | # On the other hand, if this 1421 | # tag is set to NO the size of the Perl module output will be much smaller 1422 | # and Perl will parse it just the same. 1423 | 1424 | PERLMOD_PRETTY = YES 1425 | 1426 | # The names of the make variables in the generated doxyrules.make file 1427 | # are prefixed with the string contained in PERLMOD_MAKEVAR_PREFIX. 1428 | # This is useful so different doxyrules.make files included by the same 1429 | # Makefile don't overwrite each other's variables. 1430 | 1431 | PERLMOD_MAKEVAR_PREFIX = 1432 | 1433 | #--------------------------------------------------------------------------- 1434 | # Configuration options related to the preprocessor 1435 | #--------------------------------------------------------------------------- 1436 | 1437 | # If the ENABLE_PREPROCESSING tag is set to YES (the default) Doxygen will 1438 | # evaluate all C-preprocessor directives found in the sources and include 1439 | # files. 1440 | 1441 | ENABLE_PREPROCESSING = YES 1442 | 1443 | # If the MACRO_EXPANSION tag is set to YES Doxygen will expand all macro 1444 | # names in the source code. If set to NO (the default) only conditional 1445 | # compilation will be performed. Macro expansion can be done in a controlled 1446 | # way by setting EXPAND_ONLY_PREDEF to YES. 1447 | 1448 | MACRO_EXPANSION = NO 1449 | 1450 | # If the EXPAND_ONLY_PREDEF and MACRO_EXPANSION tags are both set to YES 1451 | # then the macro expansion is limited to the macros specified with the 1452 | # PREDEFINED and EXPAND_AS_DEFINED tags. 1453 | 1454 | EXPAND_ONLY_PREDEF = NO 1455 | 1456 | # If the SEARCH_INCLUDES tag is set to YES (the default) the includes files 1457 | # pointed to by INCLUDE_PATH will be searched when a #include is found. 1458 | 1459 | SEARCH_INCLUDES = YES 1460 | 1461 | # The INCLUDE_PATH tag can be used to specify one or more directories that 1462 | # contain include files that are not input files but should be processed by 1463 | # the preprocessor. 1464 | 1465 | INCLUDE_PATH = 1466 | 1467 | # You can use the INCLUDE_FILE_PATTERNS tag to specify one or more wildcard 1468 | # patterns (like *.h and *.hpp) to filter out the header-files in the 1469 | # directories. If left blank, the patterns specified with FILE_PATTERNS will 1470 | # be used. 1471 | 1472 | INCLUDE_FILE_PATTERNS = 1473 | 1474 | # The PREDEFINED tag can be used to specify one or more macro names that 1475 | # are defined before the preprocessor is started (similar to the -D option of 1476 | # gcc). The argument of the tag is a list of macros of the form: name 1477 | # or name=definition (no spaces). If the definition and the = are 1478 | # omitted =1 is assumed. To prevent a macro definition from being 1479 | # undefined via #undef or recursively expanded use the := operator 1480 | # instead of the = operator. 1481 | 1482 | PREDEFINED = 1483 | 1484 | # If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then 1485 | # this tag can be used to specify a list of macro names that should be expanded. 1486 | # The macro definition that is found in the sources will be used. 1487 | # Use the PREDEFINED tag if you want to use a different macro definition that 1488 | # overrules the definition found in the source code. 1489 | 1490 | EXPAND_AS_DEFINED = 1491 | 1492 | # If the SKIP_FUNCTION_MACROS tag is set to YES (the default) then 1493 | # doxygen's preprocessor will remove all references to function-like macros 1494 | # that are alone on a line, have an all uppercase name, and do not end with a 1495 | # semicolon, because these will confuse the parser if not removed. 1496 | 1497 | SKIP_FUNCTION_MACROS = YES 1498 | 1499 | #--------------------------------------------------------------------------- 1500 | # Configuration::additions related to external references 1501 | #--------------------------------------------------------------------------- 1502 | 1503 | # The TAGFILES option can be used to specify one or more tagfiles. 1504 | # Optionally an initial location of the external documentation 1505 | # can be added for each tagfile. The format of a tag file without 1506 | # this location is as follows: 1507 | # 1508 | # TAGFILES = file1 file2 ... 1509 | # Adding location for the tag files is done as follows: 1510 | # 1511 | # TAGFILES = file1=loc1 "file2 = loc2" ... 1512 | # where "loc1" and "loc2" can be relative or absolute paths or 1513 | # URLs. If a location is present for each tag, the installdox tool 1514 | # does not have to be run to correct the links. 1515 | # Note that each tag file must have a unique name 1516 | # (where the name does NOT include the path) 1517 | # If a tag file is not located in the directory in which doxygen 1518 | # is run, you must also specify the path to the tagfile here. 1519 | 1520 | TAGFILES = 1521 | 1522 | # When a file name is specified after GENERATE_TAGFILE, doxygen will create 1523 | # a tag file that is based on the input files it reads. 1524 | 1525 | GENERATE_TAGFILE = 1526 | 1527 | # If the ALLEXTERNALS tag is set to YES all external classes will be listed 1528 | # in the class index. If set to NO only the inherited external classes 1529 | # will be listed. 1530 | 1531 | ALLEXTERNALS = NO 1532 | 1533 | # If the EXTERNAL_GROUPS tag is set to YES all external groups will be listed 1534 | # in the modules index. If set to NO, only the current project's groups will 1535 | # be listed. 1536 | 1537 | EXTERNAL_GROUPS = YES 1538 | 1539 | # The PERL_PATH should be the absolute path and name of the perl script 1540 | # interpreter (i.e. the result of `which perl'). 1541 | 1542 | PERL_PATH = /usr/bin/perl 1543 | 1544 | #--------------------------------------------------------------------------- 1545 | # Configuration options related to the dot tool 1546 | #--------------------------------------------------------------------------- 1547 | 1548 | # If the CLASS_DIAGRAMS tag is set to YES (the default) Doxygen will 1549 | # generate a inheritance diagram (in HTML, RTF and LaTeX) for classes with base 1550 | # or super classes. Setting the tag to NO turns the diagrams off. Note that 1551 | # this option also works with HAVE_DOT disabled, but it is recommended to 1552 | # install and use dot, since it yields more powerful graphs. 1553 | 1554 | CLASS_DIAGRAMS = YES 1555 | 1556 | # You can define message sequence charts within doxygen comments using the \msc 1557 | # command. Doxygen will then run the mscgen tool (see 1558 | # http://www.mcternan.me.uk/mscgen/) to produce the chart and insert it in the 1559 | # documentation. The MSCGEN_PATH tag allows you to specify the directory where 1560 | # the mscgen tool resides. If left empty the tool is assumed to be found in the 1561 | # default search path. 1562 | 1563 | MSCGEN_PATH = 1564 | 1565 | # If set to YES, the inheritance and collaboration graphs will hide 1566 | # inheritance and usage relations if the target is undocumented 1567 | # or is not a class. 1568 | 1569 | HIDE_UNDOC_RELATIONS = YES 1570 | 1571 | # If you set the HAVE_DOT tag to YES then doxygen will assume the dot tool is 1572 | # available from the path. This tool is part of Graphviz, a graph visualization 1573 | # toolkit from AT&T and Lucent Bell Labs. The other options in this section 1574 | # have no effect if this option is set to NO (the default) 1575 | 1576 | HAVE_DOT = YES 1577 | 1578 | # The DOT_NUM_THREADS specifies the number of dot invocations doxygen is 1579 | # allowed to run in parallel. When set to 0 (the default) doxygen will 1580 | # base this on the number of processors available in the system. You can set it 1581 | # explicitly to a value larger than 0 to get control over the balance 1582 | # between CPU load and processing speed. 1583 | 1584 | DOT_NUM_THREADS = 0 1585 | 1586 | # By default doxygen will use the Helvetica font for all dot files that 1587 | # doxygen generates. When you want a differently looking font you can specify 1588 | # the font name using DOT_FONTNAME. You need to make sure dot is able to find 1589 | # the font, which can be done by putting it in a standard location or by setting 1590 | # the DOTFONTPATH environment variable or by setting DOT_FONTPATH to the 1591 | # directory containing the font. 1592 | 1593 | DOT_FONTNAME = Helvetica 1594 | 1595 | # The DOT_FONTSIZE tag can be used to set the size of the font of dot graphs. 1596 | # The default size is 10pt. 1597 | 1598 | DOT_FONTSIZE = 10 1599 | 1600 | # By default doxygen will tell dot to use the Helvetica font. 1601 | # If you specify a different font using DOT_FONTNAME you can use DOT_FONTPATH to 1602 | # set the path where dot can find it. 1603 | 1604 | DOT_FONTPATH = 1605 | 1606 | # If the CLASS_GRAPH and HAVE_DOT tags are set to YES then doxygen 1607 | # will generate a graph for each documented class showing the direct and 1608 | # indirect inheritance relations. Setting this tag to YES will force the 1609 | # the CLASS_DIAGRAMS tag to NO. 1610 | 1611 | CLASS_GRAPH = YES 1612 | 1613 | # If the COLLABORATION_GRAPH and HAVE_DOT tags are set to YES then doxygen 1614 | # will generate a graph for each documented class showing the direct and 1615 | # indirect implementation dependencies (inheritance, containment, and 1616 | # class references variables) of the class with other documented classes. 1617 | 1618 | COLLABORATION_GRAPH = YES 1619 | 1620 | # If the GROUP_GRAPHS and HAVE_DOT tags are set to YES then doxygen 1621 | # will generate a graph for groups, showing the direct groups dependencies 1622 | 1623 | GROUP_GRAPHS = YES 1624 | 1625 | # If the UML_LOOK tag is set to YES doxygen will generate inheritance and 1626 | # collaboration diagrams in a style similar to the OMG's Unified Modeling 1627 | # Language. 1628 | 1629 | UML_LOOK = NO 1630 | 1631 | # If set to YES, the inheritance and collaboration graphs will show the 1632 | # relations between templates and their instances. 1633 | 1634 | TEMPLATE_RELATIONS = NO 1635 | 1636 | # If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDE_GRAPH, and HAVE_DOT 1637 | # tags are set to YES then doxygen will generate a graph for each documented 1638 | # file showing the direct and indirect include dependencies of the file with 1639 | # other documented files. 1640 | 1641 | INCLUDE_GRAPH = YES 1642 | 1643 | # If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDED_BY_GRAPH, and 1644 | # HAVE_DOT tags are set to YES then doxygen will generate a graph for each 1645 | # documented header file showing the documented files that directly or 1646 | # indirectly include this file. 1647 | 1648 | INCLUDED_BY_GRAPH = YES 1649 | 1650 | # If the CALL_GRAPH and HAVE_DOT options are set to YES then 1651 | # doxygen will generate a call dependency graph for every global function 1652 | # or class method. Note that enabling this option will significantly increase 1653 | # the time of a run. So in most cases it will be better to enable call graphs 1654 | # for selected functions only using the \callgraph command. 1655 | 1656 | CALL_GRAPH = YES 1657 | 1658 | # If the CALLER_GRAPH and HAVE_DOT tags are set to YES then 1659 | # doxygen will generate a caller dependency graph for every global function 1660 | # or class method. Note that enabling this option will significantly increase 1661 | # the time of a run. So in most cases it will be better to enable caller 1662 | # graphs for selected functions only using the \callergraph command. 1663 | 1664 | CALLER_GRAPH = NO 1665 | 1666 | # If the GRAPHICAL_HIERARCHY and HAVE_DOT tags are set to YES then doxygen 1667 | # will generate a graphical hierarchy of all classes instead of a textual one. 1668 | 1669 | GRAPHICAL_HIERARCHY = YES 1670 | 1671 | # If the DIRECTORY_GRAPH, SHOW_DIRECTORIES and HAVE_DOT tags are set to YES 1672 | # then doxygen will show the dependencies a directory has on other directories 1673 | # in a graphical way. The dependency relations are determined by the #include 1674 | # relations between the files in the directories. 1675 | 1676 | DIRECTORY_GRAPH = YES 1677 | 1678 | # The DOT_IMAGE_FORMAT tag can be used to set the image format of the images 1679 | # generated by dot. Possible values are svg, png, jpg, or gif. 1680 | # If left blank png will be used. If you choose svg you need to set 1681 | # HTML_FILE_EXTENSION to xhtml in order to make the SVG files 1682 | # visible in IE 9+ (other browsers do not have this requirement). 1683 | 1684 | DOT_IMAGE_FORMAT = png 1685 | 1686 | # If DOT_IMAGE_FORMAT is set to svg, then this option can be set to YES to 1687 | # enable generation of interactive SVG images that allow zooming and panning. 1688 | # Note that this requires a modern browser other than Internet Explorer. 1689 | # Tested and working are Firefox, Chrome, Safari, and Opera. For IE 9+ you 1690 | # need to set HTML_FILE_EXTENSION to xhtml in order to make the SVG files 1691 | # visible. Older versions of IE do not have SVG support. 1692 | 1693 | INTERACTIVE_SVG = NO 1694 | 1695 | # The tag DOT_PATH can be used to specify the path where the dot tool can be 1696 | # found. If left blank, it is assumed the dot tool can be found in the path. 1697 | 1698 | DOT_PATH = 1699 | 1700 | # The DOTFILE_DIRS tag can be used to specify one or more directories that 1701 | # contain dot files that are included in the documentation (see the 1702 | # \dotfile command). 1703 | 1704 | DOTFILE_DIRS = 1705 | 1706 | # The MSCFILE_DIRS tag can be used to specify one or more directories that 1707 | # contain msc files that are included in the documentation (see the 1708 | # \mscfile command). 1709 | 1710 | MSCFILE_DIRS = 1711 | 1712 | # The DOT_GRAPH_MAX_NODES tag can be used to set the maximum number of 1713 | # nodes that will be shown in the graph. If the number of nodes in a graph 1714 | # becomes larger than this value, doxygen will truncate the graph, which is 1715 | # visualized by representing a node as a red box. Note that doxygen if the 1716 | # number of direct children of the root node in a graph is already larger than 1717 | # DOT_GRAPH_MAX_NODES then the graph will not be shown at all. Also note 1718 | # that the size of a graph can be further restricted by MAX_DOT_GRAPH_DEPTH. 1719 | 1720 | DOT_GRAPH_MAX_NODES = 50 1721 | 1722 | # The MAX_DOT_GRAPH_DEPTH tag can be used to set the maximum depth of the 1723 | # graphs generated by dot. A depth value of 3 means that only nodes reachable 1724 | # from the root by following a path via at most 3 edges will be shown. Nodes 1725 | # that lay further from the root node will be omitted. Note that setting this 1726 | # option to 1 or 2 may greatly reduce the computation time needed for large 1727 | # code bases. Also note that the size of a graph can be further restricted by 1728 | # DOT_GRAPH_MAX_NODES. Using a depth of 0 means no depth restriction. 1729 | 1730 | MAX_DOT_GRAPH_DEPTH = 0 1731 | 1732 | # Set the DOT_TRANSPARENT tag to YES to generate images with a transparent 1733 | # background. This is disabled by default, because dot on Windows does not 1734 | # seem to support this out of the box. Warning: Depending on the platform used, 1735 | # enabling this option may lead to badly anti-aliased labels on the edges of 1736 | # a graph (i.e. they become hard to read). 1737 | 1738 | DOT_TRANSPARENT = NO 1739 | 1740 | # Set the DOT_MULTI_TARGETS tag to YES allow dot to generate multiple output 1741 | # files in one run (i.e. multiple -o and -T options on the command line). This 1742 | # makes dot run faster, but since only newer versions of dot (>1.8.10) 1743 | # support this, this feature is disabled by default. 1744 | 1745 | DOT_MULTI_TARGETS = NO 1746 | 1747 | # If the GENERATE_LEGEND tag is set to YES (the default) Doxygen will 1748 | # generate a legend page explaining the meaning of the various boxes and 1749 | # arrows in the dot generated graphs. 1750 | 1751 | GENERATE_LEGEND = YES 1752 | 1753 | # If the DOT_CLEANUP tag is set to YES (the default) Doxygen will 1754 | # remove the intermediate dot files that are used to generate 1755 | # the various graphs. 1756 | 1757 | DOT_CLEANUP = YES 1758 | --------------------------------------------------------------------------------