parse_yml.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2009, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
37 #include <boost/filesystem.hpp>
38 #include <yaml-cpp/yaml.h>
39 #include <fstream>
40 #include <ctime>
41 #include <cassert>
42 #include <cstring>
43 #include <ros/console.h>
44 
46 
48 
49 static const char CAM_YML_NAME[] = "camera_name";
50 static const char WIDTH_YML_NAME[] = "image_width";
51 static const char HEIGHT_YML_NAME[] = "image_height";
52 static const char K_YML_NAME[] = "camera_matrix";
53 static const char D_YML_NAME[] = "distortion_coefficients";
54 static const char R_YML_NAME[] = "rectification_matrix";
55 static const char P_YML_NAME[] = "projection_matrix";
56 static const char DMODEL_YML_NAME[] = "distortion_model";
57 static const char BINNING_X_YML_NAME[] = "binning_x";
58 static const char BINNING_Y_YML_NAME[] = "binning_y";
59 static const char ROI_YML_NAME[] = "roi";
60 static const char ROI_WIDTH_YML_NAME[] = "width";
61 static const char ROI_HEIGHT_YML_NAME[] = "height";
62 static const char ROI_X_OFFSET_YML_NAME[] = "x_offset";
63 static const char ROI_Y_OFFSET_YML_NAME[] = "y_offset";
64 static const char ROI_DO_RECTIFY_YML_NAME[] = "do_rectify";
65 
66 struct SimpleMatrix
67 {
68  int rows;
69  int cols;
70  double* data;
71 
72  SimpleMatrix(int rows, int cols, double* data)
73  : rows(rows), cols(cols), data(data)
74  {}
75 };
76 
77 YAML::Emitter& operator << (YAML::Emitter& out, const SimpleMatrix& m)
78 {
79  out << YAML::BeginMap;
80  out << YAML::Key << "rows" << YAML::Value << m.rows;
81  out << YAML::Key << "cols" << YAML::Value << m.cols;
82  //out << YAML::Key << "dt" << YAML::Value << "d"; // OpenCV data type specifier
83  out << YAML::Key << "data" << YAML::Value;
84  out << YAML::Flow;
85  out << YAML::BeginSeq;
86  for (int i = 0; i < m.rows*m.cols; ++i)
87  out << m.data[i];
88  out << YAML::EndSeq;
89  out << YAML::EndMap;
90  return out;
91 }
92 
93 #ifdef HAVE_NEW_YAMLCPP
94 template<typename T>
95 void operator >> (const YAML::Node& node, T& i)
96 {
97  i = node.as<T>();
98 }
99 #endif
100 
101 void operator >> (const YAML::Node& node, SimpleMatrix& m)
102 {
103  int rows, cols;
104  node["rows"] >> rows;
105  assert(rows == m.rows);
106  node["cols"] >> cols;
107  assert(cols == m.cols);
108  const YAML::Node& data = node["data"];
109  for (int i = 0; i < rows*cols; ++i)
110  data[i] >> m.data[i];
111 }
112 
114 
115 bool writeCalibrationYml(std::ostream& out, const std::string& camera_name,
116  const sensor_msgs::CameraInfo& cam_info)
117 {
118  YAML::Emitter emitter;
119  emitter << YAML::BeginMap;
120 
121 #if 0
122  // Calibration time
124  time_t raw_time;
125  time( &raw_time );
126  emitter << YAML::Key << "calibration_time";
127  emitter << YAML::Value << asctime(localtime(&raw_time));
128 #endif
129 
130  // Image dimensions
131  emitter << YAML::Key << WIDTH_YML_NAME << YAML::Value << (int)cam_info.width;
132  emitter << YAML::Key << HEIGHT_YML_NAME << YAML::Value << (int)cam_info.height;
133 
134  // Camera name and intrinsics
135  emitter << YAML::Key << CAM_YML_NAME << YAML::Value << camera_name;
136  emitter << YAML::Key << K_YML_NAME << YAML::Value << SimpleMatrix(3, 3, const_cast<double*>(&cam_info.K[0]));
137  emitter << YAML::Key << DMODEL_YML_NAME << YAML::Value << cam_info.distortion_model;
138  emitter << YAML::Key << D_YML_NAME << YAML::Value << SimpleMatrix(1, cam_info.D.size(),
139  const_cast<double*>(&cam_info.D[0]));
140  emitter << YAML::Key << R_YML_NAME << YAML::Value << SimpleMatrix(3, 3, const_cast<double*>(&cam_info.R[0]));
141  emitter << YAML::Key << P_YML_NAME << YAML::Value << SimpleMatrix(3, 4, const_cast<double*>(&cam_info.P[0]));
142 
143  // Binning
144  emitter << YAML::Key << BINNING_X_YML_NAME << YAML::Value << cam_info.binning_x;
145  emitter << YAML::Key << BINNING_Y_YML_NAME << YAML::Value << cam_info.binning_y;
146 
147  // ROI
148  emitter << YAML::Key << ROI_YML_NAME << YAML::Value;
149  emitter << YAML::BeginMap;
150  emitter << YAML::Key << ROI_X_OFFSET_YML_NAME << YAML::Value << cam_info.roi.x_offset;
151  emitter << YAML::Key << ROI_Y_OFFSET_YML_NAME << YAML::Value << cam_info.roi.y_offset;
152  emitter << YAML::Key << ROI_HEIGHT_YML_NAME << YAML::Value << cam_info.roi.height;
153  emitter << YAML::Key << ROI_WIDTH_YML_NAME << YAML::Value << cam_info.roi.width;
154  emitter << YAML::Key << ROI_DO_RECTIFY_YML_NAME << YAML::Value << (bool)cam_info.roi.do_rectify;
155  emitter << YAML::EndMap;
156 
157  emitter << YAML::EndMap;
158 
159  out << emitter.c_str();
160  return true;
161 }
162 
163 bool writeCalibrationYml(const std::string& file_name, const std::string& camera_name,
164  const sensor_msgs::CameraInfo& cam_info)
165 {
166  boost::filesystem::path dir(boost::filesystem::path(file_name).parent_path());
167  if (!dir.empty() && !boost::filesystem::exists(dir) &&
168  !boost::filesystem::create_directories(dir)){
169  ROS_ERROR("Unable to create directory for camera calibration file [%s]", dir.c_str());
170  }
171  std::ofstream out(file_name.c_str());
172  if (!out.is_open())
173  {
174  ROS_ERROR("Unable to open camera calibration file [%s] for writing", file_name.c_str());
175  return false;
176  }
177  return writeCalibrationYml(out, camera_name, cam_info);
178 }
179 
180 bool readCalibrationYml(std::istream& in, std::string& camera_name, sensor_msgs::CameraInfo& cam_info)
181 {
182  try {
183 #ifdef HAVE_NEW_YAMLCPP
184  YAML::Node doc = YAML::Load(in);
185 
186  if (doc[CAM_YML_NAME])
187  doc[CAM_YML_NAME] >> camera_name;
188  else
189  camera_name = "unknown";
190 #else
191  YAML::Parser parser(in);
192  if (!parser) {
193  ROS_ERROR("Unable to create YAML parser for camera calibration");
194  return false;
195  }
196  YAML::Node doc;
197  parser.GetNextDocument(doc);
198 
199  if (const YAML::Node* name_node = doc.FindValue(CAM_YML_NAME))
200  *name_node >> camera_name;
201  else
202  camera_name = "unknown";
203 #endif
204 
205  doc[WIDTH_YML_NAME] >> cam_info.width;
206  doc[HEIGHT_YML_NAME] >> cam_info.height;
207 
208  // Read in fixed-size matrices
209  SimpleMatrix K_(3, 3, &cam_info.K[0]);
210  doc[K_YML_NAME] >> K_;
211  SimpleMatrix R_(3, 3, &cam_info.R[0]);
212  doc[R_YML_NAME] >> R_;
213  SimpleMatrix P_(3, 4, &cam_info.P[0]);
214  doc[P_YML_NAME] >> P_;
215 
216  // Different distortion models may have different numbers of parameters
217 #ifdef HAVE_NEW_YAMLCPP
218  if (doc[DMODEL_YML_NAME]) {
219  doc[DMODEL_YML_NAME] >> cam_info.distortion_model;
220  }
221 #else
222  if (const YAML::Node* model_node = doc.FindValue(DMODEL_YML_NAME)) {
223  *model_node >> cam_info.distortion_model;
224  }
225 #endif
226  else {
227  // Assume plumb bob for backwards compatibility
228  cam_info.distortion_model = sensor_msgs::distortion_models::PLUMB_BOB;
229  ROS_WARN("Camera calibration file did not specify distortion model, assuming plumb bob");
230  }
231  const YAML::Node& D_node = doc[D_YML_NAME];
232  int D_rows, D_cols;
233  D_node["rows"] >> D_rows;
234  D_node["cols"] >> D_cols;
235  const YAML::Node& D_data = D_node["data"];
236  cam_info.D.resize(D_rows*D_cols);
237  for (int i = 0; i < D_rows*D_cols; ++i)
238  D_data[i] >> cam_info.D[i];
239 
240  if (doc[BINNING_X_YML_NAME])
241  doc[BINNING_X_YML_NAME] >> cam_info.binning_x;
242  if (doc[BINNING_Y_YML_NAME])
243  doc[BINNING_Y_YML_NAME] >> cam_info.binning_y;
244 
245  if (doc[ROI_YML_NAME]) {
246  const YAML::Node &roi_node = doc[ROI_YML_NAME];
247  roi_node[ROI_X_OFFSET_YML_NAME] >> cam_info.roi.x_offset;
248  roi_node[ROI_Y_OFFSET_YML_NAME] >> cam_info.roi.y_offset;
249  roi_node[ROI_HEIGHT_YML_NAME] >> cam_info.roi.height;
250  roi_node[ROI_WIDTH_YML_NAME] >> cam_info.roi.width;
251  bool do_rectify;
252  roi_node[ROI_DO_RECTIFY_YML_NAME] >> do_rectify;
253  cam_info.roi.do_rectify = do_rectify;
254  }
255 
256  return true;
257  }
258  catch (YAML::Exception& e) {
259  ROS_ERROR("Exception parsing YAML camera calibration:\n%s", e.what());
260  return false;
261  }
262 }
263 
264 bool readCalibrationYml(const std::string& file_name, std::string& camera_name,
265  sensor_msgs::CameraInfo& cam_info)
266 {
267  std::ifstream fin(file_name.c_str());
268  if (!fin.good()) {
269  ROS_INFO("Unable to open camera calibration file [%s]", file_name.c_str());
270  return false;
271  }
272  bool success = readCalibrationYml(fin, camera_name, cam_info);
273  if (!success)
274  ROS_ERROR("Failed to parse camera calibration from file [%s]", file_name.c_str());
275  return success;
276 }
277 
278 } //namespace camera_calibration_parsers
distortion_models.h
camera_calibration_parsers::readCalibrationYml
bool readCalibrationYml(std::istream &in, std::string &camera_name, sensor_msgs::CameraInfo &cam_info)
Read calibration parameters from a YAML file.
Definition: parse_yml.cpp:212
parser
Definition: parser.py:1
camera_calibration_parsers
Definition: parse.h:42
console.h
parse_yml.h
ROS_WARN
#define ROS_WARN(...)
camera_calibration_parsers::writeCalibrationYml
bool writeCalibrationYml(std::ostream &out, const std::string &camera_name, const sensor_msgs::CameraInfo &cam_info)
Write calibration parameters to a file in YAML format.
Definition: parse_yml.cpp:147
ROS_ERROR
#define ROS_ERROR(...)
sensor_msgs::distortion_models::PLUMB_BOB
const std::string PLUMB_BOB
ROS_INFO
#define ROS_INFO(...)


camera_calibration_parsers
Author(s): Patrick Mihelich
autogenerated on Sat Jan 20 2024 03:14:48