MRPT
1.9.9
|
This class represent a pinhole camera model for Monocular SLAM and implements some associated Jacobians.
The camera parameters are accessible in the public member CCamModel::cam
Definition at line 34 of file CCamModel.h.
#include <mrpt/vision/CCamModel.h>
Classes | |
struct | CameraTempVariables |
Public Member Functions | |
CCamModel () | |
Default Constructor. More... | |
void | loadFromConfigFile (const mrpt::config::CConfigFileBase &source, const std::string §ion) override |
This method load the options from a ".ini"-like file or memory-stored string list. More... | |
void | dumpToTextStream (std::ostream &out) const override |
This method displays clearly all the contents of the structure in textual form, sending it to a CStream. More... | |
CCamModel (const mrpt::config::CConfigFileBase &cfgIni) | |
Constructor from a ini file. More... | |
void | jacob_undistor_fm (const mrpt::img::TPixelCoordf &uvd, math::CMatrixDouble &J_undist) |
Jacobian for undistortion the image coordinates. More... | |
void | jacob_undistor (const mrpt::img::TPixelCoordf &p, mrpt::math::CMatrixDouble &J_undist) |
Calculate the image coordinates undistorted. More... | |
void | distort_a_point (const mrpt::img::TPixelCoordf &p, mrpt::img::TPixelCoordf &distorted_p) |
Return the pixel position distorted by the camera. More... | |
void | undistort_point (const mrpt::img::TPixelCoordf &p, mrpt::img::TPixelCoordf &undistorted_p) |
Return the pixel position undistorted by the camera The input values 'col' and 'row' will be replace for the new values (undistorted) More... | |
void | project_3D_point (const mrpt::math::TPoint3D &p3D, mrpt::img::TPixelCoordf &distorted_p) const |
Return the (distorted) pixel position of a 3D point given in coordinates relative to the camera (+Z pointing forward, +X to the right) More... | |
void | unproject_3D_point (const mrpt::img::TPixelCoordf &distorted_p, mrpt::math::TPoint3D &p3D) const |
Return the 3D location of a point (at a fixed distance z=1), for the given (distorted) pixel position. More... | |
void | jacobian_project_with_distortion (const mrpt::math::TPoint3D &p3D, math::CMatrixDouble &dh_dy) const |
Jacobian of the projection of 3D points (with distortion), as done in project_3D_point , evaluated at the point p3D (read below the full explanation) More... | |
void | jacobian_unproject_with_distortion (const mrpt::img::TPixelCoordf &p, math::CMatrixDouble &dy_dh) const |
Jacobian of the unprojection of a pixel (with distortion) back into a 3D point, as done in unproject_3D_point , evaluated at the pixel p. More... | |
template<typename T , typename POINT > | |
void | getTemporaryVariablesForTransform (const POINT &p, CameraTempVariables< T > &v) const |
template<typename T , typename POINT , typename PIXEL > | |
void | getFullProjection (const POINT &pIn, PIXEL &pOut) const |
template<typename T , typename PIXEL > | |
void | getFullProjectionT (const CameraTempVariables< T > &tmp, PIXEL &pOut) const |
template<typename T , typename POINT , typename MATRIX > | |
void | getFullJacobian (const POINT &pIn, MATRIX &mOut) const |
template<typename T , typename POINT , typename MATRIX > | |
void | getFullJacobianT (const POINT &pIn, const CameraTempVariables< T > &tmp, MATRIX &mOut) const |
template<typename POINTIN , typename POINTOUT , typename MAT22 > | |
void | getFullInverseModelWithJacobian (const POINTIN &pIn, POINTOUT &pOut, MAT22 &jOut) const |
void | loadFromConfigFileName (const std::string &config_file, const std::string §ion) |
Behaves like loadFromConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to load the file. More... | |
virtual void | saveToConfigFile (mrpt::config::CConfigFileBase &target, const std::string §ion) const |
This method saves the options to a ".ini"-like file or memory-stored string list. More... | |
void | saveToConfigFileName (const std::string &config_file, const std::string §ion) const |
Behaves like saveToConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to save the file. More... | |
void | dumpToConsole () const |
Just like dumpToTextStream() but sending the text to the console (std::cout) More... | |
Public Attributes | |
mrpt::img::TCamera | cam |
The parameters of a camera. More... | |
Static Protected Member Functions | |
static void | dumpVar_int (std::ostream &out, const char *varName, int v) |
Used to print variable info from dumpToTextStream with the macro LOADABLEOPTS_DUMP_VAR. More... | |
static void | dumpVar_float (std::ostream &out, const char *varName, float v) |
static void | dumpVar_double (std::ostream &out, const char *varName, double v) |
static void | dumpVar_bool (std::ostream &out, const char *varName, bool v) |
static void | dumpVar_string (std::ostream &out, const char *varName, const std::string &v) |
Private Member Functions | |
mrpt::math::CMatrixFixedNumeric< double, 2, 2 > | firstInverseJacobian () const |
mrpt::math::CMatrixFixedNumeric< double, 4, 2 > | secondInverseJacobian () const |
mrpt::math::CMatrixFixedNumeric< double, 3, 4 > | thirdInverseJacobian () const |
CCamModel::CCamModel | ( | ) |
mrpt::vision::CCamModel::CCamModel | ( | const mrpt::config::CConfigFileBase & | cfgIni | ) |
Constructor from a ini file.
void CCamModel::distort_a_point | ( | const mrpt::img::TPixelCoordf & | p, |
mrpt::img::TPixelCoordf & | distorted_p | ||
) |
Return the pixel position distorted by the camera.
Definition at line 104 of file CCamModel.cpp.
References cam, mrpt::img::TCamera::cx(), mrpt::img::TCamera::cy(), mrpt::img::TCamera::k1(), mrpt::square(), mrpt::img::TPixelCoordf::x, and mrpt::img::TPixelCoordf::y.
|
inherited |
Just like dumpToTextStream() but sending the text to the console (std::cout)
Definition at line 44 of file CLoadableOptions.cpp.
References mrpt::config::CLoadableOptions::dumpToTextStream().
Referenced by mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel().
|
overridevirtual |
This method displays clearly all the contents of the structure in textual form, sending it to a CStream.
Reimplemented from mrpt::config::CLoadableOptions.
Definition at line 330 of file CCamModel.cpp.
References MRPT_UNUSED_PARAM.
|
staticprotectedinherited |
Definition at line 63 of file CLoadableOptions.cpp.
References mrpt::format(), and LOADABLEOPTS_COLUMN_WIDTH.
|
staticprotectedinherited |
Definition at line 57 of file CLoadableOptions.cpp.
References mrpt::format(), and LOADABLEOPTS_COLUMN_WIDTH.
|
staticprotectedinherited |
Definition at line 51 of file CLoadableOptions.cpp.
References mrpt::format(), and LOADABLEOPTS_COLUMN_WIDTH.
|
staticprotectedinherited |
Used to print variable info from dumpToTextStream with the macro LOADABLEOPTS_DUMP_VAR.
Definition at line 45 of file CLoadableOptions.cpp.
References mrpt::format(), and LOADABLEOPTS_COLUMN_WIDTH.
|
staticprotectedinherited |
Definition at line 70 of file CLoadableOptions.cpp.
References mrpt::format(), and LOADABLEOPTS_COLUMN_WIDTH.
|
inlineprivate |
Definition at line 246 of file CCamModel.h.
Referenced by getFullInverseModelWithJacobian().
|
inline |
Definition at line 278 of file CCamModel.h.
References cam, mrpt::img::TCamera::cx(), mrpt::img::TCamera::cy(), firstInverseJacobian(), mrpt::img::TCamera::fx(), mrpt::img::TCamera::fy(), mrpt::img::TCamera::k1(), mrpt::img::TCamera::k2(), mrpt::img::TCamera::k3(), mrpt::img::TCamera::p1(), mrpt::img::TCamera::p2(), secondInverseJacobian(), mrpt::square(), and thirdInverseJacobian().
|
inline |
Definition at line 195 of file CCamModel.h.
References getFullJacobianT(), and getTemporaryVariablesForTransform().
|
inline |
Definition at line 203 of file CCamModel.h.
References cam, mrpt::img::TCamera::fx(), mrpt::img::TCamera::fy(), mrpt::vision::CCamModel::CameraTempVariables< T >::K, mrpt::img::TCamera::k1(), mrpt::img::TCamera::k2(), mrpt::img::TCamera::k3(), mrpt::img::TCamera::p1(), mrpt::img::TCamera::p2(), mrpt::vision::CCamModel::CameraTempVariables< T >::R, mrpt::square(), mrpt::vision::CCamModel::CameraTempVariables< T >::x_, and mrpt::vision::CCamModel::CameraTempVariables< T >::y_.
Referenced by getFullJacobian().
|
inline |
Definition at line 179 of file CCamModel.h.
References getFullProjectionT(), and getTemporaryVariablesForTransform().
|
inline |
Definition at line 187 of file CCamModel.h.
References cam, mrpt::img::TCamera::cx(), mrpt::img::TCamera::cy(), mrpt::img::TCamera::fx(), mrpt::img::TCamera::fy(), mrpt::vision::CCamModel::CameraTempVariables< T >::x__, and mrpt::vision::CCamModel::CameraTempVariables< T >::y__.
Referenced by getFullProjection().
|
inline |
Definition at line 164 of file CCamModel.h.
References cam, mrpt::img::TCamera::k1(), mrpt::img::TCamera::k2(), mrpt::img::TCamera::k3(), mrpt::img::TCamera::p1(), mrpt::img::TCamera::p2(), and mrpt::square().
Referenced by getFullJacobian(), and getFullProjection().
void CCamModel::jacob_undistor | ( | const mrpt::img::TPixelCoordf & | p, |
mrpt::math::CMatrixDouble & | J_undist | ||
) |
Calculate the image coordinates undistorted.
Definition at line 57 of file CCamModel.cpp.
References cam, mrpt::img::TCamera::cx(), mrpt::img::TCamera::cy(), mrpt::img::TCamera::k1(), and mrpt::square().
void CCamModel::jacob_undistor_fm | ( | const mrpt::img::TPixelCoordf & | uvd, |
math::CMatrixDouble & | J_undist | ||
) |
Jacobian for undistortion the image coordinates.
Definition at line 26 of file CCamModel.cpp.
References cam, mrpt::img::TCamera::cx(), mrpt::img::TCamera::cy(), mrpt::img::TCamera::fx(), mrpt::img::TCamera::fy(), mrpt::img::TCamera::k1(), and mrpt::img::TCamera::k2().
void CCamModel::jacobian_project_with_distortion | ( | const mrpt::math::TPoint3D & | p3D, |
math::CMatrixDouble & | dh_dy | ||
) | const |
Jacobian of the projection of 3D points (with distortion), as done in project_3D_point , evaluated at the point p3D (read below the full explanation)
We define as the projected point in pixels (origin at the top-left corner), and as the 3D point in space, in coordinates relative to the camera (+Z pointing forwards).
Then this method computes the 2x3 Jacobian:
With:
where is the focal length in units of pixel sizes in x and y, respectively. And, if we define:
then:
Definition at line 198 of file CCamModel.cpp.
References ASSERT_, cam, mrpt::img::TCamera::fx(), mrpt::img::TCamera::fy(), mrpt::img::TCamera::k1(), mrpt::square(), mrpt::math::TPoint3D::x, mrpt::math::TPoint3D::y, and mrpt::math::TPoint3D::z.
void CCamModel::jacobian_unproject_with_distortion | ( | const mrpt::img::TPixelCoordf & | p, |
math::CMatrixDouble & | dy_dh | ||
) | const |
Jacobian of the unprojection of a pixel (with distortion) back into a 3D point, as done in unproject_3D_point , evaluated at the pixel p.
Definition at line 263 of file CCamModel.cpp.
References cam, mrpt::img::TCamera::cx(), mrpt::img::TCamera::cy(), mrpt::img::TCamera::fx(), mrpt::img::TCamera::fy(), mrpt::img::TCamera::k1(), and mrpt::square().
|
overridevirtual |
This method load the options from a ".ini"-like file or memory-stored string list.
Only those parameters found in the given "section" and having the same name that the variable are loaded. Those not found in the file will stay with their previous values (usually the default values loaded at initialization). An example of an ".ini" file:
Implements mrpt::config::CLoadableOptions.
Definition at line 298 of file CCamModel.cpp.
References ASSERT_, cam, MRPT_END, MRPT_LOAD_HERE_CONFIG_VAR_NO_DEFAULT, MRPT_START, mrpt::img::TCamera::setDistortionParamsVector(), and mrpt::img::TCamera::setIntrinsicParamsFromValues().
|
inherited |
Behaves like loadFromConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to load the file.
Definition at line 22 of file CLoadableOptions.cpp.
References mrpt::config::CLoadableOptions::loadFromConfigFile().
void CCamModel::project_3D_point | ( | const mrpt::math::TPoint3D & | p3D, |
mrpt::img::TPixelCoordf & | distorted_p | ||
) | const |
Return the (distorted) pixel position of a 3D point given in coordinates relative to the camera (+Z pointing forward, +X to the right)
Definition at line 150 of file CCamModel.cpp.
References ASSERT_, cam, mrpt::img::TCamera::cx(), mrpt::img::TCamera::cy(), mrpt::img::TCamera::fx(), mrpt::img::TCamera::fy(), mrpt::img::TCamera::k1(), mrpt::square(), mrpt::img::TPixelCoordf::x, mrpt::math::TPoint3D::x, mrpt::img::TPixelCoordf::y, mrpt::math::TPoint3D::y, and mrpt::math::TPoint3D::z.
|
virtualinherited |
This method saves the options to a ".ini"-like file or memory-stored string list.
Reimplemented in mrpt::vision::TMultiResDescOptions, mrpt::vision::TMultiResDescMatchOptions, mrpt::nav::CPTG_RobotShape_Circular, mrpt::nav::CPTG_RobotShape_Polygonal, mrpt::nav::CParameterizedTrajectoryGenerator, mrpt::maps::TSetOfMetricMapInitializers, mrpt::nav::CAbstractPTGBasedReactive::TAbstractPTGNavigatorParams, mrpt::nav::CAbstractNavigator::TAbstractNavigatorParams, mrpt::nav::CPTG_DiffDrive_CollisionGridBased, mrpt::nav::CWaypointsNavigator::TWaypointsNavigatorParams, mrpt::nav::CHolonomicFullEval::TOptions, mrpt::bayes::CParticleFilter::TParticleFilterOptions, mrpt::nav::CReactiveNavigationSystem::TReactiveNavigatorParams, mrpt::nav::CHolonomicND::TOptions, mrpt::maps::TMapGenericParams, mrpt::nav::CMultiObjectiveMotionOptimizerBase::TParamsBase, mrpt::nav::CHolonomicVFF::TOptions, mrpt::slam::CICP::TConfigParams, mrpt::slam::CIncrementalMapPartitioner::TOptions, mrpt::maps::CPointCloudFilterByDistance::TOptions, mrpt::nav::CPTG_DiffDrive_C, mrpt::maps::TMetricMapInitializer, mrpt::nav::CPTG_DiffDrive_alpha, mrpt::nav::CMultiObjMotionOpt_Scalarization::TParams, mrpt::nav::CPTG_DiffDrive_CC, mrpt::nav::CPTG_DiffDrive_CCS, mrpt::nav::CPTG_DiffDrive_CS, and mrpt::nav::CPTG_Holo_Blend.
Definition at line 29 of file CLoadableOptions.cpp.
References MRPT_UNUSED_PARAM.
Referenced by mrpt::config::CLoadableOptions::dumpToTextStream(), and mrpt::config::CLoadableOptions::saveToConfigFileName().
|
inherited |
Behaves like saveToConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to save the file.
Definition at line 37 of file CLoadableOptions.cpp.
References mrpt::config::CLoadableOptions::saveToConfigFile().
|
inlineprivate |
Definition at line 253 of file CCamModel.h.
Referenced by getFullInverseModelWithJacobian().
|
inlineprivate |
Definition at line 262 of file CCamModel.h.
Referenced by getFullInverseModelWithJacobian().
void CCamModel::undistort_point | ( | const mrpt::img::TPixelCoordf & | p, |
mrpt::img::TPixelCoordf & | undistorted_p | ||
) |
Return the pixel position undistorted by the camera The input values 'col' and 'row' will be replace for the new values (undistorted)
Definition at line 126 of file CCamModel.cpp.
References ASSERT_, cam, mrpt::img::TCamera::getDistortionParamsAsVector(), mrpt::img::TCamera::intrinsicParams, and mrpt::vision::pinhole::undistort_points().
void CCamModel::unproject_3D_point | ( | const mrpt::img::TPixelCoordf & | distorted_p, |
mrpt::math::TPoint3D & | p3D | ||
) | const |
Return the 3D location of a point (at a fixed distance z=1), for the given (distorted) pixel position.
Definition at line 178 of file CCamModel.cpp.
References cam, mrpt::img::TCamera::cx(), mrpt::img::TCamera::cy(), mrpt::img::TCamera::fx(), mrpt::img::TCamera::fy(), mrpt::img::TCamera::k1(), mrpt::square(), mrpt::img::TPixelCoordf::x, mrpt::math::TPoint3D::x, mrpt::img::TPixelCoordf::y, mrpt::math::TPoint3D::y, and mrpt::math::TPoint3D::z.
mrpt::img::TCamera mrpt::vision::CCamModel::cam |
The parameters of a camera.
Definition at line 38 of file CCamModel.h.
Referenced by distort_a_point(), getFullInverseModelWithJacobian(), getFullJacobianT(), getFullProjectionT(), getTemporaryVariablesForTransform(), jacob_undistor(), jacob_undistor_fm(), jacobian_project_with_distortion(), jacobian_unproject_with_distortion(), loadFromConfigFile(), project_3D_point(), undistort_point(), and unproject_3D_point().
Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 7d5e6d718 Fri Aug 24 01:51:28 2018 +0200 at lun nov 2 08:35:50 CET 2020 |