Struct CalibrationTarget

Struct Documentation

struct CalibrationTarget

Struct resembling the used calibration target, and its geometry.

Public Functions

inline void createArUcoBoard()

Method to create ArUco Board based on the marker positions and their ids.

inline void readFromYamlFile(const std::string iFilePath)

Read parameters from given yaml file.

Parameters:

iFilePath[in] Path to yaml file. It is assumed that the yaml file exist. Thus, no check is performed.

inline bool isValid() const

Returns true if target specifications are valid. False, otherwise.

inline bool isLocalPointInsideCutout(const float iPntX, const float iPntY, float *opDistance = nullptr, float *opPenalty = nullptr) const

Method to test whether a point lies inside a cutout.

Loops over all cutouts and performs individual test.

Parameters:
  • iPntX[in] X-value of the point in the local coordinate system of the calibration target.

  • iPntY[in] Y-value of the point in the local coordinate system of the calibration target.

  • opDistance[out] Pointer to return value providing the distance to the center of the cutout. Set to nullptr if not used.

  • opPenalty[out] Pointer to return value providing a penalty based on the distance of the point to the center of the cutout.

Returns:

True, if point is inside the cutout. False, otherwise.

inline bool isLocalPointInsideCutout(const cv::Vec2f iPnt, float *opDistance = nullptr, float *opPenalty = nullptr) const

Method to test whether a point lies inside a cutout.

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Loops over all cutouts and performs individual test.

Parameters:
  • iPnt[in] 2D point given in the local coordinate system of the calibration target.

  • opDistance[out] Pointer to return value providing the distance to the center of the cutout. Set to nullptr if not used.

  • opPenalty[out] Pointer to return value providing a penalty based on the distance of the point to the center of the cutout.

inline bool isLocalPointInlier(const float iPntX, const float iPntY, float *opDistance = nullptr, float *opPenalty = nullptr) const

Method to test whether a point (given in local coordinates) is an inlier, i.e. lies on target board.

Parameters:
  • iPntX[in] X-value of the point in the local coordinate system of the calibration target.

  • iPntY[in] Y-value of the point in the local coordinate system of the calibration target.

  • opDistance[out] Pointer to return value providing the distance. Set to nullptr if not used.

  • opPenalty[out] Pointer to return value providing a penalty based on the distance.

Returns:

True, if point lies on the board. False, otherwise.

template<typename PointT>
inline void computeMarkerCornersFromPose(const Eigen::Vector3f &iCenter, const Eigen::Vector3f &iUp, const Eigen::Vector3f &iNormal, std::vector<uint> &oMarkerIds, std::vector<std::array<PointT, 4>> &oMarkerCorners)

Compute 3D coordinates of each marker corner based on the 6DOF pose of the calibration target.

Template Parameters:

PointT – Class used for the marker corner points

Parameters:
  • iCenter[in] Center point of the calibration target pose.

  • iUp[in] Up vector of the calibration target pose.

  • iNormal[in] Normal vector of the calibration target pose.

  • oMarkerIds[out] List of marker IDs for which the coordinates were computed.

  • oMarkerCorners[out] List of 4D arrays holding the 3D corner points of each marker corresponding to the ID in oMarkerIDs. The corner points are given in clockwise order, starting from the top left.

template<typename PointT>
inline void computePoseFromTopLeftMarkerCorners(const std::vector<uint> &iMarkerIds, const std::vector<PointT> &iTlMarkerCorners, Eigen::Vector3f &oCenter, Eigen::Vector3f &oUp, Eigen::Vector3f &oRight, Eigen::Vector3f &oNormal)

Compute calibration target pose from coordinates of top-left marker corners.

Template Parameters:

PointT – Class used for the marker corner points

Parameters:
  • iMarkerIds[in] List of marker IDs for which the top-left corner coordinate has been observed.

  • iTlMarkerCorners[in] 3D points of the top-left marker corners corresponding to the IDs in iMarkerIds

  • oCenter[out] Translational vector as seen from the reference coordinate system.

  • oUp[out] Up vector as seen from the reference coordinate system (normalized).

  • oRight[out] Right vector as seen from the reference coordinate system (normalized).

  • oNormal[out] Normal vector as seen from the reference coordinate system and pointing into direction of the origin of the reference coordinate system (normalized).

Public Members

cv::Size2f boardSize = cv::Size2f()

Size of calibration board in meters.

float markerSize = 0.0f

Side length of aruco markers in meters.

std::vector<int> markerIds = {}

IDs of marker used (order: clockwise, starting from top left of board)

std::vector<cv::Point3f> markerPositions = {}

x,y,z marker positions (top-left) on board relative to top-left corner (planar –> z = 0)

std::vector<std::shared_ptr<Cutout>> pBoardCutouts = {}

cutouts on board

int minMarkerDetection = 3

minimum number of markers that need to be detected.

std::string cadModelMeshPath = ""

file path to CAD model of the calibration target as mesh

std::string cadModelCloudPath = ""

file path to CAD model of the calibration target as cloud

cv::Ptr<cv::aruco::Board> pArucoBoard = nullptr

Pointer to ArUco board.

cv::Ptr<cv::aruco::Dictionary> pArucoDictionary = nullptr

Pointer to ArUco dictoionary used (Default DICT_6X6_250)

Public Static Functions

static inline void computePose(const Eigen::Vector3f &iCenter, const Eigen::Vector3f &iUp, const Eigen::Vector3f &iNormal, lib3d::Extrinsics &oPose)

Compute extrinsic pose based on given vectors.

Parameters:
  • iCenter[in] Translational vector as seen from the reference coordinate system.

  • iUp[in] Up vector as seen from the reference coordinate system.

  • iNormal[in] Normal vector as seen from the reference coordinate system and pointing into direction of the origin of the reference coordinate system.

  • oPose[out] Computed pose with transformation direction local to ref.

static inline void decomposePose(const lib3d::Extrinsics &iPose, Eigen::Vector3f &oCenter, Eigen::Vector3f &oUp, Eigen::Vector3f &oNormal)

Decompose extrinsic pose into three vectors.

Parameters:
  • iPose[in] Extrinsic pose.

  • oCenter[out] Translational vector as seen from the reference coordinate system.

  • oUp[out] Up vector as seen from the reference coordinate system (normalized).

  • oNormal[out] Normal vector as seen from the reference coordinate system and pointing into direction of the origin of the reference coordinate system (normalized).

static inline void computePlaneParametersFromPose(const lib3d::Extrinsics &iPose, cv::Vec4d &oPlaneParameters)

Compute 4D plane parameters from lib3D::Extrinsics pose.

Parameters:
  • iPose[in] Board pose.

  • oPlaneParameters[out] 4D plane parameters.