SampleMarkerlessDetector.cpp
Go to the documentation of this file.
00001 #include "CvTestbed.h"
00002 #include "GlutViewer.h"
00003 #include "Shared.h"
00004 #include "FernImageDetector.h"
00005 #include "FernPoseEstimator.h"
00006 
00007 using namespace alvar;
00008 using namespace std;
00009 
00010 bool init = true;
00011 std::stringstream calibrationFilename;
00012 FernPoseEstimator fernEstimator;
00013 FernImageDetector fernDetector(true);
00014 Drawable d;
00015 cv::Mat gray;
00016 bool reset = false;
00017 
00018 void videocallback(IplImage *image)
00019 {
00020     bool flip_image = (image->origin?true:false);
00021     if (flip_image) {
00022         cvFlip(image);
00023         image->origin = !image->origin;
00024     }
00025 
00026     if (init) {
00027         init = false;
00028         cout << "Loading calibration: " << calibrationFilename.str();
00029         if (fernEstimator.setCalibration(calibrationFilename.str(), image->width, image->height)) {
00030             cout << " [Ok]" << endl;
00031         } else {
00032             fernEstimator.setResolution(image->width, image->height);
00033             cout << " [Fail]" << endl;
00034         }
00035         double p[16];
00036         fernEstimator.camera().GetOpenglProjectionMatrix(p, image->width, image->height);
00037         GlutViewer::SetGlProjectionMatrix(p);
00038         d.SetScale(10);
00039         gray = cv::Mat(image);
00040     }
00041 
00042     if (image->nChannels == 3) {
00043         cv::Mat img = cvarrToMat(image);
00044         cv::cvtColor(img, gray, CV_RGB2GRAY);
00045     }
00046     else {
00047         gray = image;
00048     }
00049 
00050     vector<CvPoint2D64f> ipts;
00051     vector<CvPoint3D64f> mpts;
00052 
00053     fernDetector.findFeatures(gray, true);
00054     fernDetector.imagePoints(ipts);
00055     fernDetector.modelPoints(mpts, true);
00056     double test = fernDetector.inlierRatio();
00057     if (test > 0.15 && mpts.size() > 4) {
00058         fernEstimator.calculateFromPointCorrespondences(mpts, ipts);
00059     }
00060 
00061     GlutViewer::DrawableClear();
00062     Pose pose = fernEstimator.pose();
00063     pose.GetMatrixGL(d.gl_mat);
00064     GlutViewer::DrawableAdd(&d);
00065 
00066     if (flip_image) {
00067         cvFlip(image);
00068         image->origin = !image->origin;
00069     }
00070 }
00071 
00072 int main(int argc, char *argv[])
00073 {
00074     try {
00075         // Output usage message
00076         std::string filename(argv[0]);
00077         filename = filename.substr(filename.find_last_of('\\') + 1);
00078         std::cout << "SampleMarkerlessDetector" << std::endl;
00079         std::cout << "========================" << std::endl;
00080         std::cout << std::endl;
00081         std::cout << "Description:" << std::endl;
00082         std::cout << "  This is an example of how to use the 'FernImageDetector' and" << std::endl;
00083         std::cout << "  'FernPoseEstimator' classes to detect and track an image and" << std::endl;
00084         std::cout << "  visualize it using 'GlutViewer'. The classification must first" << std::endl;
00085         std::cout << "  be trained with the SampleMarkerlessCreator sample and the" << std::endl;
00086         std::cout << "  resulting file passed as an argument to this sample." << std::endl;
00087         std::cout << std::endl;
00088         std::cout << "  For optimal results, a high quality USB camera or a Firewire" << std::endl;
00089         std::cout << "  camera is necessary. It is also advised to calibrate the camera" << std::endl;
00090         std::cout << "  using the SampleCamCalib sample. It should be noted that the size" << std::endl;
00091         std::cout << "  of the trained image will affect the optimal distance for detection." << std::endl;
00092         std::cout << std::endl;
00093         std::cout << "Usage:" << std::endl;
00094         std::cout << "  " << filename << " filename [device]" << std::endl;
00095         std::cout << std::endl;
00096         std::cout << "    filename the filename of classifier (.dat)" << std::endl;
00097         std::cout << "    device   integer selecting device from enumeration list (default 0)" << std::endl;
00098         std::cout << "             highgui capture devices are prefered" << std::endl;
00099         std::cout << std::endl;
00100         std::cout << "Keyboard Shortcuts:" << std::endl;
00101         std::cout << "  q: quit" << std::endl;
00102         std::cout << std::endl;
00103 
00104         if (argc < 2) {
00105             std::cout << "Filename not specified." << std::endl;
00106             return 0;
00107         }
00108         std::string classifierFilename(argv[1]);
00109 
00110         // Initialise GlutViewer and CvTestbed
00111         GlutViewer::Start(argc, argv, 640, 480);
00112         CvTestbed::Instance().SetVideoCallback(videocallback);
00113 
00114         // Enumerate possible capture plugins
00115         CaptureFactory::CapturePluginVector plugins = CaptureFactory::instance()->enumeratePlugins();
00116         if (plugins.size() < 1) {
00117             std::cout << "Could not find any capture plugins." << std::endl;
00118             return 0;
00119         }
00120 
00121         // Display capture plugins
00122         std::cout << "Available Plugins: ";
00123         outputEnumeratedPlugins(plugins);
00124         std::cout << std::endl;
00125 
00126         // Enumerate possible capture devices
00127         CaptureFactory::CaptureDeviceVector devices = CaptureFactory::instance()->enumerateDevices();
00128         if (devices.size() < 1) {
00129             std::cout << "Could not find any capture devices." << std::endl;
00130             return 0;
00131         }
00132 
00133         // Check command line argument for which device to use
00134         int selectedDevice = defaultDevice(devices);
00135         if (argc > 2) {
00136             selectedDevice = atoi(argv[2]);
00137         }
00138         if (selectedDevice >= (int)devices.size()) {
00139             selectedDevice = defaultDevice(devices);
00140         }
00141         
00142         // Display capture devices
00143         std::cout << "Enumerated Capture Devices:" << std::endl;
00144         outputEnumeratedDevices(devices, selectedDevice);
00145         std::cout << std::endl;
00146         
00147         // Create capture object from camera
00148         Capture *cap = CaptureFactory::instance()->createCapture(devices[selectedDevice]);
00149         std::string uniqueName = devices[selectedDevice].uniqueName();
00150 
00151         // Handle capture lifecycle and start video capture
00152         // Note that loadSettings/saveSettings are not supported by all plugins
00153         if (cap) {
00154             std::cout << "Loading classifier." << std::endl;
00155             if (!fernDetector.read(classifierFilename)) {
00156                 std::cout << "Loading classifier failed." << std::endl;
00157                 cap->stop();
00158                 delete cap;
00159                 return 1;
00160             }
00161 
00162             std::stringstream settingsFilename;
00163             settingsFilename << "camera_settings_" << uniqueName << ".xml";
00164             calibrationFilename << "camera_calibration_" << uniqueName << ".xml";
00165             
00166             cap->start();
00167             cap->setResolution(640, 480);
00168             
00169             if (cap->loadSettings(settingsFilename.str())) {
00170                 std::cout << "Loading settings: " << settingsFilename.str() << std::endl;
00171             }
00172 
00173             std::stringstream title;
00174             title << "SampleMarkerDetector (" << cap->captureDevice().captureType() << ")";
00175 
00176             CvTestbed::Instance().StartVideo(cap, title.str().c_str());
00177 
00178             if (cap->saveSettings(settingsFilename.str())) {
00179                 std::cout << "Saving settings: " << settingsFilename.str() << std::endl;
00180             }
00181 
00182             cap->stop();
00183             delete cap;
00184         }
00185         else if (CvTestbed::Instance().StartVideo(0, argv[0])) {
00186         }
00187         else {
00188             std::cout << "Could not initialize the selected capture backend." << std::endl;
00189         }
00190 
00191         return 0;
00192     }
00193     catch (const std::exception &e) {
00194         std::cout << "Exception: " << e.what() << endl;
00195     }
00196     catch (...) {
00197         std::cout << "Exception: unknown" << std::endl;
00198     }
00199 }


ar_track_alvar
Author(s): Scott Niekum
autogenerated on Thu Jun 6 2019 21:12:54