Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
32 commits
Select commit Hold shift + click to select a range
482ec9e
Remove unused variable
Soldann Jul 14, 2022
112c795
Do minor cleaning of frame constructor
DavidPetkovsek Jul 26, 2022
105ec8c
Pragma once, remove config.cc and .h
DavidPetkovsek Jul 26, 2022
3f89307
Add isInertial & hasMulticam to CameraType
DavidPetkovsek Jul 26, 2022
98d7fd3
Increase efficiency of frame ctor
DavidPetkovsek Jul 26, 2022
18d924e
build.sh
Soldann Jul 26, 2022
eacb18c
Move static initializer before exit early
DavidPetkovsek Jul 26, 2022
7c08658
Fix adding keypoints to _keypoints
DavidPetkovsek Jul 26, 2022
693b99d
Update frame ctor to init all vars
DavidPetkovsek Jul 26, 2022
6fb0d9d
Merge branch 'master' into 54-better-pointer-thread-management
DavidPetkovsek Jul 26, 2022
70a2d26
Clean up & change static cast NULL to nullptr
DavidPetkovsek Jul 26, 2022
924eea5
Merge branch '54-better-pointer-thread-management' of github.com:Sold…
Soldann Jul 26, 2022
dc7147e
NULL to nullptr
DavidPetkovsek Jul 26, 2022
d08474d
Add Camera class that handles ExtractORB threads
DavidPetkovsek Jul 26, 2022
288e985
Merge branch '54-better-pointer-thread-management' of github.com:Sold…
Soldann Jul 27, 2022
7efa8c9
Fixed mutex initialization and destruction issues
DavidPetkovsek Jul 27, 2022
fb73114
Merge branch '54-better-pointer-thread-management' of github.com:Sold…
Soldann Jul 27, 2022
d8ee34f
remove empty covisible list print
Soldann Jul 27, 2022
0e58055
Removed potential memory leak candidates: mpORBextractorLeft, mpORBex…
DavidPetkovsek Jul 28, 2022
60ec46b
Changed some params/functions to const refs/functions
DavidPetkovsek Jul 28, 2022
55cb4c2
reverted the change to make it work
Ryan-Red Jul 28, 2022
52de2ff
reverted the revert to the change and uncommented line
ethanseq Jul 28, 2022
c094fe5
Checked optimizer.cc for potential memory leaks and converted frame m…
DavidPetkovsek Jul 29, 2022
57243c2
Merge branch '54-better-pointer-thread-management' of github.com:Sold…
DavidPetkovsek Jul 29, 2022
2a528de
Changed Map to be a shared pointer
DavidPetkovsek Aug 2, 2022
75eb60a
Fix immediate sophus error
DavidPetkovsek Aug 3, 2022
fca3753
No more sophus error
DavidPetkovsek Aug 5, 2022
bb3e541
Changed namespace from ORB_SLAM3 to MORB_SLAM and got correct pose va…
Soldann Aug 8, 2022
444f9c9
Changed prefix for project header files to MORB_SLAM
DavidPetkovsek Aug 8, 2022
d414eea
merge
DavidPetkovsek Aug 8, 2022
9cefbe9
revert header files from merge
Soldann Aug 8, 2022
88a7ec1
add include
Soldann Aug 8, 2022
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 8 additions & 8 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -45,20 +45,20 @@ Examples/Stereo-Inertial/stereo_inertial_realsense_t265
Examples/Stereo-Inertial/stereo_inertial_realsense_D435i


Examples/ROS/ORB_SLAM3/Mono
Examples/ROS/ORB_SLAM3/Mono_Inertial
Examples/ROS/ORB_SLAM3/MonoAR
Examples/ROS/ORB_SLAM3/RGBD
Examples/ROS/ORB_SLAM3/Stereo
Examples/ROS/ORB_SLAM3/Stereo_Inertial
Examples/ROS/MORB_SLAM/Mono
Examples/ROS/MORB_SLAM/Mono_Inertial
Examples/ROS/MORB_SLAM/MonoAR
Examples/ROS/MORB_SLAM/RGBD
Examples/ROS/MORB_SLAM/Stereo
Examples/ROS/MORB_SLAM/Stereo_Inertial

Examples/Calibration/recorder_realsense_D435i

Examples/Tests/viewer_dataset
Examples/Tests/sophus_test

Examples/ROS/ORB_SLAM3/CMakeLists.txt.user
Examples/ROS/ORB_SLAM3/build/
Examples/ROS/MORB_SLAM/CMakeLists.txt.user
Examples/ROS/MORB_SLAM/build/

KeyFrameTrajectory.txt
CameraTrajectory.txt
Expand Down
64 changes: 32 additions & 32 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ endif()

LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules)

find_package(OpenCV 4.4)
find_package(OpenCV 4.2)
if(NOT OpenCV_FOUND)
message(FATAL_ERROR "OpenCV > 4.4 not found.")
endif()
Expand All @@ -50,6 +50,7 @@ find_package(realsense2)

add_library(${PROJECT_NAME} SHARED
src/System.cc
src/Camera.cpp
src/Tracking.cc
src/LocalMapping.cc
src/LoopClosing.cc
Expand All @@ -75,38 +76,37 @@ src/OptimizableTypes.cpp
src/MLPnPsolver.cpp
src/GeometricTools.cc
src/TwoViewReconstruction.cc
src/Config.cc
src/Settings.cc
include/System.h
include/Tracking.h
include/LocalMapping.h
include/LoopClosing.h
include/ORBextractor.h
include/ORBmatcher.h
include/FrameDrawer.h
include/Converter.h
include/MapPoint.h
include/KeyFrame.h
include/Atlas.h
include/Map.h
include/MapDrawer.h
include/Optimizer.h
include/Frame.h
include/KeyFrameDatabase.h
include/Sim3Solver.h
include/Viewer.h
include/ImuTypes.h
include/G2oTypes.h
include/CameraModels/GeometricCamera.h
include/CameraModels/Pinhole.h
include/CameraModels/KannalaBrandt8.h
include/OptimizableTypes.h
include/MLPnPsolver.h
include/GeometricTools.h
include/TwoViewReconstruction.h
include/SerializationUtils.h
include/Config.h
include/Settings.h)
include/MORB_SLAM/System.h
include/MORB_SLAM/Camera.hpp
include/MORB_SLAM/Tracking.h
include/MORB_SLAM/LocalMapping.h
include/MORB_SLAM/LoopClosing.h
include/MORB_SLAM/ORBextractor.h
include/MORB_SLAM/ORBmatcher.h
include/MORB_SLAM/FrameDrawer.h
include/MORB_SLAM/Converter.h
include/MORB_SLAM/MapPoint.h
include/MORB_SLAM/KeyFrame.h
include/MORB_SLAM/Atlas.h
include/MORB_SLAM/Map.h
include/MORB_SLAM/MapDrawer.h
include/MORB_SLAM/Optimizer.h
include/MORB_SLAM/Frame.h
include/MORB_SLAM/KeyFrameDatabase.h
include/MORB_SLAM/Sim3Solver.h
include/MORB_SLAM/Viewer.h
include/MORB_SLAM/ImuTypes.h
include/MORB_SLAM/G2oTypes.h
include/MORB_SLAM/CameraModels/GeometricCamera.h
include/MORB_SLAM/CameraModels/Pinhole.h
include/MORB_SLAM/CameraModels/KannalaBrandt8.h
include/MORB_SLAM/OptimizableTypes.h
include/MORB_SLAM/MLPnPsolver.h
include/MORB_SLAM/GeometricTools.h
include/MORB_SLAM/TwoViewReconstruction.h
include/MORB_SLAM/SerializationUtils.h
include/MORB_SLAM/Settings.h)


add_subdirectory(Thirdparty/g2o)
Expand Down
2 changes: 1 addition & 1 deletion Examples/Calibration/recorder_realsense_D435i.cc
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ int main(int argc, char **argv) {
sigemptyset(&sigIntHandler.sa_mask);
sigIntHandler.sa_flags = 0;

sigaction(SIGINT, &sigIntHandler, NULL);
sigaction(SIGINT, &sigIntHandler, nullptr);
b_continue_session = true;

double offset = 0; // ms
Expand Down
2 changes: 1 addition & 1 deletion Examples/Calibration/recorder_realsense_T265.cc
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ int main(int argc, char **argv) {
sigemptyset(&sigIntHandler.sa_mask);
sigIntHandler.sa_flags = 0;

sigaction(SIGINT, &sigIntHandler, NULL);
sigaction(SIGINT, &sigIntHandler, nullptr);
b_continue_session = true;

double offset = 0; // ms
Expand Down
14 changes: 7 additions & 7 deletions Examples/Monocular-Inertial/mono_inertial_euroc.cc
Original file line number Diff line number Diff line change
Expand Up @@ -26,9 +26,9 @@

#include<opencv2/opencv.hpp>

#include<System.h>
#include<Viewer.h>
#include "ImuTypes.h"
#include<MORB_SLAM/System.h>
#include<MORB_SLAM/Viewer.h>
#include "MORB_SLAM/ImuTypes.h"

using namespace std;

Expand Down Expand Up @@ -118,8 +118,8 @@ int main(int argc, char *argv[])
cout.precision(17);

// Create SLAM system. It initializes all system threads and gets ready to process frames.
ORB_SLAM3::System_ptr SLAM = std::make_shared<ORB_SLAM3::System>(argv[1],argv[2],ORB_SLAM3::CameraType::IMU_MONOCULAR);
ORB_SLAM3::Viewer viewer(SLAM, argv[2]);
MORB_SLAM::System_ptr SLAM = std::make_shared<MORB_SLAM::System>(argv[1],argv[2],MORB_SLAM::CameraType::IMU_MONOCULAR);
MORB_SLAM::Viewer viewer(SLAM, argv[2]);
float imageScale = SLAM->GetImageScale();

#ifdef REGISTER_TIMES
Expand All @@ -132,7 +132,7 @@ int main(int argc, char *argv[])

// Main loop
cv::Mat im;
vector<ORB_SLAM3::IMU::Point> vImuMeas;
vector<MORB_SLAM::IMU::Point> vImuMeas;
proccIm = 0;
for(int ni=0; ni<nImages[seq]; ni++, proccIm++)
{
Expand Down Expand Up @@ -172,7 +172,7 @@ int main(int argc, char *argv[])

while(vTimestampsImu[seq][first_imu[seq]]<=vTimestampsCam[seq][ni])
{
vImuMeas.push_back(ORB_SLAM3::IMU::Point(vAcc[seq][first_imu[seq]].x,vAcc[seq][first_imu[seq]].y,vAcc[seq][first_imu[seq]].z,
vImuMeas.push_back(MORB_SLAM::IMU::Point(vAcc[seq][first_imu[seq]].x,vAcc[seq][first_imu[seq]].y,vAcc[seq][first_imu[seq]].z,
vGyro[seq][first_imu[seq]].x,vGyro[seq][first_imu[seq]].y,vGyro[seq][first_imu[seq]].z,
vTimestampsImu[seq][first_imu[seq]]));
first_imu[seq]++;
Expand Down
14 changes: 7 additions & 7 deletions Examples/Monocular-Inertial/mono_inertial_realsense_D435i.cc
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,8 @@
#include <librealsense2/rs.hpp>
#include "librealsense2/rsutil.h"

#include <System.h>
#include <Viewer.h>
#include <MORB_SLAM/System.h>
#include <MORB_SLAM/Viewer.h>

using namespace std;

Expand Down Expand Up @@ -116,7 +116,7 @@ int main(int argc, char **argv) {
sigemptyset(&sigIntHandler.sa_mask);
sigIntHandler.sa_flags = 0;

sigaction(SIGINT, &sigIntHandler, NULL);
sigaction(SIGINT, &sigIntHandler, nullptr);
b_continue_session = true;

double offset = 0; // ms
Expand Down Expand Up @@ -258,7 +258,7 @@ int main(int argc, char **argv) {

rs2::pipeline_profile pipe_profile = pipe.start(cfg, imu_callback);

vector<ORB_SLAM3::IMU::Point> vImuMeas;
vector<MORB_SLAM::IMU::Point> vImuMeas;
rs2::stream_profile cam_stream = pipe_profile.get_stream(RS2_STREAM_INFRARED, 1);


Expand Down Expand Up @@ -288,8 +288,8 @@ int main(int argc, char **argv) {


// Create SLAM system. It initializes all system threads and gets ready to process frames.
ORB_SLAM3::System_ptr SLAM = std::make_shared<ORB_SLAM3::System>(argv[1],argv[2],ORB_SLAM3::CameraType::IMU_MONOCULAR, file_name);
ORB_SLAM3::Viewer viewer(SLAM, argv[2]);
MORB_SLAM::System_ptr SLAM = std::make_shared<MORB_SLAM::System>(argv[1],argv[2],MORB_SLAM::CameraType::IMU_MONOCULAR, file_name);
MORB_SLAM::Viewer viewer(SLAM, argv[2]);
float imageScale = SLAM->GetImageScale();

double timestamp;
Expand Down Expand Up @@ -356,7 +356,7 @@ int main(int argc, char **argv) {

for(size_t i=0; i<vGyro.size(); ++i)
{
ORB_SLAM3::IMU::Point lastPoint(vAccel[i].x, vAccel[i].y, vAccel[i].z,
MORB_SLAM::IMU::Point lastPoint(vAccel[i].x, vAccel[i].y, vAccel[i].z,
vGyro[i].x, vGyro[i].y, vGyro[i].z,
vGyro_times[i]);
vImuMeas.push_back(lastPoint);
Expand Down
16 changes: 8 additions & 8 deletions Examples/Monocular-Inertial/mono_inertial_realsense_t265.cc
Original file line number Diff line number Diff line change
Expand Up @@ -29,10 +29,10 @@

#include <librealsense2/rs.hpp>

#include <System.h>
#include <Viewer.h>
#include <MORB_SLAM/System.h>
#include <MORB_SLAM/Viewer.h>
#include <condition_variable>
#include "ImuTypes.h"
#include "MORB_SLAM/ImuTypes.h"

using namespace std;

Expand Down Expand Up @@ -65,8 +65,8 @@ int main(int argc, char **argv)
// bFileName = true; // UNUSED
}

ORB_SLAM3::System_ptr SLAM = std::make_shared<ORB_SLAM3::System>(argv[1],argv[2],ORB_SLAM3::CameraType::IMU_MONOCULAR, file_name);
ORB_SLAM3::Viewer viewer(SLAM, argv[2]);
MORB_SLAM::System_ptr SLAM = std::make_shared<MORB_SLAM::System>(argv[1],argv[2],MORB_SLAM::CameraType::IMU_MONOCULAR, file_name);
MORB_SLAM::Viewer viewer(SLAM, argv[2]);
float imageScale = SLAM->GetImageScale();

struct sigaction sigIntHandler;
Expand All @@ -75,7 +75,7 @@ int main(int argc, char **argv)
sigemptyset(&sigIntHandler.sa_mask);
sigIntHandler.sa_flags = 0;

sigaction(SIGINT, &sigIntHandler, NULL);
sigaction(SIGINT, &sigIntHandler, nullptr);
b_continue_session = true;

double offset = 0; // ms
Expand Down Expand Up @@ -206,7 +206,7 @@ int main(int argc, char **argv)


// Create SLAM system. It initializes all system threads and gets ready to process frames.
vector<ORB_SLAM3::IMU::Point> vImuMeas;
vector<MORB_SLAM::IMU::Point> vImuMeas;

double timestamp;
cv::Mat im;
Expand Down Expand Up @@ -286,7 +286,7 @@ int main(int argc, char **argv)


for(size_t i=0; i<vGyro.size(); ++i){
ORB_SLAM3::IMU::Point lastPoint(vAccel[i].x, vAccel[i].y, vAccel[i].z,
MORB_SLAM::IMU::Point lastPoint(vAccel[i].x, vAccel[i].y, vAccel[i].z,
vGyro[i].x, vGyro[i].y, vGyro[i].z,
vGyro_times[i]);
vImuMeas.push_back(lastPoint);
Expand Down
14 changes: 7 additions & 7 deletions Examples/Monocular-Inertial/mono_inertial_tum_vi.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,9 @@

#include<opencv2/opencv.hpp>

#include<System.h>
#include<Viewer.h>
#include "ImuTypes.h"
#include<MORB_SLAM/System.h>
#include<MORB_SLAM/Viewer.h>
#include "MORB_SLAM/ImuTypes.h"

using namespace std;

Expand Down Expand Up @@ -117,8 +117,8 @@ int main(int argc, char **argv)
cout << "IMU data in the sequence: " << nImu << endl << endl;*/

// Create SLAM system. It initializes all system threads and gets ready to process frames.
ORB_SLAM3::System_ptr SLAM = std::make_shared<ORB_SLAM3::System>(argv[1],argv[2],ORB_SLAM3::CameraType::IMU_MONOCULAR, file_name);
ORB_SLAM3::Viewer viewer(SLAM, argv[2]);
MORB_SLAM::System_ptr SLAM = std::make_shared<MORB_SLAM::System>(argv[1],argv[2],MORB_SLAM::CameraType::IMU_MONOCULAR, file_name);
MORB_SLAM::Viewer viewer(SLAM, argv[2]);
float imageScale = SLAM->GetImageScale();

#ifdef REGISTER_TIMES
Expand All @@ -131,7 +131,7 @@ int main(int argc, char **argv)

// Main loop
cv::Mat im;
vector<ORB_SLAM3::IMU::Point> vImuMeas;
vector<MORB_SLAM::IMU::Point> vImuMeas;
proccIm = 0;
cv::Ptr<cv::CLAHE> clahe = cv::createCLAHE(3.0, cv::Size(8, 8));
for(int ni=0; ni<nImages[seq]; ni++, proccIm++)
Expand Down Expand Up @@ -164,7 +164,7 @@ int main(int argc, char **argv)

while(vTimestampsImu[seq][first_imu[seq]]<=vTimestampsCam[seq][ni])
{
vImuMeas.push_back(ORB_SLAM3::IMU::Point(vAcc[seq][first_imu[seq]].x,vAcc[seq][first_imu[seq]].y,vAcc[seq][first_imu[seq]].z,
vImuMeas.push_back(MORB_SLAM::IMU::Point(vAcc[seq][first_imu[seq]].x,vAcc[seq][first_imu[seq]].y,vAcc[seq][first_imu[seq]].z,
vGyro[seq][first_imu[seq]].x,vGyro[seq][first_imu[seq]].y,vGyro[seq][first_imu[seq]].z,
vTimestampsImu[seq][first_imu[seq]]));
// cout << "t_imu = " << fixed << vImuMeas.back().t << endl;
Expand Down
8 changes: 4 additions & 4 deletions Examples/Monocular/mono_euroc.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@

#include<opencv2/opencv.hpp>

#include<System.h>
#include<Viewer.h>
#include<MORB_SLAM/System.h>
#include<MORB_SLAM/Viewer.h>

using namespace std;

Expand Down Expand Up @@ -81,8 +81,8 @@ int main(int argc, char **argv)
// int fps = 20; // UNUSED
// float dT = 1.f/fps; // UNUSED
// Create SLAM system. It initializes all system threads and gets ready to process frames.
ORB_SLAM3::System_ptr SLAM = std::make_shared<ORB_SLAM3::System>(argv[1],argv[2],ORB_SLAM3::CameraType::MONOCULAR);
ORB_SLAM3::Viewer viewer(SLAM, argv[2]);
MORB_SLAM::System_ptr SLAM = std::make_shared<MORB_SLAM::System>(argv[1],argv[2],MORB_SLAM::CameraType::MONOCULAR);
MORB_SLAM::Viewer viewer(SLAM, argv[2]);
float imageScale = SLAM->GetImageScale();

#ifdef REGISTER_TIMES
Expand Down
10 changes: 5 additions & 5 deletions Examples/Monocular/mono_kitti.cc
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@

#include <opencv2/opencv.hpp>

#include <System.h>
#include <Viewer.h>
#include <MORB_SLAM/System.h>
#include <MORB_SLAM/Viewer.h>

using namespace std;

Expand All @@ -48,8 +48,8 @@ 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_SLAM3::System_ptr SLAM = std::make_shared<ORB_SLAM3::System>(argv[1],argv[2],ORB_SLAM3::CameraType::MONOCULAR);
ORB_SLAM3::Viewer viewer(SLAM, argv[2]);
MORB_SLAM::System_ptr SLAM = std::make_shared<MORB_SLAM::System>(argv[1],argv[2],MORB_SLAM::CameraType::MONOCULAR);
MORB_SLAM::Viewer viewer(SLAM, argv[2]);
float imageScale = SLAM->GetImageScale();

// Vector for tracking time statistics
Expand Down Expand Up @@ -97,7 +97,7 @@ int main(int argc, char **argv)
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();

// Pass the image to the SLAM system
auto pos = SLAM->TrackMonocular(im,tframe,vector<ORB_SLAM3::IMU::Point>(), vstrImageFilenames[ni]);
auto pos = SLAM->TrackMonocular(im,tframe,vector<MORB_SLAM::IMU::Point>(), vstrImageFilenames[ni]);

std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();

Expand Down
Loading