diff --git a/src/TransformWithCovariance.cpp b/src/TransformWithCovariance.cpp index caa95313..07a777b4 100644 --- a/src/TransformWithCovariance.cpp +++ b/src/TransformWithCovariance.cpp @@ -131,6 +131,19 @@ TransformWithCovariance TransformWithCovariance::operator*(const TransformWithCo return TransformWithCovariance(p, t, cov); } +std::pair TransformWithCovariance::composePointWithCovariance(const Eigen::Vector3d& point, const Eigen::Matrix3d& cov) const +{ + Eigen::Matrix3d R( getTransform().linear() ); + Eigen::Quaterniond q( R ); + Eigen::Matrix J; + J << Eigen::Matrix3d::Identity(), drx_by_dr( q, point ); + + Eigen::Matrix3d tr_point_cov = J*getCovariance()*J.transpose(); + tr_point_cov += R*cov*R.transpose(); + + return std::make_pair(getTransform() * point, tr_point_cov); +} + TransformWithCovariance TransformWithCovariance::inverse() const { // short path if there is no uncertainty diff --git a/src/TransformWithCovariance.hpp b/src/TransformWithCovariance.hpp index 6d99f80c..579fd882 100644 --- a/src/TransformWithCovariance.hpp +++ b/src/TransformWithCovariance.hpp @@ -98,6 +98,11 @@ namespace base { /** alias for the composition of two transforms */ TransformWithCovariance operator*( const TransformWithCovariance& trans ) const; + + /** performs a composition of this transform with a given point with covariance. + */ + std::pair + composePointWithCovariance( const Eigen::Vector3d& point, const Eigen::Matrix3d& cov ) const; TransformWithCovariance inverse() const;