Struct CameraCalibration¶
Defined in File schemas.hpp
Struct Documentation¶
-
struct CameraCalibration¶
Camera calibration parameters.
Public Functions
-
FoxgloveError encode(uint8_t *ptr, size_t len, size_t *encoded_len)¶
Encoded the CameraCalibration as protobuf to the provided buffer.
On success, writes the serialized length to *encoded_len. If the provided buffer has insufficient capacity, writes the required capacity to *encoded_len and returns FoxgloveError::BufferTooShort. If the message cannot be encoded, writes the reason to stderr and returns FoxgloveError::EncodeError.
- Parameters:
ptr – the destination buffer. must point to at least len valid bytes.
len – the length of the destination buffer.
encoded_len – where the serialized length or required capacity will be written to.
Public Members
-
std::string frame_id¶
Frame of reference for the camera. The origin of the frame is the optical center of the camera. +x points to the right in the image, +y points down, and +z points into the plane of the image.
-
uint32_t width = 0¶
Image width.
-
uint32_t height = 0¶
Image height.
-
std::string distortion_model¶
Name of distortion model.
Supported parameters:
plumb_bob
(k1, k2, p1, p2, k3),rational_polynomial
(k1, k2, p1, p2, k3, k4, k5, k6), andkannala_brandt
(k1, k2, k3, k4).plumb_bob
andrational_polynomial
models are based on the pinhole model OpenCV’s pinhole camera model. Thekannala_brandt
model matches the OpenvCV fisheye model.
-
std::vector<double> d¶
Distortion parameters.
-
std::array<double, 9> k¶
Intrinsic camera matrix (3x3 row-major matrix)
A 3x3 row-major matrix for the raw (distorted) image.
Projects 3D points in the camera coordinate frame to 2D pixel coordinates using the focal lengths (fx, fy) and principal point (cx, cy).
@brief [fx 0 cx] @brief K = [ 0 fy cy] @brief [ 0 0 1] @brief
-
std::array<double, 9> r¶
Rectification matrix (stereo cameras only, 3x3 row-major matrix)
A rotation matrix aligning the camera coordinate system to the ideal stereo image plane so that epipolar lines in both stereo images are parallel.
-
std::array<double, 12> p¶
Projection/camera matrix (3x4 row-major matrix)
@brief [fx' 0 cx' Tx] @brief P = [ 0 fy' cy' Ty] @brief [ 0 0 1 0] @brief
By convention, this matrix specifies the intrinsic (camera) matrix of the processed (rectified) image. That is, the left 3x3 portion is the normal camera intrinsic matrix for the rectified image.
It projects 3D points in the camera coordinate frame to 2D pixel coordinates using the focal lengths (fx’, fy’) and principal point (cx’, cy’) - these may differ from the values in K.
For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will also have R = the identity and P[1:3,1:3] = K.
Foxglove currently does not support displaying stereo images, so Tx and Ty are ignored.
Given a 3D point [X Y Z]’, the projection (x, y) of the point onto the rectified image is given by:
@brief [u v w]' = P * [X Y Z 1]' @brief x = u / w @brief y = v / w @brief
This holds for both images of a stereo pair.
Public Static Functions
-
static Schema schema()¶
Get the CameraCalibration schema.
The schema data returned is statically allocated.
-
FoxgloveError encode(uint8_t *ptr, size_t len, size_t *encoded_len)¶