| |
- se2_l2(...) method of builtins.PyCapsule instance
- se2_l2(*args, **kwargs)
Overloaded function.
1. se2_l2(in_correspondences: mrpt.pymrpt.mrpt.tfest.TMatchingPairListTempl_float_t, out_transformation: mrpt.pymrpt.mrpt.math.TPose2D) -> bool
2. se2_l2(in_correspondences: mrpt.pymrpt.mrpt.tfest.TMatchingPairListTempl_float_t, out_transformation: mrpt.pymrpt.mrpt.math.TPose2D, out_estimateCovariance: mrpt.pymrpt.mrpt.math.CMatrixFixed_double_3UL_3UL_t) -> bool
Least-squares (L2 norm) solution to finding the optimal SE(2) (x,y,yaw)
between two reference frames.
The optimal transformation `q` fulfills
, that is, the
transformation of frame `other` with respect to `this`.
The set of correspondences.
The pose that minimizes the mean-square-error
between all the correspondences.
If provided (!=nullptr) this will contain
on return a 3x3 covariance matrix with the NORMALIZED optimal estimate
uncertainty. This matrix must be multiplied by
, the variance
of matched points in
and
(see paper
https://www.mrpt.org/Paper:Occupancy_Grid_Matching)
True if there are at least two correspondences, or false if one or
none, thus we cannot establish any correspondence.
robustRigidTransformation
Reference for covariance calculation: J.L. Blanco, J.
Gonzalez-Jimenez, J.A. Fernandez-Madrigal, "A Robust, Multi-Hypothesis
Approach to Matching Occupancy Grid Maps", Robotica, 2013.
http://dx.doi.org/10.1017/S0263574712000732
[New in MRPT 1.3.0] This function replaces
mrpt::scanmatching::leastSquareErrorRigidTransformation()
This function is hand-optimized for SSE2 architectures (if SSE2 is
enabled from CMake)
se3_l2, se2_l2_robust
C++: mrpt::tfest::se2_l2(const class mrpt::tfest::TMatchingPairListTempl<float> &, struct mrpt::math::TPose2D &, class mrpt::math::CMatrixFixed<double, 3, 3> *) --> bool
3. se2_l2(in_correspondences: mrpt.pymrpt.mrpt.tfest.TMatchingPairListTempl_float_t, out_transformation: mrpt.pymrpt.mrpt.poses.CPosePDFGaussian) -> bool
C++: mrpt::tfest::se2_l2(const class mrpt::tfest::TMatchingPairListTempl<float> &, class mrpt::poses::CPosePDFGaussian &) --> bool
- se2_l2_robust(...) method of builtins.PyCapsule instance
- se2_l2_robust(in_correspondences: mrpt.pymrpt.mrpt.tfest.TMatchingPairListTempl_float_t, in_normalizationStd: float, in_ransac_params: mrpt.pymrpt.mrpt.tfest.TSE2RobustParams, out_results: mrpt.pymrpt.mrpt.tfest.TSE2RobustResult) -> bool
Robust least-squares (L2 norm) solution to finding the optimal SE(2)
(x,y,yaw) between two reference frames.
This method implements a RANSAC-based robust estimation, returning a
probability distribution over all the possibilities as a Sum of Gaussians.
The optimal transformation `q` fulfills
, that is, the
transformation of frame `other` with respect to `this`.
The technique was described in the paper:
- J.L. Blanco, J. Gonzalez-Jimenez, J.A. Fernandez-Madrigal, "A Robust,
Multi-Hypothesis Approach to Matching Occupancy Grid Maps", Robotica, 2013.
http://dx.doi.org/10.1017/S0263574712000732
This works as follows:
- Repeat "ransac_nSimulations" times:
- Randomly pick TWO correspondences from the set "in_correspondences".
- Compute the associated rigid transformation.
- For "ransac_maxSetSize" randomly selected correspondences, test for
"consensus" with the current group:
- If if is compatible (ransac_mahalanobisDistanceThreshold), grow
the "consensus set"
- If not, do not add it.
For more details refer to the tutorial on
* href="http://www.mrpt.org/Scan_Matching_Algorithms">scan matching
methods.
The standard deviation (not variance)
of landmarks/points/features being matched in X,Y. Used to normalize
covariances returned as the SoG. (Refer to paper)
NOTE: Parameter `ransac_maxSetSize` should be set to
`in_correspondences.size()` to make sure that every correspondence is tested
for each random permutation.
True upon success, false if no subset was found with the minimum
number of correspondences.
[New in MRPT 1.3.0] This function replaces
mrpt::scanmatching::robustRigidTransformation()
se3_l2, se2_l2_robust
C++: mrpt::tfest::se2_l2_robust(const class mrpt::tfest::TMatchingPairListTempl<float> &, const double, const struct mrpt::tfest::TSE2RobustParams &, struct mrpt::tfest::TSE2RobustResult &) --> bool
- se3_l2(...) method of builtins.PyCapsule instance
- se3_l2(*args, **kwargs)
Overloaded function.
1. se3_l2(in_correspondences: mrpt.pymrpt.mrpt.tfest.TMatchingPairListTempl_float_t, out_transform: mrpt.pymrpt.mrpt.poses.CPose3DQuat, out_scale: float) -> bool
2. se3_l2(in_correspondences: mrpt.pymrpt.mrpt.tfest.TMatchingPairListTempl_float_t, out_transform: mrpt.pymrpt.mrpt.poses.CPose3DQuat, out_scale: float, forceScaleToUnity: bool) -> bool
Least-squares (L2 norm) solution to finding the optimal SE(3) transform
between two reference frames using the "quaternion" or Horn's method
The optimal transformation `q` fulfills
, that is, the
transformation of frame `other` with respect to `this`.
The coordinates of the input points for the
two coordinate systems "this" and "other"
The output transformation
The computed scale of the optimal
transformation (will be 1.0 for a perfectly rigid translation + rotation).
Whether or not force the scale employed to
rotate the coordinate systems to one (rigid transformation)
[New in MRPT 1.3.0] This function replaces
mrpt::scanmatching::leastSquareErrorRigidTransformation6DRANSAC() and
mrpt::scanmatching::HornMethod()
se2_l2, se3_l2_robust
C++: mrpt::tfest::se3_l2(const class mrpt::tfest::TMatchingPairListTempl<float> &, class mrpt::poses::CPose3DQuat &, double &, bool) --> bool
- se3_l2_robust(...) method of builtins.PyCapsule instance
- se3_l2_robust(in_correspondences: mrpt.pymrpt.mrpt.tfest.TMatchingPairListTempl_float_t, in_params: mrpt.pymrpt.mrpt.tfest.TSE3RobustParams, out_results: mrpt.pymrpt.mrpt.tfest.TSE3RobustResult) -> bool
Least-squares (L2 norm) solution to finding the optimal SE(3) transform
between two reference frames using RANSAC and the "quaternion" or Horn's
method
The optimal transformation `q` fulfills
, that is, the
transformation of frame `other` with respect to `this`.
The set of correspondences.
Method parameters (see docs for TSE3RobustParams)
Results: transformation, scale, etc.
True if the minimum number of correspondences was found, false
otherwise.
Implemented by FAMD, 2008. Re-factored by JLBC, 2015.
[New in MRPT 1.3.0] This function replaces
mrpt::scanmatching::leastSquareErrorRigidTransformation6DRANSAC()
se2_l2, se3_l2
C++: mrpt::tfest::se3_l2_robust(const class mrpt::tfest::TMatchingPairListTempl<float> &, const struct mrpt::tfest::TSE3RobustParams &, struct mrpt::tfest::TSE3RobustResult &) --> bool
|