37 #include <boost/filesystem.hpp>
38 #include <yaml-cpp/yaml.h>
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";
72 SimpleMatrix(
int rows,
int cols,
double* data)
73 : rows(rows), cols(cols), data(data)
77 YAML::Emitter& operator << (YAML::Emitter& out,
const SimpleMatrix& m)
79 out << YAML::BeginMap;
80 out << YAML::Key <<
"rows" << YAML::Value << m.rows;
81 out << YAML::Key <<
"cols" << YAML::Value << m.cols;
83 out << YAML::Key <<
"data" << YAML::Value;
85 out << YAML::BeginSeq;
86 for (
int i = 0; i < m.rows*m.cols; ++i)
93 #ifdef HAVE_NEW_YAMLCPP
95 void operator >> (
const YAML::Node& node, T& i)
101 void operator >> (
const YAML::Node& node, SimpleMatrix& m)
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];
116 const sensor_msgs::CameraInfo& cam_info)
118 YAML::Emitter emitter;
119 emitter << YAML::BeginMap;
126 emitter << YAML::Key <<
"calibration_time";
127 emitter << YAML::Value << asctime(localtime(&raw_time));
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;
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]));
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;
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;
157 emitter << YAML::EndMap;
159 out << emitter.c_str();
164 const sensor_msgs::CameraInfo& cam_info)
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());
171 std::ofstream out(file_name.c_str());
174 ROS_ERROR(
"Unable to open camera calibration file [%s] for writing", file_name.c_str());
180 bool readCalibrationYml(std::istream& in, std::string& camera_name, sensor_msgs::CameraInfo& cam_info)
183 #ifdef HAVE_NEW_YAMLCPP
184 YAML::Node doc = YAML::Load(in);
186 if (doc[CAM_YML_NAME])
187 doc[CAM_YML_NAME] >> camera_name;
189 camera_name =
"unknown";
193 ROS_ERROR(
"Unable to create YAML parser for camera calibration");
197 parser.GetNextDocument(doc);
199 if (
const YAML::Node* name_node = doc.FindValue(CAM_YML_NAME))
200 *name_node >> camera_name;
202 camera_name =
"unknown";
205 doc[WIDTH_YML_NAME] >> cam_info.width;
206 doc[HEIGHT_YML_NAME] >> cam_info.height;
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_;
217 #ifdef HAVE_NEW_YAMLCPP
218 if (doc[DMODEL_YML_NAME]) {
219 doc[DMODEL_YML_NAME] >> cam_info.distortion_model;
222 if (
const YAML::Node* model_node = doc.FindValue(DMODEL_YML_NAME)) {
223 *model_node >> cam_info.distortion_model;
229 ROS_WARN(
"Camera calibration file did not specify distortion model, assuming plumb bob");
231 const YAML::Node& D_node = doc[D_YML_NAME];
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];
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;
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;
252 roi_node[ROI_DO_RECTIFY_YML_NAME] >> do_rectify;
253 cam_info.roi.do_rectify = do_rectify;
258 catch (YAML::Exception& e) {
259 ROS_ERROR(
"Exception parsing YAML camera calibration:\n%s", e.what());
265 sensor_msgs::CameraInfo& cam_info)
267 std::ifstream fin(file_name.c_str());
269 ROS_INFO(
"Unable to open camera calibration file [%s]", file_name.c_str());
274 ROS_ERROR(
"Failed to parse camera calibration from file [%s]", file_name.c_str());