Creates a rectangular cuboid model. More...
#include "ros/ros.h"
#include <iostream>
#include <iomanip>
#include <vector>
#include <string>
#include <sstream>
#include <opencv/cv.h>
#include <opencv/highgui.h>
#include "../MetaFile.h"
#include "DUtils.h"
#include "DUtilsCV.h"
#include "DVision.h"
Go to the source code of this file.
Classes | |
struct | tParams |
struct | tParamsPatch |
Typedefs | |
typedef DVision::Bundle::CameraFile::Camera | Camera |
typedef DVision::PMVS::PLYFile | PLYFile |
typedef DVision::PMVS::PLYFile::PLYPoint | PLYPoint |
Functions | |
void | calculatePatchTransformations (std::vector< cv::Mat > &oTps, float W, float H, float D) |
void | createCamera (const cv::Mat &im, float width, float height, const cv::Mat &oTp, Camera &camera) |
void | createPLYpoints (const cv::Mat &img, float width, float height, const cv::Mat &oTp, const DVision::SurfSet &surfset, std::vector< PLYPoint > &plypoints) |
void | cropImage (cv::Mat &im, float ¤t_width, float ¤t_height, float max_width, float max_height) |
int | main (int argc, char *argv[]) |
bool | parseParams (int argc, char *argv[], tParams ¶ms) |
void | saveFace (const std::string &model_dir, int face_idx, const cv::Mat &img, const DVision::SurfSet &surfs, const std::vector< PLYPoint > &plypoints, const Camera &camera) |
Variables | |
static const int | DEFAULT_HESSIAN_THRESHOLD = 300 |
Creates a rectangular cuboid model.
Creates a recognition model of an object composed of several planes that form a rectangular cuboid. The model is defined by its faces and its width, height and depth.
This file is part of the RoboEarth ROS WP1 package.
It file was originally created for RoboEarth. The research leading to these results has received funding from the European Union Seventh Framework Programme FP7/2007-2013 under grant agreement no248942 RoboEarth.
Copyright (C) 2010 by Dorian Galvez-Lopez, University of Zaragoza
This program is free software: you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation, either version 3 of the License, or any later version.
This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public License along with this program. If not, see <http://www.gnu.org/licenses/>.
Definition in file createCubeModel.cpp.
Definition at line 78 of file createCubeModel.cpp.
typedef DVision::PMVS::PLYFile PLYFile |
Usage: createCubeModel <object name>=""> <Wo> <Ho> <Do> <output model="" dir>=""> {<patch a>=""> <wa> <ha> | - } [ ... [ {<patch f>=""> <wf> <hf> | - } ] ]
object name Wo, Ho, Do: real dimensions of the rectangular cuboid in metres (width, height and depth) output model dir: directory to store the model files patch X: path to the undistorted image of face X. wX, hX: real dimensions in metres of the image given for the face
The order of the faces and their orientation is documented here: http://www.roboearth.org/wiki/Re_vision:_Creating_object_recognition_models
Note: A patch can be skipped with a hyphen - Note: If the real dimensions of a patch are bigger than those of the corresponding face of the object, the image is cropped (anchor in the center) to make its dimensions consistent with the object. If the real dimensions of the patch are smaller than those of the object, the patch is assumed to be in the center of the corresponding face of the object.
Definition at line 76 of file createCubeModel.cpp.
Definition at line 77 of file createCubeModel.cpp.
void calculatePatchTransformations | ( | std::vector< cv::Mat > & | oTps, |
float | W, | ||
float | H, | ||
float | D | ||
) |
Computes the transformations to convert points from the general object reference to each patch local reference
oTps | vector with the 6 transformations in order (from A to F) |
W | |
H | |
D | real dimensions of the object |
Definition at line 360 of file createCubeModel.cpp.
void createCamera | ( | const cv::Mat & | im, |
float | width, | ||
float | height, | ||
const cv::Mat & | oTp, | ||
Camera & | camera | ||
) |
Creates a virtual camera that would watch a patch in the given pose The virtual camera is suposed to be oriented as the patch, at a distance of 1 metre
im | image |
width | |
height | real dimensions of the given image |
oTp | pose of patch in the object frame |
camera | virtual camera |
Definition at line 422 of file createCubeModel.cpp.
void createPLYpoints | ( | const cv::Mat & | img, |
float | width, | ||
float | height, | ||
const cv::Mat & | oTp, | ||
const DVision::SurfSet & | surfset, | ||
std::vector< PLYPoint > & | plypoints | ||
) |
Generates the 3D points of the given surf features. The 3D points are given in the object reference, located in the center of the object, x pointing right, y pointing down, z going away the camera.
img | source color image |
width | |
height | dimensions of the real object in metres. One dimension can be zero |
oTp | transformation from the object frame to this patch frame |
surfset | surfs extracted from img |
plypoint | created 3d points |
Definition at line 439 of file createCubeModel.cpp.
void cropImage | ( | cv::Mat & | im, |
float & | current_width, | ||
float & | current_height, | ||
float | max_width, | ||
float | max_height | ||
) |
Crops the given image so that it does not exceed the maximum dimensions
im | image |
current_width | (in/out) |
current_height | (in/out) current dimensions in metres of the image. They are updated with the final width and height |
max_width | |
max_height | desired dimensions in metres |
Definition at line 386 of file createCubeModel.cpp.
int main | ( | int | argc, |
char * | argv[] | ||
) |
Definition at line 182 of file createCubeModel.cpp.
bool parseParams | ( | int | argc, |
char * | argv[], | ||
tParams & | params | ||
) |
Parses the parameters given to the program
argc | |
argv | |
params | parameters obtained |
Definition at line 301 of file createCubeModel.cpp.
void saveFace | ( | const std::string & | model_dir, |
int | face_idx, | ||
const cv::Mat & | img, | ||
const DVision::SurfSet & | surfs, | ||
const std::vector< PLYPoint > & | plypoints, | ||
const Camera & | camera | ||
) |
Generates under the directory model_dir the files of one face of the model
model_dir | output model directory |
face_idx | index of this face |
img | face image |
surfs | surfs from img |
plypoints | 3d coords of the surfs keypoints |
camera | intrinsic parameters of camera |
Definition at line 499 of file createCubeModel.cpp.
const int DEFAULT_HESSIAN_THRESHOLD = 300 [static] |
Definition at line 178 of file createCubeModel.cpp.