-
Notifications
You must be signed in to change notification settings - Fork 3
/
Copy pathapriltag.js
191 lines (172 loc) · 7.68 KB
/
apriltag.js
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
importScripts('apriltag_wasm.js');
importScripts("https://unpkg.com/comlink/dist/umd/comlink.js");
/**
* This is a wrapper class that calls apriltag_wasm to load the WASM module and wraps the c implementation calls.
* The apriltag dectector uses the tag36h11 family.
* For tag pose estimation, call set_tag_size allows to indicate the size of known tags.
* If size is not defined using set_tag_size() will default to the defaukt tag size of 0.15 meters
*
*/
class Apriltag {
/**
* Contructor
* @param {function} onDetectorReadyCallback Callback when the detector is ready
*/
constructor(onDetectorReadyCallback) {
//detectorOptions = detectorOptions || {};
this.onDetectorReadyCallback = onDetectorReadyCallback;
// detector options
this._opt = {
// Decimate input image by this factor
quad_decimate: 2.0,
// What Gaussian blur should be applied to the segmented image; standard deviation in pixels
quad_sigma: 0.0,
// Use this many CPU threads (no effect)
nthreads: 1,
// Spend more time trying to align edges of tags
refine_edges: 1,
// Maximum detections to return (0=return all)
max_detections: 0,
// Return pose (requires camera parameters)
return_pose: 1,
// Return pose solutions details
return_solutions: 1
}
let _this = this;
AprilTagWasm().then(function (Module) {
console.log("Apriltag WASM module loaded.");
_this.onWasmInit(Module);
});
}
/**
* Init warapper calls
* @param {*} Module WASM module instance
*/
onWasmInit(Module) {
// save a reference to the module here
this._Module = Module;
//int atagjs_init(); Init the apriltag detector with default options
this._init = Module.cwrap('atagjs_init', 'number', []);
//int atagjs_destroy(); Releases resources allocated by the wasm module
this._destroy = Module.cwrap('atagjs_destroy', 'number', []);
//int atagjs_set_detector_options(float decimate, float sigma, int nthreads, int refine_edges, int max_detections, int return_pose, int return_solutions); Sets the given detector options
this._set_detector_options = Module.cwrap('atagjs_set_detector_options', 'number', ['number', 'number', 'number', 'number', 'number', 'number', 'number']);
//int atagjs_set_pose_info(double fx, double fy, double cx, double cy); Sets the tag size (meters) and camera intrinsics (in pixels) for tag pose estimation
this._set_pose_info = Module.cwrap('atagjs_set_pose_info', 'number', ['number', 'number', 'number', 'number']);
//uint8_t* atagjs_set_img_buffer(int width, int height, int stride); Creates/changes size of the image buffer where we receive the images to process
this._set_img_buffer = Module.cwrap('atagjs_set_img_buffer', 'number', ['number', 'number', 'number']);
//void *atagjs_set_tag_size(int tagid, double size)
this._atagjs_set_tag_size = Module.cwrap('atagjs_set_tag_size', null, ['number', 'number']);
//t_str_json* atagjs_detect(); Detect tags in image previously stored in the buffer.
//returns pointer to buffer starting with an int32 indicating the size of the remaining buffer (a string of chars with the json describing the detections)
this._detect = Module.cwrap('atagjs_detect', 'number', []);
// inits detector
this._init();
// set max_detections = 0, meaning no max; will return all detections
//options: float decimate, float sigma, int nthreads, int refine_edges, int max_detections, int return_pose, int return_solutions
this._set_detector_options(
this._opt.quad_decimate,
this._opt.quad_sigma,
this._opt.nthreads,
this._opt.refine_edges,
this._opt.max_detections,
this._opt.return_pose,
this._opt.return_solutions);
this.onDetectorReadyCallback();
}
/**
* **public** detect method
* @param {Array} grayscaleImg grayscale image buffer
* @param {Number} imgWidth image with
* @param {Number} imgHeight image height
* @return {detection} detection object
*/
detect(grayscaleImg, imgWidth, imgHeight) {
// set_img_buffer allocates the buffer for image and returns it; just returns the previously allocated buffer if size has not changed
let imgBuffer = this._set_img_buffer(imgWidth, imgHeight, imgWidth);
if (imgWidth * imgHeight < grayscaleImg.length) return { result: "Image data too large." };
this._Module.HEAPU8.set(grayscaleImg, imgBuffer); // copy grayscale image data
let strJsonPtr = this._detect();
/* detect returns a pointer to a t_str_json c struct as follows
size_t len; // string length
char *str;
size_t alloc_size; // allocated size */
let strJsonLen = this._Module.getValue(strJsonPtr, "i32"); // get len from struct
if (strJsonLen == 0) { // returned empty string
return [];
}
let strJsonStrPtr = this._Module.getValue(strJsonPtr + 4, "i32"); // get *str from struct
const strJsonView = new Uint8Array(this._Module.HEAP8.buffer, strJsonStrPtr, strJsonLen);
let detectionsJson = ''; // build this javascript string from returned characters
for (let i = 0; i < strJsonLen; i++) {
detectionsJson += String.fromCharCode(strJsonView[i]);
}
//console.log(detectionsJson);
let detections = JSON.parse(detectionsJson);
return detections;
}
/**
* **public** set camera parameters
* @param {Number} fx camera focal length
* @param {Number} fy camera focal length
* @param {Number} cx camera principal point
* @param {Number} cy camera principal point
*/
set_camera_info(fx, fy, cx, cy) {
this._set_pose_info(fx, fy, cx, cy);
}
/**
* **public** set size of known tag (size in meters)
* @param {Number} tagid the tag id
* @param {Number} size the size of the tag in meters
*/
set_tag_size(tagid, size) {
this._atagjs_set_tag_size(tagid, size);
}
/**
* **public** set maximum detections to return (0=return all)
* @param {Number} maxDetections
*/
set_max_detections(maxDetections) {
this._opt.max_detections = maxDetections;
this._set_detector_options(
this._opt.quad_decimate,
this._opt.quad_sigma,
this._opt.nthreads,
this._opt.refine_edges,
this._opt.max_detections,
this._opt.return_pose,
this._opt.return_solutions);
}
/**
* **public** set return pose estimate (0=do not return; 1=return)
* @param {Number} returnPose
*/
set_return_pose(returnPose) {
this._opt.return_pose = returnPose;
this._set_detector_options(
this._opt.quad_decimate,
this._opt.quad_sigma,
this._opt.nthreads,
this._opt.refine_edges,
this._opt.max_detections,
this._opt.return_pose,
this._opt.return_solutions);
}
/**
* **public** set return pose estimate alternative solution details (0=do not return; 1=return)
* @param {Number} returnSolutions
*/
set_return_solutions(returnSolutions) {
this._opt.return_solutions = returnSolutions;
this._set_detector_options(
this._opt.quad_decimate,
this._opt.quad_sigma,
this._opt.nthreads,
this._opt.refine_edges,
this._opt.max_detections,
this._opt.return_pose,
this._opt.return_solutions);
}
}
Comlink.expose(Apriltag);