calibration.cc 9.7 KB

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