|
| 1 | +/** |
| 2 | +* This file is a modified version of ORB-SLAM2.<https://github.com/raulmur/ORB_SLAM2> |
| 3 | +* |
| 4 | +* This file is part of DynaSLAM. |
| 5 | +* Copyright (C) 2018 Berta Bescos <bbescos at unizar dot es> (University of Zaragoza) |
| 6 | +* For more information see <https://github.com/bertabescos/DynaSLAM>. |
| 7 | +* |
| 8 | +*/ |
| 9 | + |
| 10 | + |
| 11 | +#include<iostream> |
| 12 | +#include<algorithm> |
| 13 | +#include<fstream> |
| 14 | +#include<chrono> |
| 15 | +#include<iomanip> |
| 16 | +#include <unistd.h> |
| 17 | +#include<opencv2/core/core.hpp> |
| 18 | + |
| 19 | +#include "Geometry.h" |
| 20 | +#include "MaskNet.h" |
| 21 | +#include"System.h" |
| 22 | + |
| 23 | +using namespace std; |
| 24 | + |
| 25 | +void LoadImages(const string &strSequence, vector<string> &vstrImageFilenames, |
| 26 | + vector<double> &vTimestamps); |
| 27 | + |
| 28 | +int main(int argc, char **argv) |
| 29 | +{ |
| 30 | + if(argc != 4 && argc != 5) |
| 31 | + { |
| 32 | + cerr << endl << "Usage: ./mono_carla path_to_vocabulary path_to_settings path_to_sequence (path_to_masks)" << endl; |
| 33 | + return 1; |
| 34 | + } |
| 35 | + |
| 36 | + // Retrieve paths to images |
| 37 | + vector<string> vstrImageFilenames; |
| 38 | + vector<double> vTimestamps; |
| 39 | + LoadImages(string(argv[3]), vstrImageFilenames, vTimestamps); |
| 40 | + |
| 41 | + int nImages = vstrImageFilenames.size(); |
| 42 | + |
| 43 | + // Initialize Mask R-CNN |
| 44 | + DynaSLAM::SegmentDynObject *MaskNet; |
| 45 | + if (argc==5) |
| 46 | + { |
| 47 | + cout << "Loading Mask R-CNN. This could take a while..." << endl; |
| 48 | + MaskNet = new DynaSLAM::SegmentDynObject(); |
| 49 | + cout << "Mask R-CNN loaded!" << endl; |
| 50 | + } |
| 51 | + |
| 52 | + // Create SLAM system. It initializes all system threads and gets ready to process frames. |
| 53 | + ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::MONOCULAR,true); |
| 54 | + |
| 55 | + // Vector for tracking time statistics |
| 56 | + vector<float> vTimesTrack; |
| 57 | + vTimesTrack.resize(nImages); |
| 58 | + |
| 59 | + cout << endl << "-------" << endl; |
| 60 | + cout << "Start processing sequence ..." << endl; |
| 61 | + cout << "Images in the sequence: " << nImages << endl << endl; |
| 62 | + |
| 63 | + // Main loop |
| 64 | + cv::Mat im; |
| 65 | + |
| 66 | + // Dilation settings |
| 67 | + int dilation_size = 15; |
| 68 | + cv::Mat kernel = getStructuringElement(cv::MORPH_ELLIPSE, |
| 69 | + cv::Size( 2*dilation_size + 1, 2*dilation_size+1 ), |
| 70 | + cv::Point( dilation_size, dilation_size ) ); |
| 71 | + |
| 72 | + for(int ni=0; ni<nImages; ni++) |
| 73 | + { |
| 74 | + // Read image from file |
| 75 | + im = cv::imread(vstrImageFilenames[ni],CV_LOAD_IMAGE_UNCHANGED); |
| 76 | + double tframe = vTimestamps[ni]; |
| 77 | + |
| 78 | + if(im.empty()) |
| 79 | + { |
| 80 | + cerr << endl << "Failed to load image at: " << vstrImageFilenames[ni] << endl; |
| 81 | + return 1; |
| 82 | + } |
| 83 | + |
| 84 | +#ifdef COMPILEDWITHC11 |
| 85 | + std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); |
| 86 | +#else |
| 87 | + std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now(); |
| 88 | +#endif |
| 89 | + |
| 90 | + // Segment out the images |
| 91 | + int h = im.rows; |
| 92 | + int w = im.cols; |
| 93 | + cv::Mat mask = cv::Mat::ones(h,w,CV_8U); |
| 94 | + if(argc == 5) |
| 95 | + { |
| 96 | + cv::Mat maskRCNN; |
| 97 | + maskRCNN = MaskNet->GetSegmentation(im,string(argv[4]),vstrImageFilenames[ni].replace( |
| 98 | + vstrImageFilenames[ni].begin(), vstrImageFilenames[ni].end()-10,"")); |
| 99 | + cv::Mat maskRCNNdil = maskRCNN.clone(); |
| 100 | + cv::dilate(maskRCNN, maskRCNNdil, kernel); |
| 101 | + mask = mask - maskRCNN; |
| 102 | + } |
| 103 | + |
| 104 | + // Pass the image to the SLAM system |
| 105 | + SLAM.TrackMonocular(im, mask, tframe); |
| 106 | + |
| 107 | +#ifdef COMPILEDWITHC11 |
| 108 | + std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now(); |
| 109 | +#else |
| 110 | + std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now(); |
| 111 | +#endif |
| 112 | + |
| 113 | + double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count(); |
| 114 | + |
| 115 | + vTimesTrack[ni]=ttrack; |
| 116 | + |
| 117 | + // Wait to load the next frame |
| 118 | + double T=0; |
| 119 | + if(ni<nImages-1) |
| 120 | + T = vTimestamps[ni+1]-tframe; |
| 121 | + else if(ni>0) |
| 122 | + T = tframe-vTimestamps[ni-1]; |
| 123 | + |
| 124 | + if(ttrack<T) |
| 125 | + usleep((T-ttrack)*1e6); |
| 126 | + } |
| 127 | + |
| 128 | + // Stop all threads |
| 129 | + SLAM.Shutdown(); |
| 130 | + |
| 131 | + // Tracking time statistics |
| 132 | + sort(vTimesTrack.begin(),vTimesTrack.end()); |
| 133 | + float totaltime = 0; |
| 134 | + for(int ni=0; ni<nImages; ni++) |
| 135 | + { |
| 136 | + totaltime+=vTimesTrack[ni]; |
| 137 | + } |
| 138 | + cout << "-------" << endl << endl; |
| 139 | + cout << "median tracking time: " << vTimesTrack[nImages/2] << endl; |
| 140 | + cout << "mean tracking time: " << totaltime/nImages << endl; |
| 141 | + |
| 142 | + // Save camera trajectory |
| 143 | + SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt"); |
| 144 | + |
| 145 | + return 0; |
| 146 | +} |
| 147 | + |
| 148 | +void LoadImages(const string &strPathToSequence, vector<string> &vstrImageFilenames, vector<double> &vTimestamps) |
| 149 | +{ |
| 150 | + ifstream fTimes; |
| 151 | + string strPathTimeFile = strPathToSequence + "/times.txt"; |
| 152 | + fTimes.open(strPathTimeFile.c_str()); |
| 153 | + while(!fTimes.eof()) |
| 154 | + { |
| 155 | + string s; |
| 156 | + getline(fTimes,s); |
| 157 | + if(!s.empty()) |
| 158 | + { |
| 159 | + stringstream ss; |
| 160 | + ss << s; |
| 161 | + double t; |
| 162 | + ss >> t; |
| 163 | + vTimestamps.push_back(t); |
| 164 | + } |
| 165 | + } |
| 166 | + |
| 167 | + string strPrefixLeft = strPathToSequence + "/image_0/"; |
| 168 | + |
| 169 | + const int nTimes = vTimestamps.size(); |
| 170 | + vstrImageFilenames.resize(nTimes); |
| 171 | + |
| 172 | + for(int i=0; i<nTimes; i++) |
| 173 | + { |
| 174 | + stringstream ss; |
| 175 | + ss << setfill('0') << setw(6) << i; |
| 176 | + vstrImageFilenames[i] = strPrefixLeft + ss.str() + ".png"; |
| 177 | + } |
| 178 | +} |
| 179 | + |
0 commit comments