8 #ifndef META_OCEAN_GEOMETRY_CAMERA_CALIBRATION_H
9 #define META_OCEAN_GEOMETRY_CAMERA_CALIBRATION_H
78 inline const Vector2* corners()
const;
96 inline bool isEmpty()
const;
119 template <
typename TF,
typename TS>
static inline bool compareFirst(
const std::pair<TF, TS>& first,
const std::pair<TF, TS>& second);
211 static bool determineBestMatchingFovX(
const unsigned int width,
const unsigned int height,
const ConstIndexedAccessor<HomogenousMatrix4>& posesAccessor,
const ConstIndexedAccessor<Vectors3>& objectPointGroupAccessor,
const ConstIndexedAccessor<Vectors2>& imagePointGroupAccessor,
Scalar& idealFovX,
const bool twoIterations =
true,
const Scalar lowestFovX =
Numeric::deg2rad(25),
const Scalar highestFovX =
Numeric::deg2rad(75),
const unsigned int steps = 20u,
NonconstIndexedAccessor<HomogenousMatrix4>* idealPoses =
nullptr);
235 return patternCorners;
240 return patternTimestamp;
245 return patternRows.empty();
248 template <
typename TF,
typename TS>
251 return first.first < second.first;
This class implements a base class for all indexed-based accessors allowing a constant reference acce...
Definition: Accessor.h:241
Definition of a class holding the information about one calibration pattern.
Definition: CameraCalibration.h:41
Pattern(const PatternRows &rows, const Timestamp timestamp)
Creates a new pattern object.
Timestamp patternTimestamp
Pattern timestamp.
Definition: CameraCalibration.h:130
Pattern()
Creates an empty pattern object.
PatternRows patternRows
Pattern rows.
Definition: CameraCalibration.h:124
Vectors2 PatternRow
Definition of a (row) vector holding 2D positions.
Definition: CameraCalibration.h:47
static bool compareFirst(const std::pair< TF, TS > &first, const std::pair< TF, TS > &second)
Compares the first elements of two pairs.
Definition: CameraCalibration.h:249
std::vector< PatternRow > PatternRows
Definition of a vector holding rows.
Definition: CameraCalibration.h:52
const PatternRows & rows() const
Returns the rows of this pattern.
Definition: CameraCalibration.h:228
bool isEmpty() const
Returns whether the pattern object holds not valid corners.
Definition: CameraCalibration.h:243
const Vector2 * corners() const
Returns the four corners of this pattern.
Definition: CameraCalibration.h:233
Box2 boundingBox() const
Returns the bounding box of this pattern.
Timestamp timestamp() const
Returns the timestmap of this pattern.
Definition: CameraCalibration.h:238
Scalar distance(const Pattern &pattern) const
Returns the minimal sum of square distances between the corners of two calibration patterns.
void changeSize(const Scalar sizeFactor)
Applies a size factor to resize the entire pattern.
This class implements functions to calibrate a camera, to determine the profile of a camera.
Definition: CameraCalibration.h:34
static bool determineCameraCalibration(const PinholeCamera &roughCamera, const ObjectPointGroups &objectPointGroups, const ImagePointGroups &imagePointGroups, PinholeCamera &pinholeCamera, Scalar *sqrAccuracy=nullptr)
Determines the camera calibration while a rough camera calibration is already known.
static bool successiveCameraPoseOptimization(const PinholeCamera &pinholeCamera, const HomogenousMatrices4 &poses, const ObjectPointGroups &objectPointGroups, const ImagePointGroups &imagePointGroups, PinholeCamera &optimizedCamera, HomogenousMatrices4 &optimizedPoses, Scalar *initialSqrError=nullptr, Scalar *finalSqrError=nullptr)
Applies one camera and one pose optimization successively for a given set of poses and corresponding ...
static bool determineIntrinsicCameraMatrixPlanar(const ConstIndexedAccessor< Vectors3 > &objectPointGroups, const ConstIndexedAccessor< Vectors2 > &imagePointGroups, SquareMatrix3 &intrinsic, SquareMatrices3 *homographies=nullptr, Indices32 *validGroupIndices=nullptr)
Determines the intrinsic camera matrix for several groups of corresponding 2D/3D points.
static bool determineCameraCalibrationPlanar(const unsigned int width, const unsigned int height, const ConstIndexedAccessor< Vectors3 > &objectPointGroups, const ConstIndexedAccessor< Vectors2 > &imagePointGroups, PinholeCamera &pinholeCamera, const unsigned int iterations=20u, Scalar *sqrAccuracy=nullptr)
Determines the camera calibration for several individual groups of 3D object points all lying on the ...
std::vector< Pattern > Patterns
Definition of a vector holding calibration patterns.
Definition: CameraCalibration.h:136
static bool determineBestMatchingFovX(const unsigned int width, const unsigned int height, const ConstIndexedAccessor< HomogenousMatrix4 > &posesAccessor, const ConstIndexedAccessor< Vectors3 > &objectPointGroupAccessor, const ConstIndexedAccessor< Vectors2 > &imagePointGroupAccessor, Scalar &idealFovX, const bool twoIterations=true, const Scalar lowestFovX=Numeric::deg2rad(25), const Scalar highestFovX=Numeric::deg2rad(75), const unsigned int steps=20u, NonconstIndexedAccessor< HomogenousMatrix4 > *idealPoses=nullptr)
Determines the horizontal field of view that matches best to a set of poses, object point and image p...
static bool createCorrespondences(const Pattern &pattern, const Vector2 &boxSize, ObjectPoints &objectPoints, ImagePoints &imagePoints)
Creates point correspondences from a given calibration pattern.
This class implements a base class for all indexed-based accessors allowing a non-constant reference ...
Definition: Accessor.h:284
static constexpr T deg2rad(const T deg)
Converts deg to rad.
Definition: Numeric.h:3232
This class implements a timestamp.
Definition: Timestamp.h:36
std::vector< Index32 > Indices32
Definition of a vector holding 32 bit index values.
Definition: Base.h:96
std::vector< ObjectPoint > ObjectPoints
Definition of a vector holding 3D object points.
Definition: geometry/Geometry.h:129
std::vector< ObjectPoints > ObjectPointGroups
Definition of a vector holding object points, so we have groups of object points.
Definition: geometry/Geometry.h:135
std::vector< ImagePoint > ImagePoints
Definition of a vector holding 2D image points.
Definition: geometry/Geometry.h:123
std::vector< ImagePoints > ImagePointGroups
Definition of a vector holding image points, so we have groups of image points.
Definition: geometry/Geometry.h:141
float Scalar
Definition of a scalar type.
Definition: Math.h:128
std::vector< HomogenousMatrix4 > HomogenousMatrices4
Definition of a vector holding HomogenousMatrix4 objects.
Definition: HomogenousMatrix4.h:73
std::vector< SquareMatrix3 > SquareMatrices3
Definition of a vector holding SquareMatrix3 objects.
Definition: SquareMatrix3.h:71
std::vector< Vector2 > Vectors2
Definition of a vector holding Vector2 objects.
Definition: Vector2.h:64
The namespace covering the entire Ocean framework.
Definition: Accessor.h:15