parse_yml.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 * 
00004 *  Copyright (c) 2009, Willow Garage, Inc.
00005 *  All rights reserved.
00006 * 
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 * 
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 * 
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #include "camera_calibration_parsers/parse_yml.h"
00036 #include <sensor_msgs/distortion_models.h>
00037 #include <yaml-cpp/yaml.h>
00038 #include <fstream>
00039 #include <ctime>
00040 #include <cassert>
00041 #include <cstring>
00042 #include <ros/console.h>
00043 
00044 namespace camera_calibration_parsers {
00045 
00047 
00048 static const char CAM_YML_NAME[]    = "camera_name";
00049 static const char WIDTH_YML_NAME[]  = "image_width";
00050 static const char HEIGHT_YML_NAME[] = "image_height";
00051 static const char K_YML_NAME[]      = "camera_matrix";
00052 static const char D_YML_NAME[]      = "distortion_coefficients";
00053 static const char R_YML_NAME[]      = "rectification_matrix";
00054 static const char P_YML_NAME[]      = "projection_matrix";
00055 static const char DMODEL_YML_NAME[] = "distortion_model";
00056 
00057 struct SimpleMatrix
00058 {
00059   int rows;
00060   int cols;
00061   double* data;
00062 
00063   SimpleMatrix(int rows, int cols, double* data)
00064     : rows(rows), cols(cols), data(data)
00065   {}
00066 };
00067 
00068 YAML::Emitter& operator << (YAML::Emitter& out, const SimpleMatrix& m)
00069 {
00070   out << YAML::BeginMap;
00071   out << YAML::Key << "rows" << YAML::Value << m.rows;
00072   out << YAML::Key << "cols" << YAML::Value << m.cols;
00073   //out << YAML::Key << "dt"   << YAML::Value << "d"; // OpenCV data type specifier
00074   out << YAML::Key << "data" << YAML::Value;
00075   out << YAML::Flow;
00076   out << YAML::BeginSeq;
00077   for (int i = 0; i < m.rows*m.cols; ++i)
00078     out << m.data[i];
00079   out << YAML::EndSeq;
00080   out << YAML::EndMap;
00081   return out;
00082 }
00083 
00084 #ifdef HAVE_NEW_YAMLCPP
00085 template<typename T>
00086 void operator >> (const YAML::Node& node, T& i)
00087 {
00088   i = node.as<T>();
00089 }
00090 #endif
00091 
00092 void operator >> (const YAML::Node& node, SimpleMatrix& m)
00093 {
00094   int rows, cols;
00095   node["rows"] >> rows;
00096   assert(rows == m.rows);
00097   node["cols"] >> cols;
00098   assert(cols == m.cols);
00099   const YAML::Node& data = node["data"];
00100   for (int i = 0; i < rows*cols; ++i)
00101     data[i] >> m.data[i];
00102 }
00103 
00105 
00106 bool writeCalibrationYml(std::ostream& out, const std::string& camera_name,
00107                          const sensor_msgs::CameraInfo& cam_info)
00108 {
00109   YAML::Emitter emitter;
00110   emitter << YAML::BeginMap;
00111 
00112 #if 0
00113   // Calibration time
00115   time_t raw_time;
00116   time( &raw_time );
00117   emitter << YAML::Key << "calibration_time";
00118   emitter << YAML::Value << asctime(localtime(&raw_time));
00119 #endif
00120 
00121   // Image dimensions
00122   emitter << YAML::Key << WIDTH_YML_NAME << YAML::Value << (int)cam_info.width;
00123   emitter << YAML::Key << HEIGHT_YML_NAME << YAML::Value << (int)cam_info.height;
00124   
00125   // Camera name and intrinsics
00126   emitter << YAML::Key << CAM_YML_NAME << YAML::Value << camera_name;
00127   emitter << YAML::Key << K_YML_NAME << YAML::Value << SimpleMatrix(3, 3, const_cast<double*>(&cam_info.K[0]));
00128   emitter << YAML::Key << DMODEL_YML_NAME << YAML::Value << cam_info.distortion_model;
00129   emitter << YAML::Key << D_YML_NAME << YAML::Value << SimpleMatrix(1, cam_info.D.size(),
00130                                                                     const_cast<double*>(&cam_info.D[0]));
00131   emitter << YAML::Key << R_YML_NAME << YAML::Value << SimpleMatrix(3, 3, const_cast<double*>(&cam_info.R[0]));
00132   emitter << YAML::Key << P_YML_NAME << YAML::Value << SimpleMatrix(3, 4, const_cast<double*>(&cam_info.P[0]));
00133 
00134   emitter << YAML::EndMap;
00135 
00136   out << emitter.c_str();
00137   return true;
00138 }
00139 
00140 bool writeCalibrationYml(const std::string& file_name, const std::string& camera_name,
00141                          const sensor_msgs::CameraInfo& cam_info)
00142 {
00143   std::ofstream out(file_name.c_str());
00144   if (!out.is_open())
00145   {
00146     ROS_ERROR("Unable to open camera calibration file [%s] for writing", file_name.c_str());
00147     return false;
00148   }
00149   return writeCalibrationYml(out, camera_name, cam_info);
00150 }
00151 
00152 bool readCalibrationYml(std::istream& in, std::string& camera_name, sensor_msgs::CameraInfo& cam_info)
00153 {
00154   try {
00155 #ifdef HAVE_NEW_YAMLCPP
00156     YAML::Node doc = YAML::Load(in);
00157 
00158     if (doc[CAM_YML_NAME])
00159       doc[CAM_YML_NAME] >> camera_name;
00160     else
00161       camera_name = "unknown";
00162 #else
00163     YAML::Parser parser(in);
00164     if (!parser) {
00165       ROS_ERROR("Unable to create YAML parser for camera calibration");
00166       return false;
00167     }
00168     YAML::Node doc;
00169     parser.GetNextDocument(doc);
00170 
00171     if (const YAML::Node* name_node = doc.FindValue(CAM_YML_NAME))
00172       *name_node >> camera_name;
00173     else
00174       camera_name = "unknown";
00175 #endif
00176 
00177     doc[WIDTH_YML_NAME] >> cam_info.width;
00178     doc[HEIGHT_YML_NAME] >> cam_info.height;
00179 
00180     // Read in fixed-size matrices
00181     SimpleMatrix K_(3, 3, &cam_info.K[0]);
00182     doc[K_YML_NAME] >> K_;
00183     SimpleMatrix R_(3, 3, &cam_info.R[0]);
00184     doc[R_YML_NAME] >> R_;
00185     SimpleMatrix P_(3, 4, &cam_info.P[0]);
00186     doc[P_YML_NAME] >> P_;
00187 
00188     // Different distortion models may have different numbers of parameters
00189 #ifdef HAVE_NEW_YAMLCPP
00190     if (doc[DMODEL_YML_NAME]) {
00191       doc[DMODEL_YML_NAME] >> cam_info.distortion_model;
00192     }
00193 #else
00194     if (const YAML::Node* model_node = doc.FindValue(DMODEL_YML_NAME)) {
00195       *model_node >> cam_info.distortion_model;
00196     }
00197 #endif
00198     else {
00199       // Assume plumb bob for backwards compatibility
00200       cam_info.distortion_model = sensor_msgs::distortion_models::PLUMB_BOB;
00201       ROS_WARN("Camera calibration file did not specify distortion model, assuming plumb bob");
00202     }
00203     const YAML::Node& D_node = doc[D_YML_NAME];
00204     int D_rows, D_cols;
00205     D_node["rows"] >> D_rows;
00206     D_node["cols"] >> D_cols;
00207     const YAML::Node& D_data = D_node["data"];
00208     cam_info.D.resize(D_rows*D_cols);
00209     for (int i = 0; i < D_rows*D_cols; ++i)
00210       D_data[i] >> cam_info.D[i];
00211   
00212     return true;
00213   }
00214   catch (YAML::Exception& e) {
00215     ROS_ERROR("Exception parsing YAML camera calibration:\n%s", e.what());
00216     return false;
00217   }
00218 }
00219 
00220 bool readCalibrationYml(const std::string& file_name, std::string& camera_name,
00221                         sensor_msgs::CameraInfo& cam_info)
00222 {
00223   std::ifstream fin(file_name.c_str());
00224   if (!fin.good()) {
00225     ROS_ERROR("Unable to open camera calibration file [%s]", file_name.c_str());
00226     return false;
00227   }
00228   bool success = readCalibrationYml(fin, camera_name, cam_info);
00229   if (!success)
00230     ROS_ERROR("Failed to parse camera calibration from file [%s]", file_name.c_str());
00231   return success;
00232 }
00233 
00234 } //namespace camera_calibration_parsers


camera_calibration_parsers
Author(s): Patrick Mihelich
autogenerated on Mon Oct 6 2014 00:42:35