Go to the documentation of this file.00001
00014 #include <iostream>
00015 #include <fstream>
00016 #include <string>
00017 #include <cmath>
00018 #include <limits>
00019 #include <yaml-cpp/yaml.h>
00020
00021 #ifdef HAVE_NEW_YAMLCPP
00022 namespace YAML {
00023
00024
00025
00026 template<typename T>
00027 void operator >> (const YAML::Node& node, T& i) {
00028 i = node.as<T>();
00029 }
00030 }
00031 #endif // HAVE_NEW_YAMLCPP
00032
00033 #include <ros/ros.h>
00034 #include <velodyne_pointcloud/calibration.h>
00035
00036 namespace velodyne_pointcloud
00037 {
00038
00039 const std::string NUM_LASERS = "num_lasers";
00040 const std::string DISTANCE_RESOLUTION = "distance_resolution";
00041 const std::string LASERS = "lasers";
00042 const std::string LASER_ID = "laser_id";
00043 const std::string ROT_CORRECTION = "rot_correction";
00044 const std::string VERT_CORRECTION = "vert_correction";
00045 const std::string DIST_CORRECTION = "dist_correction";
00046 const std::string TWO_PT_CORRECTION_AVAILABLE =
00047 "two_pt_correction_available";
00048 const std::string DIST_CORRECTION_X = "dist_correction_x";
00049 const std::string DIST_CORRECTION_Y = "dist_correction_y";
00050 const std::string VERT_OFFSET_CORRECTION = "vert_offset_correction";
00051 const std::string HORIZ_OFFSET_CORRECTION = "horiz_offset_correction";
00052 const std::string MAX_INTENSITY = "max_intensity";
00053 const std::string MIN_INTENSITY = "min_intensity";
00054 const std::string FOCAL_DISTANCE = "focal_distance";
00055 const std::string FOCAL_SLOPE = "focal_slope";
00056
00058 void operator >> (const YAML::Node& node,
00059 std::pair<int, LaserCorrection>& correction)
00060 {
00061 node[LASER_ID] >> correction.first;
00062 node[ROT_CORRECTION] >> correction.second.rot_correction;
00063 node[VERT_CORRECTION] >> correction.second.vert_correction;
00064 node[DIST_CORRECTION] >> correction.second.dist_correction;
00065 #ifdef HAVE_NEW_YAMLCPP
00066 if (node[TWO_PT_CORRECTION_AVAILABLE])
00067 node[TWO_PT_CORRECTION_AVAILABLE] >>
00068 correction.second.two_pt_correction_available;
00069 #else
00070 if (const YAML::Node *pName = node.FindValue(TWO_PT_CORRECTION_AVAILABLE))
00071 *pName >> correction.second.two_pt_correction_available;
00072 #endif
00073 else
00074 correction.second.two_pt_correction_available = false;
00075 node[DIST_CORRECTION_X] >> correction.second.dist_correction_x;
00076 node[DIST_CORRECTION_Y] >> correction.second.dist_correction_y;
00077 node[VERT_OFFSET_CORRECTION] >> correction.second.vert_offset_correction;
00078 #ifdef HAVE_NEW_YAMLCPP
00079 if (node[HORIZ_OFFSET_CORRECTION])
00080 node[HORIZ_OFFSET_CORRECTION] >>
00081 correction.second.horiz_offset_correction;
00082 #else
00083 if (const YAML::Node *pName = node.FindValue(HORIZ_OFFSET_CORRECTION))
00084 *pName >> correction.second.horiz_offset_correction;
00085 #endif
00086 else
00087 correction.second.horiz_offset_correction = 0;
00088
00089 const YAML::Node * max_intensity_node = NULL;
00090 #ifdef HAVE_NEW_YAMLCPP
00091 if (node[MAX_INTENSITY]) {
00092 const YAML::Node max_intensity_node_ref = node[MAX_INTENSITY];
00093 max_intensity_node = &max_intensity_node_ref;
00094 }
00095 #else
00096 if (const YAML::Node *pName = node.FindValue(MAX_INTENSITY))
00097 max_intensity_node = pName;
00098 #endif
00099 if (max_intensity_node) {
00100 float max_intensity_float;
00101 *max_intensity_node >> max_intensity_float;
00102 correction.second.max_intensity = floor(max_intensity_float);
00103 }
00104 else {
00105 correction.second.max_intensity = 255;
00106 }
00107
00108 const YAML::Node * min_intensity_node = NULL;
00109 #ifdef HAVE_NEW_YAMLCPP
00110 if (node[MIN_INTENSITY]) {
00111 const YAML::Node min_intensity_node_ref = node[MIN_INTENSITY];
00112 min_intensity_node = &min_intensity_node_ref;
00113 }
00114 #else
00115 if (const YAML::Node *pName = node.FindValue(MIN_INTENSITY))
00116 min_intensity_node = pName;
00117 #endif
00118 if (min_intensity_node) {
00119 float min_intensity_float;
00120 *min_intensity_node >> min_intensity_float;
00121 correction.second.min_intensity = floor(min_intensity_float);
00122 }
00123 else {
00124 correction.second.min_intensity = 0;
00125 }
00126 node[FOCAL_DISTANCE] >> correction.second.focal_distance;
00127 node[FOCAL_SLOPE] >> correction.second.focal_slope;
00128
00129
00130 correction.second.cos_rot_correction =
00131 cosf(correction.second.rot_correction);
00132 correction.second.sin_rot_correction =
00133 sinf(correction.second.rot_correction);
00134 correction.second.cos_vert_correction =
00135 cosf(correction.second.vert_correction);
00136 correction.second.sin_vert_correction =
00137 sinf(correction.second.vert_correction);
00138
00139 correction.second.laser_ring = 0;
00140 }
00141
00143 void operator >> (const YAML::Node& node, Calibration& calibration)
00144 {
00145 int num_lasers;
00146 node[NUM_LASERS] >> num_lasers;
00147 float distance_resolution_m;
00148 node[DISTANCE_RESOLUTION] >> distance_resolution_m;
00149 const YAML::Node& lasers = node[LASERS];
00150 calibration.laser_corrections.clear();
00151 calibration.num_lasers = num_lasers;
00152 calibration.distance_resolution_m = distance_resolution_m;
00153 calibration.laser_corrections.resize(num_lasers);
00154 for (int i = 0; i < num_lasers; i++) {
00155 std::pair<int, LaserCorrection> correction;
00156 lasers[i] >> correction;
00157 const int index = correction.first;
00158 if( index >= calibration.laser_corrections.size() )
00159 {
00160 calibration.laser_corrections.resize( index+1 );
00161 }
00162 calibration.laser_corrections[index] = (correction.second);
00163 calibration.laser_corrections_map.insert(correction);
00164 }
00165
00166
00167
00168
00169
00170 double next_angle = -std::numeric_limits<double>::infinity();
00171 for (int ring = 0; ring < num_lasers; ++ring) {
00172
00173
00174 double min_seen = std::numeric_limits<double>::infinity();
00175 int next_index = num_lasers;
00176 for (int j = 0; j < num_lasers; ++j) {
00177
00178 double angle = calibration.laser_corrections[j].vert_correction;
00179 if (next_angle < angle && angle < min_seen) {
00180 min_seen = angle;
00181 next_index = j;
00182 }
00183 }
00184
00185 if (next_index < num_lasers) {
00186
00187
00188 calibration.laser_corrections[next_index].laser_ring = ring;
00189 next_angle = min_seen;
00190 if (calibration.ros_info) {
00191 ROS_INFO("laser_ring[%2u] = %2u, angle = %+.6f",
00192 next_index, ring, next_angle);
00193 }
00194 }
00195 }
00196 }
00197
00198 YAML::Emitter& operator << (YAML::Emitter& out,
00199 const std::pair<int, LaserCorrection> correction)
00200 {
00201 out << YAML::BeginMap;
00202 out << YAML::Key << LASER_ID << YAML::Value << correction.first;
00203 out << YAML::Key << ROT_CORRECTION <<
00204 YAML::Value << correction.second.rot_correction;
00205 out << YAML::Key << VERT_CORRECTION <<
00206 YAML::Value << correction.second.vert_correction;
00207 out << YAML::Key << DIST_CORRECTION <<
00208 YAML::Value << correction.second.dist_correction;
00209 out << YAML::Key << TWO_PT_CORRECTION_AVAILABLE <<
00210 YAML::Value << correction.second.two_pt_correction_available;
00211 out << YAML::Key << DIST_CORRECTION_X <<
00212 YAML::Value << correction.second.dist_correction_x;
00213 out << YAML::Key << DIST_CORRECTION_Y <<
00214 YAML::Value << correction.second.dist_correction_y;
00215 out << YAML::Key << VERT_OFFSET_CORRECTION <<
00216 YAML::Value << correction.second.vert_offset_correction;
00217 out << YAML::Key << HORIZ_OFFSET_CORRECTION <<
00218 YAML::Value << correction.second.horiz_offset_correction;
00219 out << YAML::Key << MAX_INTENSITY <<
00220 YAML::Value << correction.second.max_intensity;
00221 out << YAML::Key << MIN_INTENSITY <<
00222 YAML::Value << correction.second.min_intensity;
00223 out << YAML::Key << FOCAL_DISTANCE <<
00224 YAML::Value << correction.second.focal_distance;
00225 out << YAML::Key << FOCAL_SLOPE <<
00226 YAML::Value << correction.second.focal_slope;
00227 out << YAML::EndMap;
00228 return out;
00229 }
00230
00231 YAML::Emitter& operator <<
00232 (YAML::Emitter& out, const Calibration& calibration)
00233 {
00234 out << YAML::BeginMap;
00235 out << YAML::Key << NUM_LASERS <<
00236 YAML::Value << calibration.laser_corrections.size();
00237 out << YAML::Key << DISTANCE_RESOLUTION <<
00238 YAML::Value << calibration.distance_resolution_m;
00239 out << YAML::Key << LASERS << YAML::Value << YAML::BeginSeq;
00240 for (std::map<int, LaserCorrection>::const_iterator
00241 it = calibration.laser_corrections_map.begin();
00242 it != calibration.laser_corrections_map.end(); it++)
00243 {
00244 out << *it;
00245 }
00246 out << YAML::EndSeq;
00247 out << YAML::EndMap;
00248 return out;
00249 }
00250
00251 void Calibration::read(const std::string& calibration_file) {
00252 std::ifstream fin(calibration_file.c_str());
00253 if (!fin.is_open()) {
00254 initialized = false;
00255 return;
00256 }
00257 initialized = true;
00258 try {
00259 YAML::Node doc;
00260 #ifdef HAVE_NEW_YAMLCPP
00261 fin.close();
00262 doc = YAML::LoadFile(calibration_file);
00263 #else
00264 YAML::Parser parser(fin);
00265 parser.GetNextDocument(doc);
00266 #endif
00267 doc >> *this;
00268 } catch (YAML::Exception &e) {
00269 std::cerr << "YAML Exception: " << e.what() << std::endl;
00270 initialized = false;
00271 }
00272 fin.close();
00273 }
00274
00275 void Calibration::write(const std::string& calibration_file) {
00276 std::ofstream fout(calibration_file.c_str());
00277 YAML::Emitter out;
00278 out << *this;
00279 fout << out.c_str();
00280 fout.close();
00281 }
00282
00283 }