00001
00044 #include "ros/ros.h"
00045
00046 #include <iostream>
00047 #include <iomanip>
00048 #include <vector>
00049 #include <string>
00050 #include <sstream>
00051
00052 #include <opencv/cv.h>
00053 #include <opencv/highgui.h>
00054
00055 #include "../MetaFile.h"
00056
00057 #include "DUtils.h"
00058 #include "DUtilsCV.h"
00059 #include "DVision.h"
00060
00061 typedef DVision::PMVS::PLYFile PLYFile;
00062 typedef DVision::PMVS::PLYFile::PLYPoint PLYPoint;
00063 typedef DVision::Bundle::CameraFile::Camera Camera;
00064
00065 using namespace std;
00066
00067
00068
00080 void createPLYpoints(const cv::Mat &img, float width, float height,
00081 const DVision::SurfSet &surfset, std::vector<PLYPoint> &plypoints);
00082
00092 void createCamera(const cv::Mat &im, float width, float height,
00093 Camera &camera);
00094
00104 void saveFace(const std::string &model_dir, int face_idx, const cv::Mat &img,
00105 const DVision::SurfSet &surfs, const std::vector<PLYPoint> &plypoints,
00106 const Camera &camera);
00107
00108
00109
00110 static const int DEFAULT_HESSIAN_THRESHOLD = 400;
00111
00112
00113
00114 int main(int argc, char **argv)
00115 {
00116 ros::init(argc, argv, "createPlanarModel");
00117
00118 if(argc < 6)
00119 {
00120 ROS_WARN("Usage: createPlanarModel <training image> <object name> "
00121 "<width (m)> <height (m)> <output model dir> [surf threshold]");
00122 return 1;
00123 }
00124
00125 cout << argc << endl;
00126
00127 string image_file = argv[1];
00128 string object_name = argv[2];
00129 float width = atof(argv[3]);
00130 float height = atof(argv[4]);
00131 string out_model_dir = argv[5];
00132 int hessian = (argc >= 7 ? atoi(argv[6]) : DEFAULT_HESSIAN_THRESHOLD);
00133
00134 ROS_INFO("Reading image...");
00135 cv::Mat img_color = cv::imread(image_file, 1);
00136 cv::Mat bw_img = cv::imread(image_file, 0);
00137
00138 ROS_INFO("Extracting SURFs (hessian threshold: %d)...", hessian);
00139 DVision::SurfSet surfset;
00140 surfset.Extract(bw_img, hessian);
00141 ROS_INFO(" %d points obtained", surfset.size());
00142
00143 ROS_INFO("Computing 3D coords and camera info...");
00144 vector<PLYPoint> plypoints;
00145 createPLYpoints(img_color, width, height, surfset, plypoints);
00146
00147 Camera camera;
00148 createCamera(img_color, width, height, camera);
00149
00150 ROS_INFO("Creating meta data...");
00151 MetaFile::MetaData meta;
00152 meta.Name = object_name;
00153 meta.NFaces = 1;
00154 meta.Type = "planar";
00155 meta.Dimensions.Planar.Width = width;
00156 meta.Dimensions.Planar.Height = height;
00157 meta.Dimensions.Planar.Depth = 0;
00158 meta.Dimensions.Planar.Faces.resize(1);
00159 meta.Dimensions.Planar.Faces[0].Width = width;
00160 meta.Dimensions.Planar.Faces[0].Height = height;
00161 meta.Dimensions.Planar.Faces[0].oTf = cv::Mat::eye(4,4,CV_64F);
00162
00163
00164
00165
00166
00167 ROS_INFO("Saving...");
00168
00169 if(!DUtils::FileFunctions::DirExists(out_model_dir.c_str()))
00170 DUtils::FileFunctions::MkDir(out_model_dir.c_str());
00171
00172 saveFace(out_model_dir, 0, img_color, surfset, plypoints, camera);
00173 MetaFile::saveFile(out_model_dir + "/meta.xml", meta);
00174
00175 ROS_INFO("Done");
00176
00177 return 0;
00178 }
00179
00180
00181
00182 void createPLYpoints(const cv::Mat &img, float width, float height,
00183 const DVision::SurfSet &surfset, std::vector<PLYPoint> &plypoints)
00184 {
00185 plypoints.resize(0);
00186 if(surfset.keys.empty()) return;
00187
00188 double mperpixel;
00189 if(width > 0.f && height > 0.f)
00190 mperpixel = ((width / (float)img.cols) + (height / (float)img.rows)) / 2.f;
00191 else if(width > 0.f) mperpixel = width / (float)img.cols;
00192 else mperpixel = height / (float)img.rows;
00193
00194 const float cx = (float)img.cols / 2.f;
00195 const float cy = (float)img.rows / 2.f;
00196
00197 vector<cv::Mat> bgr_planes;
00198 cv::split(img, bgr_planes);
00199
00200 plypoints.reserve(surfset.size());
00201
00202 vector<cv::KeyPoint>::const_iterator kit;
00203 for(kit = surfset.keys.begin(); kit != surfset.keys.end(); ++kit)
00204 {
00205 plypoints.push_back(PLYPoint());
00206 PLYPoint &p = plypoints.back();
00207
00208 p.x = (kit->pt.x - cx) * mperpixel;
00209 p.y = (kit->pt.y - cy) * mperpixel;
00210 p.z = 0.;
00211
00212 p.nx = 0.;
00213 p.ny = 0.;
00214 p.nz = 1.;
00215
00216 p.r = bgr_planes[2].at<uchar>(kit->pt.y, kit->pt.x);
00217 p.g = bgr_planes[1].at<uchar>(kit->pt.y, kit->pt.x);
00218 p.b = bgr_planes[0].at<uchar>(kit->pt.y, kit->pt.x);
00219 }
00220
00221 }
00222
00223
00224
00225 void createCamera(const cv::Mat &im, float width, float height,
00226 Camera &camera)
00227 {
00228 cv::Mat cTo = DUtilsCV::Transformations::transl(0, 0, 1);
00229
00230 float fx = im.cols / width;
00231 float fy = im.rows / height;
00232 camera.f = (fx + fy) / 2;
00233 camera.k1 = camera.k2 = 0;
00234
00235 camera.t = cv::Mat::zeros(3, 1, CV_64F);
00236 DUtilsCV::Transformations::decomposeRt(cTo, camera.R, camera.t);
00237 }
00238
00239
00240
00241 void saveFace(const std::string &model_dir, int face_idx, const cv::Mat &img,
00242 const DVision::SurfSet &surfs, const std::vector<PLYPoint> &plypoints,
00243 const Camera &camera)
00244 {
00245 stringstream prefix;
00246 prefix << model_dir << "/face_" << setw(3) << setfill('0') << face_idx;
00247
00248 cv::imwrite(prefix.str() + ".png", img);
00249 surfs.Save(prefix.str() + ".key.gz");
00250 PLYFile::saveFile(prefix.str() + ".ply", plypoints);
00251 camera.save(prefix.str() + ".txt",
00252 "Fake camera. Assumes cx=w/2, cy=h/2, Z_object=1");
00253 }
00254
00255
00256