Skip to content

Commit

Permalink
fix build
Browse files Browse the repository at this point in the history
  • Loading branch information
poifull10 committed Apr 4, 2020
1 parent f2e6f51 commit 57c551e
Show file tree
Hide file tree
Showing 13 changed files with 1,509 additions and 1,493 deletions.
84 changes: 44 additions & 40 deletions Examples/Monocular/mono_euroc.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,15 +18,15 @@
* along with ORB-SLAM2. If not, see <http://www.gnu.org/licenses/>.
*/

#include <iostream>
#include <algorithm>
#include <fstream>
#include <chrono>
#include "unistd.h"

#include<iostream>
#include<algorithm>
#include<fstream>
#include<chrono>
#include <opencv2/core/core.hpp>

#include<opencv2/core/core.hpp>

#include<System.h>
#include <System.h>

using namespace std;

Expand All @@ -35,9 +35,10 @@ void LoadImages(const string &strImagePath, const string &strPathTimes,

int main(int argc, char **argv)
{
if(argc != 5)
if (argc != 5)
{
cerr << endl << "Usage: ./mono_tum path_to_vocabulary path_to_settings path_to_image_folder path_to_times_file" << endl;
cerr << endl
<< "Usage: ./mono_tum path_to_vocabulary path_to_settings path_to_image_folder path_to_times_file" << endl;
return 1;
}

Expand All @@ -48,35 +49,38 @@ int main(int argc, char **argv)

int nImages = vstrImageFilenames.size();

if(nImages<=0)
if (nImages <= 0)
{
cerr << "ERROR: Failed to load images" << endl;
return 1;
}

// Create SLAM system. It initializes all system threads and gets ready to process frames.
ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::MONOCULAR,true);
ORB_SLAM2::System SLAM(argv[1], argv[2], ORB_SLAM2::System::MONOCULAR, true);

// Vector for tracking time statistics
vector<float> vTimesTrack;
vTimesTrack.resize(nImages);

cout << endl << "-------" << endl;
cout << endl
<< "-------" << endl;
cout << "Start processing sequence ..." << endl;
cout << "Images in the sequence: " << nImages << endl << endl;
cout << "Images in the sequence: " << nImages << endl
<< endl;

// Main loop
cv::Mat im;
for(int ni=0; ni<nImages; ni++)
for (int ni = 0; ni < nImages; ni++)
{
// Read image from file
im = cv::imread(vstrImageFilenames[ni],CV_LOAD_IMAGE_UNCHANGED);
im = cv::imread(vstrImageFilenames[ni], CV_LOAD_IMAGE_UNCHANGED);
double tframe = vTimestamps[ni];

if(im.empty())
if (im.empty())
{
cerr << endl << "Failed to load image at: "
<< vstrImageFilenames[ni] << endl;
cerr << endl
<< "Failed to load image at: "
<< vstrImageFilenames[ni] << endl;
return 1;
}

Expand All @@ -87,42 +91,43 @@ int main(int argc, char **argv)
#endif

// Pass the image to the SLAM system
SLAM.TrackMonocular(im,tframe);
SLAM.TrackMonocular(im, tframe);

#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
#endif

double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
double ttrack = std::chrono::duration_cast<std::chrono::duration<double>>(t2 - t1).count();

vTimesTrack[ni]=ttrack;
vTimesTrack[ni] = ttrack;

// Wait to load the next frame
double T=0;
if(ni<nImages-1)
T = vTimestamps[ni+1]-tframe;
else if(ni>0)
T = tframe-vTimestamps[ni-1];

if(ttrack<T)
usleep((T-ttrack)*1e6);
double T = 0;
if (ni < nImages - 1)
T = vTimestamps[ni + 1] - tframe;
else if (ni > 0)
T = tframe - vTimestamps[ni - 1];

if (ttrack < T)
usleep((T - ttrack) * 1e6);
}

// Stop all threads
SLAM.Shutdown();

// Tracking time statistics
sort(vTimesTrack.begin(),vTimesTrack.end());
sort(vTimesTrack.begin(), vTimesTrack.end());
float totaltime = 0;
for(int ni=0; ni<nImages; ni++)
for (int ni = 0; ni < nImages; ni++)
{
totaltime+=vTimesTrack[ni];
totaltime += vTimesTrack[ni];
}
cout << "-------" << endl << endl;
cout << "median tracking time: " << vTimesTrack[nImages/2] << endl;
cout << "mean tracking time: " << totaltime/nImages << endl;
cout << "-------" << endl
<< endl;
cout << "median tracking time: " << vTimesTrack[nImages / 2] << endl;
cout << "mean tracking time: " << totaltime / nImages << endl;

// Save camera trajectory
SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");
Expand All @@ -137,19 +142,18 @@ void LoadImages(const string &strImagePath, const string &strPathTimes,
fTimes.open(strPathTimes.c_str());
vTimeStamps.reserve(5000);
vstrImages.reserve(5000);
while(!fTimes.eof())
while (!fTimes.eof())
{
string s;
getline(fTimes,s);
if(!s.empty())
getline(fTimes, s);
if (!s.empty())
{
stringstream ss;
ss << s;
vstrImages.push_back(strImagePath + "/" + ss.str() + ".png");
double t;
ss >> t;
vTimeStamps.push_back(t/1e9);

vTimeStamps.push_back(t / 1e9);
}
}
}
83 changes: 44 additions & 39 deletions Examples/Monocular/mono_kitti.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,16 +18,16 @@
* along with ORB-SLAM2. If not, see <http://www.gnu.org/licenses/>.
*/

#include <iostream>
#include <algorithm>
#include <fstream>
#include <chrono>
#include <iomanip>
#include "unistd.h"

#include<iostream>
#include<algorithm>
#include<fstream>
#include<chrono>
#include<iomanip>
#include <opencv2/core/core.hpp>

#include<opencv2/core/core.hpp>

#include"System.h"
#include "System.h"

using namespace std;

Expand All @@ -36,9 +36,10 @@ void LoadImages(const string &strSequence, vector<string> &vstrImageFilenames,

int main(int argc, char **argv)
{
if(argc != 4)
if (argc != 4)
{
cerr << endl << "Usage: ./mono_kitti path_to_vocabulary path_to_settings path_to_sequence" << endl;
cerr << endl
<< "Usage: ./mono_kitti path_to_vocabulary path_to_settings path_to_sequence" << endl;
return 1;
}

Expand All @@ -50,27 +51,30 @@ int main(int argc, char **argv)
int nImages = vstrImageFilenames.size();

// Create SLAM system. It initializes all system threads and gets ready to process frames.
ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::MONOCULAR,true);
ORB_SLAM2::System SLAM(argv[1], argv[2], ORB_SLAM2::System::MONOCULAR, true);

// Vector for tracking time statistics
vector<float> vTimesTrack;
vTimesTrack.resize(nImages);

cout << endl << "-------" << endl;
cout << endl
<< "-------" << endl;
cout << "Start processing sequence ..." << endl;
cout << "Images in the sequence: " << nImages << endl << endl;
cout << "Images in the sequence: " << nImages << endl
<< endl;

// Main loop
cv::Mat im;
for(int ni=0; ni<nImages; ni++)
for (int ni = 0; ni < nImages; ni++)
{
// Read image from file
im = cv::imread(vstrImageFilenames[ni],CV_LOAD_IMAGE_UNCHANGED);
im = cv::imread(vstrImageFilenames[ni], CV_LOAD_IMAGE_UNCHANGED);
double tframe = vTimestamps[ni];

if(im.empty())
if (im.empty())
{
cerr << endl << "Failed to load image at: " << vstrImageFilenames[ni] << endl;
cerr << endl
<< "Failed to load image at: " << vstrImageFilenames[ni] << endl;
return 1;
}

Expand All @@ -81,45 +85,46 @@ int main(int argc, char **argv)
#endif

// Pass the image to the SLAM system
SLAM.TrackMonocular(im,tframe);
SLAM.TrackMonocular(im, tframe);

#ifdef COMPILEDWITHC11
std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
#endif

double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
double ttrack = std::chrono::duration_cast<std::chrono::duration<double>>(t2 - t1).count();

vTimesTrack[ni]=ttrack;
vTimesTrack[ni] = ttrack;

// Wait to load the next frame
double T=0;
if(ni<nImages-1)
T = vTimestamps[ni+1]-tframe;
else if(ni>0)
T = tframe-vTimestamps[ni-1];

if(ttrack<T)
usleep((T-ttrack)*1e6);
double T = 0;
if (ni < nImages - 1)
T = vTimestamps[ni + 1] - tframe;
else if (ni > 0)
T = tframe - vTimestamps[ni - 1];

if (ttrack < T)
usleep((T - ttrack) * 1e6);
}

// Stop all threads
SLAM.Shutdown();

// Tracking time statistics
sort(vTimesTrack.begin(),vTimesTrack.end());
sort(vTimesTrack.begin(), vTimesTrack.end());
float totaltime = 0;
for(int ni=0; ni<nImages; ni++)
for (int ni = 0; ni < nImages; ni++)
{
totaltime+=vTimesTrack[ni];
totaltime += vTimesTrack[ni];
}
cout << "-------" << endl << endl;
cout << "median tracking time: " << vTimesTrack[nImages/2] << endl;
cout << "mean tracking time: " << totaltime/nImages << endl;
cout << "-------" << endl
<< endl;
cout << "median tracking time: " << vTimesTrack[nImages / 2] << endl;
cout << "mean tracking time: " << totaltime / nImages << endl;

// Save camera trajectory
SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");
SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");

return 0;
}
Expand All @@ -129,11 +134,11 @@ void LoadImages(const string &strPathToSequence, vector<string> &vstrImageFilena
ifstream fTimes;
string strPathTimeFile = strPathToSequence + "/times.txt";
fTimes.open(strPathTimeFile.c_str());
while(!fTimes.eof())
while (!fTimes.eof())
{
string s;
getline(fTimes,s);
if(!s.empty())
getline(fTimes, s);
if (!s.empty())
{
stringstream ss;
ss << s;
Expand All @@ -148,7 +153,7 @@ void LoadImages(const string &strPathToSequence, vector<string> &vstrImageFilena
const int nTimes = vTimestamps.size();
vstrImageFilenames.resize(nTimes);

for(int i=0; i<nTimes; i++)
for (int i = 0; i < nTimes; i++)
{
stringstream ss;
ss << setfill('0') << setw(6) << i;
Expand Down
Loading

0 comments on commit 57c551e

Please sign in to comment.