Main MRPT website > C++ reference for MRPT 1.9.9
VelodyneCalibration.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #include "obs-precomp.h" // Precompiled headers
11 
13 #include <mrpt/utils/bits.h>
14 #include <iostream>
15 #include <map>
16 
17 #undef _UNICODE // JLBC, for xmlParser
18 #include "xmlparser/xmlParser.h"
19 
20 // ======= Default calibration files ========================
23 // ======= End of default calibration files =================
24 
25 using namespace std;
26 using namespace mrpt::obs;
27 
28 VelodyneCalibration::PerLaserCalib::PerLaserCalib()
29  : azimuthCorrection(.0),
30  verticalCorrection(.0),
31  distanceCorrection(.0),
32  verticalOffsetCorrection(.0),
33  horizontalOffsetCorrection(.0),
34  sinVertCorrection(.0),
35  cosVertCorrection(1.0),
36  sinVertOffsetCorrection(.0),
37  cosVertOffsetCorrection(1.0)
38 {
39 }
40 
43 {
44  XMLNode& root = *reinterpret_cast<XMLNode*>(node);
45 
46  XMLNode node_bs = root.getChildNode("boost_serialization");
47  if (node_bs.isEmpty())
48  throw std::runtime_error("Cannot find XML node: 'boost_serialization'");
49 
50  XMLNode node_DB = node_bs.getChildNode("DB");
51  if (node_DB.isEmpty())
52  throw std::runtime_error("Cannot find XML node: 'DB'");
53 
54  XMLNode node_enabled_ = node_DB.getChildNode("enabled_");
55  if (node_enabled_.isEmpty())
56  throw std::runtime_error("Cannot find XML node: 'enabled_'");
57 
58  // Clear previous contents:
59  clear();
60 
61  XMLNode node_enabled_count = node_enabled_.getChildNode("count");
62  if (node_enabled_count.isEmpty())
63  throw std::runtime_error("Cannot find XML node: 'enabled_::count'");
64  const int nEnabled = atoi(node_enabled_count.getText());
65  if (nEnabled <= 0 || nEnabled > 10000)
66  throw std::runtime_error(
67  "Senseless value found reading 'enabled_::count'");
68 
69  int enabledCount = 0;
70  for (int i = 0; i < nEnabled; i++)
71  {
72  XMLNode node_enabled_ith = node_enabled_.getChildNode("item", i);
73  if (node_enabled_ith.isEmpty())
74  throw std::runtime_error(
75  "Cannot find the expected number of XML nodes: "
76  "'enabled_::item'");
77  const int enable_val = atoi(node_enabled_ith.getText());
78  if (enable_val) ++enabledCount;
79  }
80 
81  // enabledCount = number of lasers in the LIDAR
82  this->laser_corrections.resize(enabledCount);
83 
84  XMLNode node_points_ = node_DB.getChildNode("points_");
85  if (node_points_.isEmpty())
86  throw std::runtime_error("Cannot find XML node: 'points_'");
87 
88  for (int i = 0;; ++i)
89  {
90  XMLNode node_points_item = node_points_.getChildNode("item", i);
91  if (node_points_item.isEmpty()) break;
92 
93  XMLNode node_px = node_points_item.getChildNode("px");
94  if (node_px.isEmpty())
95  throw std::runtime_error(
96  "Cannot find XML node: 'points_::item::px'");
97 
98  XMLNode node_px_id = node_px.getChildNode("id_");
99  if (node_px_id.isEmpty())
100  throw std::runtime_error(
101  "Cannot find XML node: 'points_::item::px::id_'");
102  const int id = atoi(node_px_id.getText());
103  ASSERT_ABOVEEQ_(id, 0);
104  if (id >= enabledCount) continue; // ignore
105 
107 
108  {
109  XMLNode node = node_px.getChildNode("rotCorrection_");
110  if (node.isEmpty())
111  throw std::runtime_error(
112  "Cannot find XML node: "
113  "'points_::item::px::rotCorrection_'");
114  plc->azimuthCorrection = atof(node.getText());
115  }
116  {
117  XMLNode node = node_px.getChildNode("vertCorrection_");
118  if (node.isEmpty())
119  throw std::runtime_error(
120  "Cannot find XML node: "
121  "'points_::item::px::vertCorrection_'");
122  plc->verticalCorrection = atof(node.getText());
123  }
124  {
125  XMLNode node = node_px.getChildNode("distCorrection_");
126  if (node.isEmpty())
127  throw std::runtime_error(
128  "Cannot find XML node: "
129  "'points_::item::px::distCorrection_'");
130  plc->distanceCorrection = 0.01f * atof(node.getText());
131  }
132  {
133  XMLNode node = node_px.getChildNode("vertOffsetCorrection_");
134  if (node.isEmpty())
135  throw std::runtime_error(
136  "Cannot find XML node: "
137  "'points_::item::px::vertOffsetCorrection_'");
138  plc->verticalOffsetCorrection = 0.01f * atof(node.getText());
139  }
140  {
141  XMLNode node = node_px.getChildNode("horizOffsetCorrection_");
142  if (node.isEmpty())
143  throw std::runtime_error(
144  "Cannot find XML node: "
145  "'points_::item::px::horizOffsetCorrection_'");
146  plc->horizontalOffsetCorrection = 0.01f * atof(node.getText());
147  }
148 
149  plc->sinVertCorrection =
151  plc->cosVertCorrection =
153 
158  }
159 
160  return true; // Ok
161 }
162 
163 bool VelodyneCalibration::loadFromXMLText(const std::string& xml_file_contents)
164 {
165  try
166  {
167  XMLResults results;
168  XMLNode root =
169  XMLNode::parseString(xml_file_contents.c_str(), nullptr, &results);
170 
171  if (results.error != eXMLErrorNone)
172  {
173  cerr << "[VelodyneCalibration::loadFromXMLText] Error parsing XML "
174  "content: "
175  << XMLNode::getError(results.error) << " at line "
176  << results.nLine << ":" << results.nColumn << endl;
177  return false;
178  }
179 
180  return internal_loadFromXMLNode(reinterpret_cast<void*>(&root));
181  }
182  catch (exception& e)
183  {
184  cerr << "[VelodyneCalibration::loadFromXMLFile] Exception:" << endl
185  << e.what() << endl;
186  return false;
187  }
188 }
189 
190 /** Loads calibration from file. \return false on any error, true on success */
191 // See reference code in:
192 // vtkVelodyneHDLReader::vtkInternal::LoadCorrectionsFile()
194  const std::string& velodyne_calibration_xml_filename)
195 {
196  try
197  {
198  XMLResults results;
200  velodyne_calibration_xml_filename.c_str(), nullptr, &results);
201 
202  if (results.error != eXMLErrorNone)
203  {
204  cerr << "[VelodyneCalibration::loadFromXMLFile] Error loading XML "
205  "file: "
206  << XMLNode::getError(results.error) << " at line "
207  << results.nLine << ":" << results.nColumn << endl;
208  return false;
209  }
210  return internal_loadFromXMLNode(reinterpret_cast<void*>(&root));
211  }
212  catch (exception& e)
213  {
214  cerr << "[VelodyneCalibration::loadFromXMLFile] Exception:" << endl
215  << e.what() << endl;
216  return false;
217  }
218 }
219 
220 bool VelodyneCalibration::empty() const { return laser_corrections.empty(); }
222 std::map<std::string, VelodyneCalibration> cache_default_calibs;
223 
224 // It always return a calibration structure, but it may be empty if the model
225 // name is unknown.
227  const std::string& lidar_model)
228 {
229  // Cached calib data?
231  cache_default_calibs.find(lidar_model);
232  if (it != cache_default_calibs.end()) return it->second;
233 
234  VelodyneCalibration result; // Leave empty to indicate unknown model
235  std::string xml_contents;
236 
237  if (lidar_model == "VLP16")
238  xml_contents = velodyne_default_calib_VLP16;
239  else if (lidar_model == "HDL32")
240  xml_contents = velodyne_default_calib_HDL32;
241  else
242  {
243  }
244 
245  if (!xml_contents.empty())
246  {
247  if (!result.loadFromXMLText(xml_contents))
248  std::cerr << "[VelodyneCalibration::LoadDefaultCalibration] Error "
249  "parsing default XML calibration file for model '"
250  << lidar_model << "'\n";
251  }
252 
253  cache_default_calibs[lidar_model] = result;
254  return cache_default_calibs[lidar_model];
255 }
Velodyne calibration data, for usage in mrpt::obs::CObservationVelodyneScan.
const char * velodyne_default_calib_HDL32
bool loadFromXMLFile(const std::string &velodyne_calibration_xml_filename)
Loads calibration from file, in the format supplied by the manufacturer.
bool loadFromXMLText(const std::string &xml_file_contents)
Loads calibration from a string containing an entire XML calibration file.
double DEG2RAD(const double x)
Degrees to radians.
Main Class representing a XML node.
Definition: xmlParser.h:314
int nColumn
Definition: xmlParser.h:278
VelodyneCalibration()
Default ctor (leaves all empty)
static XMLNode parseString(XMLCSTR lpXMLString, XMLCSTR tag=nullptr, XMLResults *pResults=nullptr)
Parse an XML string and return the root of a XMLNode tree representing the string.
Definition: xmlParser.cpp:2216
void clear()
Clear all previous contents.
char isEmpty() const
is this node Empty?
Definition: xmlParser.cpp:3417
STL namespace.
const Scalar * const_iterator
Definition: eigen_plugins.h:27
static XMLCSTR getError(XMLError error)
this gives you a
Definition: xmlParser.cpp:83
XMLCSTR getText(int i=0) const
return ith text field
Definition: xmlParser.cpp:3397
std::vector< PerLaserCalib > laser_corrections
This namespace contains representation of robot actions and observations.
GLsizei const GLchar ** string
Definition: glext.h:4101
std::map< std::string, VelodyneCalibration > cache_default_calibs
static XMLNode parseFile(XMLCSTR filename, XMLCSTR tag=nullptr, XMLResults *pResults=nullptr)
Parse an XML file and return the root of a XMLNode tree representing the file.
Definition: xmlParser.cpp:2283
#define ASSERT_ABOVEEQ_(__A, __B)
bool empty() const
Returns true if no calibration has been loaded yet.
GLuint id
Definition: glext.h:3909
enum XMLError error
Definition: xmlParser.h:277
const char * velodyne_default_calib_VLP16
static const VelodyneCalibration & LoadDefaultCalibration(const std::string &lidar_model)
Loads default calibration files for common LIDAR models.
Structure used to obtain error details if the parse fails.
Definition: xmlParser.h:275
XMLNode getChildNode(int i=0) const
return ith child node
Definition: xmlParser.cpp:3402



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019