#include <Extrinsic.hpp>
Public Member Functions | |
| Extrinsic (Intrinsic intr, vecPoint2D imgPoint, vecPoint3D objPoint) | |
| Extrinsic (Intrinsic intr, vecPoint2D imgPoint, vecPoint3D objPoint, float &error) | |
| Extrinsic (Intrinsic intr, cv::Mat &rmat, cv::Mat &tvec) | |
| float | error () |
| const cv::Mat & | rotationMatrix () |
| const cv::Mat & | rotationVector () |
| const cv::Mat & | translationVector () |
| Point2D | project (Point3D pt) |
| vecPoint2D | project (vecPoint3D objPoints) |
| vecPoint3D | objPoints () |
| vecPoint2D | imgPoints () |
Contains rotation matrix and translation vector
| aram::Extrinsic::Extrinsic | ( | Intrinsic | intr, |
| vecPoint2D | imgPoint, | ||
| vecPoint3D | objPoint | ||
| ) |
Compute extrinsics parameters using solvePnP (see OpenCV)
| [in] | Intrinsic | intr intrinsics parameters for the camera |
| [in] | vecPoint2D | imgPoint |
| [in] | vecPoint3D | objPoint |
| aram::Extrinsic::Extrinsic | ( | Intrinsic | intr, |
| vecPoint2D | imgPoint, | ||
| vecPoint3D | objPoint, | ||
| float & | error | ||
| ) |
Compute extrinsics parameters using solvePnP (see OpenCV)
| [in] | Intrinsic | intr intrinsics parameters for the camera |
| [in] | vecPoint2D | imgPoint |
| [in] | vecPoint3D | objPoint |
| [out] | float | &error reprojection error |
| aram::Extrinsic::Extrinsic | ( | Intrinsic | intr, |
| cv::Mat & | rmat, | ||
| cv::Mat & | tvec | ||
| ) |
Store rotation matrix and translation matrix
| [in] | Intrinsic | intr intrinsics parameters for the camera |
| [in] | cv::Mat | &rmat rotation matrix |
| [in] | cv::Mat | &tvec translation vector |
| float aram::Extrinsic::error | ( | ) |
Compute reprojection error
| vecPoint2D aram::Extrinsic::imgPoints | ( | ) |
Getter
| vecPoint3D aram::Extrinsic::objPoints | ( | ) |
Getter
Project a 3d point on image
| [in] | Point3D | pt point to project (3D space) |
| vecPoint2D aram::Extrinsic::project | ( | vecPoint3D | objPoints | ) |
Project 3d points on image
| [in] | vecPoint3D | objPoints point to project (3D space) |
| const cv::Mat & aram::Extrinsic::rotationMatrix | ( | ) |
Get rotation matrix
| const cv::Mat & aram::Extrinsic::rotationVector | ( | ) |
Get rotation vector
| const cv::Mat & aram::Extrinsic::translationVector | ( | ) |
Get translation vector
1.8.6