29 #ifndef HECTOR_DEBUG_INFO_PROVIDER_H__ 30 #define HECTOR_DEBUG_INFO_PROVIDER_H__ 37 #include "hector_mapping/HectorDebugInfo.h" 60 hector_mapping::HectorIterData iterData;
62 for (
int i=0; i < 9; ++i){
63 iterData.hessian[i] =
static_cast<double>(hessian.data()[i]);
64 iterData.determinant = hessian.determinant();
66 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3f> eig(hessian);
68 const Eigen::Vector3f& eigValues (eig.eigenvalues());
69 iterData.conditionNum = eigValues[2] / eigValues[0];
72 iterData.determinant2d = hessian.block<2,2>(0,0).determinant();
73 Eigen::SelfAdjointEigenSolver<Eigen::Matrix2f> eig2d(hessian.block<2,2>(0,0));
75 const Eigen::Vector2f& eigValues2d (eig2d.eigenvalues());
76 iterData.conditionNum2d = eigValues2d[1] / eigValues2d[0];
void publish(const boost::shared_ptr< M > &message) const
virtual void addHessianMatrix(const Eigen::Matrix3f &hessian)
virtual void addPoseLikelihood(float lh)
virtual void sendAndResetData()
hector_mapping::HectorDebugInfo debugInfo
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher debugInfoPublisher_
HectorDebugInfoProvider()