8#ifndef META_OCEAN_MATH_PINHOLE_CAMERA_H
9#define META_OCEAN_MATH_PINHOLE_CAMERA_H
32template <
typename T>
class PinholeCameraT;
184 OS_FOCAL_LENGTHS = 2,
186 OS_INTRINSIC_PARAMETERS = 4,
188 OS_FOCAL_LENGTHS_DISTORTION = 6,
190 OS_SYMMETRIC_INTRINSIC_PARAMETERS_DISTORTIONS = 7,
192 OS_INTRINSIC_PARAMETERS_DISTORTIONS = 8,
194 OS_DISTORTION = 0x1000 | 4,
196 OS_INTRINSIC_PARAMETERS_RADIAL_DISTORTION = 0x1000 | 6
216 inline DistortionLookup();
296 PinholeCameraT(
const unsigned int width,
const unsigned int height,
const T focalX,
const T focalY,
const T principalX,
const T principalY);
319 PinholeCameraT(
const unsigned int width,
const unsigned int height,
const T* parameters,
const bool radialDistortion =
true,
const bool tangentialDistortion =
true);
352 PinholeCameraT(
const unsigned int width,
const unsigned int height,
const T fovX);
364 PinholeCameraT(
const unsigned int width,
const unsigned int height,
const T fovX,
const T principalX,
const T principalY);
372 template <
typename U>
383 template <
typename TParameter>
521 template <
typename TParameter>
540 void copyElements(T* arrayValues,
const bool copyRadialDistortion =
true,
const bool copyTangentialDistortion =
true)
const;
577 bool isDistortionPlausible(
const T symmetricFocalLengthRatio = T(1.05),
const T modelAccuracy = T(0.001),
const T symmetricDistortionRatio = T(1.08))
const;
589 template <
bool tUseBorderDistortionIfOuts
ide>
619 template <
bool tUseBorderDistortionIfOuts
ide>
676 template <
bool tUseBorderDistortionIfOuts
ide>
695 template <
bool tUseBorderDistortionIfOuts
ide>
706 template <
bool tUseBorderDistortionIfOuts
ide>
724 template <
bool tUseBorderDistortionIfOuts
ide>
741 template <
bool tUseBorderDistortionIfOuts
ide>
758 template <
bool tUseBorderDistortionIfOuts
ide>
776 template <
bool tUseBorderDistortionIfOuts
ide>
792 template <
bool tUseBorderDistortionIfOuts
ide>
810 template <
bool tUseBorderDistortionIfOuts
ide>
827 template <
bool tDistortImagePo
int,
bool tUseBorderDistortionIfOuts
ide>
844 template <
bool tUseBorderDistortionIfOuts
ide>
861 template <
bool tUseBorderDistortionIfOuts
ide>
874 template <
bool tUseBorderDistortionIfOuts
ide>
892 template <
bool tUseBorderDistortionIfOuts
ide>
908 template <
bool tUseBorderDistortionIfOuts
ide>
1175 template <
typename U,
bool tUseDistortionParameters>
1202 explicit inline operator bool()
const;
1225 template <
bool tUseBorderDistortionIfOuts
ide>
1269 VectorT2<T> dampedNormalized(
const VectorT2<T>& normalized,
const T dampingFactor,
const T leftNormalizedBorder,
const T rightNormalizedBorder,
const T topNormalizedBorder,
const T bottomNormalizedBorder)
const;
1274 unsigned int width_ = 0u;
1277 unsigned int height_ = 0u;
1292template <
typename T>
1298template <
typename T>
1305template <
typename T>
1312template <
typename T>
1319template <
typename T>
1326template <
typename T>
1332template <
typename T>
1338template <
typename T>
1344template <
typename T>
1350template <
typename T>
1351template <
typename U>
1362template <
typename T>
1363template <
typename TParameter>
1366 static_assert((std::is_same<TParameter, float>::value) || (std::is_same<TParameter, double>::value),
"Invalid TParameter, must be 'float' or 'double'!");
1368 ocean_assert(width != 0u && height != 0u);
1369 ocean_assert(parameters !=
nullptr);
1371 switch (parameterConfiguration)
1373 case PC_3_PARAMETERS_ONE_FOCAL_LENGTH:
1375 const T focalLength = T(parameters[0]);
1377 const T principalPointX = T(parameters[1]);
1378 const T principalPointY = T(parameters[2]);
1380 constexpr T radialDistortion = T(0);
1381 constexpr T tangentialDistortion = T(0);
1387 case PC_4_PARAMETERS:
1389 const T focalLengthX = T(parameters[0]);
1390 const T focalLengthY = T(parameters[1]);
1392 const T principalPointX = T(parameters[2]);
1393 const T principalPointY = T(parameters[3]);
1395 constexpr T radialDistortion = T(0);
1396 constexpr T tangentialDistortion = T(0);
1402 case PC_7_PARAMETERS_ONE_FOCAL_LENGTH:
1404 const T focalLength = T(parameters[0]);
1406 const T principalPointX = T(parameters[1]);
1407 const T principalPointY = T(parameters[2]);
1409 const T radialDistortion0 = T(parameters[3]);
1410 const T radialDistortion1 = T(parameters[4]);
1412 const T tangentialDistortion0 = T(parameters[5]);
1413 const T tangentialDistortion1 = T(parameters[6]);
1419 case PC_8_PARAMETERS:
1421 const T focalLengthX = T(parameters[0]);
1422 const T focalLengthY = T(parameters[1]);
1424 const T principalPointX = T(parameters[2]);
1425 const T principalPointY = T(parameters[3]);
1427 const T radialDistortion0 = T(parameters[4]);
1428 const T radialDistortion1 = T(parameters[5]);
1430 const T tangentialDistortion0 = T(parameters[6]);
1431 const T tangentialDistortion1 = T(parameters[7]);
1441 ocean_assert(
false &&
"Invalid parameter configuration!");
1444template <
typename T>
1447 return radialDistortion_.first != 0 || radialDistortion_.second != 0
1448 || tangentialDistortion_.first != 0 || tangentialDistortion_.second != 0;
1451template <
typename T>
1457template <
typename T>
1463template <
typename T>
1466 return VectorT2<T>(principalPointX(), principalPointY());
1469template <
typename T>
1472 return intrinsics_(6);
1475template <
typename T>
1478 return intrinsics_(7);
1481template <
typename T>
1484 return intrinsics_(0);
1487template <
typename T>
1490 return intrinsics_(4);
1493template <
typename T>
1496 ocean_assert((std::is_same<T, float>::value) || intrinsics_.
inverted() == invertedIntrinsics_);
1499 return invertedIntrinsics_(0);
1502template <
typename T>
1505 ocean_assert((std::is_same<T, float>::value) || intrinsics_.
inverted() == invertedIntrinsics_);
1508 return invertedIntrinsics_(4);
1511template <
typename T>
1514 radialDistortion_ = radial;
1517template <
typename T>
1520 tangentialDistortion_ = tangential;
1523template <
typename T>
1524template <
bool tUseBorderDistortionIfOuts
ide>
1527 ocean_assert(iterations >= 1u && iterations <= 1000u && zoom >
NumericT<T>::eps());
1530 if (!hasDistortionParameters())
1535 const T invZoom = T(1) / zoom;
1537 const VectorT2<T> nDistorted((distorted.
x() - principalPointX()) * inverseFocalLengthX() * invZoom, (distorted.
y() - principalPointY()) * inverseFocalLengthY() * invZoom);
1539 const VectorT2<T> nMainOffset(distortNormalized<tUseBorderDistortionIfOutside>(nDistorted, invZoom) - nDistorted);
1540 VectorT2<T> nIntermediateUndistorted(nDistorted - nMainOffset);
1542 unsigned int i = 0u;
1544 while (i++ < iterations)
1546 const VectorT2<T> nIntermediateDistorted(distortNormalized<tUseBorderDistortionIfOutside>(nIntermediateUndistorted, invZoom));
1547 const VectorT2<T> nIntermediateOffset(nDistorted - nIntermediateDistorted);
1549 nIntermediateUndistorted = nIntermediateUndistorted + nIntermediateOffset * T(0.75);
1551 const T offsetPixelX =
NumericT<T>::abs(nIntermediateOffset.
x() * focalLengthX());
1552 const T offsetPixelY =
NumericT<T>::abs(nIntermediateOffset.
y() * focalLengthY());
1554 if (offsetPixelX < 0.05 && offsetPixelY < 0.05)
1559 if (offsetPixelX > T(width_ * 10u) || offsetPixelY > T(height_ * 10u))
1565 return VectorT2<T>(nIntermediateUndistorted.
x() * focalLengthX() * zoom + principalPointX(), nIntermediateUndistorted.
y() * focalLengthY() * zoom + principalPointY());
1568template <
typename T>
1569template <
bool tUseBorderDistortionIfOuts
ide>
1572 if (hasDistortionParameters())
1574 if constexpr (tUseBorderDistortionIfOutside)
1576 const VectorT2<T> nUndistorted((undistorted.
x() - principalPointX()) * inverseFocalLengthX(),
1577 (undistorted.
y() - principalPointY()) * inverseFocalLengthY());
1579 const VectorT2<T> clampedNormalizedImagePoint(
minmax(-principalPointX() * inverseFocalLengthX(), nUndistorted.
x(), (T(width_) - principalPointX()) * inverseFocalLengthX()),
1580 minmax(-principalPointY() * inverseFocalLengthY(), nUndistorted.
y(), (T(height_) - principalPointY()) * inverseFocalLengthY()));
1582 const T
sqr = clampedNormalizedImagePoint.
sqr();
1584 const T radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
1586 const T tangentialDistortionCorrectionX = tangentialDistortion_.first * 2 * clampedNormalizedImagePoint.
x() * clampedNormalizedImagePoint.
y()
1587 + tangentialDistortion_.second * (
sqr + 2 *
NumericT<T>::sqr(clampedNormalizedImagePoint.
x()));
1589 const T tangentialDistortionCorrectionY = tangentialDistortion_.first * (
sqr + 2 *
NumericT<T>::sqr(clampedNormalizedImagePoint.
y()))
1590 + tangentialDistortion_.second * 2 * clampedNormalizedImagePoint.
x() * clampedNormalizedImagePoint.
y();
1592 return VectorT2<T>((nUndistorted.
x() * radialDistortionFactor + tangentialDistortionCorrectionX) * focalLengthX() + principalPointX(),
1593 (nUndistorted.
y() * radialDistortionFactor + tangentialDistortionCorrectionY) * focalLengthY() + principalPointY());
1597 const VectorT2<T> nUndistorted((undistorted.
x() - principalPointX()) * inverseFocalLengthX(),
1598 (undistorted.
y() - principalPointY()) * inverseFocalLengthY());
1600 const T
sqr = nUndistorted.
sqr();
1602 const T radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
1604 const T tangentialDistortionCorrectionX = tangentialDistortion_.first * 2 * nUndistorted.
x() * nUndistorted.
y()
1607 const T tangentialDistortionCorrectionY = tangentialDistortion_.first * (
sqr + 2 *
NumericT<T>::sqr(nUndistorted.
y()))
1608 + tangentialDistortion_.second * 2 * nUndistorted.
x() * nUndistorted.
y();
1610 return VectorT2<T>((nUndistorted.
x() * radialDistortionFactor + tangentialDistortionCorrectionX) * focalLengthX() + principalPointX(),
1611 (nUndistorted.
y() * radialDistortionFactor + tangentialDistortionCorrectionY) * focalLengthY() + principalPointY());
1620template <
typename T>
1621template <
typename TParameter>
1631 TParameter(focalLengthX()),
1632 TParameter(focalLengthY()),
1634 TParameter(principalPointX()),
1635 TParameter(principalPointY()),
1637 TParameter(radialDistortion_.first),
1638 TParameter(radialDistortion_.second),
1639 TParameter(tangentialDistortion_.first),
1640 TParameter(tangentialDistortion_.second),
1643 ocean_assert(parameters.size() == 8);
1645 parameterConfiguration = PC_8_PARAMETERS;
1654 parameterConfiguration = PC_UNKNOWN;
1658template <
typename T>
1661 ocean_assert(isValid());
1662 ocean_assert(signedBorder < T(std::min(width_ / 2u, height_ / 2u)));
1664 return imagePoint.
x() >= signedBorder && imagePoint.
y() >= signedBorder
1665 && imagePoint.
x() < T(width_) - signedBorder && imagePoint.
y() < T(height_) - signedBorder;
1668template <
typename T>
1675 debugCameraMatrix(0, 0) *= zoom;
1676 debugCameraMatrix(1, 1) *= zoom;
1677 debugCameraMatrix[15] = 1;
1683 ocean_assert(transformationMatrix.
isValid());
1685 ocean_assert(transformationMatrix == debugTransformationMatrix);
1691template <
typename T>
1692template <
typename U,
bool tUseDistortionParameters>
1695 ocean_assert(isValid());
1696 ocean_assert(jx !=
nullptr && jy !=
nullptr);
1698 if (tUseDistortionParameters && hasDistortionParameters())
1700 const U x = U(flippedCameraObjectPoint.
x());
1701 const U y = U(flippedCameraObjectPoint.
y());
1702 const U z = U(flippedCameraObjectPoint.
z());
1704 const U fx = U(focalLengthX());
1705 const U fy = U(focalLengthY());
1707 const U k1 = U(radialDistortion().first);
1708 const U k2 = U(radialDistortion().second);
1710 const U p1 = U(tangentialDistortion().first);
1711 const U p2 = U(tangentialDistortion().second);
1714 const U invZ = U(1) / z;
1716 const U u = x * invZ;
1717 const U v = y * invZ;
1719 const U dist1_u = U(1) + U(6) * p2 * u + U(2) * p1 * v + k1 * (U(3) * u * u + v * v) + k2 * (u * u + v * v) * (U(5) * u * u + v * v);
1720 const U dist2_u_1_v = U(2) * (p1 * u + v * (p2 + u * (k1 + U(2) * k2 * (u * u + v * v))));
1721 const U dist2_v = U(1) + U(2) * p2 * u + U(6) * p1 * v + k1 * (u * u + U(3) * v * v) + k2 * (u * u + v * v) * (u * u + U(5) * v * v);
1723 const U Fx_w_dist1_u = fx * invZ * dist1_u;
1724 const U Fy_w_dist2_u = fy * invZ * dist2_u_1_v;
1726 const U Fx_w_dist1_v = fx * invZ * dist2_u_1_v;
1727 const U Fy_w_dist2_v = fy * invZ * dist2_v;
1729 const U Fx_w2__ = -fx * invZ * invZ * (x * dist1_u + y * dist2_u_1_v);
1730 const U Fy_w2__ = -fy * invZ * invZ * (x * dist2_u_1_v + y * dist2_v);
1732 jx[0] = Fx_w_dist1_u;
1733 jx[1] = Fx_w_dist1_v;
1736 jy[0] = Fy_w_dist2_u;
1737 jy[1] = Fy_w_dist2_v;
1743 const U invZ = U(1) / U(flippedCameraObjectPoint.
z());
1745 const U fx_z = U(focalLengthX()) * invZ;
1746 const U fy_z = U(focalLengthY()) * invZ;
1748 const U fx_x_z2 = -fx_z * U(flippedCameraObjectPoint.
x()) * invZ;
1749 const U fy_y_z2 = -fy_z * U(flippedCameraObjectPoint.
y()) * invZ;
1761template <
typename T>
1764 return width_ != 0u && height_ != 0u;
1767template <
typename T>
1768template <
bool tUseBorderDistortionIfOuts
ide>
1771 if (undistortImagePoint)
1773 return invertedIntrinsics_ * undistort<tUseBorderDistortionIfOutside>(imagePoint);
1776 return invertedIntrinsics_ * imagePoint;
1779template <
typename T>
1782 if (undistortImagePoint)
1784 return invertedIntrinsics_ * undistortDamped(imagePoint);
1787 return invertedIntrinsics_ * imagePoint;
1790template <
typename T>
1791template <
bool tUseBorderDistortionIfOuts
ide>
1794 ocean_assert(isValid());
1796 if (distortImagePoints)
1798 if constexpr (tUseBorderDistortionIfOutside)
1800 const VectorT2<T> clampedNormalizedImagePoint(
minmax(-principalPointX() * inverseFocalLengthX(), normalizedImagePoint.
x(), (T(width_) - principalPointX()) * inverseFocalLengthX()),
1801 minmax(-principalPointY() * inverseFocalLengthY(), normalizedImagePoint.
y(), (T(height_) - principalPointY()) * inverseFocalLengthY()));
1804 if (tangentialDistortion_.first == 0 && tangentialDistortion_.second == 0)
1806 const T
sqr = clampedNormalizedImagePoint.
sqr();
1807 const T radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
1809 return VectorT2<T>((normalizedImagePoint.
x() * radialDistortionFactor) * focalLengthX() + principalPointX(),
1810 (normalizedImagePoint.
y() * radialDistortionFactor) * focalLengthY() + principalPointY());
1814 ocean_assert(tangentialDistortion_.first != 0 || tangentialDistortion_.second != 0);
1816 const T
sqr = clampedNormalizedImagePoint.
sqr();
1817 const T radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
1819 const T tangentialDistortionCorrectionX = tangentialDistortion_.first * 2 * clampedNormalizedImagePoint.
x() * clampedNormalizedImagePoint.
y()
1820 + tangentialDistortion_.second * (
sqr + 2 *
NumericT<T>::sqr(clampedNormalizedImagePoint.
x()));
1822 const T tangentialDistortionCorrectionY = tangentialDistortion_.first * (
sqr + 2 *
NumericT<T>::sqr(clampedNormalizedImagePoint.
y()))
1823 + tangentialDistortion_.second * 2 * clampedNormalizedImagePoint.
x() * clampedNormalizedImagePoint.
y();
1825 return VectorT2<T>((normalizedImagePoint.
x() * radialDistortionFactor + tangentialDistortionCorrectionX) * focalLengthX() + principalPointX(),
1826 (normalizedImagePoint.
y() * radialDistortionFactor + tangentialDistortionCorrectionY) * focalLengthY() + principalPointY());
1832 if (tangentialDistortion_.first == 0 && tangentialDistortion_.second == 0)
1834 const T
sqr = normalizedImagePoint.
sqr();
1835 const T radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
1837 return VectorT2<T>((normalizedImagePoint.
x() * radialDistortionFactor) * focalLengthX() + principalPointX(),
1838 (normalizedImagePoint.
y() * radialDistortionFactor) * focalLengthY() + principalPointY());
1842 ocean_assert(tangentialDistortion_.first != 0 || tangentialDistortion_.second != 0);
1844 const T
sqr = normalizedImagePoint.
sqr();
1845 const T radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
1847 const T tangentialDistortionCorrectionX = tangentialDistortion_.first * 2 * normalizedImagePoint.
x() * normalizedImagePoint.
y()
1850 const T tangentialDistortionCorrectionY = tangentialDistortion_.first * (
sqr + 2 *
NumericT<T>::sqr(normalizedImagePoint.
y()))
1851 + tangentialDistortion_.second * 2 * normalizedImagePoint.
x() * normalizedImagePoint.
y();
1853 return VectorT2<T>((normalizedImagePoint.
x() * radialDistortionFactor + tangentialDistortionCorrectionX) * focalLengthX() + principalPointX(),
1854 (normalizedImagePoint.
y() * radialDistortionFactor + tangentialDistortionCorrectionY) * focalLengthY() + principalPointY());
1860 return VectorT2<T>(normalizedImagePoint.
x() * focalLengthX() + principalPointX(), normalizedImagePoint.
y() * focalLengthY() + principalPointY());
1864template <
typename T>
1865template <
bool tUseBorderDistortionIfOuts
ide>
1868 ocean_assert(numberNormalizedImagePoints == 0u || (normalizedImagePoints && imagePoints));
1870 const T leftClamping = -principalPointX() * inverseFocalLengthX();
1871 const T rightClamping = (T(width_) - principalPointX()) * inverseFocalLengthX();
1872 const T topClamping = -principalPointY() * inverseFocalLengthY();
1873 const T bottomClamping = (T(height_) - principalPointY()) * inverseFocalLengthY();
1875 if (distortImagePoints && hasDistortionParameters())
1878 if (tangentialDistortion_.first == 0 && tangentialDistortion_.second == 0)
1880 T
sqr, radialDistortionFactor;
1882 for (
unsigned int n = 0u; n < numberNormalizedImagePoints; ++n)
1884 const VectorT2<T>& normalizedImagePoint(normalizedImagePoints[n]);
1886 if constexpr (tUseBorderDistortionIfOutside)
1888 const VectorT2<T> clampedNormalizedImagePoint(
minmax(leftClamping, normalizedImagePoint.
x(), rightClamping),
minmax(topClamping, normalizedImagePoint.
y(), bottomClamping));
1890 sqr = clampedNormalizedImagePoint.
sqr();
1891 radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
1893 imagePoints[n].
x() = (normalizedImagePoint.
x() * radialDistortionFactor) * focalLengthX() + principalPointX();
1894 imagePoints[n].
y() = (normalizedImagePoint.
y() * radialDistortionFactor) * focalLengthY() + principalPointY();
1898 sqr = normalizedImagePoint.
sqr();
1899 radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
1901 imagePoints[n].
x() = (normalizedImagePoint.
x() * radialDistortionFactor) * focalLengthX() + principalPointX();
1902 imagePoints[n].
y() = (normalizedImagePoint.
y() * radialDistortionFactor) * focalLengthY() + principalPointY();
1908 ocean_assert(tangentialDistortion_.first != 0 || tangentialDistortion_.second != 0);
1909 T
sqr, radialDistortionFactor, tangentialDistortionCorrectionX, tangentialDistortionCorrectionY;
1911 for (
unsigned int n = 0u; n < numberNormalizedImagePoints; ++n)
1913 const VectorT2<T>& normalizedImagePoint(normalizedImagePoints[n]);
1915 if constexpr (tUseBorderDistortionIfOutside)
1917 const VectorT2<T> clampedNormalizedImagePoint(
minmax(leftClamping, normalizedImagePoint.
x(), rightClamping),
minmax(topClamping, normalizedImagePoint.
y(), bottomClamping));
1919 sqr = clampedNormalizedImagePoint.
sqr();
1920 radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
1922 tangentialDistortionCorrectionX = tangentialDistortion_.first * 2 * clampedNormalizedImagePoint.
x() * clampedNormalizedImagePoint.
y()
1923 + tangentialDistortion_.second * (
sqr + 2 *
NumericT<T>::sqr(clampedNormalizedImagePoint.
x()));
1925 tangentialDistortionCorrectionY = tangentialDistortion_.first * (
sqr + 2 *
NumericT<T>::sqr(clampedNormalizedImagePoint.
y()))
1926 + tangentialDistortion_.second * 2 * clampedNormalizedImagePoint.
x() * clampedNormalizedImagePoint.
y();
1928 imagePoints[n].
x() = (normalizedImagePoint.
x() * radialDistortionFactor + tangentialDistortionCorrectionX) * focalLengthX() + principalPointX();
1929 imagePoints[n].
y() = (normalizedImagePoint.
y() * radialDistortionFactor + tangentialDistortionCorrectionY) * focalLengthY() + principalPointY();
1933 sqr = normalizedImagePoint.
sqr();
1934 radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
1936 tangentialDistortionCorrectionX = tangentialDistortion_.first * 2 * normalizedImagePoint.
x() * normalizedImagePoint.
y()
1939 tangentialDistortionCorrectionY = tangentialDistortion_.first * (
sqr + 2 *
NumericT<T>::sqr(normalizedImagePoint.
y()))
1940 + tangentialDistortion_.second * 2 * normalizedImagePoint.
x() * normalizedImagePoint.
y();
1942 imagePoints[n].
x() = (normalizedImagePoint.
x() * radialDistortionFactor + tangentialDistortionCorrectionX) * focalLengthX() + principalPointX();
1943 imagePoints[n].
y() = (normalizedImagePoint.
y() * radialDistortionFactor + tangentialDistortionCorrectionY) * focalLengthY() + principalPointY();
1950 for (
unsigned int n = 0u; n < numberNormalizedImagePoints; ++n)
1952 const VectorT2<T>& normalizedImagePoint(normalizedImagePoints[n]);
1954 imagePoints[n].
x() = normalizedImagePoint.
x() * focalLengthX() + principalPointX();
1955 imagePoints[n].
y() = normalizedImagePoint.
y() * focalLengthY() + principalPointY();
1960template <
typename T>
1961template <
bool tUseBorderDistortionIfOuts
ide>
1968template <
typename T>
1969template <
bool tUseBorderDistortionIfOuts
ide>
1976template <
typename T>
1977template <
bool tUseBorderDistortionIfOuts
ide>
1984template <
typename T>
1985template <
bool tUseBorderDistortionIfOuts
ide>
1989 ocean_assert(numberObjectPoints == 0u || (worldObjectPoints !=
nullptr && imagePoints !=
nullptr));
1991 return projectToImageIF<tUseBorderDistortionIfOutside>(
CameraT<T>::standard2InvertedFlipped(world_T_camera), worldObjectPoints, numberObjectPoints, distortImagePoints, imagePoints, zoom);
1994template <
typename T>
1995template <
bool tUseBorderDistortionIfOuts
ide>
1999 ocean_assert(worldLine.
isValid());
2004template <
typename T>
2005template <
bool tUseBorderDistortionIfOuts
ide>
2010 const VectorT3<T> transformedObjectPoint(flippedCamera_T_world * worldObjectPoint);
2013 const T factor = T(1) / transformedObjectPoint.
z();
2015 const VectorT2<T> normalizedImagePoint(transformedObjectPoint.
x() * factor, transformedObjectPoint.
y() * factor);
2017 if (!distortImagePoint)
2019 return VectorT2<T>(normalizedImagePoint.
x() * focalLengthX() * zoom + principalPointX(), normalizedImagePoint.
y() * focalLengthY() * zoom + principalPointY());
2022 if constexpr (tUseBorderDistortionIfOutside)
2024 const T invZoom = T(1) / zoom;
2026 const VectorT2<T> clampedNormalizedImagePoint(
minmax(-principalPointX() * inverseFocalLengthX() * invZoom, normalizedImagePoint.
x(), (T(width_) - principalPointX()) * inverseFocalLengthX() * invZoom),
2027 minmax(-principalPointY() * inverseFocalLengthY() * invZoom, normalizedImagePoint.
y(), (T(height_) - principalPointY()) * inverseFocalLengthY() * invZoom));
2029 const T
sqr = clampedNormalizedImagePoint.
sqr();
2031 const T radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
2033 const T tangentialDistortionCorrectionX = tangentialDistortion_.first * 2 * clampedNormalizedImagePoint.
x() * clampedNormalizedImagePoint.
y()
2034 + tangentialDistortion_.second * (
sqr + 2 *
NumericT<T>::sqr(clampedNormalizedImagePoint.
x()));
2036 const T tangentialDistortionCorrectionY = tangentialDistortion_.first * (
sqr + 2 *
NumericT<T>::sqr(clampedNormalizedImagePoint.
y()))
2037 + tangentialDistortion_.second * 2 * clampedNormalizedImagePoint.
x() * clampedNormalizedImagePoint.
y();
2039 return VectorT2<T>((normalizedImagePoint.
x() * radialDistortionFactor + tangentialDistortionCorrectionX) * focalLengthX() * zoom + principalPointX(),
2040 (normalizedImagePoint.
y() * radialDistortionFactor + tangentialDistortionCorrectionY) * focalLengthY() * zoom + principalPointY());
2044 const T
sqr = normalizedImagePoint.
sqr();
2046 const T radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
2048 const T tangentialDistortionCorrectionX = tangentialDistortion_.first * 2 * normalizedImagePoint.
x() * normalizedImagePoint.
y()
2051 const T tangentialDistortionCorrectionY = tangentialDistortion_.first * (
sqr + 2 *
NumericT<T>::sqr(normalizedImagePoint.
y()))
2052 + tangentialDistortion_.second * 2 * normalizedImagePoint.
x() * normalizedImagePoint.
y();
2054 return VectorT2<T>((normalizedImagePoint.
x() * radialDistortionFactor + tangentialDistortionCorrectionX) * focalLengthX() * zoom + principalPointX(),
2055 (normalizedImagePoint.
y() * radialDistortionFactor + tangentialDistortionCorrectionY) * focalLengthY() * zoom + principalPointY());
2059template <
typename T>
2060template <
bool tUseBorderDistortionIfOuts
ide>
2064 ocean_assert(worldObjectBox.
isValid());
2067 const unsigned int numberBoxImagePoints = worldObjectBox.
corners(boxObjectCorners);
2070 for (
unsigned int n = 0; n < numberBoxImagePoints; ++n)
2072 result += projectToImageIF<tUseBorderDistortionIfOutside>(flippedCamera_T_world, boxObjectCorners[n], distortImagePoint, zoom);
2078template <
typename T>
2079template <
bool tUseBorderDistortionIfOuts
ide>
2083 ocean_assert(worldObjectTriangle.
isValid());
2085 return TriangleT2<T>(projectToImageIF<tUseBorderDistortionIfOutside>(flippedCamera_T_world, worldObjectTriangle.
point0(), distortImagePoint, zoom),
2086 projectToImageIF<tUseBorderDistortionIfOutside>(flippedCamera_T_world, worldObjectTriangle.
point1(), distortImagePoint, zoom),
2087 projectToImageIF<tUseBorderDistortionIfOutside>(flippedCamera_T_world, worldObjectTriangle.
point2(), distortImagePoint, zoom));
2090template <
typename T>
2091template <
bool tUseBorderDistortionIfOuts
ide>
2096 if (distortImagePoint)
2098 if constexpr (tUseBorderDistortionIfOutside)
2100 const T invZoom = T(1) / zoom;
2102 const VectorT2<T> clampedNormalizedImagePoint(
minmax(-principalPointX() * inverseFocalLengthX() * invZoom, normalizedObjectPoint.
x(), (T(width_) - principalPointX()) * inverseFocalLengthX() * invZoom),
2103 minmax(-principalPointY() * inverseFocalLengthY() * invZoom, normalizedObjectPoint.
y(), (T(height_) - principalPointY()) * inverseFocalLengthY() * invZoom));
2105 const T
sqr = clampedNormalizedImagePoint.
sqr();
2107 const T radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
2109 const T tangentialDistortionCorrectionX = tangentialDistortion_.first * 2 * clampedNormalizedImagePoint.
x() * clampedNormalizedImagePoint.
y()
2110 + tangentialDistortion_.second * (
sqr + 2 *
NumericT<T>::sqr(clampedNormalizedImagePoint.
x()));
2112 const T tangentialDistortionCorrectionY = tangentialDistortion_.first * (
sqr + 2 *
NumericT<T>::sqr(clampedNormalizedImagePoint.
y()))
2113 + tangentialDistortion_.second * 2 * clampedNormalizedImagePoint.
x() * clampedNormalizedImagePoint.
y();
2115 return VectorT2<T>((normalizedObjectPoint.
x() * radialDistortionFactor + tangentialDistortionCorrectionX) * focalLengthX() * zoom + principalPointX(),
2116 (normalizedObjectPoint.
y() * radialDistortionFactor + tangentialDistortionCorrectionY) * focalLengthY() * zoom + principalPointY());
2120 const T
sqr = normalizedObjectPoint.
sqr();
2122 const T radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
2124 const T tangentialDistortionCorrectionX = tangentialDistortion_.first * 2 * normalizedObjectPoint.
x() * normalizedObjectPoint.
y()
2127 const T tangentialDistortionCorrectionY = tangentialDistortion_.first * (
sqr + 2 *
NumericT<T>::sqr(normalizedObjectPoint.
y()))
2128 + tangentialDistortion_.second * 2 * normalizedObjectPoint.
x() * normalizedObjectPoint.
y();
2130 return VectorT2<T>((normalizedObjectPoint.
x() * radialDistortionFactor + tangentialDistortionCorrectionX) * focalLengthX() * zoom + principalPointX(),
2131 (normalizedObjectPoint.
y() * radialDistortionFactor + tangentialDistortionCorrectionY) * focalLengthY() * zoom + principalPointY());
2136 return VectorT2<T>(normalizedObjectPoint.
x() * focalLengthX() * zoom + principalPointX(), normalizedObjectPoint.
y() * focalLengthY() * zoom + principalPointY());
2140template <
typename T>
2141template <
bool tUseBorderDistortionIfOuts
ide>
2145 ocean_assert((worldObjectPoints !=
nullptr && imagePoints !=
nullptr) || numberObjectPoints == 0u);
2147 if (distortImagePoints && hasDistortionParameters())
2149 const T invZoom = T(1) / zoom;
2151 const T leftClamping = -principalPointX() * inverseFocalLengthX() * invZoom;
2152 const T rightClamping = (T(width_) - principalPointX()) * inverseFocalLengthX() * invZoom;
2153 const T topClamping = -principalPointY() * inverseFocalLengthY() * invZoom;
2154 const T bottomClamping = (T(height_) - principalPointY()) * inverseFocalLengthY() * invZoom;
2157 if (tangentialDistortion_.first == 0 && tangentialDistortion_.second == 0)
2159 for (
size_t n = 0; n < numberObjectPoints; ++n)
2161 const VectorT3<T> objectPoint(flippedCamera_T_world * worldObjectPoints[n]);
2164 const T factor = 1 / objectPoint.
z();
2166 const VectorT2<T> normalizedImagePoint(objectPoint.
x() * factor, objectPoint.
y() * factor);
2168 if constexpr (tUseBorderDistortionIfOutside)
2170 const VectorT2<T> clampedNormalizedImagePoint(
minmax(leftClamping, normalizedImagePoint.
x(), rightClamping),
minmax(topClamping, normalizedImagePoint.
y(), bottomClamping));
2172 const T
sqr = clampedNormalizedImagePoint.
sqr();
2173 const T radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
2175 *imagePoints =
VectorT2<T>((normalizedImagePoint.
x() * radialDistortionFactor) * focalLengthX() * zoom + principalPointX(),
2176 (normalizedImagePoint.
y() * radialDistortionFactor) * focalLengthY() * zoom + principalPointY());
2180 const T
sqr = normalizedImagePoint.
sqr();
2181 const T radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
2183 *imagePoints =
VectorT2<T>((normalizedImagePoint.
x() * radialDistortionFactor) * focalLengthX() * zoom + principalPointX(),
2184 (normalizedImagePoint.
y() * radialDistortionFactor) * focalLengthY() * zoom + principalPointY());
2192 ocean_assert(tangentialDistortion_.first != 0 || tangentialDistortion_.second != 0);
2194 for (
size_t n = 0; n < numberObjectPoints; ++n)
2196 const VectorT3<T> objectPoint(flippedCamera_T_world * worldObjectPoints[n]);
2199 const T factor = 1 / objectPoint.
z();
2201 const VectorT2<T> normalizedImagePoint(objectPoint.
x() * factor, objectPoint.
y() * factor);
2203 if constexpr (tUseBorderDistortionIfOutside)
2205 const VectorT2<T> clampedNormalizedImagePoint(
minmax(leftClamping, normalizedImagePoint.
x(), rightClamping),
minmax(topClamping, normalizedImagePoint.
y(), bottomClamping));
2207 const T
sqr = clampedNormalizedImagePoint.
sqr();
2208 const T radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
2210 const T tangentialDistortionCorrectionX = tangentialDistortion_.first * 2 * clampedNormalizedImagePoint.
x() * clampedNormalizedImagePoint.
y()
2211 + tangentialDistortion_.second * (
sqr + 2 *
NumericT<T>::sqr(clampedNormalizedImagePoint.
x()));
2213 const T tangentialDistortionCorrectionY = tangentialDistortion_.first * (
sqr + 2 *
NumericT<T>::sqr(clampedNormalizedImagePoint.
y()))
2214 + tangentialDistortion_.second * 2 * clampedNormalizedImagePoint.
x() * clampedNormalizedImagePoint.
y();
2216 *imagePoints =
VectorT2<T>((normalizedImagePoint.
x() * radialDistortionFactor + tangentialDistortionCorrectionX) * focalLengthX() * zoom + principalPointX(),
2217 (normalizedImagePoint.
y() * radialDistortionFactor + tangentialDistortionCorrectionY) * focalLengthY() * zoom + principalPointY());
2221 const T
sqr = normalizedImagePoint.
sqr();
2222 const T radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
2224 const T tangentialDistortionCorrectionX = tangentialDistortion_.first * 2 * normalizedImagePoint.
x() * normalizedImagePoint.
y()
2227 const T tangentialDistortionCorrectionY = tangentialDistortion_.first * (
sqr + 2 *
NumericT<T>::sqr(normalizedImagePoint.
y()))
2228 + tangentialDistortion_.second * 2 * normalizedImagePoint.
x() * normalizedImagePoint.
y();
2230 *imagePoints =
VectorT2<T>((normalizedImagePoint.
x() * radialDistortionFactor + tangentialDistortionCorrectionX) * focalLengthX() * zoom + principalPointX(),
2231 (normalizedImagePoint.
y() * radialDistortionFactor + tangentialDistortionCorrectionY) * focalLengthY() * zoom + principalPointY());
2242 ocean_assert(transformationIF.
isValid());
2244 for (
size_t n = 0; n < numberObjectPoints; ++n)
2246 const VectorT3<T> transformedObjectPoint(transformationIF * worldObjectPoints[n]);
2249 const T factor = 1 / transformedObjectPoint.
z();
2251 *imagePoints++ =
VectorT2<T>(transformedObjectPoint.
x() * factor, transformedObjectPoint.
y() * factor);
2256template <
typename T>
2257template <
bool tUseBorderDistortionIfOuts
ide>
2261 ocean_assert(worldLine.
isValid());
2263 const VectorT2<T> firstImagePoint(projectToImageIF<tUseBorderDistortionIfOutside>(flippedCamera_T_world, worldLine.
point(), distortProjectedLine, zoom));
2264 const VectorT2<T> secondImagePoint(projectToImageIF<tUseBorderDistortionIfOutside>(flippedCamera_T_world, worldLine.
point(10), distortProjectedLine, zoom));
2266 if (firstImagePoint == secondImagePoint)
2271 return LineT2<T>(firstImagePoint, (secondImagePoint - firstImagePoint).normalized());
2274template <
typename T>
2281template <
typename T>
2288template <
typename T>
2295template <
typename T>
2299 ocean_assert(numberObjectPoints == 0u || (objectPoints && imagePoints));
2304template <
typename T>
2305template <
bool tDistortImagePo
int,
bool tUseBorderDistortionIfOuts
ide>
2310 const VectorT3<T> transformedObjectPoint(iFlippedExtrinsic * objectPoint);
2313 const T factor = T(1) / transformedObjectPoint.
z();
2316 const VectorT2<T> normalizedImagePoint(transformedObjectPoint.
x() * factor, transformedObjectPoint.
y() * factor);
2318 if (!tDistortImagePoint)
2320 return VectorT2<T>(normalizedImagePoint.
x() * focalLengthX() * zoom + principalPointX(), normalizedImagePoint.
y() * focalLengthY() * zoom + principalPointY());
2323 if constexpr (tUseBorderDistortionIfOutside)
2325 const T invZoom = T(1) / zoom;
2327 const VectorT2<T> clampedNormalizedImagePoint(
minmax(-principalPointX() * inverseFocalLengthX() * invZoom, normalizedImagePoint.
x(), (T(width_) - principalPointX()) * inverseFocalLengthX() * invZoom),
2328 minmax(-principalPointY() * inverseFocalLengthY() * invZoom, normalizedImagePoint.
y(), (T(height_) - principalPointY()) * inverseFocalLengthY() * invZoom));
2330 const T
sqr = clampedNormalizedImagePoint.
sqr();
2332 const T radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
2334 const T tangentialDistortionCorrectionX = tangentialDistortion_.first * 2 * clampedNormalizedImagePoint.
x() * clampedNormalizedImagePoint.
y()
2335 + tangentialDistortion_.second * (
sqr + 2 *
NumericT<T>::sqr(clampedNormalizedImagePoint.
x()));
2337 const T tangentialDistortionCorrectionY = tangentialDistortion_.first * (
sqr + 2 *
NumericT<T>::sqr(clampedNormalizedImagePoint.
y()))
2338 + tangentialDistortion_.second * 2 * clampedNormalizedImagePoint.
x() * clampedNormalizedImagePoint.
y();
2340 return VectorT2<T>((normalizedImagePoint.
x() * radialDistortionFactor + tangentialDistortionCorrectionX) * focalLengthX() * zoom + principalPointX(),
2341 (normalizedImagePoint.
y() * radialDistortionFactor + tangentialDistortionCorrectionY) * focalLengthY() * zoom + principalPointY());
2345 const T
sqr = normalizedImagePoint.
sqr();
2347 const T radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
2349 const T tangentialDistortionCorrectionX = tangentialDistortion_.first * 2 * normalizedImagePoint.
x() * normalizedImagePoint.
y()
2352 const T tangentialDistortionCorrectionY = tangentialDistortion_.first * (
sqr + 2 *
NumericT<T>::sqr(normalizedImagePoint.
y()))
2353 + tangentialDistortion_.second * 2 * normalizedImagePoint.
x() * normalizedImagePoint.
y();
2355 return VectorT2<T>((normalizedImagePoint.
x() * radialDistortionFactor + tangentialDistortionCorrectionX) * focalLengthX() * zoom + principalPointX(),
2356 (normalizedImagePoint.
y() * radialDistortionFactor + tangentialDistortionCorrectionY) * focalLengthY() * zoom + principalPointY());
2360template <
typename T>
2393 const VectorT3<T> testVector(
VectorT3<T>((position(0) - principalPointX()) * inverseFocalLengthX(), (position(1) - principalPointY()) * -inverseFocalLengthY(), -1).normalized());
2401 return VectorT3<T>((position(0) - principalPointX()) * inverseFocalLengthX(), (position(1) - principalPointY()) * -inverseFocalLengthY(), -1).
normalized();
2405 return VectorT3<T>((position(0) - principalPointX()) * inverseFocalLengthX(), (position(1) - principalPointY()) * -inverseFocalLengthY(), -1);
2409template <
typename T>
2442 const T invZoom = T(1) / zoom;
2446 const VectorT3<T> testVector(
VectorT3<T>((position(0) - principalPointX()) * inverseFocalLengthX() * invZoom, (position(1) - principalPointY()) * -inverseFocalLengthY() * invZoom, -1).normalized());
2454 return VectorT3<T>((position(0) - principalPointX()) * inverseFocalLengthX() * invZoom, (position(1) - principalPointY()) * -inverseFocalLengthY() * invZoom, -1).
normalized();
2458 return VectorT3<T>((position(0) - principalPointX()) * inverseFocalLengthX() * invZoom, (position(1) - principalPointY()) * -inverseFocalLengthY() * invZoom, -1);
2462template <
typename T>
2482 const VectorT3<T> testVector(distance * (position(0) - principalPointX()) * inverseFocalLengthX(), distance * (position(1) - principalPointY()) * -inverseFocalLengthY(), -distance);
2488 return VectorT3<T>(distance * (position(0) - principalPointX()) * inverseFocalLengthX(), distance * (position(1) - principalPointY()) * -inverseFocalLengthY(), -distance);
2491template <
typename T>
2511 const T invZoom = T(1) / zoom;
2515 const VectorT3<T> testVector(distance * (position(0) - principalPointX()) * inverseFocalLengthX() * invZoom, distance * (position(1) - principalPointY()) * -inverseFocalLengthY() * invZoom, -distance);
2521 return VectorT3<T>(distance * (position(0) - principalPointX()) * inverseFocalLengthX() * invZoom, distance * (position(1) - principalPointY()) * -inverseFocalLengthY() * invZoom, -distance);
2524template <
typename T>
2529 const VectorT3<T> testVector(
VectorT3<T>((position(0) - principalPointX()) * inverseFocalLengthX(), (position(1) - principalPointY()) * inverseFocalLengthY(), 1).normalized());
2530 ocean_assert((std::is_same<T, float>::value) || position.
isEqual(projectToImageIF<false>(
HomogenousMatrixT4<T>(
true), testVector,
false), T(0.01)));
2535 return VectorT3<T>((position(0) - principalPointX()) * inverseFocalLengthX(), (position(1) - principalPointY()) * inverseFocalLengthY(), 1).
normalized();
2539 return VectorT3<T>((position(0) - principalPointX()) * inverseFocalLengthX(), (position(1) - principalPointY()) * inverseFocalLengthY(), 1);
2543template <
typename T>
2548 const T invZoom = T(1) / zoom;
2552 const VectorT3<T> testVector(
VectorT3<T>((position(0) - principalPointX()) * inverseFocalLengthX() * invZoom, (position(1) - principalPointY()) * inverseFocalLengthY() * invZoom, 1).normalized());
2559 return VectorT3<T>((position(0) - principalPointX()) * inverseFocalLengthX() * invZoom, (position(1) - principalPointY()) * inverseFocalLengthY() * invZoom, 1).
normalized();
2563 return VectorT3<T>((position(0) - principalPointX()) * inverseFocalLengthX() * invZoom, (position(1) - principalPointY()) * inverseFocalLengthY() * invZoom, 1);
2567template <
typename T>
2577template <
typename T>
2582 return LineT3<T>(world_t_camera, world_Q_camera * vector(position, zoom));
2585template <
typename T>
2600 const T inverseFocalLengthX = T(1) / focalLengthX();
2601 const T inverseFocalLengthY = T(1) / focalLengthY();
2603 invertedIntrinsics_(0, 0) = inverseFocalLengthX;
2604 invertedIntrinsics_(1, 1) = inverseFocalLengthY;
2605 invertedIntrinsics_(0, 2) = - principalPointX() * inverseFocalLengthX;
2606 invertedIntrinsics_(1, 2) = - principalPointY() * inverseFocalLengthY;
2607 invertedIntrinsics_(2, 2) = 1;
2609 ocean_assert(invertedIntrinsics_(1, 0) == 0);
2610 ocean_assert(invertedIntrinsics_(2, 0) == 0);
2611 ocean_assert(invertedIntrinsics_(0, 1) == 0);
2612 ocean_assert(invertedIntrinsics_(2, 1) == 0);
2615template <
typename T>
2618 return !(*
this == camera);
2621template <
typename T>
2627template <
typename T>
2628template <
bool tUseBorderDistortionIfOuts
ide>
2633 if (hasDistortionParameters())
2635 if constexpr (tUseBorderDistortionIfOutside)
2637 const VectorT2<T> clampedNormalizedImagePoint(
minmax(-principalPointX() * inverseFocalLengthX() * invZoom, undistortedNormalized.
x(), (T(width_) - principalPointX()) * inverseFocalLengthX() * invZoom),
2638 minmax(-principalPointY() * inverseFocalLengthY() * invZoom, undistortedNormalized.
y(), (T(height_) - principalPointY()) * inverseFocalLengthY() * invZoom));
2640 const T
sqr = clampedNormalizedImagePoint.
sqr();
2642 const T radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
2644 const T tangentialDistortionCorrectionX = tangentialDistortion_.first * 2 * clampedNormalizedImagePoint.
x() * clampedNormalizedImagePoint.
y()
2645 + tangentialDistortion_.second * (
sqr + 2 *
NumericT<T>::sqr(clampedNormalizedImagePoint.
x()));
2647 const T tangentialDistortionCorrectionY = tangentialDistortion_.first * (
sqr + 2 *
NumericT<T>::sqr(clampedNormalizedImagePoint.
y()))
2648 + tangentialDistortion_.second * 2 * clampedNormalizedImagePoint.
x() * clampedNormalizedImagePoint.
y();
2650 return VectorT2<T>(undistortedNormalized.
x() * radialDistortionFactor + tangentialDistortionCorrectionX,
2651 undistortedNormalized.
y() * radialDistortionFactor + tangentialDistortionCorrectionY);
2655 const T
sqr = undistortedNormalized.
sqr();
2657 const T radialDistortionFactor = T(1) + radialDistortion_.first *
sqr + radialDistortion_.second *
NumericT<T>::sqr(
sqr);
2659 const T tangentialDistortionCorrectionX = tangentialDistortion_.first * 2 * undistortedNormalized.
x() * undistortedNormalized.
y()
2662 const T tangentialDistortionCorrectionY = tangentialDistortion_.first * (
sqr + 2 *
NumericT<T>::sqr(undistortedNormalized.
y()))
2663 + tangentialDistortion_.second * 2 * undistortedNormalized.
x() * undistortedNormalized.
y();
2665 return VectorT2<T>(undistortedNormalized.
x() * radialDistortionFactor + tangentialDistortionCorrectionX,
2666 undistortedNormalized.
y() * radialDistortionFactor + tangentialDistortionCorrectionY);
2671 return undistortedNormalized;
This class implements an axis aligned 2D box object.
Definition Box2.h:68
This class implements an axis aligned 3D bounding box.
Definition Box3.h:67
bool isValid() const
Returns whether the bounding box is valid.
unsigned int corners(VectorT3< T > *corners) const
Returns the corner positions of this box.
This class implements the base class for all cameras.
Definition Camera.h:54
This class implements a 4x4 homogeneous transformation matrix using floating point values with the pr...
Definition HomogenousMatrix4.h:110
SquareMatrixT3< T > rotationMatrix() const
Returns the rotation matrix of the transformation.
Definition HomogenousMatrix4.h:1493
VectorT3< T > translation() const
Returns the translation of the transformation.
Definition HomogenousMatrix4.h:1381
bool isValid() const
Returns whether this matrix is a valid homogeneous transformation.
Definition HomogenousMatrix4.h:1806
QuaternionT< T > rotation() const
Returns the rotation of the transformation as quaternion.
Definition HomogenousMatrix4.h:1388
This class implements an infinite line in 2D space.
Definition Line2.h:83
This class implements an infinite line in 3D space.
Definition Line3.h:68
bool isValid() const
Returns whether this line has valid parameters.
Definition Line3.h:301
const VectorT3< T > & point() const
Returns a point on the line.
Definition Line3.h:269
This class implements a 2D lookup object with values at the bins' center positions defining the indiv...
Definition Lookup2.h:198
This class provides basic numeric functionalities.
Definition Numeric.h:57
static T abs(const T value)
Returns the absolute value of a given value.
Definition Numeric.h:1220
static constexpr T sqr(const T value)
Returns the square of a given value.
Definition Numeric.h:1495
This class encapsulates a lookup table for camera distortion offsets allowing for faster un-distortio...
Definition PinholeCamera.h:203
DistortionLookup(const PinholeCameraT< T > &camera, const unsigned int binSize)
Creates an lookup object for a given camera.
VectorT2< T > undistortionOffset(const VectorT2< T > &distortedImagePoint) const
Returns the offset that needs to be added to an distorted image point so that it would be undistorted...
Definition PinholeCamera.h:1306
VectorT2< T > undistortedImagePointBicubic(const VectorT2< T > &distortedImagePoint) const
Returns the undistorted image point for a given (distorted) image point (by application of a bicubic ...
Definition PinholeCamera.h:1313
VectorT2< T > undistortionOffsetBicubic(const VectorT2< T > &distortedImagePoint) const
Returns the offset that needs to be added to an distorted image point so that it would be undistorted...
Definition PinholeCamera.h:1320
VectorT2< T > undistortedImagePoint(const VectorT2< T > &distortedImagePoint) const
Returns the undistorted image point for a given (distorted) image point (by application of a bilinear...
Definition PinholeCamera.h:1299
DistortionLookup()
Creates an invalid lookup object.
Definition PinholeCamera.h:1293
LookupTable distortionLookupTable
The distortion lookup table.
Definition PinholeCamera.h:256
LookupCenter2< VectorT2< T >, T > LookupTable
Definition of a lookup table for 2D vectors.
Definition PinholeCamera.h:209
Definition of a pinhole camera model.
Definition PinholeCamera.h:114
std::pair< T, T > DistortionPair
Definition of a pair of distortion values.
Definition PinholeCamera.h:123
VectorT2< T > projectToImageIF(const HomogenousMatrixT4< T > &flippedCamera_T_world, const VectorT3< T > &worldObjectPoint, 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:2306
void setTangentialDistortion(const DistortionPair &tangential)
Sets the tangential distortion parameters.
Definition PinholeCamera.h:1518
VectorT2< T > imagePoint2normalizedImagePoint(const VectorT2< T > &imagePoint, const bool undistortImagePoint) const
Calculates the normalized image point corresponding to a given (distorted) image point.
Definition PinholeCamera.h:1769
unsigned int width() const
Returns the width of the camera image.
Definition PinholeCamera.h:1452
PinholeCameraT(const unsigned int width, const unsigned int height, const T focalX, const T focalY, const T principalX, const T principalY, const DistortionPair &radial, const DistortionPair &tangential)
Creates a new PinholeCameraT<T> object by it's given intrinsic parameters.
VectorT2< T > projectToImageDamped(const HomogenousMatrixT4< T > &extrinsic, const VectorT3< T > &objectPoint, const bool distortImagePoint, const T dampingFactor=T(1), const T zoom=T(1)) const
Projects a 3D object point to the 2D image plane of the camera by a given extrinsic camera matrix.
Definition PinholeCamera.h:2275
T fovYBottom() const
Returns the bottom field of view in y direction.
bool isEqual(const PinholeCameraT< T > &camera, const T eps=NumericT< T >::eps()) const
Returns whether two camera profiles are identical up to a given epsilon.
bool isInside(const VectorT2< T > &imagePoint, const T signedBorder=T(0)) const
Returns whether a given 2D image point lies inside the camera frame.
Definition PinholeCamera.h:1659
T fovYTop() const
Returns the top field of view in y direction.
VectorT2< T > dampedNormalized(const VectorT2< T > &normalized, const T dampingFactor, const T invZoom) const
Determines the damped normalized coordinate for a given normalized coordinate.
PinholeCameraT(const unsigned int width, const unsigned int height, const T *parameters, const bool radialDistortion=true, const bool tangentialDistortion=true)
Creates a new PinholeCameraT<T> object by it's given intrinsic parameters.
T principalPointX() const
Returns the x-value of the principal point of the camera image in the pixel domain.
Definition PinholeCamera.h:1470
DistortionPair tangentialDistortion_
Pair of tangential distortion parameters.
Definition PinholeCamera.h:1289
PinholeCameraT()=default
Standard constructor.
const SquareMatrixT3< T > & invertedIntrinsic() const
Returns the inverted intrinsic camera matrix.
Definition PinholeCamera.h:1333
bool operator==(const PinholeCameraT< T > &camera) const
Returns whether two camera objects are identical up to a small epsilon.
VectorT2< T > principalPoint() const
Returns the coordinate of the principal point of the camera image in the pixel domain.
Definition PinholeCamera.h:1464
void copyParameters(unsigned int &width, unsigned int &height, std::vector< TParameter > ¶meters, ParameterConfiguration ¶meterConfiguration) const
Copies the parameters of this camera.
Definition PinholeCamera.h:1622
BoxT2< T > projectToImage(const HomogenousMatrixT4< T > &world_T_camera, const BoxT3< T > &worldObjectBox, const bool distortImagePoint, const T zoom=T(1)) const
Projects a 3D box to the 2D image plane of the camera by a given camera pose.
Definition PinholeCamera.h:1970
PinholeCameraT(const unsigned int width, const unsigned int height, const ParameterConfiguration parameterConfiguration, const TParameter *parameters)
Creates a new camera object with parameters with specific configuration.
Definition PinholeCamera.h:1364
TriangleT2< T > projectToImageIF(const HomogenousMatrixT4< T > &flippedCamera_T_world, const TriangleT3< T > &worldObjectTriangle, const bool distortImagePoint, const T zoom=T(1)) const
Projects a 3D triangle to the 2D image plane of the camera by a given extrinsic camera pose.
Definition PinholeCamera.h:2080
VectorT2< T > projectToImageIF(const VectorT2< T > &normalizedObjectPoint, const bool distortImagePoint, const T zoom=T(1)) const
Transforms a normalized object point (a 3D object point transformed by the inverted and flipped extri...
Definition PinholeCamera.h:2092
bool isDistortionPlausible(const T symmetricFocalLengthRatio=T(1.05), const T modelAccuracy=T(0.001), const T symmetricDistortionRatio=T(1.08)) const
Checks whether the distortion of this camera is plausible.
VectorT2< T > dampedNormalized(const VectorT2< T > &normalized, const T dampingFactor, const T leftNormalizedBorder, const T rightNormalizedBorder, const T topNormalizedBorder, const T bottomNormalizedBorder) const
Determines the damped normalized coordinate for a given normalized coordinate.
LineT3< T > ray(const VectorT2< T > &position, const HomogenousMatrixT4< T > &world_T_camera, const T zoom=T(1)) const
Returns a ray starting at the camera's center and intersection a given 2D point on the image plane.
Definition PinholeCamera.h:2568
T fovXRight() const
Returns the right field of view in x direction.
BoxT2< T > projectToImageDamped(const HomogenousMatrixT4< T > &extrinsic, const BoxT3< T > &objectBox, const bool distortImagePoint, const T dampingFactor=T(1), const T zoom=T(1)) const
Projects a 3D box to the 2D image plane of the camera by a given inverse extrinsic camera matrix.
Definition PinholeCamera.h:2282
VectorT2< T > distortDamped(const VectorT2< T > &undistorted, const T dampingFactor=T(1), const T zoom=T(1)) const
Returns the distorted position of a given undistorted position defined in pixel coordinates.
VectorT2< T > distort(const VectorT2< T > &undistorted) const
Returns the distorted position of a given undistorted position defined in pixel coordinates.
Definition PinholeCamera.h:1570
LineT3< T > ray(const VectorT2< T > &position, const VectorT3< T > &world_t_camera, const QuaternionT< T > &world_Q_camera, const T zoom=T(1)) const
Returns a ray starting at the camera's center and intersection a given 2D point on the image plane.
Definition PinholeCamera.h:2578
PinholeCameraT(const unsigned int width, const unsigned int height, const T fovX, const T principalX, const T principalY)
Creates a new PinholeCameraT<T> object by the given frame dimensions, the ideal field of view,...
PinholeCameraT(const SquareMatrixT3< T > &intrinsic)
Creates a new PinholeCameraT<T> object by a given projection matrix with the intrinsic camera paramet...
VectorT2< T > distortNormalized(const VectorT2< T > &undistortedNormalized, const T invZoom) const
Returns the distorted position of a given undistorted normalized position.
Definition PinholeCamera.h:2629
BoxT2< T > projectToImageDampedIF(const HomogenousMatrixT4< T > &iFlippedExtrinsic, const BoxT3< T > &objectBox, const bool distortImagePoint, const T dampingFactor=T(1), const T zoom=T(1)) const
Projects a 3D box to the 2D image plane of the camera by a given inverse extrinsic camera matrix.
VectorT2< T > undistort(const VectorT2< T > &distorted, const unsigned int iterations=10u, const T zoom=T(1)) const
Returns the undistorted position of a given distorted position defined in pixel coordinates.
Definition PinholeCamera.h:1525
bool isValid() const
Returns whether this camera is valid.
Definition PinholeCamera.h:1762
VectorT3< T > vectorToPlane(const VectorT2< T > &position, const T distance, const T zoom) const
Returns a vector starting at the camera's center and intersecting a given 2D point on the image plane...
Definition PinholeCamera.h:2492
void setRadialDistortion(const DistortionPair &radial)
Sets the radial distortion parameters.
Definition PinholeCamera.h:1512
BoxT2< T > projectToImageIF(const HomogenousMatrixT4< T > &flippedCamera_T_world, const BoxT3< T > &worldObjectBox, const bool distortImagePoint, const T zoom=T(1)) const
Projects a 3D box to the 2D image plane of the camera by a given inverse camera pose.
Definition PinholeCamera.h:2061
T focalLengthY() const
Returns the vertical focal length parameter.
Definition PinholeCamera.h:1488
SquareMatrixT3< T > invertedIntrinsics_
Inverted intrinsic camera matrix.
Definition PinholeCamera.h:1283
PinholeCameraT(const PinholeCameraT< U > &pinholeCamera, const bool copyDistortionParameters=true)
Copy constructor for a pinhole camera with difference element data type than T.
Definition PinholeCamera.h:1352
bool hasDistortionParameters() const
Returns whether this camera object has specified distortion parameters.
Definition PinholeCamera.h:1445
VectorT2< T > projectToImageDampedIF(const HomogenousMatrixT4< T > &iFlippedExtrinsic, const VectorT3< T > &objectPoint, const bool distortImagePoint, const T dampingFactor=T(1), const T zoom=T(1)) const
Projects a 3D object point to the 2D image plane of the camera by a given inverse extrinsic camera ma...
const SquareMatrixT3< T > & intrinsic() const
Returns the intrinsic camera matrix.
Definition PinholeCamera.h:1327
T calculateCosBetween(const VectorT2< T > &first, const VectorT2< T > &second) const
Returns the cosine of the viewing angle between two undistorted points on the camera's image plane.
TriangleT2< T > projectToImageDamped(const HomogenousMatrixT4< T > &extrinsic, const TriangleT3< T > &objectTriangle, const bool distortImagePoint, const T dampingFactor=T(1), const T zoom=T(1)) const
Projects a 3D triangle to the 2D image plane of the camera by a given extrinsic camera matrix.
Definition PinholeCamera.h:2289
PinholeCameraT(const unsigned int width, const unsigned int height, const T focalX, const T focalY, const T principalX, const T principalY)
Creates a new PinholeCameraT<T> object by it's given intrinsic parameters.
void calculateInverseIntrinsic()
Determines the inverse of the intrinsic camera matrix.
Definition PinholeCamera.h:2586
void projectToImageDamped(const HomogenousMatrixT4< T > &extrinsic, const VectorT3< T > *objectPoints, const size_t numberObjectPoints, const bool distortImagePoints, VectorT2< T > *imagePoints, const T dampingFactor=T(1), const T zoom=T(1)) const
Projects a set of 3D object points onto an image plane of the camera by a given extrinsic camera matr...
Definition PinholeCamera.h:2296
VectorT3< T > vectorToPlane(const VectorT2< T > &position, const T distance) const
Returns a vector starting at the camera's center and intersecting a given 2D point on the image plane...
Definition PinholeCamera.h:2463
bool rotation(const VectorT2< T > &undistortedPosition, T &angleX, T &angleY) const
Gets two rotation parameters of the viewing ray for a given undistorted 2D position in the camera ima...
T fovY() const
Returns the field of view in x direction of the camera.
SquareMatrixT3< T > intrinsics_
Intrinsic camera matrix.
Definition PinholeCamera.h:1280
T fovDiagonal() const
Returns the diagonal field of view of the camera.
SquareMatrixT4< T > frustumMatrix(const T nearDistance, const T farDistance) const
Returns the 4x4 frustum projection matrix corresponding to this camera.
HomogenousMatrixT4< T > transformationMatrixIF(const HomogenousMatrixT4< T > &iFlippedExtrinsic, const T zoom=T(1)) const
Returns a 4x4 homogeneous transformation matrix (corresponding to a 3x4 matrix) that covers an extrin...
Definition PinholeCamera.h:1669
void normalizedImagePoints2imagePoints(const VectorT2< T > *normalizedImagePoints, const size_t numberNormalizedImagePoints, const bool distortImagePoints, VectorT2< T > *imagePoints) const
Calculates the image points corresponding to a set of given normalized image points.
Definition PinholeCamera.h:1866
T TScalar
The scalar data type of this object.
Definition PinholeCamera.h:120
VectorT3< T > vectorIF(const VectorT2< T > &position, const bool makeUnitVector=true) const
Returns a vector starting at the camera's center and intersecting a given 2D point on the image plane...
Definition PinholeCamera.h:2525
OptimizationStrategy
Definition of individual optimization strategies for camera parameters.
Definition PinholeCamera.h:178
unsigned int height() const
Returns the height of the camera image.
Definition PinholeCamera.h:1458
const DistortionPair & radialDistortion() const
Returns the pair of radial distortion parameters.
Definition PinholeCamera.h:1339
DistortionPair radialDistortion_
Pair of radial distortion parameters for r^2 and r^4.
Definition PinholeCamera.h:1286
TriangleT2< T > projectToImage(const HomogenousMatrixT4< T > &world_T_camera, const TriangleT3< T > &worldObjectTriangle, const bool distortImagePoint, const T zoom=T(1)) const
Projects a 3D triangle to the 2D image plane of the camera by a given camera pose.
Definition PinholeCamera.h:1978
VectorT3< T > vectorIF(const VectorT2< T > &position, const T zoom, const bool makeUnitVector) const
Returns a vector starting at the camera's center and intersecting a given 2D point on the image plane...
Definition PinholeCamera.h:2544
void applyZoomFactor(const T relativeZoom)
Applies a given (relative) zoom factor which mainly multiplies the focal length parameters by the giv...
T inverseFocalLengthX() const
Returns the inverse horizontal focal length parameter.
Definition PinholeCamera.h:1494
PinholeCameraT(const SquareMatrixT3< T > &intrinsic, const unsigned int width, const unsigned int height)
Creates a new PinholeCameraT<T> object by the given intrinsic camera matrix and width and height of t...
PinholeCameraT(const unsigned int width, const unsigned int height, const T fovX)
Creates a new PinholeCameraT<T> object by the given width, height and field of view of a camera.
const DistortionPair & tangentialDistortion() const
Returns the pair of tangential distortion parameters.
Definition PinholeCamera.h:1345
VectorT2< T > normalizedImagePoint2imagePoint(const VectorT2< T > &normalizedImagePoint, const bool distortImagePoint) const
Calculates the image point corresponding to a given normalized image point.
Definition PinholeCamera.h:1792
VectorT2< T > distortNormalizedDamped(const VectorT2< T > &undistortedNormalized, const T dampingFactor, const T invZoom) const
Returns the distorted position of a given undistorted normalized position.
void copyElements(T *arrayValues, const bool copyRadialDistortion=true, const bool copyTangentialDistortion=true) const
Copies the elements of this camera to an array with 4 to 8 floating point values.
void projectToImageDampedIF(const HomogenousMatrixT4< T > &invertedFlippedExtrinsic, const VectorT3< T > *objectPoints, const size_t numberObjectPoints, const bool distortImagePoints, VectorT2< T > *imagePoints, const T dampingFactor=T(1), const T zoom=T(1)) const
Projects a set of 3D object points onto an image plane of the camera by a given inverse extrinsic cam...
ParameterConfiguration
Definition of individual parameter configurations.
Definition PinholeCamera.h:129
@ PC_7_PARAMETERS_ONE_FOCAL_LENGTH
7 parameters with order: focal length (one identical value for horizontal and vertical direction),...
Definition PinholeCamera.h:160
@ PC_3_PARAMETERS_ONE_FOCAL_LENGTH
3 parameters with order: focal length (one identical value for horizontal and vertical direction),...
Definition PinholeCamera.h:141
@ PC_4_PARAMETERS
4 parameters with order: horizontal focal length, vertical focal length, horizontal principal point,...
Definition PinholeCamera.h:150
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:2006
T principalPointY() const
Returns the y-value of the principal point of the camera image in the pixel domain.
Definition PinholeCamera.h:1476
LineT2< T > projectToImage(const HomogenousMatrixT4< T > &world_T_camera, const LineT3< T > &worldLine, const bool distortProjectedLine, const T zoom=T(1)) const
Projects a 3D line onto an image plane of the camera by a given camera pose.
Definition PinholeCamera.h:1996
T fovX() const
Returns the field of view in x direction of the camera.
T calculateAngleBetween(const VectorT2< T > &first, const VectorT2< T > &second) const
Returns the viewing angle between two undistorted points on the camera's image plane.
VectorT2< T > undistortDamped(const VectorT2< T > &distorted, const T dampingFactor=T(1), const unsigned int iterations=10u, const T zoom=T(1)) const
Returns the undistorted position of a given distorted position defined in pixel coordinates.
PinholeCameraT(const unsigned int width, const unsigned int height, const PinholeCameraT< T > &camera)
Creates a new camera object with specified frame dimension and intrinsic camera parameters best match...
bool operator!=(const PinholeCameraT< T > &camera) const
Returns whether two camera objects are not identical up to a small epsilon.
Definition PinholeCamera.h:2616
PinholeCameraT(const SquareMatrixT3< T > &intrinsic, const unsigned int width, const unsigned int height, const DistortionPair &radial, const DistortionPair &tangential)
Creates a new PinholeCameraT<T> object by the given intrinsic camera matrix, the width and height and...
T fovXLeft() const
Returns the left field of view in x direction.
T inverseFocalLengthY() const
Returns the inverse vertical focal length parameter.
Definition PinholeCamera.h:1503
VectorT3< T > vector(const VectorT2< T > &position, const T zoom, const bool makeUnitVector=true) const
Returns a vector starting at the camera's center and intersecting a given 2D point on the image plane...
Definition PinholeCamera.h:2410
bool setIntrinsic(const SquareMatrixT3< T > &intrinsic)
Sets the intrinsic camera matrix.
VectorT2< T > imagePoint2normalizedImagePointDamped(const VectorT2< T > &imagePoint, const bool undistortImagePoint) const
Calculates the normalized image point corresponding to a given (distorted) image point.
Definition PinholeCamera.h:1780
PinholeCameraT(const T subFrameLeft, const T subFrameTop, const unsigned int subFrameWidth, const unsigned int subFrameHeight, const PinholeCameraT< T > &camera)
Creates a new sub-frame camera profile based on a camera profile of the entire camera frame.
LineT2< T > projectToImageIF(const HomogenousMatrixT4< T > &flippedCamera_T_world, const LineT3< T > &worldLine, const bool distortProjectedLine, const T zoom=T(1)) const
Projects a 3D line onto an image plane of the camera by a given inverse camera pose.
Definition PinholeCamera.h:2258
void pointJacobian2x3IF(const VectorT3< U > &flippedCameraObjectPoint, U *jx, U *jy) const
Calculates the 2x3 jacobian matrix for the 3D object point projection into the camera frame.
Definition PinholeCamera.h:1693
void projectToImageIF(const HomogenousMatrixT4< T > &flippedCamera_T_world, const VectorT3< T > *worldObjectPoints, const size_t numberObjectPoints, const bool distortImagePoints, VectorT2< T > *imagePoints, const T zoom=T(1)) const
Projects a set of 3D object points onto an image plane of the camera by a given inverse camera pose.
Definition PinholeCamera.h:2142
friend class PinholeCameraT
Definition PinholeCamera.h:115
TriangleT2< T > projectToImageDampedIF(const HomogenousMatrixT4< T > &iFlippedExtrinsic, const TriangleT3< T > &objectTriangle, const bool distortImagePoint, const T dampingFactor=T(1), const T zoom=T(1)) const
Projects a 3D triangle to the 2D image plane of the camera by a given inverse extrinsic camera matrix...
void projectToImage(const HomogenousMatrixT4< T > &world_T_camera, const VectorT3< T > *worldObjectPoints, const size_t numberObjectPoints, const bool distortImagePoints, VectorT2< T > *imagePoints, const T zoom=T(1)) const
Projects a set of 3D object points onto an image plane of the camera by a given camera pose.
Definition PinholeCamera.h:1986
VectorT2< T > projectToImage(const HomogenousMatrixT4< T > &world_T_camera, const VectorT3< T > &worldObjectPoint, 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 camera pose.
Definition PinholeCamera.h:1962
T focalLengthX() const
Returns the horizontal focal length parameter.
Definition PinholeCamera.h:1482
VectorT3< T > vector(const VectorT2< T > &position, const bool makeUnitVector=true) const
Returns a vector starting at the camera's center and intersecting a given 2D point on the image plane...
Definition PinholeCamera.h:2361
This class implements a unit quaternion rotation.
Definition Quaternion.h:100
bool isValid() const
Returns whether this quaternion is a valid unit quaternion.
Definition Quaternion.h:901
This class implements a 3x3 square matrix.
Definition SquareMatrix3.h:88
SquareMatrixT3< T > inverted() const
Returns the inverted matrix of this matrix.
Definition SquareMatrix3.h:1176
This class implements a 4x4 square matrix.
Definition SquareMatrix4.h:85
This class implements a 2D triangle with Cartesian coordinates.
Definition Triangle2.h:81
This class implements a 3D triangle.
Definition Triangle3.h:80
const VectorT3< T > & point0() const
Returns the first point of this triangle.
Definition Triangle3.h:278
bool isValid() const
Returns whether this triangle is valid.
Definition Triangle3.h:580
const VectorT3< T > & point2() const
Returns the third point of this triangle.
Definition Triangle3.h:290
const VectorT3< T > & point1() const
Returns the second point of this triangle.
Definition Triangle3.h:284
This class implements a vector with two elements.
Definition Vector2.h:96
const T & x() const noexcept
Returns the x value.
Definition Vector2.h:710
const T & y() const noexcept
Returns the y value.
Definition Vector2.h:722
bool isEqual(const VectorT2< T > &vector, const T eps) const
Returns whether two vectors are equal up to a specified epsilon.
Definition Vector2.h:758
T sqr() const
Returns the square of the vector length.
Definition Vector2.h:633
This class implements a vector with three elements.
Definition Vector3.h:97
const T & y() const noexcept
Returns the y value.
Definition Vector3.h:824
const T & x() const noexcept
Returns the x value.
Definition Vector3.h:812
VectorT3< T > normalized() const
Returns the normalized vector.
Definition Vector3.h:617
const T & z() const noexcept
Returns the z value.
Definition Vector3.h:836
T length() const
Returns the length of the vector.
Definition Vector3.h:676
T minmax(const T &lowerBoundary, const T &value, const T &upperBoundary)
This function fits a given parameter into a specified value range.
Definition base/Utilities.h:927
unsigned int sqr(const char value)
Returns the square value of a given value.
Definition base/Utilities.h:1053
PinholeCameraT< double > PinholeCameraD
Definition of an pinhole camera object with double precision.
Definition PinholeCamera.h:46
PinholeCameraT< float > PinholeCameraF
Definition of an pinhole camera object with float precision.
Definition PinholeCamera.h:53
PinholeCamerasT< double > PinholeCamerasD
Definition of a vector holding PinholeCameraD objects.
Definition PinholeCamera.h:75
PinholeCamerasT< Scalar > PinholeCameras
Definition of a vector holding pinhole camera objects.
Definition PinholeCamera.h:68
std::vector< PinholeCameraT< T > > PinholeCamerasT
Definition of a typename alias for vectors with PinholeCameraT objects.
Definition PinholeCamera.h:61
PinholeCameraT< Scalar > PinholeCamera
Definition of an pinhole camera object with Scalar precision.
Definition PinholeCamera.h:39
PinholeCamerasT< float > PinholeCamerasF
Definition of a vector holding PinholeCameraF objects.
Definition PinholeCamera.h:82
The namespace covering the entire Ocean framework.
Definition Accessor.h:15