39 #include <boost/spirit/include/phoenix_stl.hpp> 
   40 #include <boost/spirit/include/qi.hpp> 
   41 #include <boost/spirit/include/classic_core.hpp> 
   42 #include <boost/spirit/include/classic_file_iterator.hpp> 
   43 #include <boost/spirit/include/classic_confix.hpp> 
   44 #include <boost/spirit/include/classic_loops.hpp> 
   45 #include <boost/typeof/typeof.hpp> 
   46 #include <boost/filesystem.hpp> 
   53 using namespace BOOST_SPIRIT_CLASSIC_NS;
 
   63   SimpleMatrix(
int rows, 
int cols, 
const double* data)
 
   64     : rows(rows), cols(cols), data(data)
 
   68 std::ostream& operator << (std::ostream& out, 
const SimpleMatrix& m)
 
   70   for (
int i = 0; i < m.rows; ++i) {
 
   71     for (
int j = 0; j < m.cols; ++j) {
 
   72       out << m.data[m.cols*i+j] << 
" ";
 
   82                          const sensor_msgs::CameraInfo& cam_info)
 
   86       cam_info.D.size() != 5) {
 
   87     ROS_ERROR(
"Videre INI format can only save calibrations using the plumb bob distortion model. " 
   88               "Use the YAML format instead.\n" 
   89               "\tdistortion_model = '%s', expected '%s'\n" 
   90               "\tD.size() = %d, expected 5", cam_info.distortion_model.c_str(),
 
   98   out << 
"# Camera intrinsics\n\n";
 
  100   out << 
"[image]\n\n";
 
  101   out << 
"width\n" << cam_info.width << 
"\n\n";
 
  102   out << 
"height\n" << cam_info.height << 
"\n\n";
 
  103   out << 
"[" << camera_name << 
"]\n\n";
 
  105   out << 
"camera matrix\n"     << SimpleMatrix(3, 3, &cam_info.K[0]);
 
  106   out << 
"\ndistortion\n"      << SimpleMatrix(1, 5, &cam_info.D[0]);
 
  107   out << 
"\n\nrectification\n" << SimpleMatrix(3, 3, &cam_info.R[0]);
 
  108   out << 
"\nprojection\n"      << SimpleMatrix(3, 4, &cam_info.P[0]);
 
  114                          const sensor_msgs::CameraInfo& cam_info)
 
  116   boost::filesystem::path dir(boost::filesystem::path(file_name).parent_path());
 
  117   if (!dir.empty() && !boost::filesystem::exists(dir) &&
 
  118      !boost::filesystem::create_directories(dir)){
 
  119     ROS_ERROR(
"Unable to create directory for camera calibration file [%s]", dir.c_str());
 
  121   std::ofstream out(file_name.c_str());
 
  124     ROS_ERROR(
"Unable to open camera calibration file [%s] for writing", file_name.c_str());
 
  132 template <
typename T>
 
  133 struct ArrayAssignActor
 
  135   ArrayAssignActor(T* start)
 
  139   void operator()(T val)
 const 
  148 template <
typename T>
 
  149 ArrayAssignActor<T> array_assign_a(T* start)
 
  151   return ArrayAssignActor<T>(
start);
 
  154 template <
typename Iterator>
 
  155 bool parseCalibrationIniRange(Iterator first, Iterator last,
 
  156                               std::string& camera_name, sensor_msgs::CameraInfo& cam_info)
 
  161   bool have_externals = 
false;
 
  162   double trans[3], rot[3];
 
  170       >> uint_p[assign_a(cam_info.width)]
 
  172       >> uint_p[assign_a(cam_info.height)]
 
  176   BOOST_AUTO(externals,
 
  179       >> repeat_p(3)[real_p[array_assign_a(trans)]]
 
  181       >> repeat_p(3)[real_p[array_assign_a(rot)]]
 
  185   BOOST_AUTO(name, confix_p(
'[', (*anychar_p)[assign_a(camera_name)], 
']'));
 
  191       >> repeat_p(9)[real_p[array_assign_a(&cam_info.K[0])]]
 
  193       >> *(real_p[push_back_a(cam_info.D)])
 
  195       >> repeat_p(9)[real_p[array_assign_a(&cam_info.R[0])]]
 
  197       >> repeat_p(12)[real_p[array_assign_a(&cam_info.P[0])]]
 
  201   BOOST_AUTO(ini_grammar,
 
  203       >> !externals[assign_a(have_externals, 
true)]
 
  207   BOOST_AUTO(skip, space_p | comment_p(
'#'));
 
  209   parse_info<Iterator> info = parse(first, last, ini_grammar, skip);
 
  212   if (cam_info.D.size() == 5)
 
  214   else if (cam_info.D.size() == 8)
 
  221 bool readCalibrationIni(std::istream& in, std::string& camera_name, sensor_msgs::CameraInfo& cam_info)
 
  223   std::istream_iterator<char> first(in), last;
 
  224   return parseCalibrationIniRange(first, last, camera_name, cam_info);
 
  228                         sensor_msgs::CameraInfo& cam_info)
 
  230   typedef file_iterator<char> Iterator;
 
  232   Iterator first(file_name);
 
  234     ROS_INFO(
"Unable to open camera calibration file [%s]", file_name.c_str());
 
  237   Iterator last = first.make_end();
 
  239   return parseCalibrationIniRange(first, last, camera_name, cam_info);
 
  243                          sensor_msgs::CameraInfo& cam_info)
 
  245   return parseCalibrationIniRange(buffer.begin(), buffer.end(), camera_name, cam_info);