Skip to content

Commit bc169c0

Browse files
committedNov 9, 2018
CARLA example
1 parent 4cfc0cc commit bc169c0

File tree

3 files changed

+248
-1
lines changed

3 files changed

+248
-1
lines changed
 

‎CMakeLists.txt

+12-1
Original file line numberDiff line numberDiff line change
@@ -32,11 +32,13 @@ endif()
3232

3333
LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules)
3434

35+
message("PROJECT_SOURCE_DIR: " ${OpenCV_DIR})
3536
find_package(OpenCV 2.4.11 QUIET)
3637
if(NOT OpenCV_FOUND)
38+
message("OpenCV > 2.4.11 not found.")
3739
find_package(OpenCV 3.0 QUIET)
3840
if(NOT OpenCV_FOUND)
39-
message(FATAL_ERROR "OpenCV > 2.4.11 not found.")
41+
message(FATAL_ERROR "OpenCV > 3.0 not found.")
4042
endif()
4143
endif()
4244

@@ -48,6 +50,11 @@ endif()
4850
# endif()
4951
#endif()
5052

53+
find_package(Qt5Widgets REQUIRED)
54+
find_package(Qt5Concurrent REQUIRED)
55+
find_package(Qt5OpenGL REQUIRED)
56+
find_package(Qt5Test REQUIRED)
57+
5158
find_package(PythonLibs REQUIRED)
5259
if (NOT PythonLibs_FOUND)
5360
message(FATAL_ERROR "PYTHON LIBS not found.")
@@ -140,3 +147,7 @@ add_executable(mono_kitti
140147
Examples/Monocular/mono_kitti.cc)
141148
target_link_libraries(mono_kitti ${PROJECT_NAME})
142149

150+
add_executable(mono_carla
151+
Examples/Monocular/mono_carla.cc)
152+
target_link_libraries(mono_carla ${PROJECT_NAME})
153+

‎Examples/Monocular/CARLA.yaml

+57
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,57 @@
1+
%YAML:1.0
2+
3+
#--------------------------------------------------------------------------------------------
4+
# Camera Parameters. Adjust them!
5+
#--------------------------------------------------------------------------------------------
6+
7+
# Camera calibration and distortion parameters (OpenCV)
8+
Camera.fx: 400
9+
Camera.fy: 400
10+
Camera.cx: 400
11+
Camera.cy: 300
12+
13+
Camera.k1: 0.0
14+
Camera.k2: 0.0
15+
Camera.p1: 0.0
16+
Camera.p2: 0.0
17+
18+
# Camera frames per second
19+
Camera.fps: 10.0
20+
21+
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
22+
Camera.RGB: 1
23+
24+
#--------------------------------------------------------------------------------------------
25+
# ORB Parameters
26+
#--------------------------------------------------------------------------------------------
27+
28+
# ORB Extractor: Number of features per image
29+
ORBextractor.nFeatures: 2000
30+
31+
# ORB Extractor: Scale factor between levels in the scale pyramid
32+
ORBextractor.scaleFactor: 1.2
33+
34+
# ORB Extractor: Number of levels in the scale pyramid
35+
ORBextractor.nLevels: 8
36+
37+
# ORB Extractor: Fast threshold
38+
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
39+
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
40+
# You can lower these values if your images have low contrast
41+
ORBextractor.iniThFAST: 20
42+
ORBextractor.minThFAST: 7
43+
44+
#--------------------------------------------------------------------------------------------
45+
# Viewer Parameters
46+
#--------------------------------------------------------------------------------------------
47+
Viewer.KeyFrameSize: 0.1
48+
Viewer.KeyFrameLineWidth: 1
49+
Viewer.GraphLineWidth: 1
50+
Viewer.PointSize: 2
51+
Viewer.CameraSize: 0.15
52+
Viewer.CameraLineWidth: 2
53+
Viewer.ViewpointX: 0
54+
Viewer.ViewpointY: -10
55+
Viewer.ViewpointZ: -0.1
56+
Viewer.ViewpointF: 2000
57+

‎Examples/Monocular/mono_carla.cc

+179
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,179 @@
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

Comments
 (0)
Please sign in to comment.