Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
24 commits
Select commit Hold shift + click to select a range
e3c85cf
`make` set to use `$(nproc)`
uni-paul-taylor2 Feb 6, 2025
1b24986
`make` set to use `$(nproc)`
uni-paul-taylor2 Feb 6, 2025
41418cb
Spelling Error Correction
uni-paul-taylor2 Feb 6, 2025
9e626e4
Rename REAMDME.md to README.md
uni-paul-taylor2 Feb 6, 2025
22e5be9
switch from `make` to `ninja`
uni-paul-taylor2 Feb 6, 2025
c1d1537
build_ros also switched from `make` to `ninja`
uni-paul-taylor2 Feb 6, 2025
cf93431
add an install prefix (ninja doesn't have one by default?)
uni-paul-taylor2 Feb 11, 2025
8e7df11
Update build_ros.sh
uni-paul-taylor2 Feb 11, 2025
89434fe
Update build_ros.sh
uni-paul-taylor2 Feb 11, 2025
53ac8f2
trying reverting to `make`
uni-paul-taylor2 Feb 11, 2025
16dfc3a
trying reverting to `make`
uni-paul-taylor2 Feb 11, 2025
bf0a1ca
Update build.sh
uni-paul-taylor2 Feb 14, 2025
6733565
install target set
uni-paul-taylor2 Feb 14, 2025
414a744
Update build.sh
uni-paul-taylor2 Feb 14, 2025
cbcaa64
`C++14` used instead of `C++11`
uni-paul-taylor2 Feb 17, 2025
e6a43a1
Documentation Updated
uni-paul-taylor2 Feb 17, 2025
118c7f1
rename `REAMDE.md` to `README.md` in examples
uni-paul-taylor2 Feb 17, 2025
0a6b08d
changed flag from `COMPILEDWITHC11` to `COMPILEDWITHC14`
uni-paul-taylor2 Feb 18, 2025
321cb0a
changed Examples_old flags from `COMPILEDWITHC11` to `COMPILEDWITHC14`
uni-paul-taylor2 Feb 18, 2025
462d092
ros build returns from `ninja` to `make`
uni-paul-taylor2 Feb 24, 2025
c2a05a5
add uninstall logic part 1
uni-paul-taylor2 Feb 25, 2025
3660af3
add uninstall logic part 2
uni-paul-taylor2 Feb 25, 2025
e762aab
part 1 for find_package
uni-paul-taylor2 Feb 25, 2025
42e13ce
more `cmake` configuration
uni-paul-taylor2 Feb 25, 2025
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
39 changes: 27 additions & 12 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,20 +12,15 @@ set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3")
set(CMAKE_C_FLAGS_RELEASE "${CMAKE_C_FLAGS_RELEASE} -march=native")
set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -march=native")

# Check C++11 or C++0x support
# Check C++14 support
include(CheckCXXCompilerFlag)
CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
if(COMPILER_SUPPORTS_CXX11)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
add_definitions(-DCOMPILEDWITHC11)
message(STATUS "Using flag -std=c++11.")
elseif(COMPILER_SUPPORTS_CXX0X)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x")
add_definitions(-DCOMPILEDWITHC0X)
message(STATUS "Using flag -std=c++0x.")
CHECK_CXX_COMPILER_FLAG("-std=c++14" COMPILER_SUPPORTS_CXX14)
if(COMPILER_SUPPORTS_CXX14)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14")
add_definitions(-DCOMPILEDWITHC14)
message(STATUS "Using flag -std=c++14.")
else()
message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.")
message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++14 support. Please use a different C++ compiler.")
endif()

LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules)
Expand Down Expand Up @@ -388,3 +383,23 @@ if(realsense2_FOUND)
Examples_old/Stereo-Inertial/stereo_inertial_realsense_D435i.cc)
target_link_libraries(stereo_inertial_realsense_D435i_old ${PROJECT_NAME})
endif()

#Install Rule
install(TARGETS ORB_SLAM3
RUNTIME DESTINATION bin
LIBRARY DESTINATION lib
ARCHIVE DESTINATION lib
)
install(DIRECTORY ${PROJECT_SOURCE_DIR}/include/ DESTINATION include/${PROJECT_NAME}) #include/ORB_SLAM3

#Uninstall Rule
if(EXISTS "${CMAKE_BINARY_DIR}/install_manifest.txt")
configure_file("${CMAKE_CURRENT_SOURCE_DIR}/cmake_uninstall.cmake.in"
"${CMAKE_BINARY_DIR}/cmake_uninstall.cmake" @ONLY)
endif()

#for find_package
configure_file(${CMAKE_SOURCE_DIR}/cmake/ORB_SLAM3Config.cmake.in
${CMAKE_BINARY_DIR}/ORB_SLAM3Config.cmake @ONLY)
install(FILES ${CMAKE_BINARY_DIR}/ORB_SLAM3Config.cmake
DESTINATION lib/cmake/ORB_SLAM3)
10 changes: 5 additions & 5 deletions Dependencies.md
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
##List of Known Dependencies
###ORB-SLAM3 v1.0
## List of Known Dependencies
### ORB-SLAM3 v1.0

In this document we list all the pieces of code included by ORB-SLAM3 and linked libraries which are not property of the authors of ORB-SLAM3.


#####Code in **src** and **include** folders
##### Code in **src** and **include** folders

* *ORBextractor.cc*.
This is a modified version of orb.cpp of OpenCV library. The original code is BSD licensed.
Expand All @@ -21,7 +21,7 @@ The original code is BSD licensed.
The code is from: http://graphics.stanford.edu/~seander/bithacks.html#CountBitsSetParallel.
The code is in the public domain.

#####Code in Thirdparty folder
##### Code in Thirdparty folder

* All code in **DBoW2** folder.
This is a modified version of [DBoW2](https://github.com/dorian3d/DBoW2) and [DLib](https://github.com/dorian3d/DLib) library. All files included are BSD licensed.
Expand All @@ -32,7 +32,7 @@ This is a modified version of [g2o](https://github.com/RainerKuemmerle/g2o). All
* All code in **Sophus** folder.
This is a modified version of [Sophus](https://github.com/strasdat/Sophus). [MIT license](https://en.wikipedia.org/wiki/MIT_License).

#####Library dependencies
##### Library dependencies

* **Pangolin (visualization and user interface)**.
[MIT license](https://en.wikipedia.org/wiki/MIT_License).
Expand Down
8 changes: 4 additions & 4 deletions Examples/Monocular-Inertial/mono_inertial_euroc.cc
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@ int main(int argc, char *argv[])
if(imageScale != 1.f)
{
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
Expand All @@ -158,7 +158,7 @@ int main(int argc, char *argv[])
int height = im.rows * imageScale;
cv::resize(im, im, cv::Size(width, height));
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
Expand All @@ -184,7 +184,7 @@ int main(int argc, char *argv[])
}
}

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
Expand All @@ -194,7 +194,7 @@ int main(int argc, char *argv[])
// cout << "tframe = " << tframe << endl;
SLAM.TrackMonocular(im,tframe,vImuMeas); // TODO change to monocular_inertial

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand Down
10 changes: 5 additions & 5 deletions Examples/Monocular-Inertial/mono_inertial_realsense_D435i.cc
Original file line number Diff line number Diff line change
Expand Up @@ -314,7 +314,7 @@ int main(int argc, char **argv) {
if(!image_ready)
cond_image_rec.wait(lk);

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point time_Start_Process = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point time_Start_Process = std::chrono::monotonic_clock::now();
Expand Down Expand Up @@ -365,7 +365,7 @@ int main(int argc, char **argv) {
if(imageScale != 1.f)
{
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
Expand All @@ -375,7 +375,7 @@ int main(int argc, char **argv) {
int height = im.rows * imageScale;
cv::resize(im, im, cv::Size(width, height));
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
Expand All @@ -386,7 +386,7 @@ int main(int argc, char **argv) {
}

#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_Start_Track = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_Start_Track = std::chrono::monotonic_clock::now();
Expand All @@ -395,7 +395,7 @@ int main(int argc, char **argv) {
// Pass the image to the SLAM system
SLAM.TrackMonocular(im, timestamp, vImuMeas);
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_End_Track = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_End_Track = std::chrono::monotonic_clock::now();
Expand Down
10 changes: 5 additions & 5 deletions Examples/Monocular-Inertial/mono_inertial_realsense_t265.cc
Original file line number Diff line number Diff line change
Expand Up @@ -230,7 +230,7 @@ int main(int argc, char **argv)
while(!image_ready)
cond_image_rec.wait(lk);

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point time_Start_Process = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point time_Start_Process = std::chrono::monotonic_clock::now();
Expand All @@ -257,7 +257,7 @@ int main(int argc, char **argv)
else
{
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
Expand All @@ -267,7 +267,7 @@ int main(int argc, char **argv)
int height = imCV.rows * imageScale;
cv::resize(imCV, im, cv::Size(width, height));
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
Expand Down Expand Up @@ -308,15 +308,15 @@ int main(int argc, char **argv)
}
}

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_Start_Track = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_Start_Track = std::chrono::monotonic_clock::now();
#endif
// Pass the image to the SLAM system
SLAM.TrackMonocular(im, timestamp, vImuMeas);

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_End_Track = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_End_Track = std::chrono::monotonic_clock::now();
Expand Down
8 changes: 4 additions & 4 deletions Examples/Monocular-Inertial/mono_inertial_tum_vi.cc
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,7 @@ int main(int argc, char **argv)
if(imageScale != 1.f)
{
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
Expand All @@ -182,7 +182,7 @@ int main(int argc, char **argv)
int height = im.rows * imageScale;
cv::resize(im, im, cv::Size(width, height));
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
Expand All @@ -195,7 +195,7 @@ int main(int argc, char **argv)
// cout << "first imu: " << first_imu[seq] << endl;
/*cout << "first imu time: " << fixed << vTimestampsImu[first_imu] << endl;
cout << "size vImu: " << vImuMeas.size() << endl;*/
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
Expand All @@ -205,7 +205,7 @@ int main(int argc, char **argv)
// cout << "tframe = " << tframe << endl;
SLAM.TrackMonocular(im,tframe,vImuMeas); // TODO change to monocular_inertial

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
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 @@ -109,7 +109,7 @@ int main(int argc, char **argv)
if(imageScale != 1.f)
{
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
Expand All @@ -119,7 +119,7 @@ int main(int argc, char **argv)
int height = im.rows * imageScale;
cv::resize(im, im, cv::Size(width, height));
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
Expand All @@ -129,7 +129,7 @@ int main(int argc, char **argv)
#endif
}

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
Expand All @@ -139,7 +139,7 @@ int main(int argc, char **argv)
// cout << "tframe = " << tframe << endl;
SLAM.TrackMonocular(im,tframe); // TODO change to monocular_inertial

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand Down
8 changes: 4 additions & 4 deletions Examples/Monocular/mono_kitti.cc
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ int main(int argc, char **argv)
if(imageScale != 1.f)
{
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
Expand All @@ -88,7 +88,7 @@ int main(int argc, char **argv)
int height = im.rows * imageScale;
cv::resize(im, im, cv::Size(width, height));
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
Expand All @@ -98,7 +98,7 @@ int main(int argc, char **argv)
#endif
}

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
Expand All @@ -107,7 +107,7 @@ int main(int argc, char **argv)
// Pass the image to the SLAM system
SLAM.TrackMonocular(im,tframe,vector<ORB_SLAM3::IMU::Point>(), vstrImageFilenames[ni]);

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand Down
10 changes: 5 additions & 5 deletions Examples/Monocular/mono_realsense_D435i.cc
Original file line number Diff line number Diff line change
Expand Up @@ -228,7 +228,7 @@ int main(int argc, char **argv) {
if(!image_ready)
cond_image_rec.wait(lk);

#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point time_Start_Process = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point time_Start_Process = std::chrono::monotonic_clock::now();
Expand All @@ -247,7 +247,7 @@ int main(int argc, char **argv) {
if(imageScale != 1.f)
{
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
Expand All @@ -258,7 +258,7 @@ int main(int argc, char **argv) {
cv::resize(im, im, cv::Size(width, height));

#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
Expand All @@ -269,7 +269,7 @@ int main(int argc, char **argv) {
}

#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_Start_Track = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_Start_Track = std::chrono::monotonic_clock::now();
Expand All @@ -278,7 +278,7 @@ int main(int argc, char **argv) {
// Stereo images are already rectified.
SLAM.TrackMonocular(im, timestamp);
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_End_Track = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_End_Track = std::chrono::monotonic_clock::now();
Expand Down
8 changes: 4 additions & 4 deletions Examples/Monocular/mono_realsense_t265.cc
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@ int main(int argc, char **argv)
if(imageScale != 1.f)
{
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
Expand All @@ -126,7 +126,7 @@ int main(int argc, char **argv)
int height = imCV.rows * imageScale;
cv::resize(imCV, imCV, cv::Size(width, height));
#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
Expand All @@ -141,7 +141,7 @@ int main(int argc, char **argv)
//clahe->apply(imRight,imRight);

#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
#else
std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
Expand All @@ -152,7 +152,7 @@ int main(int argc, char **argv)
SLAM.TrackMonocular(imCV, timestamp_ms);

#ifdef REGISTER_TIMES
#ifdef COMPILEDWITHC11
#ifdef COMPILEDWITHC14
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();
Expand Down
Loading