|
Apriltag WASM Detector
Apriltag detector using the apriltag C library and compiled to WASM using emscripten.
|
Apriltag detection to be compile with emscripten. More...
#include <stdio.h>#include <stdint.h>#include <inttypes.h>#include <ctype.h>#include <unistd.h>#include <math.h>#include "apriltag.h"#include "apriltag_pose.h"#include "tag36h11.h"#include "tag25h9.h"#include "tag16h5.h"#include "tagCircle21h7.h"#include "tagStandard41h12.h"#include "common/getopt.h"#include "common/image_u8.h"#include "common/image_u8x4.h"#include "common/pjpeg.h"#include "common/zarray.h"#include "apriltag_js.h"#include "str_json.h"
Functions | |
| EMSCRIPTEN_KEEPALIVE 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... | |
| EMSCRIPTEN_KEEPALIVE int | atagjs_destroy () |
| Releases resources. More... | |
| EMSCRIPTEN_KEEPALIVE 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... | |
| EMSCRIPTEN_KEEPALIVE int | atagjs_set_pose_info (double fx, double fy, double cx, double cy) |
| Sets camera intrinsics (in pixels) for tag pose estimation. More... | |
| EMSCRIPTEN_KEEPALIVE 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... | |
| EMSCRIPTEN_KEEPALIVE t_str_json * | atagjs_detect () |
| Detect tags in image stored in the buffer (g_img_buf) More... | |
Apriltag detection to be compile with emscripten.
Uses the apriltaf library; exposes a simple interface for a web app to use apriltags once it is compiled to WASM using emscripten
Copyright (C) Wiselab CMU.
| EMSCRIPTEN_KEEPALIVE int atagjs_destroy | ( | ) |
Releases resources.
| EMSCRIPTEN_KEEPALIVE t_str_json* atagjs_detect | ( | ) |
Detect tags in image stored in the buffer (g_img_buf)
| EMSCRIPTEN_KEEPALIVE 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.
| EMSCRIPTEN_KEEPALIVE 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.
| decimate | Decimate input image by this factor |
| sigma | Apply low-pass blur to input; negative sharpens |
| nthreads | Use this many CPU threads |
| refine_edges | Spend more time trying to align edges of tags |
| max_detections | Maximum number of detections to return (0=no max) |
| return_pose | Detect returns pose of detected tags (0=does not return pose; returns pose otherwise) |
| return_solutions | Detect returns details about both solutions of the pose estimation, if available |
| EMSCRIPTEN_KEEPALIVE 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.
| width | Width of the image |
| height | Height of the image |
| stride | How many pixels per row (=width typically) |
| EMSCRIPTEN_KEEPALIVE int atagjs_set_pose_info | ( | double | fx, |
| double | fy, | ||
| double | cx, | ||
| double | cy | ||
| ) |
Sets camera intrinsics (in pixels) for tag pose estimation.
| fx | x focal lenght in pixels |
| fy | y focal lenght in pixels |
| cx | x principal point in pixels |
| cy | y principal point in pixels |
1.8.13