diff --git a/src/rviz/default_plugin/covariance_visual.cpp b/src/rviz/default_plugin/covariance_visual.cpp index 5f1c2993e3..5a93229dbf 100644 --- a/src/rviz/default_plugin/covariance_visual.cpp +++ b/src/rviz/default_plugin/covariance_visual.cpp @@ -350,12 +350,18 @@ void CovarianceVisual::setCovariance(const geometry_msgs::PoseWithCovariance& po // Map covariance to a Eigen::Matrix Eigen::Map > covariance(pose.covariance.data()); + Eigen::Quaterniond qori(ori.w,ori.x,ori.y,ori.z); + Eigen::Matrix3d rotmat = qori.toRotationMatrix(); + Eigen::Matrix6d covarianceRotated = covariance; + covarianceRotated.bottomRightCorner(3,3) = rotmat.transpose()*covariance.bottomRightCorner(3,3)*rotmat; + + updatePosition(covariance); if (!pose_2d_) { - updateOrientation(covariance, kRoll); - updateOrientation(covariance, kPitch); - updateOrientation(covariance, kYaw); + updateOrientation(covarianceRotated, kRoll); + updateOrientation(covarianceRotated, kPitch); + updateOrientation(covarianceRotated, kYaw); } else {