HectorDebugInfoProvider.h
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2011, Stefan Kohlbrecher, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Simulation, Systems Optimization and Robotics
13 // group, TU Darmstadt nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
29 #ifndef HECTOR_DEBUG_INFO_PROVIDER_H__
30 #define HECTOR_DEBUG_INFO_PROVIDER_H__
31 
33 #include "util/UtilFunctions.h"
34 
35 #include "ros/ros.h"
36 
37 #include "hector_mapping/HectorDebugInfo.h"
38 
39 
41 {
42 public:
43 
45  {
46  ros::NodeHandle nh_;
47 
48  debugInfoPublisher_ = nh_.advertise<hector_mapping::HectorDebugInfo>("hector_debug_info", 50, true);
49  };
50 
51  virtual void sendAndResetData()
52  {
54  debugInfo.iterData.clear();
55  }
56 
57 
58  virtual void addHessianMatrix(const Eigen::Matrix3f& hessian)
59  {
60  hector_mapping::HectorIterData iterData;
61 
62  for (int i=0; i < 9; ++i){
63  iterData.hessian[i] = static_cast<double>(hessian.data()[i]);
64  iterData.determinant = hessian.determinant();
65 
66  Eigen::SelfAdjointEigenSolver<Eigen::Matrix3f> eig(hessian);
67 
68  const Eigen::Vector3f& eigValues (eig.eigenvalues());
69  iterData.conditionNum = eigValues[2] / eigValues[0];
70 
71 
72  iterData.determinant2d = hessian.block<2,2>(0,0).determinant();
73  Eigen::SelfAdjointEigenSolver<Eigen::Matrix2f> eig2d(hessian.block<2,2>(0,0));
74 
75  const Eigen::Vector2f& eigValues2d (eig2d.eigenvalues());
76  iterData.conditionNum2d = eigValues2d[1] / eigValues2d[0];
77  }
78 
79  debugInfo.iterData.push_back(iterData);
80  }
81 
82  virtual void addPoseLikelihood(float lh)
83  {
84 
85  }
86 
87 
88  hector_mapping::HectorDebugInfo debugInfo;
89 
91 
92 };
93 
94 #endif
void publish(const boost::shared_ptr< M > &message) const
virtual void addHessianMatrix(const Eigen::Matrix3f &hessian)
virtual void addPoseLikelihood(float lh)
hector_mapping::HectorDebugInfo debugInfo
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)


hector_mapping
Author(s): Stefan Kohlbrecher
autogenerated on Sun Nov 3 2019 03:18:33