Ocean
Ocean::Geometry::Utilities Class Reference

This class implements utilities function for the tracking library. More...

Static Public Member Functions

static ObjectPoint backProjectImagePoint (const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &pose, const Plane3 &plane, const ImagePoint &imagePoint, const bool useDistortionParameters, bool *frontObjectPoint=nullptr)
 Projects one image points onto a 3D plane and returns the resulting 3D object point. More...
 
static ObjectPoints backProjectImagePoints (const AnyCamera &anyCamera, const HomogenousMatrix4 &world_T_camera, const Plane3 &plane, const ImagePoint *imagePoints, const size_t numberImagePoints, Indices32 *frontObjectPointIndices=nullptr)
 Projects a set of given image points onto a 3D plane and returns the resulting 3D object points. More...
 
static ObjectPoints backProjectImagePoints (const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &pose, const Plane3 &plane, const ImagePoint *imagePoints, const size_t numberImagePoints, const bool useDistortionParameters, Indices32 *frontObjectPointIndices=nullptr)
 Deprecated. More...
 
static ObjectPoints backProjectImagePoints (const AnyCamera &anyCamera, const HomogenousMatrix4 &world_T_camera, const Cylinder3 &cylinder, const ImagePoint *imagePoints, const size_t numberImagePoints, Indices32 &intersectingPointIndices)
 Projects a set of given image points onto a 3D cylinder and returns only the resulting 3D object points for rays that intersect the cylinder. More...
 
static ObjectPoints backProjectImagePoints (const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &pose, const Cylinder3 &cylinder, const ImagePoint *imagePoints, const size_t numberImagePoints, const bool useDistortionParameters, Indices32 &intersectingPointIndices)
 Deprecated. More...
 
static ObjectPoints backProjectImagePoints (const AnyCamera &anyCamera, const HomogenousMatrix4 &world_T_camera, const Cone3 &cone, const ImagePoint *imagePoints, const size_t numberImagePoints, Indices32 &intersectingPointIndices)
 Projects a set of given image points onto a 3D cone and returns only the resulting 3D object points for rays that intersect the cone. More...
 
static ObjectPoints backProjectImagePoints (const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &pose, const Cone3 &cone, const ImagePoint *imagePoints, const size_t numberImagePoints, const bool useDistortionParameters, Indices32 &intersectingPointIndices)
 Deprecated. More...
 
static ObjectPoints backProjectImagePointsDamped (const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &pose, const Plane3 &plane, const ImagePoint *imagePoints, const size_t numberImagePoints, const bool useDistortionParameters, Indices32 *frontObjectPointIndices=nullptr)
 Projects a set of given image points onto a 3D plane and returns the resulting 3D object points. More...
 
static Vectors3 createObjectPoints (const AnyCamera &camera, const HomogenousMatrix4 &world_T_camera, const ConstIndexedAccessor< Vector2 > &imagePoints, const Scalar distance)
 Creates a set of 3D object points for a set of given 2D image points. More...
 
static ObjectPoints createObjectPoints (const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &pose, const ConstIndexedAccessor< ImagePoint > &imagePoints, const bool useDistortionParameters, const Scalar distance)
 Deprecated. More...
 
static void triangulateObjectPoints (const AnyCamera &camera0, const AnyCamera &camera1, const HomogenousMatrix4 &world_T_camera0, const HomogenousMatrix4 &world_T_camera1, const ConstIndexedAccessor< Vector2 > &imagePoints0, const ConstIndexedAccessor< Vector2 > &imagePoints1, Vectors3 &objectPoints, Indices32 &validIndices, const bool onlyFrontPoints=true, const Scalar maximalSqrError=Scalar(3 *3))
 Determines 3D object points by triangulating two sets of 2D image points from different camera poses. More...
 
static Triangles3 backProjectTriangles (const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &pose, const Plane3 &plane, const Triangle2 *triangles, const size_t numberTriangles, const bool useDistortionParameters)
 Projects a set of given 2D image triangles onto a 3D plane and returns the resulting 3D object triangles. More...
 
static size_t countFrontObjectPoints (const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &pose, const ObjectPoint *objectPoints, const size_t numberObjectPoints)
 Counts the number of object points that are in front of a given camera. More...
 
static size_t countFrontObjectPointsIF (const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &invertedFlippedPose, const ObjectPoint *objectPoints, const size_t numberObjectPoints)
 Counts the number of object points that are in front of a given camera. More...
 
static size_t countFrontObjectPoints (const PinholeCamera &cameraFirst, const PinholeCamera &cameraSecond, const HomogenousMatrix4 &poseFirst, const HomogenousMatrix4 &poseSecond, const ImagePoint *imagePointsFirst, const ImagePoint *imagePointsSecond, const size_t correspondences)
 Counts the number of object points that are visible in two individual camera frames and are located in front of both cameras. More...
 
static SquareMatrix2 covarianceMatrix (const ImagePoint *imagePoints, const size_t number, const Scalar minimalSigma=0)
 Creates the covariance matrix for a given set of image points. More...
 
static SquareMatrix2 covarianceMatrix (const ImagePoint *imagePoints, const size_t number, const ImagePoint &meanPoint, const Scalar minimalSigma=0)
 Creates the covariance matrix for a given set of image points. More...
 
static SquareMatrix2 covarianceMatrix (const ImagePoint *imagePoints, const unsigned int *indices, const size_t numberIndices, const Scalar minimalSigma, ImagePoint &meanPoint)
 Creates the covariance matrix for a given set of image points. More...
 
static SquareMatrix2 covarianceMatrix (const Vector2 &direction0, const Scalar sigma0, const Vector2 &direction1, const Scalar sigma1)
 Creates a covariance matrix by two given orthogonal vectors. More...
 
static SquareMatrix2 covarianceMatrix (const Vector2 &direction0, const Vector2 &direction1)
 Creates a covariance matrix by two given orthogonal vectors. More...
 
static SquareMatrix2 covarianceMatrix (const Vector2 &majorDirection, const Scalar minimalSigma=1, const Scalar minorFactor=Scalar(0.01))
 Creates a covariance matrix by one given vector representing the major axis. More...
 
static bool decomposeCovarianceMatrix (const SquareMatrix2 &covarianceMatrix, Vector2 &direction0, Vector2 &direction1)
 Decomposes a covariance matrix. More...
 
static bool isPolygonConvex (const Vector2 *vertices, const size_t size, const bool strict=true)
 Returns whether a polygon of given 2D points is convex. More...
 
static Scalar computePolygonArea (const Vector2 *vertices, size_t size)
 Compute the area of a polygon. More...
 
static Scalar computePolygonArea (const Vectors2 &vertices)
 Compute the area of a polygon. More...
 
static Scalar computePolygonAreaSigned (const Vector2 *vertices, size_t size)
 Compute the signed area of a polygon The value of the area will be positive if the vertices are in counter-clockwise order and negative if they are in clock-wise order. More...
 
static Scalar computePolygonAreaSigned (const Vectors2 &vertices)
 Compute the signed area of a polygon The value of the area will be positive if the vertices are in counter-clockwise order and negative if they are in clock-wise order. More...
 
static bool isInsideConvexPolygon (const Vector2 *vertices, size_t size, const Vector2 &point)
 Returns whether a given point lies inside a convex polygon. More...
 
static bool isInsideConvexPolygon (const Vectors2 &vertices, const Vector2 &point)
 Returns whether a given point lies inside a convex polygon. More...
 
static bool intersectConvexPolygons (const Vector2 *vertices0, const size_t size0, const Vector2 *vertices1, const size_t size1, Vectors2 &intersectedPolygon)
 Computation of the intersection of two convex polygons. More...
 
static bool intersectConvexPolygons (const Vectors2 &vertices0, const Vectors2 &vertices1, Vectors2 &intersectedPolygon)
 Computation of the intersection of two convex polygons. More...
 
template<typename TAccessor >
static ImagePoint meanImagePoint (const TAccessor &imagePointAccessor)
 Returns the mean position of a set of given 2D points. More...
 
template<typename TAccessor >
static ObjectPoint meanObjectPoint (const TAccessor &objectPointAccessor)
 Returns the mean position of a set of given 3D points. More...
 
template<typename TAccessor >
static ImagePoint medianImagePoint (const TAccessor &imagePointAccessor)
 Returns the median position of a set of given 2D points. More...
 
template<typename TAccessor >
static ObjectPoint medianObjectPoint (const TAccessor &objectPointAccessor)
 Returns the median position of a set of given 3D points. More...
 
template<typename TAccessor >
static Scalar medianDistance (const ImagePoint &imagePoint, const TAccessor &imagePointAccessor)
 Returns the median distance between a given 2D object point and a set of given 2D points. More...
 
template<typename TAccessor >
static Scalar medianDistance (const ObjectPoint &objectPoint, const TAccessor &objectPointAccessor)
 Returns the median distance between a given 3D object point and a set of given 3D points. More...
 
static SquareMatrix3 createRandomHomography (const unsigned int width, const unsigned height, const Scalar maxTranslation)
 Create a random homography transformation The homography is created in such a way that points in an output image are mapped into the input image, i.e., inputPoints_i = homography * outputPoints_i. More...
 
static HomogenousMatrix4 randomCameraPose (const PinholeCamera &pinholeCamera, const Line3 &worldObjectPointRay, const Vector2 &distortedImagePoint, const Scalar distance)
 Deprecated. More...
 
static HomogenousMatrix4 randomCameraPose (const FisheyeCamera &fisheyeCamera, const Line3 &worldObjectPointRay, const Vector2 &distortedImagePoint, const Scalar distance)
 Deprecated. More...
 
static HomogenousMatrix4 randomCameraPose (const AnyCamera &anyCamera, const Line3 &worldObjectPointRay, const Vector2 &distortedImagePoint, const Scalar distance)
 Returns a random 6-DOF camera pose for any camera which observes a given 3D object point at a specified 2D image point location while having a specified distance to the 3D object point. More...
 

Detailed Description

This class implements utilities function for the tracking library.

Member Function Documentation

◆ backProjectImagePoint()

static ObjectPoint Ocean::Geometry::Utilities::backProjectImagePoint ( const PinholeCamera pinholeCamera,
const HomogenousMatrix4 pose,
const Plane3 plane,
const ImagePoint imagePoint,
const bool  useDistortionParameters,
bool *  frontObjectPoint = nullptr 
)
static

Projects one image points onto a 3D plane and returns the resulting 3D object point.

Beware: The back projected point may be located behind the camera due to the position and orientation of the given plane!
Beware: Ensure that the given plane is not parallel with the viewing direction of the camera.

Parameters
pinholeCameraThe pinhole camera object
posePose of the camera
plane3D plane that is used to determine the position of the back-projected 3D object point
imagePointImage point that will be back-projected
useDistortionParametersTrue, to use the distortion parameters of the camera
frontObjectPointOptional resulting statement whether the resulting object point is located in front of the camera; True, if so
Returns
Resulting 3D object point

◆ backProjectImagePoints() [1/6]

static ObjectPoints Ocean::Geometry::Utilities::backProjectImagePoints ( const AnyCamera anyCamera,
const HomogenousMatrix4 world_T_camera,
const Cone3 cone,
const ImagePoint imagePoints,
const size_t  numberImagePoints,
Indices32 intersectingPointIndices 
)
static

Projects a set of given image points onto a 3D cone and returns only the resulting 3D object points for rays that intersect the cone.

Parameters
anyCameraThe camera profile defining the projection and distortion
world_T_cameraThe transformation from the camera coordinate system to world coordinates, worldPoint = world_T_camera * cameraPoint, must be valid
cone3D cone that is used to determine the position of the back-projected 3D object points
imagePointsImage points that will be back-projected
numberImagePointsNumber of given image points
intersectingPointIndicesOutput indices of all 2D points whose rays actually intersect with the cone
Returns
Resulting 3D object points

◆ backProjectImagePoints() [2/6]

static ObjectPoints Ocean::Geometry::Utilities::backProjectImagePoints ( const AnyCamera anyCamera,
const HomogenousMatrix4 world_T_camera,
const Cylinder3 cylinder,
const ImagePoint imagePoints,
const size_t  numberImagePoints,
Indices32 intersectingPointIndices 
)
static

Projects a set of given image points onto a 3D cylinder and returns only the resulting 3D object points for rays that intersect the cylinder.

Parameters
anyCameraThe camera profile defining the projection and distortion
world_T_cameraThe transformation from the camera coordinate system to world coordinates, worldPoint = world_T_camera * cameraPoint, must be valid
cylinder3D cylinder that is used to determine the position of the back-projected 3D object points
imagePointsImage points that will be back-projected
numberImagePointsNumber of given image points
intersectingPointIndicesOutput indices of all 2D points whose rays actually intersect with the cylinder
Returns
Resulting 3D object points

◆ backProjectImagePoints() [3/6]

static ObjectPoints Ocean::Geometry::Utilities::backProjectImagePoints ( const AnyCamera anyCamera,
const HomogenousMatrix4 world_T_camera,
const Plane3 plane,
const ImagePoint imagePoints,
const size_t  numberImagePoints,
Indices32 frontObjectPointIndices = nullptr 
)
static

Projects a set of given image points onto a 3D plane and returns the resulting 3D object points.

Beware: The back projected points may be located behind the camera due to the position and orientation of the given plane!
Beware: Ensure that the given plane is not parallel with the viewing direction of the camera.

Parameters
anyCameraThe camera profile defining the projection and distortion
world_T_cameraThe transformation from the camera coordinate system to world coordinates, worldPoint = world_T_camera * cameraPoint, must be valid
plane3D plane that is used to determine the position of the back-projected 3D object points
imagePointsImage points that will be back-projected
numberImagePointsNumber of given image points
frontObjectPointIndicesOptional resulting indices of all object points lying in front of the camera
Returns
Resulting 3D object points
See also
backProjectImagePointsDamped().

◆ backProjectImagePoints() [4/6]

static ObjectPoints Ocean::Geometry::Utilities::backProjectImagePoints ( const PinholeCamera pinholeCamera,
const HomogenousMatrix4 pose,
const Cone3 cone,
const ImagePoint imagePoints,
const size_t  numberImagePoints,
const bool  useDistortionParameters,
Indices32 intersectingPointIndices 
)
static

Deprecated.

Projects a set of given image points onto a 3D cone and returns only the resulting 3D object points for rays that intersect the cone. Optional camera distortion will be clamped at the border of the camera's frame.

Parameters
pinholeCameraThe pinhole camera profile defining the projection and optional distortion
posePose of the camera
cone3D cone that is used to determine the position of the back-projected 3D object points
imagePointsImage points that will be back-projected
numberImagePointsNumber of given image points
useDistortionParametersTrue, to use the distortion parameters of the camera
intersectingPointIndicesOutput indices of all 2D points whose rays actually intersect with the cone
Returns
Resulting 3D object points

◆ backProjectImagePoints() [5/6]

static ObjectPoints Ocean::Geometry::Utilities::backProjectImagePoints ( const PinholeCamera pinholeCamera,
const HomogenousMatrix4 pose,
const Cylinder3 cylinder,
const ImagePoint imagePoints,
const size_t  numberImagePoints,
const bool  useDistortionParameters,
Indices32 intersectingPointIndices 
)
static

Deprecated.

Projects a set of given image points onto a 3D cylinder and returns only the resulting 3D object points for rays that intersect the cylinder. Optional camera distortion will be clamped at the border of the camera's frame.

Parameters
pinholeCameraThe pinhole camera profile defining the projection and optional distortion
posePose of the camera
cylinder3D cylinder that is used to determine the position of the back-projected 3D object points
imagePointsImage points that will be back-projected
numberImagePointsNumber of given image points
useDistortionParametersTrue, to use the distortion parameters of the camera
intersectingPointIndicesOutput indices of all 2D points whose rays actually intersect with the cylinder
Returns
Resulting 3D object points

◆ backProjectImagePoints() [6/6]

static ObjectPoints Ocean::Geometry::Utilities::backProjectImagePoints ( const PinholeCamera pinholeCamera,
const HomogenousMatrix4 pose,
const Plane3 plane,
const ImagePoint imagePoints,
const size_t  numberImagePoints,
const bool  useDistortionParameters,
Indices32 frontObjectPointIndices = nullptr 
)
static

Deprecated.

Projects a set of given image points onto a 3D plane and returns the resulting 3D object points. Optional camera distortion will be clamped at the border of the camera's frame.
Beware: The back projected points may be located behind the camera due to the position and orientation of the given plane!
Beware: Ensure that the given plane is not parallel with the viewing direction of the camera.

Parameters
pinholeCameraThe pinhole camera profile defining the projection and optional distortion
posePose of the camera
plane3D plane that is used to determine the position of the back-projected 3D object points
imagePointsImage points that will be back-projected
numberImagePointsNumber of given image points
useDistortionParametersTrue, to use the distortion parameters of the camera
frontObjectPointIndicesOptional resulting indices of all object points lying in front of the camera
Returns
Resulting 3D object points
See also
backProjectImagePointsDamped().

◆ backProjectImagePointsDamped()

static ObjectPoints Ocean::Geometry::Utilities::backProjectImagePointsDamped ( const PinholeCamera pinholeCamera,
const HomogenousMatrix4 pose,
const Plane3 plane,
const ImagePoint imagePoints,
const size_t  numberImagePoints,
const bool  useDistortionParameters,
Indices32 frontObjectPointIndices = nullptr 
)
static

Projects a set of given image points onto a 3D plane and returns the resulting 3D object points.

Optional camera distortion will be damped outside the border of the camera's frame.
Beware: The back projected points may be located behind the camera due to the position and orientation of the given plane!
Beware: Ensure that the given plane is not parallel with the viewing direction of the camera.

Parameters
pinholeCameraThe pinhole camera profile defining the projection and optional distortion
posePose of the camera
plane3D plane that is used to determine the position of the back-projected 3D object points
imagePointsImage points that will be back-projected
numberImagePointsNumber of given image points
useDistortionParametersTrue, to use the distortion parameters of the camera
frontObjectPointIndicesOptional resulting indices of all object points lying in front of the camera
Returns
Resulting 3D object points
See also
backProjectImagePoints().

◆ backProjectTriangles()

static Triangles3 Ocean::Geometry::Utilities::backProjectTriangles ( const PinholeCamera pinholeCamera,
const HomogenousMatrix4 pose,
const Plane3 plane,
const Triangle2 triangles,
const size_t  numberTriangles,
const bool  useDistortionParameters 
)
static

Projects a set of given 2D image triangles onto a 3D plane and returns the resulting 3D object triangles.

Parameters
pinholeCameraThe pinhole camera object
posePose of the camera
plane3D plane that is used to determine the position of the back-projected 3D object points
trianglesTriangles that will be back-projected
numberTrianglesNumber of given image points
useDistortionParametersTrue, to use the distortion parameters of the camera
Returns
Resulting 3D triangles

◆ computePolygonArea() [1/2]

Scalar Ocean::Geometry::Utilities::computePolygonArea ( const Vector2 vertices,
size_t  size 
)
inlinestatic

Compute the area of a polygon.

Parameters
verticesThe vertices of a polygon (can be convex or concave but must not be self-intersecting)
sizeNumber of vertices in the polygon, range: [0, infinity)
Returns
The absolute value of the area of the polygon (this value is undefined if the polygon is self-intersecting), range: [0, infinity)

◆ computePolygonArea() [2/2]

Scalar Ocean::Geometry::Utilities::computePolygonArea ( const Vectors2 vertices)
inlinestatic

Compute the area of a polygon.

Parameters
verticesThe vertices of a polygon (can be convex or concave but must not be self-intersecting)
Returns
The absolute value of the area of the polygon (this value is undefined if the polygon is self-intersecting), range: [0, infinity)
See also
CV::Segmentation::PixelContour::area()

◆ computePolygonAreaSigned() [1/2]

static Scalar Ocean::Geometry::Utilities::computePolygonAreaSigned ( const Vector2 vertices,
size_t  size 
)
static

Compute the signed area of a polygon The value of the area will be positive if the vertices are in counter-clockwise order and negative if they are in clock-wise order.

Parameters
verticesThe vertices of a polygon (can be convex or concave but must not be self-intersecting)
sizeNumber of vertices in the polygon, range: [0, infinity)
Returns
The area of the polygon (this value is undefined if the polygon is self-intersecting), range: (-infinity, infinity)
See also
CV::Segmentation::PixelContour::areaSigned()

◆ computePolygonAreaSigned() [2/2]

Scalar Ocean::Geometry::Utilities::computePolygonAreaSigned ( const Vectors2 vertices)
inlinestatic

Compute the signed area of a polygon The value of the area will be positive if the vertices are in counter-clockwise order and negative if they are in clock-wise order.

Parameters
verticesThe vertices of a polygon (can be convex or concave but must not be self-intersecting)
Returns
The area of the polygon (this value is undefined if the polygon is self-intersecting), range: (-infinity, infinity)

◆ countFrontObjectPoints() [1/2]

static size_t Ocean::Geometry::Utilities::countFrontObjectPoints ( const PinholeCamera cameraFirst,
const PinholeCamera cameraSecond,
const HomogenousMatrix4 poseFirst,
const HomogenousMatrix4 poseSecond,
const ImagePoint imagePointsFirst,
const ImagePoint imagePointsSecond,
const size_t  correspondences 
)
static

Counts the number of object points that are visible in two individual camera frames and are located in front of both cameras.

Parameters
cameraFirstThe camera profile of the first frame, optional distortion parameters of the camera will not be considered
cameraSecondThe camera profile of the first frame, optional distortion parameters of the camera will not be considered
poseFirstPose of the first camera
poseSecondPose of the second camera
imagePointsFirstImage points located in the first frame
imagePointsSecondImage points located in the second frame, each point corresponds to one point in the first frame (correspondence is defined by index)
correspondencesNumber of given image point correspondences
Returns
Number of image points located in front of both camera

◆ countFrontObjectPoints() [2/2]

size_t Ocean::Geometry::Utilities::countFrontObjectPoints ( const PinholeCamera pinholeCamera,
const HomogenousMatrix4 pose,
const ObjectPoint objectPoints,
const size_t  numberObjectPoints 
)
inlinestatic

Counts the number of object points that are in front of a given camera.

Parameters
pinholeCameraThe pinhole camera profile to be used
posePose of the camera (extrinsic camera matrix with viewing direction along the negative z-axis)
objectPointsObject points for which the number of front object points will be determined
numberObjectPointsThe number of provided object points
Returns
Number of object points located in front of the camera
See also
countFrontObjectPointsIF().

◆ countFrontObjectPointsIF()

static size_t Ocean::Geometry::Utilities::countFrontObjectPointsIF ( const PinholeCamera pinholeCamera,
const HomogenousMatrix4 invertedFlippedPose,
const ObjectPoint objectPoints,
const size_t  numberObjectPoints 
)
static

Counts the number of object points that are in front of a given camera.

Parameters
pinholeCameraThe pinhole camera profile to be used
invertedFlippedPoseInverted and flipped pose of the camera (not the default extrinsic camera matrix)
objectPointsObject points for which the number of front object points will be determined
numberObjectPointsThe number of provided object points
Returns
Number of object points located in front of the camera
See also
countFrontObjectPoints().

◆ covarianceMatrix() [1/6]

static SquareMatrix2 Ocean::Geometry::Utilities::covarianceMatrix ( const ImagePoint imagePoints,
const size_t  number,
const ImagePoint meanPoint,
const Scalar  minimalSigma = 0 
)
static

Creates the covariance matrix for a given set of image points.

Parameters
imagePointsImage points for that the covariance will be determined
numberNumber of image points
meanPointAlready determined mean point of the provided image points
minimalSigmaDefining the minimal sigma that is applied, with range [0, infinity)
Returns
Resulting covariance matrix

◆ covarianceMatrix() [2/6]

SquareMatrix2 Ocean::Geometry::Utilities::covarianceMatrix ( const ImagePoint imagePoints,
const size_t  number,
const Scalar  minimalSigma = 0 
)
inlinestatic

Creates the covariance matrix for a given set of image points.

Parameters
imagePointsImage points for that the covariance will be determined
numberNumber of image points
minimalSigmaDefining the minimal sigma that is applied, with range [0, infinity)
Returns
Resulting covariance matrix

◆ covarianceMatrix() [3/6]

static SquareMatrix2 Ocean::Geometry::Utilities::covarianceMatrix ( const ImagePoint imagePoints,
const unsigned int *  indices,
const size_t  numberIndices,
const Scalar  minimalSigma,
ImagePoint meanPoint 
)
static

Creates the covariance matrix for a given set of image points.

Parameters
imagePointsImage points for that the covariance will be determined
indicesA set of indices that define a subset of the entire image points
numberIndicesNumber of provided indices
minimalSigmaDefining the minimal sigma that is applied, with range [0, infinity)
meanPointResulting mean point of the filtered image points
Returns
Resulting covariance matrix

◆ covarianceMatrix() [4/6]

static SquareMatrix2 Ocean::Geometry::Utilities::covarianceMatrix ( const Vector2 direction0,
const Scalar  sigma0,
const Vector2 direction1,
const Scalar  sigma1 
)
static

Creates a covariance matrix by two given orthogonal vectors.

Parameters
direction0Direction of the major axis, with unit length
sigma0Standard deviation of the major axis (equivalent to the square root of the first eigenvalue of the covariance matrix)
direction1Direction of the minor axis, perpendicular to the main direction, with unit length
sigma1Standard deviation of the second direction (equivalent to the square root of the second eigenvalue of the covariance matrix)
Returns
Resulting covariance matrix

◆ covarianceMatrix() [5/6]

static SquareMatrix2 Ocean::Geometry::Utilities::covarianceMatrix ( const Vector2 direction0,
const Vector2 direction1 
)
static

Creates a covariance matrix by two given orthogonal vectors.

Parameters
direction0Direction of the major axis, with standard deviation as length
direction1Direction of the minor axis, perpendicular to the main direction, with standard deviation as length
Returns
Resulting covariance matrix

◆ covarianceMatrix() [6/6]

static SquareMatrix2 Ocean::Geometry::Utilities::covarianceMatrix ( const Vector2 majorDirection,
const Scalar  minimalSigma = 1,
const Scalar  minorFactor = Scalar(0.01) 
)
static

Creates a covariance matrix by one given vector representing the major axis.

Parameters
majorDirectionDirection of the major axis with standard deviation as length
minimalSigmaMinimal sigma that will be used (will be used if the length of the major direction is too small)
minorFactorRatio between the sigma of the minor and the major sigma, with range (0, 1]
Returns
Resulting covariance matrix

◆ createObjectPoints() [1/2]

static Vectors3 Ocean::Geometry::Utilities::createObjectPoints ( const AnyCamera camera,
const HomogenousMatrix4 world_T_camera,
const ConstIndexedAccessor< Vector2 > &  imagePoints,
const Scalar  distance 
)
static

Creates a set of 3D object points for a set of given 2D image points.

The 3D object points will lie on the ray which intersects the individual image points and the camera's center of projection.
The distance between 3D object points and the camera's center of projection defines the locations of the object points.

Parameters
cameraThe camera profile defining the projection, must be valid
world_T_cameraThe pose of the camera, with default camera pointing towards the negative z-space with y-axis upwards, must be valid
imagePointsImage points that will be back-projected, at least one
distanceThe distance between the camera's center of project and the resulting object points, with range (0, infinity)
Returns
The resulting 3D object points, defined in world

◆ createObjectPoints() [2/2]

static ObjectPoints Ocean::Geometry::Utilities::createObjectPoints ( const PinholeCamera pinholeCamera,
const HomogenousMatrix4 pose,
const ConstIndexedAccessor< ImagePoint > &  imagePoints,
const bool  useDistortionParameters,
const Scalar  distance 
)
static

Deprecated.

Creates a set of 3D object points by a set of given 2D image points. The 3D object points are lying on the ray which intersect the individual image points and the camera's center of projection.
The distance between 3D object points and the camera's center of projection defines the locations of the object points.

Parameters
pinholeCameraThe pinhole camera profile defining the projection, must be valid
posePose of the camera, must be valid
imagePointsImage points that will be back-projected
useDistortionParametersTrue, to use the distortion parameters of the camera
distanceThe distance between the camera's center of project and the resulting object points, should be in range (0, infinity)
Returns
Resulting 3D object points

◆ createRandomHomography()

static SquareMatrix3 Ocean::Geometry::Utilities::createRandomHomography ( const unsigned int  width,
const unsigned  height,
const Scalar  maxTranslation 
)
static

Create a random homography transformation The homography is created in such a way that points in an output image are mapped into the input image, i.e., inputPoints_i = homography * outputPoints_i.

Parameters
widthThe width of the input image, range: [1, infinity)
heightThe height of the input image, range: [1, infinity)
maxTranslationA random global translation that is added to the random homography
Returns
A random homography

◆ decomposeCovarianceMatrix()

static bool Ocean::Geometry::Utilities::decomposeCovarianceMatrix ( const SquareMatrix2 covarianceMatrix,
Vector2 direction0,
Vector2 direction1 
)
static

Decomposes a covariance matrix.

Parameters
covarianceMatrixCovariance matrix that has to be decomposed
direction0Resulting major axis, with standard deviation as length (the square root of the first Eigen value)
direction1Resulting minor axis, with standard deviation as length (the square root of the second Eigen value)
Returns
True, if succeeded

◆ intersectConvexPolygons() [1/2]

static bool Ocean::Geometry::Utilities::intersectConvexPolygons ( const Vector2 vertices0,
const size_t  size0,
const Vector2 vertices1,
const size_t  size1,
Vectors2 intersectedPolygon 
)
static

Computation of the intersection of two convex polygons.

Parameters
vertices0The vertices of the first polygon
size0The number of vertices in the first polygon, range: [3, infinity)
vertices1The vertices of the second polygon
size1The number of vertices of the second polygon, range: [3, infinity)
intersectedPolygonThe resulting intersection represented as a polygon
Returns
True, if succeeded

◆ intersectConvexPolygons() [2/2]

bool Ocean::Geometry::Utilities::intersectConvexPolygons ( const Vectors2 vertices0,
const Vectors2 vertices1,
Vectors2 intersectedPolygon 
)
inlinestatic

Computation of the intersection of two convex polygons.

Parameters
vertices0The vertices of the first polygon, size: [3, infinity)
vertices1The vertices of the second polygon, size: [3, infinity)
intersectedPolygonThe resulting intersection represented as a polygon
Returns
True, if succeeded

◆ isInsideConvexPolygon() [1/2]

static bool Ocean::Geometry::Utilities::isInsideConvexPolygon ( const Vector2 vertices,
size_t  size,
const Vector2 point 
)
static

Returns whether a given point lies inside a convex polygon.

For polygons consisting of less than 3 points, this function always returns false. A point located on an edge of the polygon is considered as inside the polygon.

Parameters
verticesThe vertices of a convex polygon, can be nullptr if size == 0
sizeThe number of vertices in the polygon, range: [0, infinity)
pointThe point to be tested
Returns
True, if the point is inside the polygon, otherwise false

◆ isInsideConvexPolygon() [2/2]

bool Ocean::Geometry::Utilities::isInsideConvexPolygon ( const Vectors2 vertices,
const Vector2 point 
)
inlinestatic

Returns whether a given point lies inside a convex polygon.

For polygons consisting of less than 3 points, this function always returns false. A point located on an edge of the polygon is considered as inside the polygon.

Parameters
verticesThe vertices of a convex polygon, can be nullptr if size == 0
pointThe point to be tested
Returns
True, if the point is inside the polygon, otherwise false

◆ isPolygonConvex()

static bool Ocean::Geometry::Utilities::isPolygonConvex ( const Vector2 vertices,
const size_t  size,
const bool  strict = true 
)
static

Returns whether a polygon of given 2D points is convex.

A polygon consisting of 0 to 2 vertices is considered to be convex.

Parameters
verticesThe vertices of the polygon, can be nullptr if size == 0
sizeNumber of vertices in the polygon, range: [0, infinity)
strictIf true, the polygon is tested for strict convexity (i.e. every internal angle is less than 180 degrees), otherwise internal angles can be up equal to 180 degrees
Returns
True if the polygon is convex, otherwise false

◆ meanImagePoint()

template<typename TAccessor >
ImagePoint Ocean::Geometry::Utilities::meanImagePoint ( const TAccessor &  imagePointAccessor)
inlinestatic

Returns the mean position of a set of given 2D points.

Parameters
imagePointAccessorThe accessor providing the image points, at least one
Returns
The resulting mean position
Template Parameters
TAccessorThe data type of the accessor providing the image points

◆ meanObjectPoint()

template<typename TAccessor >
ObjectPoint Ocean::Geometry::Utilities::meanObjectPoint ( const TAccessor &  objectPointAccessor)
inlinestatic

Returns the mean position of a set of given 3D points.

Parameters
objectPointAccessorThe accessor for the object points, at least one
Returns
The resulting median position
Template Parameters
TAccessorThe data type of the accessor providing the object points

◆ medianDistance() [1/2]

template<typename TAccessor >
Scalar Ocean::Geometry::Utilities::medianDistance ( const ImagePoint imagePoint,
const TAccessor &  imagePointAccessor 
)
inlinestatic

Returns the median distance between a given 2D object point and a set of given 2D points.

Parameters
imagePointThe image point to which the median distance will be determined
imagePointAccessorThe accessor for the image points, at least one
Returns
The resulting median distance
Template Parameters
TAccessorThe data type of the accessor providing the image points

◆ medianDistance() [2/2]

template<typename TAccessor >
Scalar Ocean::Geometry::Utilities::medianDistance ( const ObjectPoint objectPoint,
const TAccessor &  objectPointAccessor 
)
inlinestatic

Returns the median distance between a given 3D object point and a set of given 3D points.

Parameters
objectPointThe object point to which the median distance will be determined
objectPointAccessorThe accessor for the object points, at least one
Returns
The resulting median distance
Template Parameters
TAccessorThe data type of the accessor providing the object points

◆ medianImagePoint()

template<typename TAccessor >
ImagePoint Ocean::Geometry::Utilities::medianImagePoint ( const TAccessor &  imagePointAccessor)
inlinestatic

Returns the median position of a set of given 2D points.

The resulting position is determined by a component-wise median determination.

Parameters
imagePointAccessorThe accessor for the image points, at least one
Returns
The resulting median position
Template Parameters
TAccessorThe data type of the accessor providing the object points

◆ medianObjectPoint()

template<typename TAccessor >
ObjectPoint Ocean::Geometry::Utilities::medianObjectPoint ( const TAccessor &  objectPointAccessor)
inlinestatic

Returns the median position of a set of given 3D points.

The resulting position is determined by a component-wise median determination.

Parameters
objectPointAccessorThe accessor for the object points, at least one
Returns
The resulting median position
Template Parameters
TAccessorThe data type of the accessor providing the object points

◆ randomCameraPose() [1/3]

static HomogenousMatrix4 Ocean::Geometry::Utilities::randomCameraPose ( const AnyCamera anyCamera,
const Line3 worldObjectPointRay,
const Vector2 distortedImagePoint,
const Scalar  distance 
)
static

Returns a random 6-DOF camera pose for any camera which observes a given 3D object point at a specified 2D image point location while having a specified distance to the 3D object point.

Parameters
anyCameraThe camera profile defining the projection, must be valid
worldObjectPointRayThe 3D ray starting at the 3D object point and pointing towards the camera's center of projection, must be valid
distortedImagePointThe 2D image point within the camera image, with range [0, anyCamera.width())x[0, anyCamera.height())
distanceThe desired distance between 3D object point and camera (center of projection), with range (0, infinity)
Returns
The 6-DOF camera pose matching with the specified constraints, will be world_T_camera

◆ randomCameraPose() [2/3]

static HomogenousMatrix4 Ocean::Geometry::Utilities::randomCameraPose ( const FisheyeCamera fisheyeCamera,
const Line3 worldObjectPointRay,
const Vector2 distortedImagePoint,
const Scalar  distance 
)
static

Deprecated.

Returns a random 6-DOF camera pose for a fisheye camera which observes a given 3D object point at a specified 2D image point location while having a specified distance to the 3D object point.

Parameters
fisheyeCameraThe fisheye camera profile defining the projection, must be valid
worldObjectPointRayThe 3D ray starting at the 3D object point and pointing towards the camera's center of projection, must be valid
distortedImagePointThe 2D image point within the fisheye camera image, with range [0, fisheyeCamera.width())x[0, fisheyeCamera.height())
distanceThe desired distance between 3D object point and camera (center of projection), with range (0, infinity)
Returns
The 6-DOF camera pose matching with the specified constraints, will be world_T_camera

◆ randomCameraPose() [3/3]

static HomogenousMatrix4 Ocean::Geometry::Utilities::randomCameraPose ( const PinholeCamera pinholeCamera,
const Line3 worldObjectPointRay,
const Vector2 distortedImagePoint,
const Scalar  distance 
)
static

Deprecated.

Returns a random 6-DOF camera pose for a pinhole camera which observes a given 3D object point at a specified 2D image point location while having a specified distance to the 3D object point.

Parameters
pinholeCameraThe pinhole camera profile defining the projection, must be valid
worldObjectPointRayThe 3D ray starting at the 3D object point and pointing towards the camera's center of projection, must be valid
distortedImagePointThe 2D image point within the fisheye camera image, with range [0, fisheyeCamera.width())x[0, fisheyeCamera.height())
distanceThe desired distance between 3D object point and camera (center of projection), with range (0, infinity)
Returns
The 6-DOF camera pose matching with the specified constraints, will be world_T_camera

◆ triangulateObjectPoints()

static void Ocean::Geometry::Utilities::triangulateObjectPoints ( const AnyCamera camera0,
const AnyCamera camera1,
const HomogenousMatrix4 world_T_camera0,
const HomogenousMatrix4 world_T_camera1,
const ConstIndexedAccessor< Vector2 > &  imagePoints0,
const ConstIndexedAccessor< Vector2 > &  imagePoints1,
Vectors3 objectPoints,
Indices32 validIndices,
const bool  onlyFrontPoints = true,
const Scalar  maximalSqrError = Scalar(3 *3) 
)
static

Determines 3D object points by triangulating two sets of 2D image points from different camera poses.

Parameters
camera0The camera profile of the first camera, must be valid
camera1The camera profile of the second camera, must be valid
world_T_camera0The camera pose of the first camera, with default camera pointing towards the negative z-space with y-axis upwards, must be valid
world_T_camera1The camera pose of the second camera, with default camera pointing towards the negative z-space with y-axis upwards, must be valid
imagePoints0The 2D image points located in the first camera
imagePoints1The 2D image points located in the second camera, each point must have a corresponding point in the first camera
objectPointsThe resulting valid 3D object points, does not provide invalid object points
validIndicesThe resulting indices of the valid point correspondences for which a 3D object points could be determined, one index of reach resulting 3D object point
onlyFrontPointsTrue, if only front object points are determined
maximalSqrErrorThe maximal squared projection pixel error for valid object points

The documentation for this class was generated from the following file: