00001 #include "camera_calibration_parsers/parse_ini.h"
00002 #include <sensor_msgs/distortion_models.h>
00003
00004 #include <boost/spirit/include/classic_core.hpp>
00005 #include <boost/spirit/include/classic_file_iterator.hpp>
00006 #include <boost/spirit/include/classic_confix.hpp>
00007 #include <boost/spirit/include/classic_loops.hpp>
00008 #include <boost/typeof/typeof.hpp>
00009 #include <iterator>
00010 #include <fstream>
00011
00012 namespace camera_calibration_parsers {
00013
00015 using namespace BOOST_SPIRIT_CLASSIC_NS;
00016
00018
00019 struct SimpleMatrix
00020 {
00021 int rows;
00022 int cols;
00023 const double* data;
00024
00025 SimpleMatrix(int rows, int cols, const double* data)
00026 : rows(rows), cols(cols), data(data)
00027 {}
00028 };
00029
00030 std::ostream& operator << (std::ostream& out, const SimpleMatrix& m)
00031 {
00032 for (int i = 0; i < m.rows; ++i) {
00033 for (int j = 0; j < m.cols; ++j) {
00034 out << m.data[m.cols*i+j] << " ";
00035 }
00036 out << std::endl;
00037 }
00038 return out;
00039 }
00040
00042
00043 bool writeCalibrationIni(std::ostream& out, const std::string& camera_name,
00044 const sensor_msgs::CameraInfo& cam_info)
00045 {
00046
00047 if (cam_info.distortion_model != sensor_msgs::distortion_models::PLUMB_BOB ||
00048 cam_info.D.size() != 5) {
00049 ROS_ERROR("Videre INI format can only save calibrations using the plumb bob distortion model. "
00050 "Use the YAML format instead.");
00051 return false;
00052 }
00053
00054 out.precision(5);
00055 out << std::fixed;
00056
00057 out << "# Camera intrinsics\n\n";
00059 out << "[image]\n\n";
00060 out << "width\n" << cam_info.width << "\n\n";
00061 out << "height\n" << cam_info.height << "\n\n";
00062 out << "[" << camera_name << "]\n\n";
00063
00064 out << "camera matrix\n" << SimpleMatrix(3, 3, &cam_info.K[0]);
00065 out << "\ndistortion\n" << SimpleMatrix(1, 5, &cam_info.D[0]);
00066 out << "\n\nrectification\n" << SimpleMatrix(3, 3, &cam_info.R[0]);
00067 out << "\nprojection\n" << SimpleMatrix(3, 4, &cam_info.P[0]);
00068
00069 return true;
00070 }
00071
00072 bool writeCalibrationIni(const std::string& file_name, const std::string& camera_name,
00073 const sensor_msgs::CameraInfo& cam_info)
00074 {
00075 std::ofstream out(file_name.c_str());
00076 return writeCalibrationIni(out, camera_name, cam_info);
00077 }
00078
00080
00081 template <typename T>
00082 struct ArrayAssignActor
00083 {
00084 ArrayAssignActor(T* start)
00085 : ptr_(start)
00086 {}
00087
00088 void operator()(T val) const
00089 {
00090 *ptr_++ = val;
00091 }
00092
00093 mutable T* ptr_;
00094 };
00095
00096
00097 template <typename T>
00098 ArrayAssignActor<T> array_assign_a(T* start)
00099 {
00100 return ArrayAssignActor<T>(start);
00101 }
00102
00103 template <typename Iterator>
00104 bool parseCalibrationIniRange(Iterator first, Iterator last,
00105 std::string& camera_name, sensor_msgs::CameraInfo& cam_info)
00106 {
00107
00108 cam_info.distortion_model = sensor_msgs::distortion_models::PLUMB_BOB;
00109 cam_info.D.resize(5);
00110
00111
00112 bool have_externals = false;
00113 double trans[3], rot[3];
00114
00116
00117
00118 BOOST_AUTO(image,
00119 str_p("[image]")
00120 >> "width"
00121 >> uint_p[assign_a(cam_info.width)]
00122 >> "height"
00123 >> uint_p[assign_a(cam_info.height)]
00124 );
00125
00126
00127 BOOST_AUTO(externals,
00128 str_p("[externals]")
00129 >> "translation"
00130 >> repeat_p(3)[real_p[array_assign_a(trans)]]
00131 >> "rotation"
00132 >> repeat_p(3)[real_p[array_assign_a(rot)]]
00133 );
00134
00135
00136 BOOST_AUTO(name, confix_p('[', (*anychar_p)[assign_a(camera_name)], ']'));
00137
00138
00139 BOOST_AUTO(camera,
00140 name
00141 >> "camera matrix"
00142 >> repeat_p(9)[real_p[array_assign_a(&cam_info.K[0])]]
00143 >> "distortion"
00144 >> repeat_p(5)[real_p[array_assign_a(&cam_info.D[0])]]
00145 >> "rectification"
00146 >> repeat_p(9)[real_p[array_assign_a(&cam_info.R[0])]]
00147 >> "projection"
00148 >> repeat_p(12)[real_p[array_assign_a(&cam_info.P[0])]]
00149 );
00150
00151
00152 BOOST_AUTO(ini_grammar,
00153 image
00154 >> !externals[assign_a(have_externals, true)]
00155 >> camera);
00156
00157
00158 BOOST_AUTO(skip, space_p | comment_p('#'));
00159
00160 parse_info<Iterator> info = parse(first, last, ini_grammar, skip);
00161 return info.hit;
00162 }
00164
00165 bool readCalibrationIni(std::istream& in, std::string& camera_name, sensor_msgs::CameraInfo& cam_info)
00166 {
00167 std::istream_iterator<char> first(in), last;
00168 return parseCalibrationIniRange(first, last, camera_name, cam_info);
00169 }
00170
00171 bool readCalibrationIni(const std::string& file_name, std::string& camera_name,
00172 sensor_msgs::CameraInfo& cam_info)
00173 {
00174 typedef file_iterator<char> Iterator;
00175
00176 Iterator first(file_name);
00177 if (!first) {
00178 ROS_ERROR("Unable to open camera calibration file [%s]", file_name.c_str());
00179 return false;
00180 }
00181 Iterator last = first.make_end();
00182
00183 return parseCalibrationIniRange(first, last, camera_name, cam_info);
00184 }
00185
00186 bool parseCalibrationIni(const std::string& buffer, std::string& camera_name,
00187 sensor_msgs::CameraInfo& cam_info)
00188 {
00189 return parseCalibrationIniRange(buffer.begin(), buffer.end(), camera_name, cam_info);
00190 }
00191
00192 }