8 #ifndef META_OCEAN_GEOMETRY_STEREOSCOPIC_GEOMETRY_H
9 #define META_OCEAN_GEOMETRY_STEREOSCOPIC_GEOMETRY_H
52 static bool cameraPose(
const PinholeCamera& pinholeCamera,
const ConstIndexedAccessor<Vector2>& imagePoints0,
const ConstIndexedAccessor<Vector2>& imagePoints1,
RandomGenerator& randomGenerator,
HomogenousMatrix4& world_T_camera1,
Vectors3* objectPoints =
nullptr,
Indices32* validIndices =
nullptr,
const Scalar maxRotationalSqrError =
Scalar(1.5 * 1.5),
const Scalar maxArbitrarySqrError =
Scalar(3.5 * 3.5),
const unsigned int iterations = 100u,
const Scalar rotationalMotionMinimalValidCorrespondencesPercent =
Scalar(0.9));
76 template <
typename TAccessorObjectPo
ints,
typename TAccessorImagePo
ints0,
typename TAccessorImagePo
ints1,
bool tUseBorderDistortionIfOuts
ide>
77 static bool determineValidCorrespondencesIF(
const PinholeCamera& pinholeCamera,
const HomogenousMatrix4& flippedCamera0_T_world,
const HomogenousMatrix4& flippedCamera1_T_world,
const TAccessorObjectPoints& objectPoints,
const TAccessorImagePoints0& imagePoints0,
const TAccessorImagePoints1& imagePoints1,
Indices32& validIndices,
const bool useDistortionParameters,
const Scalar maxSqrError =
Scalar(3.5 * 3.5),
const bool onlyFrontObjectPoints =
true,
Scalar* totalSqrError =
nullptr,
const size_t minimalValidCorrespondences = 0);
80 template <
typename TAccessorObjectPo
ints,
typename TAccessorImagePo
ints0,
typename TAccessorImagePo
ints1,
bool tUseBorderDistortionIfOuts
ide>
81 bool StereoscopicGeometry::determineValidCorrespondencesIF(
const PinholeCamera& pinholeCamera,
const HomogenousMatrix4& flippedCamera0_T_world,
const HomogenousMatrix4& flippedCamera1_T_world,
const TAccessorObjectPoints& objectPoints,
const TAccessorImagePoints0& imagePoints0,
const TAccessorImagePoints1& imagePoints1,
Indices32& validIndices,
const bool useDistortionParameters,
const Scalar maxSqrError,
const bool onlyFrontObjectPoints,
Scalar* totalSqrError,
const size_t minimalValidCorrespondences)
83 ocean_assert(pinholeCamera.
isValid());
84 ocean_assert(flippedCamera0_T_world.
isValid());
85 ocean_assert(flippedCamera1_T_world.
isValid());
86 ocean_assert(objectPoints.size() == imagePoints0.size() && imagePoints0.size() == imagePoints1.size());
87 ocean_assert(maxSqrError >= 0);
89 ocean_assert(validIndices.empty());
94 for (
size_t n = 0u; n < imagePoints0.size(); ++n)
97 if (minimalValidCorrespondences != 0 && imagePoints0.size() + validIndices.size() - n < minimalValidCorrespondences)
100 if (onlyFrontObjectPoints)
112 if (sqrDistance0 < maxSqrError && sqrDistance1 < maxSqrError)
114 validIndices.push_back((
unsigned int)n);
115 error += sqrDistance0 + sqrDistance1;
119 if (totalSqrError !=
nullptr)
121 *totalSqrError = error;
static bool isObjectPointInFrontIF(const HomogenousMatrixT4< Scalar > &flippedCamera_T_world, const VectorT3< Scalar > &objectPoint, const Scalar epsilon=NumericT< Scalar >::eps())
Determines whether a given 3D object point lies in front of a camera while the location of the camera...
Definition: Camera.h:811
This class implements function for stereoscopic geometry.
Definition: StereoscopicGeometry.h:30
static bool determineValidCorrespondencesIF(const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &flippedCamera0_T_world, const HomogenousMatrix4 &flippedCamera1_T_world, const TAccessorObjectPoints &objectPoints, const TAccessorImagePoints0 &imagePoints0, const TAccessorImagePoints1 &imagePoints1, Indices32 &validIndices, const bool useDistortionParameters, const Scalar maxSqrError=Scalar(3.5 *3.5), const bool onlyFrontObjectPoints=true, Scalar *totalSqrError=nullptr, const size_t minimalValidCorrespondences=0)
Determines valid correspondences between 2D image points and 3D camera points for two individual came...
Definition: StereoscopicGeometry.h:81
static bool cameraPose(const PinholeCamera &pinholeCamera, const ConstIndexedAccessor< Vector2 > &imagePoints0, const ConstIndexedAccessor< Vector2 > &imagePoints1, RandomGenerator &randomGenerator, HomogenousMatrix4 &world_T_camera1, Vectors3 *objectPoints=nullptr, Indices32 *validIndices=nullptr, const Scalar maxRotationalSqrError=Scalar(1.5 *1.5), const Scalar maxArbitrarySqrError=Scalar(3.5 *3.5), const unsigned int iterations=100u, const Scalar rotationalMotionMinimalValidCorrespondencesPercent=Scalar(0.9))
Determines the pose transformation between two given camera frames from which corresponding image poi...
bool isValid() const
Returns whether this matrix is a valid homogeneous transformation.
Definition: HomogenousMatrix4.h:1806
bool isValid() const
Returns whether this camera is valid.
Definition: PinholeCamera.h:1572
bool hasDistortionParameters() const
Returns whether this camera object has specified distortion parameters.
Definition: PinholeCamera.h:1293
VectorT2< T > projectToImageIF(const HomogenousMatrixT4< T > &flippedCamera_T_world, const VectorT3< T > &objectPoint, const bool distortImagePoint, const T zoom=T(1)) const
Projects a 3D object point to the 2D image plane of the camera by a given inverse camera pose.
Definition: PinholeCamera.h:1816
This class implements a generator for random numbers.
Definition: RandomGenerator.h:42
unsigned int sqrDistance(const char first, const char second)
Returns the square distance between two values.
Definition: base/Utilities.h:1089
std::vector< Index32 > Indices32
Definition of a vector holding 32 bit index values.
Definition: Base.h:96
float Scalar
Definition of a scalar type.
Definition: Math.h:128
std::vector< Vector3 > Vectors3
Definition of a vector holding Vector3 objects.
Definition: Vector3.h:65
The namespace covering the entire Ocean framework.
Definition: Accessor.h:15