Apriltag WASM Detector
Apriltag detector using the apriltag C library and compiled to WASM using emscripten.
Macros | Functions
apriltag_js.h File Reference

Definitions for the apriltag detector. More...

#include "apriltag.h"
#include "apriltag_pose.h"
#include "str_json.h"
Include dependency graph for apriltag_js.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Macros

#define STR_DET_LEN   1500
 

Functions

int atagjs_init ()
 Init the apriltag detector with given family and default options default options: quad_decimate=2.0; quad_sigma=0.0; nthreads=1; refine_edges=1; return_pose=1. More...
 
int atagjs_destroy ()
 Releases resources. More...
 
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. More...
 
int atagjs_set_pose_info (double fx, double fy, double cx, double cy)
 Sets camera intrinsics (in pixels) for tag pose estimation. More...
 
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. More...
 
t_str_jsonatagjs_detect ()
 Detect tags in image stored in the buffer (g_img_buf) More...
 

Detailed Description

Definitions for the apriltag detector.

Use apriltag library to implement a detector that runs in the browser using WASM

Copyright (C) Wiselab CMU.

Date
July, 2020

Function Documentation

◆ atagjs_destroy()

int atagjs_destroy ( )

Releases resources.

Returns
0=success

◆ atagjs_detect()

t_str_json* atagjs_detect ( )

Detect tags in image stored in the buffer (g_img_buf)

Returns
pointer to str_json structure. The data in this memory location must be consumed before the next call to detect()
Warning
caller is responsible for putting grayscale image pixels in the input buffer (g_img_buf)
caller should not release return pointer (it's reused at every detect() call); data returned must be consumed before the next call to detect()

◆ atagjs_init()

int atagjs_init ( )

Init the apriltag detector with given family and default options default options: quad_decimate=2.0; quad_sigma=0.0; nthreads=1; refine_edges=1; return_pose=1.

See also
set_detector_options for meaning of options
Returns
0=success; -1 on failure

◆ atagjs_set_detector_options()

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.

Parameters
decimateDecimate input image by this factor
sigmaApply low-pass blur to input; negative sharpens
nthreadsUse this many CPU threads
refine_edgesSpend more time trying to align edges of tags
max_detectionsMaximum number of detections to return (0=no max)
return_poseDetect returns pose of detected tags (0=does not return pose; returns pose otherwise)
return_solutionsDetect returns details about both solutions of the pose estimation, if available
Returns
0=success

◆ atagjs_set_img_buffer()

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.

Parameters
widthWidth of the image
heightHeight of the image
strideHow many pixels per row (=width typically)
Returns
the pointer to the image buffer
Warning
caller of detect is responsible for putting grayscale image pixels in this buffer

◆ atagjs_set_pose_info()

int atagjs_set_pose_info ( double  fx,
double  fy,
double  cx,
double  cy 
)

Sets camera intrinsics (in pixels) for tag pose estimation.

Parameters
fxx focal lenght in pixels
fyy focal lenght in pixels
cxx principal point in pixels
cyy principal point in pixels
Returns
0=success