35 #include <OgreSceneManager.h> 
   36 #include <OgreSceneNode.h> 
   37 #include <OgreQuaternion.h> 
   47 double deg2rad(
double degrees)
 
   49   return degrees * 4.0 * atan(1.0) / 180.0;
 
   53 void makeRightHanded(Eigen::Matrix3d& eigenvectors, Eigen::Vector3d& eigenvalues)
 
   57   Eigen::Vector3d c0 = eigenvectors.col(0);
 
   59   Eigen::Vector3d c1 = eigenvectors.col(1);
 
   61   Eigen::Vector3d c2 = eigenvectors.col(2);
 
   63   Eigen::Vector3d cc = c0.cross(c1);
 
   66     eigenvectors << c1, c0, c2;
 
   67     std::swap(eigenvalues[0], eigenvalues[1]);
 
   71     eigenvectors << c0, c1, c2;
 
   76 void makeRightHanded(Eigen::Matrix2d& eigenvectors, Eigen::Vector2d& eigenvalues)
 
   82   c0.head<2>() = eigenvectors.col(0);
 
   86   c1.head<2>() = eigenvectors.col(1);
 
   88   Eigen::Vector3d cc = c0.cross(c1);
 
   91     eigenvectors << c1.head<2>(), c0.head<2>();
 
   92     std::swap(eigenvalues[0], eigenvalues[1]);
 
   96     eigenvectors << c0.head<2>(), c1.head<2>();
 
  100 void computeShapeScaleAndOrientation3D(
const Eigen::Matrix3d& covariance,
 
  101                                        Ogre::Vector3& scale,
 
  102                                        Ogre::Quaternion& orientation)
 
  104   Eigen::Vector3d eigenvalues(Eigen::Vector3d::Identity());
 
  105   Eigen::Matrix3d eigenvectors(Eigen::Matrix3d::Zero());
 
  109   Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> eigensolver(covariance);
 
  111   if (eigensolver.info() == Eigen::Success)
 
  113     eigenvalues = eigensolver.eigenvalues();
 
  114     eigenvectors = eigensolver.eigenvectors();
 
  119         1, 
"failed to compute eigen vectors/values for position. Is the covariance matrix correct?");
 
  120     eigenvalues = Eigen::Vector3d::Zero(); 
 
  121     eigenvectors = Eigen::Matrix3d::Identity();
 
  125   makeRightHanded(eigenvectors, eigenvalues);
 
  128   orientation.FromRotationMatrix(Ogre::Matrix3( 
 
  129       eigenvectors(0, 0), eigenvectors(0, 1), eigenvectors(0, 2),
 
  130       eigenvectors(1, 0), eigenvectors(1, 1), eigenvectors(1, 2),
 
  131       eigenvectors(2, 0), eigenvectors(2, 1), eigenvectors(2, 2))); 
 
  134   scale.x = 2 * std::sqrt(eigenvalues[0]);
 
  135   scale.y = 2 * std::sqrt(eigenvalues[1]);
 
  136   scale.z = 2 * std::sqrt(eigenvalues[2]);
 
  146 void computeShapeScaleAndOrientation2D(
const Eigen::Matrix2d& covariance,
 
  147                                        Ogre::Vector3& scale,
 
  148                                        Ogre::Quaternion& orientation,
 
  149                                        Plane plane = XY_PLANE)
 
  151   Eigen::Vector2d eigenvalues(Eigen::Vector2d::Identity());
 
  152   Eigen::Matrix2d eigenvectors(Eigen::Matrix2d::Zero());
 
  156   Eigen::SelfAdjointEigenSolver<Eigen::Matrix2d> eigensolver(covariance);
 
  158   if (eigensolver.info() == Eigen::Success)
 
  160     eigenvalues = eigensolver.eigenvalues();
 
  161     eigenvectors = eigensolver.eigenvectors();
 
  166         1, 
"failed to compute eigen vectors/values for position. Is the covariance matrix correct?");
 
  167     eigenvalues = Eigen::Vector2d::Zero(); 
 
  168     eigenvectors = Eigen::Matrix2d::Identity();
 
  172   makeRightHanded(eigenvectors, eigenvalues);
 
  177   if (plane == YZ_PLANE)
 
  179     orientation.FromRotationMatrix(Ogre::Matrix3(1, 0, 0, 
 
  180                                                  0, eigenvectors(0, 0), eigenvectors(0, 1),
 
  181                                                  0, eigenvectors(1, 0), eigenvectors(1, 1))); 
 
  184     scale.y = 2 * std::sqrt(eigenvalues[0]);
 
  185     scale.z = 2 * std::sqrt(eigenvalues[1]);
 
  187   else if (plane == XZ_PLANE)
 
  189     orientation.FromRotationMatrix(
 
  190         Ogre::Matrix3(eigenvectors(0, 0), 0, eigenvectors(0, 1), 
 
  192                       eigenvectors(1, 0), 0, eigenvectors(1, 1))); 
 
  194     scale.x = 2 * std::sqrt(eigenvalues[0]);
 
  196     scale.z = 2 * std::sqrt(eigenvalues[1]);
 
  200     orientation.FromRotationMatrix(
 
  201         Ogre::Matrix3(eigenvectors(0, 0), eigenvectors(0, 1), 0, 
 
  202                       eigenvectors(1, 0), eigenvectors(1, 1), 0,
 
  205     scale.x = 2 * std::sqrt(eigenvalues[0]);
 
  206     scale.y = 2 * std::sqrt(eigenvalues[1]);
 
  211 void radianScaleToMetricScaleBounded(Ogre::Real& radian_scale, 
float max_degrees)
 
  214   if (radian_scale > deg2rad(max_degrees))
 
  215     radian_scale = deg2rad(max_degrees);
 
  216   radian_scale = 2.0 * tan(radian_scale);
 
  225                                    Ogre::SceneNode* parent_node,
 
  226                                    bool is_local_rotation,
 
  232   , local_rotation_(is_local_rotation)
 
  234   , orientation_visible_(is_visible)
 
  237   root_node_ = parent_node->createChildSceneNode();
 
  278       Ogre::Quaternion(Ogre::Degree(90), Ogre::Vector3::UNIT_X) *
 
  279       Ogre::Quaternion(Ogre::Degree(90), Ogre::Vector3::UNIT_Z));
 
  283       Ogre::Quaternion(Ogre::Degree(90), Ogre::Vector3::UNIT_Y));
 
  287       Ogre::Quaternion(Ogre::Degree(90), Ogre::Vector3::UNIT_X));
 
  297   static const double cone_origin_to_top = 0.49115;
 
  300       Ogre::Quaternion(Ogre::Degree(90), Ogre::Vector3::UNIT_Z));
 
  329   for (
unsigned i = 0; i < 3; ++i)
 
  331     if (std::isnan(pose.covariance[i]))
 
  338   pose_2d_ = pose.covariance[14] <= 0 && pose.covariance[21] <= 0 && pose.covariance[28] <= 0;
 
  343   Ogre::Quaternion ori;
 
  351   Eigen::Map<const Eigen::Matrix<double, 6, 6> > covariance(pose.covariance.data());
 
  369   Ogre::Vector3 shape_scale;
 
  370   Ogre::Quaternion shape_orientation;
 
  373     computeShapeScaleAndOrientation2D(covariance.topLeftCorner<2, 2>(), shape_scale, shape_orientation,
 
  376     shape_scale.z = 0.001;
 
  380     computeShapeScaleAndOrientation3D(covariance.topLeftCorner<3, 3>(), shape_scale, shape_orientation);
 
  384   if (!shape_scale.isNaN())
 
  392   Ogre::Vector3 shape_scale;
 
  393   Ogre::Quaternion shape_orientation;
 
  400     shape_scale.x = 2.0 * sqrt(covariance(5, 5));
 
  404     shape_scale.z = 0.001;
 
  412     radianScaleToMetricScaleBounded(shape_scale.x, 
max_degrees);
 
  419     Eigen::Matrix2d covarianceAxis;
 
  422       covarianceAxis = covariance.bottomRightCorner<2, 2>();
 
  426       covarianceAxis << covariance(3, 3), covariance(3, 5), covariance(5, 3), covariance(5, 5);
 
  428     else if (index == 
kYaw)
 
  430       covarianceAxis = covariance.block<2, 2>(3, 3);
 
  434     computeShapeScaleAndOrientation2D(covarianceAxis, shape_scale, shape_orientation, XZ_PLANE);
 
  436     shape_scale.y = 0.001;
 
  445     radianScaleToMetricScaleBounded(shape_scale.x, 
max_degrees);
 
  446     radianScaleToMetricScaleBounded(shape_scale.z, 
max_degrees);
 
  451   if (!shape_scale.isNaN())
 
  454     ROS_WARN_STREAM(
"orientation shape_scale contains NaN: " << shape_scale);
 
  511       radianScaleToMetricScaleBounded(shape_scale.x, 
max_degrees);
 
  520       radianScaleToMetricScaleBounded(shape_scale.x, 
max_degrees);
 
  521       radianScaleToMetricScaleBounded(shape_scale.z, 
max_degrees);