Function Reference
AprilTags.jl functions
AprilTags.AprilTagDetector — TypeAprilTagDetector(tagfamily=tag36h11)Create a default AprilTag detector with the 36h11 tag family Create an AprilTag detector with tag family in tagfamily::TagFamilies @enum TagFamilies tag36h11 tag25h9 tag16h5
AprilTagDetector(img)Run the april tag detector on a image
AprilTags.freeDetector! — FunctionfreeDetector!(apriltagdetector)Free the allocated memmory
AprilTags.homography_to_pose — Functionhomography_to_pose(H, f_width, f_height, c_width, c_height, [taglength = 2.0])Given a 3x3 homography matrix and the camera model (focal length and centre), compute the pose of the tag.
Notes
- Images.jl uses
::Arrayin Julia as column-major (i.e. vertical major) convention, that issize(img) == (480, 640)- Axes start top left-corner of the image plane (i.e. the image-frame):
widthis from left to right,heightis from top downward.
- The low-level
ccallwrapped C-library underneath uses the convention (i.e. the camera-frame):fx == f_width,cy == c_height, and- C-library camara coordinate system: camera looking along positive Z axis with
xto the right andydown.- C-library internally follows: https://docs.opencv.org/3.4/d9/d0c/group__calib3d.html
- The focal lengths should be given in pixels.
- The returned units are those of the tag size, therefore the translational components should be scaled with the tag size.
- The tag coordinates are from (-1,-1) to (1,1), i.e. the tag size has length of 2 units.
- Optionally, the tag length (in metre) can be passed to return a scaled value.
- Returns
::Matrix{Float64}
Related
homographytopose
AprilTags.homographytopose — Functionhomographytopose(H, f_width, f_height, c_width, c_height, [taglength = 2.0])Given a 3x3 homography matrix and the camera model (focal length and centre), compute the pose of the tag.
Notes
- Images.jl uses
::Arrayin Julia as column-major (i.e. vertical major) convention, that issize(img) == (480, 640)- Axes start top left-corner of the image plane (i.e. the image-frame):
widthis from left to right,heightis from top downward.
- The low-level
ccallwrapped C-library underneath uses the convention (i.e. the camera-frame):fx == f_width,cy == c_height, and- C-library camara coordinate system: camera looking along positive Z axis with
xto the right andydown.- C-library internally follows: https://docs.opencv.org/3.4/d9/d0c/group__calib3d.html
- The focal lengths should be given in pixels.
- The returned units are those of the tag size, therefore the translational components should be scaled with the tag size.
- The tag coordinates are from (-1,-1) to (1,1), i.e. the tag size has length of 2 units.
- Optionally, the tag length (in metre) can be passed to return a scaled value.
- Returns
::Matrix{Float64}
```
Related:
homography_to_pose
AprilTags.drawTagBox! — FunctiondrawTagBox!(image, tag)Draw a box around the tag. imageCol = RGB.(image) foreach(tag->drawTagBox!(imageCol, tag), tags)
AprilTags.drawTagAxes! — FunctiondrawTagAxes!(image, tag, CameraMatrix)Draw the tag x, y, and z axes to show the orientation. imageCol = RGB.(image) foreach(tag->drawTagAxes!(imageCol, tag, K), tags)
AprilTags.getAprilTagImage — FunctiongetAprilTagImage(tagIndex, tagfamily=tag36h11)Return an image [Gray{N0f8}] for with tagIndex from tag family in tagfamily::TagFamilies @enum TagFamilies tag36h11 tag25h9 tag16h5
AprilTags.threadcalldetect — Functionthreadcalldetect(detector, image)Run the april tag detector on a image
AprilTags.detectAndPose — FunctiondetectAndPose(
detector,
image,
f_width,
f_height,
c_width,
c_height,
taglength
)
Detect tags and calcuate the pose on them.
AprilTags.tagOrthogonalIteration — FunctiontagOrthogonalIteration(
corners,
H,
f_width,
f_height,
c_width,
c_height;
taglength,
nIters
)
Run the orthoganal iteration algorithm on the poses.
Notes
- See apriltag_pose.h
- [2]: Lu, G. D. Hager and E. Mjolsness, "Fast and globally convergent pose estimation from video images," in IEEE Transactions on Pattern Analysis and Machine Intelligence, vol. 22, no. 6, pp. 610-622, June 2000. doi: 10.1109/34.862199
- The low level C-library uses
fx=f_width.
Wrappers
AprilTags.apriltag_detector_create — Functionapriltag_detector_create()Create a AprilTag Detector object with all fields set to default value.
AprilTags.tag36h11_create — Functiontag36h11_create()Create a AprilTag family object for tag36h11 with all fields set to default value.
AprilTags.tag36h11_destroy — Functiontag36h11_destroy(tf)Destroy the AprilTag family object.
AprilTags.apriltag_detector_add_family — Functionapriltag_detector_add_family(tag_detector, tag_family)Add a tag family to an AprilTag Detector object. The caller still "owns" the family and a single instance should only be provided to one apriltag detector instance.
AprilTags.apriltag_detector_detect — Functionapriltag_detector_detect(tag_detector, image)Detect tags from an image and return an array of apriltagdetectiont*. You can use apriltagdetectionsdestroy to free the array and the detections it contains, or call detectiondestroy and zarraydestroy yourself.
AprilTags.threadcall_apriltag_detector_detect — Functionthreadcall_apriltag_detector_detect(tag_detector, image)Experimental call apriltagdetectordetect in a seperate thread using the experimantal @threadcall Detect tags from an image and return an array of apriltagdetectiont*. You can use apriltagdetectionsdestroy to free the array and the detections it contains, or call detectiondestroy and zarraydestroy yourself.
Index
AprilTags.AprilTagDetectorAprilTags.apriltag_detector_add_familyAprilTags.apriltag_detector_createAprilTags.apriltag_detector_detectAprilTags.calcCalibResidualAprilTags!AprilTags.calcCornerProjectionsAprilTags!AprilTags.detectAndPoseAprilTags.drawTagAxes!AprilTags.drawTagBox!AprilTags.freeDetector!AprilTags.getAprilTagImageAprilTags.homography_to_poseAprilTags.homographytoposeAprilTags.tag36h11_createAprilTags.tag36h11_destroyAprilTags.tagOrthogonalIterationAprilTags.threadcall_apriltag_detector_detectAprilTags.threadcalldetect