Go to the documentation of this file.00001
00002
00003 #ifndef CAMERA_CALIBRATION_PARSERS_PARSE_INI_H
00004 #define CAMERA_CALIBRATION_PARSERS_PARSE_INI_H
00005
00006 #include <string>
00007 #include <sensor_msgs/CameraInfo.h>
00008
00009 namespace camera_calibration_parsers {
00010
00018 bool writeCalibrationIni(std::ostream& out, const std::string& camera_name,
00019 const sensor_msgs::CameraInfo& cam_info);
00020
00028 bool readCalibrationIni(std::istream& in, std::string& camera_name, sensor_msgs::CameraInfo& cam_info);
00029
00037 bool writeCalibrationIni(const std::string& file_name, const std::string& camera_name,
00038 const sensor_msgs::CameraInfo& cam_info);
00039
00047 bool readCalibrationIni(const std::string& file_name, std::string& camera_name,
00048 sensor_msgs::CameraInfo& cam_info);
00049
00057 bool parseCalibrationIni(const std::string& buffer, std::string& camera_name,
00058 sensor_msgs::CameraInfo& cam_info);
00059
00060
00061
00062 }
00063
00064 #endif