calibration.cc
Go to the documentation of this file.
1 
14 #include <iostream>
15 #include <fstream>
16 #include <string>
17 #include <cmath>
18 #include <limits>
19 #include <yaml-cpp/yaml.h>
20 
21 #ifdef HAVE_NEW_YAMLCPP
22 namespace YAML {
23 
24  // The >> operator disappeared in yaml-cpp 0.5, so this function is
25  // added to provide support for code written under the yaml-cpp 0.3 API.
26  template<typename T>
27  void operator >> (const YAML::Node& node, T& i) {
28  i = node.as<T>();
29  }
30 } /* YAML */
31 #endif // HAVE_NEW_YAMLCPP
32 
33 #include <ros/ros.h>
35 
36 namespace velodyne_pointcloud
37 {
38 
39  const std::string NUM_LASERS = "num_lasers";
40  const std::string DISTANCE_RESOLUTION = "distance_resolution";
41  const std::string LASERS = "lasers";
42  const std::string LASER_ID = "laser_id";
43  const std::string ROT_CORRECTION = "rot_correction";
44  const std::string VERT_CORRECTION = "vert_correction";
45  const std::string DIST_CORRECTION = "dist_correction";
46  const std::string TWO_PT_CORRECTION_AVAILABLE =
47  "two_pt_correction_available";
48  const std::string DIST_CORRECTION_X = "dist_correction_x";
49  const std::string DIST_CORRECTION_Y = "dist_correction_y";
50  const std::string VERT_OFFSET_CORRECTION = "vert_offset_correction";
51  const std::string HORIZ_OFFSET_CORRECTION = "horiz_offset_correction";
52  const std::string MAX_INTENSITY = "max_intensity";
53  const std::string MIN_INTENSITY = "min_intensity";
54  const std::string FOCAL_DISTANCE = "focal_distance";
55  const std::string FOCAL_SLOPE = "focal_slope";
56 
58  void operator >> (const YAML::Node& node,
59  std::pair<int, LaserCorrection>& correction)
60  {
61  node[LASER_ID] >> correction.first;
62  node[ROT_CORRECTION] >> correction.second.rot_correction;
63  node[VERT_CORRECTION] >> correction.second.vert_correction;
64  node[DIST_CORRECTION] >> correction.second.dist_correction;
65 #ifdef HAVE_NEW_YAMLCPP
66  if (node[TWO_PT_CORRECTION_AVAILABLE])
68  correction.second.two_pt_correction_available;
69 #else
70  if (const YAML::Node *pName = node.FindValue(TWO_PT_CORRECTION_AVAILABLE))
71  *pName >> correction.second.two_pt_correction_available;
72 #endif
73  else
74  correction.second.two_pt_correction_available = false;
75  node[DIST_CORRECTION_X] >> correction.second.dist_correction_x;
76  node[DIST_CORRECTION_Y] >> correction.second.dist_correction_y;
77  node[VERT_OFFSET_CORRECTION] >> correction.second.vert_offset_correction;
78 #ifdef HAVE_NEW_YAMLCPP
79  if (node[HORIZ_OFFSET_CORRECTION])
81  correction.second.horiz_offset_correction;
82 #else
83  if (const YAML::Node *pName = node.FindValue(HORIZ_OFFSET_CORRECTION))
84  *pName >> correction.second.horiz_offset_correction;
85 #endif
86  else
87  correction.second.horiz_offset_correction = 0;
88 
89  const YAML::Node * max_intensity_node = NULL;
90 #ifdef HAVE_NEW_YAMLCPP
91  if (node[MAX_INTENSITY]) {
92  const YAML::Node max_intensity_node_ref = node[MAX_INTENSITY];
93  max_intensity_node = &max_intensity_node_ref;
94  }
95 #else
96  if (const YAML::Node *pName = node.FindValue(MAX_INTENSITY))
97  max_intensity_node = pName;
98 #endif
99  if (max_intensity_node) {
100  float max_intensity_float;
101  *max_intensity_node >> max_intensity_float;
102  correction.second.max_intensity = floor(max_intensity_float);
103  }
104  else {
105  correction.second.max_intensity = 255;
106  }
107 
108  const YAML::Node * min_intensity_node = NULL;
109 #ifdef HAVE_NEW_YAMLCPP
110  if (node[MIN_INTENSITY]) {
111  const YAML::Node min_intensity_node_ref = node[MIN_INTENSITY];
112  min_intensity_node = &min_intensity_node_ref;
113  }
114 #else
115  if (const YAML::Node *pName = node.FindValue(MIN_INTENSITY))
116  min_intensity_node = pName;
117 #endif
118  if (min_intensity_node) {
119  float min_intensity_float;
120  *min_intensity_node >> min_intensity_float;
121  correction.second.min_intensity = floor(min_intensity_float);
122  }
123  else {
124  correction.second.min_intensity = 0;
125  }
126  node[FOCAL_DISTANCE] >> correction.second.focal_distance;
127  node[FOCAL_SLOPE] >> correction.second.focal_slope;
128 
129  // Calculate cached values
130  correction.second.cos_rot_correction =
131  cosf(correction.second.rot_correction);
132  correction.second.sin_rot_correction =
133  sinf(correction.second.rot_correction);
134  correction.second.cos_vert_correction =
135  cosf(correction.second.vert_correction);
136  correction.second.sin_vert_correction =
137  sinf(correction.second.vert_correction);
138 
139  correction.second.laser_ring = 0; // clear initially (set later)
140  }
141 
143  void operator >> (const YAML::Node& node, Calibration& calibration)
144  {
145  int num_lasers;
146  node[NUM_LASERS] >> num_lasers;
147  float distance_resolution_m;
148  node[DISTANCE_RESOLUTION] >> distance_resolution_m;
149  const YAML::Node& lasers = node[LASERS];
150  calibration.laser_corrections.clear();
151  calibration.num_lasers = num_lasers;
152  calibration.distance_resolution_m = distance_resolution_m;
153  calibration.laser_corrections.resize(num_lasers);
154  for (int i = 0; i < num_lasers; i++) {
155  std::pair<int, LaserCorrection> correction;
156  lasers[i] >> correction;
157  const int index = correction.first;
158  if( index >= calibration.laser_corrections.size() )
159  {
160  calibration.laser_corrections.resize( index+1 );
161  }
162  calibration.laser_corrections[index] = (correction.second);
163  calibration.laser_corrections_map.insert(correction);
164  }
165 
166  // For each laser ring, find the next-smallest vertical angle.
167  //
168  // This implementation is simple, but not efficient. That is OK,
169  // since it only runs while starting up.
170  double next_angle = -std::numeric_limits<double>::infinity();
171  for (int ring = 0; ring < num_lasers; ++ring) {
172 
173  // find minimum remaining vertical offset correction
174  double min_seen = std::numeric_limits<double>::infinity();
175  int next_index = num_lasers;
176  for (int j = 0; j < num_lasers; ++j) {
177 
178  double angle = calibration.laser_corrections[j].vert_correction;
179  if (next_angle < angle && angle < min_seen) {
180  min_seen = angle;
181  next_index = j;
182  }
183  }
184 
185  if (next_index < num_lasers) { // anything found in this ring?
186 
187  // store this ring number with its corresponding laser number
188  calibration.laser_corrections[next_index].laser_ring = ring;
189  next_angle = min_seen;
190  if (calibration.ros_info) {
191  ROS_INFO("laser_ring[%2u] = %2u, angle = %+.6f",
192  next_index, ring, next_angle);
193  }
194  }
195  }
196  }
197 
198  YAML::Emitter& operator << (YAML::Emitter& out,
199  const std::pair<int, LaserCorrection> correction)
200  {
201  out << YAML::BeginMap;
202  out << YAML::Key << LASER_ID << YAML::Value << correction.first;
203  out << YAML::Key << ROT_CORRECTION <<
204  YAML::Value << correction.second.rot_correction;
205  out << YAML::Key << VERT_CORRECTION <<
206  YAML::Value << correction.second.vert_correction;
207  out << YAML::Key << DIST_CORRECTION <<
208  YAML::Value << correction.second.dist_correction;
209  out << YAML::Key << TWO_PT_CORRECTION_AVAILABLE <<
210  YAML::Value << correction.second.two_pt_correction_available;
211  out << YAML::Key << DIST_CORRECTION_X <<
212  YAML::Value << correction.second.dist_correction_x;
213  out << YAML::Key << DIST_CORRECTION_Y <<
214  YAML::Value << correction.second.dist_correction_y;
215  out << YAML::Key << VERT_OFFSET_CORRECTION <<
216  YAML::Value << correction.second.vert_offset_correction;
217  out << YAML::Key << HORIZ_OFFSET_CORRECTION <<
218  YAML::Value << correction.second.horiz_offset_correction;
219  out << YAML::Key << MAX_INTENSITY <<
220  YAML::Value << correction.second.max_intensity;
221  out << YAML::Key << MIN_INTENSITY <<
222  YAML::Value << correction.second.min_intensity;
223  out << YAML::Key << FOCAL_DISTANCE <<
224  YAML::Value << correction.second.focal_distance;
225  out << YAML::Key << FOCAL_SLOPE <<
226  YAML::Value << correction.second.focal_slope;
227  out << YAML::EndMap;
228  return out;
229  }
230 
231  YAML::Emitter& operator <<
232  (YAML::Emitter& out, const Calibration& calibration)
233  {
234  out << YAML::BeginMap;
235  out << YAML::Key << NUM_LASERS <<
236  YAML::Value << calibration.laser_corrections.size();
237  out << YAML::Key << DISTANCE_RESOLUTION <<
238  YAML::Value << calibration.distance_resolution_m;
239  out << YAML::Key << LASERS << YAML::Value << YAML::BeginSeq;
240  for (std::map<int, LaserCorrection>::const_iterator
241  it = calibration.laser_corrections_map.begin();
242  it != calibration.laser_corrections_map.end(); it++)
243  {
244  out << *it;
245  }
246  out << YAML::EndSeq;
247  out << YAML::EndMap;
248  return out;
249  }
250 
251  void Calibration::read(const std::string& calibration_file) {
252  std::ifstream fin(calibration_file.c_str());
253  if (!fin.is_open()) {
254  initialized = false;
255  return;
256  }
257  initialized = true;
258  try {
259  YAML::Node doc;
260 #ifdef HAVE_NEW_YAMLCPP
261  fin.close();
262  doc = YAML::LoadFile(calibration_file);
263 #else
264  YAML::Parser parser(fin);
265  parser.GetNextDocument(doc);
266 #endif
267  doc >> *this;
268  } catch (YAML::Exception &e) {
269  std::cerr << "YAML Exception: " << e.what() << std::endl;
270  initialized = false;
271  }
272  fin.close();
273  }
274 
275  void Calibration::write(const std::string& calibration_file) {
276  std::ofstream fout(calibration_file.c_str());
277  YAML::Emitter out;
278  out << *this;
279  fout << out.c_str();
280  fout.close();
281  }
282 
283 } /* velodyne_pointcloud */
const std::string ROT_CORRECTION
Definition: calibration.cc:43
const std::string VERT_CORRECTION
Definition: calibration.cc:44
const std::string MAX_INTENSITY
Definition: calibration.cc:52
const std::string VERT_OFFSET_CORRECTION
Definition: calibration.cc:50
YAML::Emitter & operator<<(YAML::Emitter &out, const Calibration &calibration)
Definition: calibration.cc:232
void operator>>(const YAML::Node &node, Calibration &calibration)
Definition: calibration.cc:143
const std::string DIST_CORRECTION_Y
Definition: calibration.cc:49
const std::string DIST_CORRECTION
Definition: calibration.cc:45
Calibration information for the entire device.
Definition: calibration.h:78
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
std::vector< LaserCorrection > laser_corrections
Definition: calibration.h:83
#define ROS_INFO(...)
const std::string DIST_CORRECTION_X
Definition: calibration.cc:48
const std::string LASERS
Definition: calibration.cc:41
const std::string FOCAL_SLOPE
Definition: calibration.cc:55
const std::string HORIZ_OFFSET_CORRECTION
Definition: calibration.cc:51
std::map< int, LaserCorrection > laser_corrections_map
Definition: calibration.h:82
const std::string LASER_ID
Definition: calibration.cc:42
const std::string DISTANCE_RESOLUTION
Definition: calibration.cc:40
const std::string TWO_PT_CORRECTION_AVAILABLE
Definition: calibration.cc:46
parser
const std::string FOCAL_DISTANCE
Definition: calibration.cc:54
dictionary calibration
const std::string MIN_INTENSITY
Definition: calibration.cc:53
const std::string NUM_LASERS
Definition: calibration.cc:39


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Sun Sep 6 2020 03:25:30