Go to the documentation of this file.00001
00002
00003 #ifndef CAMERA_CALIBRATION_PARSERS_PARSE_YML_H
00004 #define CAMERA_CALIBRATION_PARSERS_PARSE_YML_H
00005
00006 #include <string>
00007 #include <istream>
00008 #include <ostream>
00009 #include <sensor_msgs/CameraInfo.h>
00010
00011 namespace camera_calibration_parsers {
00012
00020 bool writeCalibrationYml(std::ostream& out, const std::string& camera_name,
00021 const sensor_msgs::CameraInfo& cam_info);
00022
00030 bool readCalibrationYml(std::istream& in, std::string& camera_name, sensor_msgs::CameraInfo& cam_info);
00031
00039 bool writeCalibrationYml(const std::string& file_name, const std::string& camera_name,
00040 const sensor_msgs::CameraInfo& cam_info);
00041
00049 bool readCalibrationYml(const std::string& file_name, std::string& camera_name,
00050 sensor_msgs::CameraInfo& cam_info);
00051
00052 }
00053
00054 #endif