class mrpt::poses::CPose3DQuatPDFGaussian
Declares a class that represents a Probability Density function (PDF) of a 3D pose using a quaternion \(p(\mathbf{x}) = [x ~ y ~ z ~ qr ~ qx ~ qy ~ qz]^\top\).
This class implements that PDF using a mono-modal Gaussian distribution. See mrpt::poses::CPose3DQuatPDF for more details, or mrpt::poses::CPose3DPDF for classes based on Euler angles instead.
Uncertainty of pose composition operations (\(y = x \oplus u\)) is implemented in the methods “CPose3DQuatPDFGaussian::operator+=” and “CPose3DQuatPDF::jacobiansPoseComposition”.
For further details on implemented methods and the theory behind them, see this report.
See also:
CPose3DQuat, CPose3DQuatPDF, CPose3DPDF, CPose3DQuatPDFGaussianInf
#include <mrpt/poses/CPose3DQuatPDFGaussian.h> class CPose3DQuatPDFGaussian: public mrpt::poses::CPose3DQuatPDF { public: // fields CPose3DQuat mean; mrpt::math::CMatrixDouble77 cov; // construction CPose3DQuatPDFGaussian(); CPose3DQuatPDFGaussian(mrpt::math::TConstructorFlags_Quaternions constructor_dummy_param); CPose3DQuatPDFGaussian(const CPose3DQuat& init_Mean); CPose3DQuatPDFGaussian(const CPose3DQuat& init_Mean, const mrpt::math::CMatrixDouble77& init_Cov); CPose3DQuatPDFGaussian(const CPosePDFGaussian& o); CPose3DQuatPDFGaussian(const CPose3DPDFGaussian& o); // methods const CPose3DQuat& getPoseMean() const; CPose3DQuat& getPoseMean(); void getMean(CPose3DQuat& mean_pose) const; virtual std::tuple<cov_mat_t, type_value> getCovarianceAndMean() const; virtual void copyFrom(const CPose3DQuatPDF& o); void copyFrom(const CPosePDF& o); void copyFrom(const CPose3DPDFGaussian& o); virtual bool saveToTextFile(const std::string& file) const; void changeCoordinatesReference(const CPose3DQuat& newReferenceBase); virtual void changeCoordinatesReference(const CPose3D& newReferenceBase); void drawSingleSample(CPose3DQuat& outPart) const; virtual void drawManySamples(size_t N, std::vector<mrpt::math::CVectorDouble>& outSamples) const; mrpt::math::CMatrixDouble77 inverseJacobian() const; virtual void inverse(CPose3DQuatPDF& o) const; mrpt::poses::CPose3DQuatPDFGaussian inverseCompositionCrossCorrelation(const mrpt::poses::CPose3DQuatPDFGaussian& pose_to) const; CPose3DQuatPDFGaussian operator - () const; void operator += (const CPose3DQuat& Ap); void operator += (const CPose3DQuatPDFGaussian& Ap); void operator -= (const CPose3DQuatPDFGaussian& Ap); double evaluatePDF(const CPose3DQuat& x) const; double evaluateNormalizedPDF(const CPose3DQuat& x) const; double mahalanobisDistanceTo(const CPose3DQuatPDFGaussian& theOther); };
Inherited Members
public: // typedefs typedef CProbabilityDensityFunction<TDATA, STATE_LEN> self_t; // methods virtual void copyFrom(const CPose3DQuatPDF& o) = 0; virtual void inverse(CPose3DQuatPDF& o) const = 0; virtual void changeCoordinatesReference(const CPose3D& newReferenceBase) = 0; template <class OPENGL_SETOFOBJECTSPTR> void getAs3DObject(OPENGL_SETOFOBJECTSPTR& out_obj) const; template <class OPENGL_SETOFOBJECTSPTR> OPENGL_SETOFOBJECTSPTR getAs3DObject() const; static CPose3DQuatPDF* createFrom2D(const CPosePDF& o); static void jacobiansPoseComposition(const CPose3DQuat& x, const CPose3DQuat& u, mrpt::math::CMatrixDouble77& df_dx, mrpt::math::CMatrixDouble77& df_du, CPose3DQuat* out_x_oplus_u = nullptr);
Fields
CPose3DQuat mean
The mean value.
mrpt::math::CMatrixDouble77 cov
The 7x7 covariance matrix.
Construction
CPose3DQuatPDFGaussian()
Default constructor - set all values to zero.
CPose3DQuatPDFGaussian(mrpt::math::TConstructorFlags_Quaternions constructor_dummy_param)
Constructor which left all the member uninitialized, for using when speed is critical - as argument, use UNINITIALIZED_QUATERNION.
CPose3DQuatPDFGaussian(const CPose3DQuat& init_Mean)
Constructor from a default mean value, covariance equals to zero.
CPose3DQuatPDFGaussian(const CPose3DQuat& init_Mean, const mrpt::math::CMatrixDouble77& init_Cov)
Constructor with mean and covariance.
CPose3DQuatPDFGaussian(const CPosePDFGaussian& o)
Constructor from a Gaussian 2D pose PDF (sets to 0 the missing variables).
CPose3DQuatPDFGaussian(const CPose3DPDFGaussian& o)
Constructor from an equivalent Gaussian in Euler angles representation.
Methods
virtual std::tuple<cov_mat_t, type_value> getCovarianceAndMean() const
Returns an estimate of the pose covariance matrix (STATE_LENxSTATE_LEN cov matrix) and the mean, both at once.
See also:
virtual void copyFrom(const CPose3DQuatPDF& o)
Copy operator, translating if necesary (for example, between particles and gaussian representations)
void copyFrom(const CPosePDF& o)
Copy operator, translating if necesary (for example, between particles and gaussian representations)
void copyFrom(const CPose3DPDFGaussian& o)
Copy operator, translating if necesary (for example, between particles and gaussian representations)
virtual bool saveToTextFile(const std::string& file) const
Save the PDF to a text file, containing the 3D pose in the first line (x y z qr qx qy qz), then the covariance matrix in the next 7 lines.
void changeCoordinatesReference(const CPose3DQuat& newReferenceBase)
this = p (+) this.
This can be used to convert a PDF from local coordinates to global, providing the point (newReferenceBase) from which “to project” the current pdf. Result PDF substituted the currently stored one in the object.
virtual void changeCoordinatesReference(const CPose3D& newReferenceBase)
this = p (+) this.
This can be used to convert a PDF from local coordinates to global, providing the point (newReferenceBase) from which “to project” the current pdf. Result PDF substituted the currently stored one in the object.
void drawSingleSample(CPose3DQuat& outPart) const
Draws a single sample from the distribution.
virtual void drawManySamples(size_t N, std::vector<mrpt::math::CVectorDouble>& outSamples) const
Draws a number of samples from the distribution, and saves as a list of 1x7 vectors, where each row contains a (x,y,z,qr,qx,qy,qz) datum.
mrpt::math::CMatrixDouble77 inverseJacobian() const
Compute the inverse Jacobian.
virtual void inverse(CPose3DQuatPDF& o) const
Returns a new PDF such as: NEW_PDF = (0,0,0) - THIS_PDF.
mrpt::poses::CPose3DQuatPDFGaussian inverseCompositionCrossCorrelation(const mrpt::poses::CPose3DQuatPDFGaussian& pose_to) const
Returns the displacement from the current pose (pose_from) to pose_to: displacement = - pose_from + pose_to It assumes that both poses are correlated via the direct generative model: pose_to = pose_from + displacement For a deeper explanation, check https://github.com/MRPT/mrpt/pull/1243.
CPose3DQuatPDFGaussian operator - () const
Unary - operator, returns the PDF of the inverse pose.
void operator += (const CPose3DQuat& Ap)
Makes: thisPDF = thisPDF + Ap, where “+” is pose composition (both the mean, and the covariance matrix are updated).
void operator += (const CPose3DQuatPDFGaussian& Ap)
Makes: thisPDF = thisPDF + Ap, where “+” is pose composition (both the mean, and the covariance matrix are updated) (see formulas in jacobiansPoseComposition ).
void operator -= (const CPose3DQuatPDFGaussian& Ap)
Makes: thisPDF = thisPDF - Ap, where “-” is pose inverse composition (both the mean, and the covariance matrix are updated).
This operation assumes statistical independence between the two variables. If you want to take into account the cross-correlation between pose_1 and pose_2, use: displacement = pose_1.inverseCompositionCrossCorrelation(pose_2) Note: Both poses are correlated if the direct generative model is pose_2 = pose_1 + displacement
See also:
inverseCompositionCrossCorrelation
double evaluatePDF(const CPose3DQuat& x) const
Evaluates the PDF at a given point.
double evaluateNormalizedPDF(const CPose3DQuat& x) const
Evaluates the ratio PDF(x) / PDF(MEAN), that is, the normalized PDF in the range [0,1].
double mahalanobisDistanceTo(const CPose3DQuatPDFGaussian& theOther)
Computes the Mahalanobis distance between the centers of two Gaussians.
The variables with a variance exactly equal to 0 are not taken into account in the process, but “infinity” is returned if the corresponding elements are not exactly equal.