Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029 #ifndef HECTOR_DEBUG_INFO_PROVIDER_H__
00030 #define HECTOR_DEBUG_INFO_PROVIDER_H__
00031
00032 #include "util/HectorDebugInfoInterface.h"
00033 #include "util/UtilFunctions.h"
00034
00035 #include "ros/ros.h"
00036
00037 #include "hector_mapping/HectorDebugInfo.h"
00038
00039
00040 class HectorDebugInfoProvider : public HectorDebugInfoInterface
00041 {
00042 public:
00043
00044 HectorDebugInfoProvider()
00045 {
00046 ros::NodeHandle nh_;
00047
00048 debugInfoPublisher_ = nh_.advertise<hector_mapping::HectorDebugInfo>("hector_debug_info", 50, true);
00049 };
00050
00051 virtual void sendAndResetData()
00052 {
00053 debugInfoPublisher_.publish(debugInfo);
00054 debugInfo.iterData.clear();
00055 }
00056
00057
00058 virtual void addHessianMatrix(const Eigen::Matrix3f& hessian)
00059 {
00060 hector_mapping::HectorIterData iterData;
00061
00062 for (int i=0; i < 9; ++i){
00063 iterData.hessian[i] = static_cast<double>(hessian.data()[i]);
00064 iterData.determinant = hessian.determinant();
00065
00066 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3f> eig(hessian);
00067
00068 const Eigen::Vector3f& eigValues (eig.eigenvalues());
00069 iterData.conditionNum = eigValues[2] / eigValues[0];
00070
00071
00072 iterData.determinant2d = hessian.block<2,2>(0,0).determinant();
00073 Eigen::SelfAdjointEigenSolver<Eigen::Matrix2f> eig2d(hessian.block<2,2>(0,0));
00074
00075 const Eigen::Vector2f& eigValues2d (eig2d.eigenvalues());
00076 iterData.conditionNum2d = eigValues2d[1] / eigValues2d[0];
00077 }
00078
00079 debugInfo.iterData.push_back(iterData);
00080 }
00081
00082 virtual void addPoseLikelihood(float lh)
00083 {
00084
00085 }
00086
00087
00088 hector_mapping::HectorDebugInfo debugInfo;
00089
00090 ros::Publisher debugInfoPublisher_;
00091
00092 };
00093
00094 #endif