main.cpp
Go to the documentation of this file.
00001 #include <stdio.h>
00002 #include <stdlib.h>
00003 #include <string.h>
00004 #include <signal.h>
00005 
00006 #include <iostream>
00007 #include <string>
00008 
00009 #include <fovis/fovis.hpp>
00010 
00011 #include "data_capture.hpp"
00012 
00013 #define dbg(...) fprintf(stderr, __VA_ARGS__)
00014 
00015 sig_atomic_t shutdown_flag = 0;
00016 static void
00017 sig_action(int signal, siginfo_t *s, void *user)
00018 {
00019   shutdown_flag = 1;
00020 }
00021 
00022 std::string
00023 isometryToString(const Eigen::Isometry3d& m)
00024 {
00025   char result[80];
00026   memset(result, 0, sizeof(result));
00027   Eigen::Vector3d xyz = m.translation();
00028   Eigen::Vector3d rpy = m.rotation().eulerAngles(0, 1, 2);
00029   snprintf(result, 79, "%6.2f %6.2f %6.2f %6.2f %6.2f %6.2f",
00030       xyz(0), xyz(1), xyz(2),
00031       rpy(0) * 180/M_PI, rpy(1) * 180/M_PI, rpy(2) * 180/M_PI);
00032   return std::string(result);
00033 }
00034 
00035 int main(int argc, char **argv)
00036 {
00037   // initialize the device
00038   fovis_example::DataCapture* cap = new fovis_example::DataCapture();
00039   if(!cap->initialize()) {
00040     fprintf(stderr, "Unable to initialize Kinect sensor\n");
00041     return 1;
00042   }
00043   if(!cap->startDataCapture()) {
00044     fprintf(stderr, "Unable to start data capture\n");
00045     return 1;
00046   }
00047 
00048   // get the RGB camera parameters of our device
00049   fovis::Rectification rect(cap->getRgbParameters());
00050 
00051   fovis::VisualOdometryOptions options =
00052       fovis::VisualOdometry::getDefaultOptions();
00053   // If we wanted to play around with the different VO parameters, we could set
00054   // them here in the "options" variable.
00055 
00056   // setup the visual odometry
00057   fovis::VisualOdometry* odom = new fovis::VisualOdometry(&rect, options);
00058 
00059   // exit cleanly on CTL-C
00060   struct sigaction new_action;
00061   new_action.sa_sigaction = sig_action;
00062   sigemptyset(&new_action.sa_mask);
00063   new_action.sa_flags = 0;
00064   sigaction(SIGINT, &new_action, NULL);
00065   sigaction(SIGTERM, &new_action, NULL);
00066   sigaction(SIGHUP, &new_action, NULL);
00067 
00068   while(!shutdown_flag) {
00069     if(!cap->captureOne()) {
00070       fprintf(stderr, "Capture failed\n");
00071       break;
00072     }
00073 
00074     odom->processFrame(cap->getGrayImage(), cap->getDepthImage());
00075 
00076     // get the integrated pose estimate.
00077     Eigen::Isometry3d cam_to_local = odom->getPose();
00078 
00079     // get the motion estimate for this frame to the previous frame.
00080     Eigen::Isometry3d motion_estimate = odom->getMotionEstimate();
00081 
00082     // display the motion estimate.  These values are all given in the RGB
00083     // camera frame, where +Z is forward, +X points right, +Y points down, and
00084     // the origin is located at the focal point of the RGB camera.
00085     std::cout << isometryToString(cam_to_local) << " " <<
00086       isometryToString(motion_estimate) << "\n";
00087   }
00088 
00089   printf("Shutting down\n");
00090   cap->stopDataCapture();
00091   delete odom;
00092   delete cap;
00093   return 0;
00094 }


libfovis
Author(s): Albert Huang, Maurice Fallon
autogenerated on Thu Jun 6 2019 20:16:12