VPI - Vision Programming Interface

3.2 Release

AprilTags

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...
 

Detailed Description

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.


Data Structure Documentation

◆ VPIAprilTagDecodeParams

struct VPIAprilTagDecodeParams

Decode parameters for vpiCreateAprilTagDetector.

Specifies family to decode and decode properties.

Definition at line 111 of file AprilTags.h.

+ Collaboration diagram for VPIAprilTagDecodeParams:
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.
  • Must be >=0.
  • Must be less than the number of tags in the family.
int32_t maxBitsCorrected Maximum number of bits to correct during decoding.
  • Must be in range [0,2]
VPIAprilTagFamily family Which family to detect.

◆ VPIAprilTagDetection

struct VPIAprilTagDetection

Stores information about an AprilTag detection from AprilTag detector.

Definition at line 772 of file Types.h.

+ Collaboration diagram for VPIAprilTagDetection:
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.

Enumeration Type Documentation

◆ 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.

Enumerator
VPI_APRILTAG_INVALID 

Invalid value.

VPI_APRILTAG_16H5 

16h5 family

VPI_APRILTAG_25H9 

25h9 family

VPI_APRILTAG_36H10 

36h10 family

VPI_APRILTAG_36H11 

36h11 family

VPI_APRILTAG_CIRCLE21H7 

Circle21h7 family.

VPI_APRILTAG_CIRCLE49H12 

Circle49h12 family.

VPI_APRILTAG_CUSTOM48H12 

Custom48h12 family.

VPI_APRILTAG_STANDARD41H12 

Standard41h12 family.

VPI_APRILTAG_STANDARD52H13 

Standard52h13 family.

Definition at line 83 of file AprilTags.h.

Function Documentation

◆ vpiInitAprilTagDecodeParams()

VPIStatus vpiInitAprilTagDecodeParams ( VPIAprilTagDecodeParams params)

#include <vpi/algo/AprilTags.h>

Initializes VPIAprilTagDecodeParams with default values.

Defaults:

Parameters
[out]paramsStructure to be filled with default values.
Return values
VPI_ERROR_INVALID_ARGUMENTparams is NULL
VPI_SUCCESSOperation executed successfully.

◆ vpiCreateAprilTagDetector()

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.

Parameters
[in]backendsVPI backends that are eligible to execute the algorithm.
[in]inputWidth,inputHeightDimensions of the input image that will be used with this payload.
  • Must be > 0.
[in]paramsDecode parameters for the detector. Pass NULL to use the defaults given by vpiInitAprilTagDecodeParams.
[out]payloadPointer to the payload variable that receives the created handle.
Return values
VPI_ERROR_INVALID_ARGUMENTpayload is NULL.
VPI_ERROR_INVALID_ARGUMENTbackends refers to an invalid backend.
VPI_ERROR_INVALID_ARGUMENTinputWidth or inputHeight outside valid range.
VPI_ERROR_INVALID_ARGUMENTparams is NULL or contains invalid configuration.
VPI_ERROR_INVALID_OPERATIONBackend hardware not available, or backend not available in current context.
VPI_ERROR_NOT_IMPLEMENTEDAlgorithm does not support the given backend.
VPI_ERROR_INVALID_CONTEXTCurrent context is destroyed.
VPI_ERROR_OUT_OF_MEMORYCannot allocate required resources.
VPI_SUCCESSOperation executed successfully.

◆ vpiSubmitAprilTagDetector()

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.

Parameters
[in]streamThe stream where the operation will be queued in.
  • Must not be NULL.
  • Stream must have enabled the backends that will execute the algorithm.
[in]backendBackend that will execute the algorithm.
  • Must be the backend specified during payload creation or 0 as a shorthand to use this backend.
[in]payloadPayload to be submitted along the other parameters.
[in]maxDetectionsMaximum number of detections to be returned in outDetections.
[in]inputInput image used for detection
  • Must not be NULL.
  • Must match dimensions used in vpiCreateAprilTagDetector.
  • Image must have enabled the backends that will execute the algorithm.
  • Must have format VPI_IMAGE_FORMAT_U8
[out]outDetectionsArray that will receive the detections. Array size is updated with the number of tags found.
  • Must not be NULL.
  • It must have type VPI_ARRAY_TYPE_APRILTAG_DETECTION.
  • Array must have enabled the backends that will execute the algorithm.
  • If more tags are detected than the array capacity, extra tag detections are discarded.
Return values
VPI_ERROR_INVALID_ARGUMENTstream is NULL.
VPI_ERROR_INVALID_ARGUMENTinput is NULL.
VPI_ERROR_INVALID_ARGUMENTinput image dimensions do not match dimensions passed to vpiCreateAprilTagDetector.
VPI_ERROR_INVALID_ARGUMENTbackend does not match the backend used to create the payload.
VPI_ERROR_INVALID_IMAGE_FORMATinput image format not supported.
VPI_ERROR_INVALID_PAYLOAD_TYPEpayload is invalid or NULL.
VPI_ERROR_NOT_IMPLEMENTEDAlgorithm does not support the given backend.
VPI_ERROR_INVALID_OPERATIONBackend hardware not available.
VPI_ERROR_INVALID_OPERATIONThe needed backends aren't enabled in stream, input or outDetections.
VPI_SUCCESSOperation executed successfully.

◆ vpiSubmitAprilTagPoseEstimation()

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.

Parameters
[in]streamThe stream where the operation will be queued in.
  • Must not be NULL.
  • Stream must have enabled the backends that will execute the algorithm.
[in]backendBackend that will execute the algorithm.
  • Valid values:
  • Backend must be enabled in current context.
[in]inDetectionsArray of AprilTag detections.
[in]intrinsicsCamera intrinsics
[in]tagSizeTag edge length
  • Must be > 0
[out]outPosesArray that will receive the pose estimations. Array size will be set to same as inDetections.
  • Must not be NULL.
  • It must have type VPI_ARRAY_TYPE_POSE.
  • Array must have enabled the backends that will execute the algorithm.
  • Capacity must be equal or greater than size of inDetections.
Return values
VPI_ERROR_INVALID_ARGUMENTstream is NULL.
VPI_ERROR_INVALID_ARGUMENTinDetections or outPoses is NULL.
VPI_ERROR_NOT_IMPLEMENTEDAlgorithm does not support the given backend.
VPI_ERROR_INVALID_OPERATIONBackend hardware not available.
VPI_ERROR_INVALID_OPERATIONThe needed backends aren't enabled in stream, inDetections or outPoses.
VPI_SUCCESSOperation executed successfully.