Detect AprilTags (https://april.eecs.umich.edu/software/apriltag) in an image. More...
Data Structures | |
struct | VPIAprilTagDecodeParams |
Decode parameters for vpiCreateAprilTagDetector. More... | |
struct | VPIAprilTagDetection |
Stores information about an AprilTag detection from AprilTag detector. More... | |
Enumerations | |
enum | VPIAprilTagFamily |
Specify the family of AprilTags to detect. More... | |
Functions | |
VPIStatus | vpiInitAprilTagDecodeParams (VPIAprilTagDecodeParams *params) |
Initializes VPIAprilTagDecodeParams with default values. More... | |
VPIStatus | vpiCreateAprilTagDetector (uint64_t backends, int32_t inputWidth, int32_t inputHeight, VPIAprilTagDecodeParams const *params, VPIPayload *payload) |
Creates a AprilTag detector payload. More... | |
VPIStatus | vpiSubmitAprilTagDetector (VPIStream stream, uint64_t backend, VPIPayload payload, uint32_t maxDetections, VPIImage input, VPIArray outDetections) |
Submits a AprilTag detector operation to the stream. More... | |
VPIStatus | vpiSubmitAprilTagPoseEstimation (VPIStream stream, uint64_t backend, VPIArray inDetections, const VPICameraIntrinsic intrinsics, float tagSize, VPIArray outPoses) |
Submits a AprilTag pose estimation operation to the stream. More... | |
Detect AprilTags (https://april.eecs.umich.edu/software/apriltag) in an image.
Refer to AprilTag Detector and Pose Estimator for more details and usage examples.
struct VPIAprilTagDecodeParams |
Decode parameters for vpiCreateAprilTagDetector.
Specifies family to decode and decode properties.
Definition at line 111 of file AprilTags.h.
Data Fields | ||
---|---|---|
const uint16_t * | tagIdFilter |
Optional array of tag ids from family which represent valid detections. Set to NULL to detect all tags from the family Data can be freed after call to vpiCreateAprilTagDetector. |
int32_t | tagIdFilterSize |
Size of tagIdFilter array if not NULL.
|
int32_t | maxBitsCorrected |
Maximum number of bits to correct during decoding.
|
VPIAprilTagFamily | family | Which family to detect. |
struct VPIAprilTagDetection |
Stores information about an AprilTag detection from AprilTag detector.
Data Fields | ||
---|---|---|
uint16_t | id | The decoded ID of the tag. |
int16_t | correctedBits | Number of bits corrected for this detection. |
float | decisionMargin |
A measure of the quality of the binary decoding process: the average difference between the intensity of a data bit versus the decision threshold. Higher numbers roughly indicate better decodes. This is a reasonable measure of detection accuracy only for very small tags. |
VPIHomographyTransform2D | homography | The 3x3 homography matrix describing the projection from an "ideal" tag (with corners at (-1,1), (1,1), (1,-1), and (-1, -1)) to pixels in the image. |
VPIKeypointF32 | center | The center of the detection in image pixel coordinates. |
VPIKeypointF32 | corners[4] | The corners of the tag in image pixel coordinates, ordered counter-clockwise. |
enum VPIAprilTagFamily |
#include <vpi/algo/AprilTags.h>
Specify the family of AprilTags to detect.
The family is defined by the layout, the number of bits in the tag and the minimum hamming distance between valid codewords.
Definition at line 83 of file AprilTags.h.
VPIStatus vpiInitAprilTagDecodeParams | ( | VPIAprilTagDecodeParams * | params | ) |
#include <vpi/algo/AprilTags.h>
Initializes VPIAprilTagDecodeParams with default values.
Defaults:
[out] | params | Structure to be filled with default values. |
VPI_ERROR_INVALID_ARGUMENT | params is NULL |
VPI_SUCCESS | Operation executed successfully. |
VPIStatus vpiCreateAprilTagDetector | ( | uint64_t | backends, |
int32_t | inputWidth, | ||
int32_t | inputHeight, | ||
VPIAprilTagDecodeParams const * | params, | ||
VPIPayload * | payload | ||
) |
#include <vpi/algo/AprilTags.h>
Creates a AprilTag detector payload.
This function allocates all temporary memory needed by the algorithm.
[in] | backends | VPI backends that are eligible to execute the algorithm.
|
[in] | inputWidth,inputHeight | Dimensions of the input image that will be used with this payload.
|
[in] | params | Decode parameters for the detector. Pass NULL to use the defaults given by vpiInitAprilTagDecodeParams. |
[out] | payload | Pointer to the payload variable that receives the created handle. |
VPI_ERROR_INVALID_ARGUMENT | payload is NULL. |
VPI_ERROR_INVALID_ARGUMENT | backends refers to an invalid backend. |
VPI_ERROR_INVALID_ARGUMENT | inputWidth or inputHeight outside valid range. |
VPI_ERROR_INVALID_ARGUMENT | params is NULL or contains invalid configuration. |
VPI_ERROR_INVALID_OPERATION | Backend hardware not available, or backend not available in current context. |
VPI_ERROR_NOT_IMPLEMENTED | Algorithm does not support the given backend. |
VPI_ERROR_INVALID_CONTEXT | Current context is destroyed. |
VPI_ERROR_OUT_OF_MEMORY | Cannot allocate required resources. |
VPI_SUCCESS | Operation executed successfully. |
VPIStatus vpiSubmitAprilTagDetector | ( | VPIStream | stream, |
uint64_t | backend, | ||
VPIPayload | payload, | ||
uint32_t | maxDetections, | ||
VPIImage | input, | ||
VPIArray | outDetections | ||
) |
#include <vpi/algo/AprilTags.h>
Submits a AprilTag detector operation to the stream.
[in] | stream | The stream where the operation will be queued in.
|
[in] | backend | Backend that will execute the algorithm.
|
[in] | payload | Payload to be submitted along the other parameters. |
[in] | maxDetections | Maximum number of detections to be returned in outDetections. |
[in] | input | Input image used for detection
|
[out] | outDetections | Array that will receive the detections. Array size is updated with the number of tags found.
|
VPI_ERROR_INVALID_ARGUMENT | stream is NULL. |
VPI_ERROR_INVALID_ARGUMENT | input is NULL. |
VPI_ERROR_INVALID_ARGUMENT | input image dimensions do not match dimensions passed to vpiCreateAprilTagDetector. |
VPI_ERROR_INVALID_ARGUMENT | backend does not match the backend used to create the payload. |
VPI_ERROR_INVALID_IMAGE_FORMAT | input image format not supported. |
VPI_ERROR_INVALID_PAYLOAD_TYPE | payload is invalid or NULL. |
VPI_ERROR_NOT_IMPLEMENTED | Algorithm does not support the given backend. |
VPI_ERROR_INVALID_OPERATION | Backend hardware not available. |
VPI_ERROR_INVALID_OPERATION | The needed backends aren't enabled in stream , input or outDetections . |
VPI_SUCCESS | Operation executed successfully. |
VPIStatus vpiSubmitAprilTagPoseEstimation | ( | VPIStream | stream, |
uint64_t | backend, | ||
VPIArray | inDetections, | ||
const VPICameraIntrinsic | intrinsics, | ||
float | tagSize, | ||
VPIArray | outPoses | ||
) |
#include <vpi/algo/AprilTags.h>
Submits a AprilTag pose estimation operation to the stream.
[in] | stream | The stream where the operation will be queued in.
|
[in] | backend | Backend that will execute the algorithm.
|
[in] | inDetections | Array of AprilTag detections.
|
[in] | intrinsics | Camera intrinsics |
[in] | tagSize | Tag edge length
|
[out] | outPoses | Array that will receive the pose estimations. Array size will be set to same as inDetections.
|
VPI_ERROR_INVALID_ARGUMENT | stream is NULL. |
VPI_ERROR_INVALID_ARGUMENT | inDetections or outPoses is NULL. |
VPI_ERROR_NOT_IMPLEMENTED | Algorithm does not support the given backend. |
VPI_ERROR_INVALID_OPERATION | Backend hardware not available. |
VPI_ERROR_INVALID_OPERATION | The needed backends aren't enabled in stream , inDetections or outPoses . |
VPI_SUCCESS | Operation executed successfully. |