From d258f7ff0b081e92399ace0c606f7b7b856467bb Mon Sep 17 00:00:00 2001 From: "H. Volkan Kasikaralar" Date: Thu, 22 Jun 2023 16:56:09 +0200 Subject: [PATCH] Add: Mono & Mono Inertial --- .gitignore | 9 +- ROS2/ORB_SLAM3/CMakeLists.txt | 87 +-- ROS2/ORB_SLAM3/src/AR/ViewerAR.cc | 640 ------------------ ROS2/ORB_SLAM3/src/AR/ViewerAR.h | 118 ---- ROS2/ORB_SLAM3/src/AR/ros_mono_ar.cc | 167 ----- ROS2/ORB_SLAM3/src/ros_mono.cc | 53 +- ROS2/ORB_SLAM3/src/ros_mono_inertial.cc | 117 ++-- ROS2/ORB_SLAM3/src/ros_rgbd.cc | 112 --- ROS2/ORB_SLAM3/src/ros_stereo.cc | 170 ----- ROS2/ORB_SLAM3/src/ros_stereo_inertial.cc | 286 -------- .../ORB_SLAM3/command.log | 4 - .../ORB_SLAM3/stderr.log | 81 --- .../ORB_SLAM3/stdout.log | 27 - .../ORB_SLAM3/stdout_stderr.log | 108 --- .../ORB_SLAM3/streams.log | 112 --- ROS2/log/build_2023-06-19_20-42-56/events.log | 124 ---- .../build_2023-06-19_20-42-56/logger_all.log | 94 --- build_ros2.sh | 4 +- 18 files changed, 122 insertions(+), 2191 deletions(-) delete mode 100644 ROS2/ORB_SLAM3/src/AR/ViewerAR.cc delete mode 100644 ROS2/ORB_SLAM3/src/AR/ViewerAR.h delete mode 100644 ROS2/ORB_SLAM3/src/AR/ros_mono_ar.cc delete mode 100644 ROS2/ORB_SLAM3/src/ros_rgbd.cc delete mode 100644 ROS2/ORB_SLAM3/src/ros_stereo.cc delete mode 100644 ROS2/ORB_SLAM3/src/ros_stereo_inertial.cc delete mode 100644 ROS2/log/build_2023-06-19_20-42-56/ORB_SLAM3/command.log delete mode 100644 ROS2/log/build_2023-06-19_20-42-56/ORB_SLAM3/stderr.log delete mode 100644 ROS2/log/build_2023-06-19_20-42-56/ORB_SLAM3/stdout.log delete mode 100644 ROS2/log/build_2023-06-19_20-42-56/ORB_SLAM3/stdout_stderr.log delete mode 100644 ROS2/log/build_2023-06-19_20-42-56/ORB_SLAM3/streams.log delete mode 100644 ROS2/log/build_2023-06-19_20-42-56/events.log delete mode 100644 ROS2/log/build_2023-06-19_20-42-56/logger_all.log diff --git a/.gitignore b/.gitignore index 7227515c0a..8eec99b009 100644 --- a/.gitignore +++ b/.gitignore @@ -64,10 +64,13 @@ Thirdparty/DBoW2/lib/ Thirdparty/g2o/build/ Thirdparty/g2o/config.h Thirdparty/g2o/lib/ +Thirdparty/Pangolin/lib/ +Thirdparty/Pangolin/build/ Vocabulary/ORBvoc.txt build/ - +install/ lib/ +log/ cmake_modules/ cmake-build-debug/ @@ -91,3 +94,7 @@ my_settings.txt borrar/* */ExecMean.txt + +ROS2/ORB_SLAM3/.vscode/c_cpp_properties.json +ROS2/ORB_SLAM3/.vscode/settings.json +.gitignore \ No newline at end of file diff --git a/ROS2/ORB_SLAM3/CMakeLists.txt b/ROS2/ORB_SLAM3/CMakeLists.txt index 64a5eb911f..1f456463a1 100644 --- a/ROS2/ORB_SLAM3/CMakeLists.txt +++ b/ROS2/ORB_SLAM3/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 2.4.6) +cmake_minimum_required(VERSION 3.5.0) #include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) project(ORB_SLAM3) @@ -7,12 +7,12 @@ set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -march=native") # Check C++11 or C++0x support include(CheckCXXCompilerFlag) -CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11) +CHECK_CXX_COMPILER_FLAG("-std=c++17" COMPILER_SUPPORTS_CXX17) 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.") +if(COMPILER_SUPPORTS_CXX17) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++17") + add_definitions(-DCOMPILEDWITHC17) + message(STATUS "Using flag -std=c++17.") elseif(COMPILER_SUPPORTS_CXX0X) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x") add_definitions(-DCOMPILEDWITHC0X) @@ -24,23 +24,28 @@ endif() LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/../../cmake_modules) find_package(OpenCV 4.0 QUIET) -#find_package(OpenCV 3.0 QUIET) -if(NOT OpenCV_FOUND) - find_package(OpenCV 2.4.3 QUIET) - if(NOT OpenCV_FOUND) - message(FATAL_ERROR "OpenCV > 2.4.3 not found.") - endif() -endif() find_package(Eigen3 3.1.0 REQUIRED) -#find_package(Pangolin REQUIRED) +find_package(Pangolin REQUIRED) +find_package(rclcpp REQUIRED) +find_package(cv_bridge REQUIRED) +find_package(sensor_msgs REQUIRED) + +set(ROS_DEPS + rclcpp + ament_cmake + cv_bridge + sensor_msgs + ) include_directories( ${PROJECT_SOURCE_DIR} ${PROJECT_SOURCE_DIR}/../../ ${PROJECT_SOURCE_DIR}/../../include ${PROJECT_SOURCE_DIR}/../../include/CameraModels +${PROJECT_SOURCE_DIR}/../../Thirdparty/Sophus ${Pangolin_INCLUDE_DIRS} +${EIGEN3_INCLUDE_DIR} ) set(LIBS @@ -57,54 +62,12 @@ ${PROJECT_SOURCE_DIR}/../../lib/libORB_SLAM3.so add_executable(Mono src/ros_mono.cc ) +target_link_libraries(Mono ${LIBS} ) +ament_target_dependencies(Mono rclcpp ${ROS_DEPS}) -target_link_libraries(Mono -${LIBS} -) - -# Node for monocular camera (Augmented Reality Demo) -add_executable(MonoAR -src/AR/ros_mono_ar.cc -src/AR/ViewerAR.h -src/AR/ViewerAR.cc -) - -target_link_libraries(MonoAR -${LIBS} -) - -# Node for stereo camera -add_executable(Stereo -src/ros_stereo.cc -) - -target_link_libraries(Stereo -${LIBS} -) - -# Node for RGB-D camera -add_executable(RGBD -src/ros_rgbd.cc -) - -target_link_libraries(RGBD -${LIBS} -) - -# Node for monocular-inertial camera -add_executable(Mono_Inertial +# Node for monocular inrtial camera +add_executable(MonoInertial src/ros_mono_inertial.cc ) - -target_link_libraries(Mono_Inertial -${LIBS} -) - -# Node for stereo-inertial camera -add_executable(Stereo_Inertial -src/ros_stereo_inertial.cc -) - -target_link_libraries(Stereo_Inertial -${LIBS} -) +target_link_libraries(MonoInertial ${LIBS} ) +ament_target_dependencies(MonoInertial rclcpp ${ROS_DEPS}) diff --git a/ROS2/ORB_SLAM3/src/AR/ViewerAR.cc b/ROS2/ORB_SLAM3/src/AR/ViewerAR.cc deleted file mode 100644 index dc9f18b7e3..0000000000 --- a/ROS2/ORB_SLAM3/src/AR/ViewerAR.cc +++ /dev/null @@ -1,640 +0,0 @@ -/** -* This file is part of ORB-SLAM3 -* -* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. -* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. -* -* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public -* License as published by the Free Software Foundation, either version 3 of the License, or -* (at your option) any later version. -* -* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even -* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -* GNU General Public License for more details. -* -* You should have received a copy of the GNU General Public License along with ORB-SLAM3. -* If not, see . -*/ - -#include "ViewerAR.h" - -#include - -#include -#include -#include - -using namespace std; - -namespace ORB_SLAM3 -{ - -const float eps = 1e-4; - -cv::Mat ExpSO3(const float &x, const float &y, const float &z) -{ - cv::Mat I = cv::Mat::eye(3,3,CV_32F); - const float d2 = x*x+y*y+z*z; - const float d = sqrt(d2); - cv::Mat W = (cv::Mat_(3,3) << 0, -z, y, - z, 0, -x, - -y, x, 0); - if(d(0),v.at(1),v.at(2)); -} - -ViewerAR::ViewerAR(){} - -void ViewerAR::Run() -{ - int w,h,wui; - - cv::Mat im, Tcw; - int status; - vector vKeys; - vector vMPs; - - while(1) - { - GetImagePose(im,Tcw,status,vKeys,vMPs); - if(im.empty()) - cv::waitKey(mT); - else - { - w = im.cols; - h = im.rows; - break; - } - } - - wui=200; - - pangolin::CreateWindowAndBind("Viewer",w+wui,h); - - glEnable(GL_DEPTH_TEST); - glEnable (GL_BLEND); - - pangolin::CreatePanel("menu").SetBounds(0.0,1.0,0.0,pangolin::Attach::Pix(wui)); - pangolin::Var menu_detectplane("menu.Insert Cube",false,false); - pangolin::Var menu_clear("menu.Clear All",false,false); - pangolin::Var menu_drawim("menu.Draw Image",true,true); - pangolin::Var menu_drawcube("menu.Draw Cube",true,true); - pangolin::Var menu_cubesize("menu. Cube Size",0.05,0.01,0.3); - pangolin::Var menu_drawgrid("menu.Draw Grid",true,true); - pangolin::Var menu_ngrid("menu. Grid Elements",3,1,10); - pangolin::Var menu_sizegrid("menu. Element Size",0.05,0.01,0.3); - pangolin::Var menu_drawpoints("menu.Draw Points",false,true); - - pangolin::Var menu_LocalizationMode("menu.Localization Mode",false,true); - bool bLocalizationMode = false; - - pangolin::View& d_image = pangolin::Display("image") - .SetBounds(0,1.0f,pangolin::Attach::Pix(wui),1.0f,(float)w/h) - .SetLock(pangolin::LockLeft, pangolin::LockTop); - - pangolin::GlTexture imageTexture(w,h,GL_RGB,false,0,GL_RGB,GL_UNSIGNED_BYTE); - - pangolin::OpenGlMatrixSpec P = pangolin::ProjectionMatrixRDF_TopLeft(w,h,fx,fy,cx,cy,0.001,1000); - - vector vpPlane; - - while(1) - { - - if(menu_LocalizationMode && !bLocalizationMode) - { - mpSystem->ActivateLocalizationMode(); - bLocalizationMode = true; - } - else if(!menu_LocalizationMode && bLocalizationMode) - { - mpSystem->DeactivateLocalizationMode(); - bLocalizationMode = false; - } - - glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); - - // Activate camera view - d_image.Activate(); - glColor3f(1.0,1.0,1.0); - - // Get last image and its computed pose from SLAM - GetImagePose(im,Tcw,status,vKeys,vMPs); - - // Add text to image - PrintStatus(status,bLocalizationMode,im); - - if(menu_drawpoints) - DrawTrackedPoints(vKeys,vMPs,im); - - // Draw image - if(menu_drawim) - DrawImageTexture(imageTexture,im); - - glClear(GL_DEPTH_BUFFER_BIT); - - // Load camera projection - glMatrixMode(GL_PROJECTION); - P.Load(); - - glMatrixMode(GL_MODELVIEW); - - // Load camera pose - LoadCameraPose(Tcw); - - // Draw virtual things - if(status==2) - { - if(menu_clear) - { - if(!vpPlane.empty()) - { - for(size_t i=0; iMapChanged()) - { - cout << "Map changed. All virtual elements are recomputed!" << endl; - bRecompute = true; - } - } - - for(size_t i=0; iRecompute(); - } - glPushMatrix(); - pPlane->glTpw.Multiply(); - - // Draw cube - if(menu_drawcube) - { - DrawCube(menu_cubesize); - } - - // Draw grid plane - if(menu_drawgrid) - { - DrawPlane(menu_ngrid,menu_sizegrid); - } - - glPopMatrix(); - } - } - } - - - } - - pangolin::FinishFrame(); - usleep(mT*1000); - } - -} - -void ViewerAR::SetImagePose(const cv::Mat &im, const cv::Mat &Tcw, const int &status, const vector &vKeys, const vector &vMPs) -{ - unique_lock lock(mMutexPoseImage); - mImage = im.clone(); - mTcw = Tcw.clone(); - mStatus = status; - mvKeys = vKeys; - mvMPs = vMPs; -} - -void ViewerAR::GetImagePose(cv::Mat &im, cv::Mat &Tcw, int &status, std::vector &vKeys, std::vector &vMPs) -{ - unique_lock lock(mMutexPoseImage); - im = mImage.clone(); - Tcw = mTcw.clone(); - status = mStatus; - vKeys = mvKeys; - vMPs = mvMPs; -} - -void ViewerAR::LoadCameraPose(const cv::Mat &Tcw) -{ - if(!Tcw.empty()) - { - pangolin::OpenGlMatrix M; - - M.m[0] = Tcw.at(0,0); - M.m[1] = Tcw.at(1,0); - M.m[2] = Tcw.at(2,0); - M.m[3] = 0.0; - - M.m[4] = Tcw.at(0,1); - M.m[5] = Tcw.at(1,1); - M.m[6] = Tcw.at(2,1); - M.m[7] = 0.0; - - M.m[8] = Tcw.at(0,2); - M.m[9] = Tcw.at(1,2); - M.m[10] = Tcw.at(2,2); - M.m[11] = 0.0; - - M.m[12] = Tcw.at(0,3); - M.m[13] = Tcw.at(1,3); - M.m[14] = Tcw.at(2,3); - M.m[15] = 1.0; - - M.Load(); - } -} - -void ViewerAR::PrintStatus(const int &status, const bool &bLocMode, cv::Mat &im) -{ - if(!bLocMode) - { - switch(status) - { - case 1: {AddTextToImage("SLAM NOT INITIALIZED",im,255,0,0); break;} - case 2: {AddTextToImage("SLAM ON",im,0,255,0); break;} - case 3: {AddTextToImage("SLAM LOST",im,255,0,0); break;} - } - } - else - { - switch(status) - { - case 1: {AddTextToImage("SLAM NOT INITIALIZED",im,255,0,0); break;} - case 2: {AddTextToImage("LOCALIZATION ON",im,0,255,0); break;} - case 3: {AddTextToImage("LOCALIZATION LOST",im,255,0,0); break;} - } - } -} - -void ViewerAR::AddTextToImage(const string &s, cv::Mat &im, const int r, const int g, const int b) -{ - int l = 10; - //imText.rowRange(im.rows-imText.rows,imText.rows) = cv::Mat::zeros(textSize.height+10,im.cols,im.type()); - cv::putText(im,s,cv::Point(l,im.rows-l),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); - cv::putText(im,s,cv::Point(l-1,im.rows-l),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); - cv::putText(im,s,cv::Point(l+1,im.rows-l),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); - cv::putText(im,s,cv::Point(l-1,im.rows-(l-1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); - cv::putText(im,s,cv::Point(l,im.rows-(l-1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); - cv::putText(im,s,cv::Point(l+1,im.rows-(l-1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); - cv::putText(im,s,cv::Point(l-1,im.rows-(l+1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); - cv::putText(im,s,cv::Point(l,im.rows-(l+1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); - cv::putText(im,s,cv::Point(l+1,im.rows-(l+1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); - - cv::putText(im,s,cv::Point(l,im.rows-l),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(r,g,b),2,8); -} - -void ViewerAR::DrawImageTexture(pangolin::GlTexture &imageTexture, cv::Mat &im) -{ - if(!im.empty()) - { - imageTexture.Upload(im.data,GL_RGB,GL_UNSIGNED_BYTE); - imageTexture.RenderToViewportFlipY(); - } -} - -void ViewerAR::DrawCube(const float &size,const float x, const float y, const float z) -{ - pangolin::OpenGlMatrix M = pangolin::OpenGlMatrix::Translate(-x,-size-y,-z); - glPushMatrix(); - M.Multiply(); - pangolin::glDrawColouredCube(-size,size); - glPopMatrix(); -} - -void ViewerAR::DrawPlane(Plane *pPlane, int ndivs, float ndivsize) -{ - glPushMatrix(); - pPlane->glTpw.Multiply(); - DrawPlane(ndivs,ndivsize); - glPopMatrix(); -} - -void ViewerAR::DrawPlane(int ndivs, float ndivsize) -{ - // Plane parallel to x-z at origin with normal -y - const float minx = -ndivs*ndivsize; - const float minz = -ndivs*ndivsize; - const float maxx = ndivs*ndivsize; - const float maxz = ndivs*ndivsize; - - - glLineWidth(2); - glColor3f(0.7f,0.7f,1.0f); - glBegin(GL_LINES); - - for(int n = 0; n<=2*ndivs; n++) - { - glVertex3f(minx+ndivsize*n,0,minz); - glVertex3f(minx+ndivsize*n,0,maxz); - glVertex3f(minx,0,minz+ndivsize*n); - glVertex3f(maxx,0,minz+ndivsize*n); - } - - glEnd(); - -} - -void ViewerAR::DrawTrackedPoints(const std::vector &vKeys, const std::vector &vMPs, cv::Mat &im) -{ - const int N = vKeys.size(); - - - for(int i=0; i &vMPs, const int iterations) -{ - // Retrieve 3D points - vector vPoints; - vPoints.reserve(vMPs.size()); - vector vPointMP; - vPointMP.reserve(vMPs.size()); - - for(size_t i=0; iObservations()>5) - { - vPoints.push_back(pMP->GetWorldPos()); - vPointMP.push_back(pMP); - } - } - } - - const int N = vPoints.size(); - - if(N<50) - return NULL; - - - // Indices for minimum set selection - vector vAllIndices; - vAllIndices.reserve(N); - vector vAvailableIndices; - - for(int i=0; i bestvDist; - - //RANSAC - for(int n=0; n(3,0); - const float b = vt.at(3,1); - const float c = vt.at(3,2); - const float d = vt.at(3,3); - - vector vDistances(N,0); - - const float f = 1.0f/sqrt(a*a+b*b+c*c+d*d); - - for(int i=0; i(0)*a+vPoints[i].at(1)*b+vPoints[i].at(2)*c+d)*f; - } - - vector vSorted = vDistances; - sort(vSorted.begin(),vSorted.end()); - - int nth = max((int)(0.2*N),20); - const float medianDist = vSorted[nth]; - - if(medianDist vbInliers(N,false); - int nInliers = 0; - for(int i=0; i vInlierMPs(nInliers,NULL); - int nin = 0; - for(int i=0; i &vMPs, const cv::Mat &Tcw):mvMPs(vMPs),mTcw(Tcw.clone()) -{ - rang = -3.14f/2+((float)rand()/RAND_MAX)*3.14f; - Recompute(); -} - -void Plane::Recompute() -{ - const int N = mvMPs.size(); - - // Recompute plane with all points - cv::Mat A = cv::Mat(N,4,CV_32F); - A.col(3) = cv::Mat::ones(N,1,CV_32F); - - o = cv::Mat::zeros(3,1,CV_32F); - - int nPoints = 0; - for(int i=0; iisBad()) - { - cv::Mat Xw = pMP->GetWorldPos(); - o+=Xw; - A.row(nPoints).colRange(0,3) = Xw.t(); - nPoints++; - } - } - A.resize(nPoints); - - cv::Mat u,w,vt; - cv::SVDecomp(A,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV); - - float a = vt.at(3,0); - float b = vt.at(3,1); - float c = vt.at(3,2); - - o = o*(1.0f/nPoints); - const float f = 1.0f/sqrt(a*a+b*b+c*c); - - // Compute XC just the first time - if(XC.empty()) - { - cv::Mat Oc = -mTcw.colRange(0,3).rowRange(0,3).t()*mTcw.rowRange(0,3).col(3); - XC = Oc-o; - } - - if((XC.at(0)*a+XC.at(1)*b+XC.at(2)*c)>0) - { - a=-a; - b=-b; - c=-c; - } - - const float nx = a*f; - const float ny = b*f; - const float nz = c*f; - - n = (cv::Mat_(3,1)<(3,1) << 0.0f, 1.0f, 0.0f); - - cv::Mat v = up.cross(n); - const float sa = cv::norm(v); - const float ca = up.dot(n); - const float ang = atan2(sa,ca); - Tpw = cv::Mat::eye(4,4,CV_32F); - - - Tpw.rowRange(0,3).colRange(0,3) = ExpSO3(v*ang/sa)*ExpSO3(up*rang); - o.copyTo(Tpw.col(3).rowRange(0,3)); - - glTpw.m[0] = Tpw.at(0,0); - glTpw.m[1] = Tpw.at(1,0); - glTpw.m[2] = Tpw.at(2,0); - glTpw.m[3] = 0.0; - - glTpw.m[4] = Tpw.at(0,1); - glTpw.m[5] = Tpw.at(1,1); - glTpw.m[6] = Tpw.at(2,1); - glTpw.m[7] = 0.0; - - glTpw.m[8] = Tpw.at(0,2); - glTpw.m[9] = Tpw.at(1,2); - glTpw.m[10] = Tpw.at(2,2); - glTpw.m[11] = 0.0; - - glTpw.m[12] = Tpw.at(0,3); - glTpw.m[13] = Tpw.at(1,3); - glTpw.m[14] = Tpw.at(2,3); - glTpw.m[15] = 1.0; - -} - -Plane::Plane(const float &nx, const float &ny, const float &nz, const float &ox, const float &oy, const float &oz) -{ - n = (cv::Mat_(3,1)<(3,1)<(3,1) << 0.0f, 1.0f, 0.0f); - - cv::Mat v = up.cross(n); - const float s = cv::norm(v); - const float c = up.dot(n); - const float a = atan2(s,c); - Tpw = cv::Mat::eye(4,4,CV_32F); - const float rang = -3.14f/2+((float)rand()/RAND_MAX)*3.14f; - cout << rang; - Tpw.rowRange(0,3).colRange(0,3) = ExpSO3(v*a/s)*ExpSO3(up*rang); - o.copyTo(Tpw.col(3).rowRange(0,3)); - - glTpw.m[0] = Tpw.at(0,0); - glTpw.m[1] = Tpw.at(1,0); - glTpw.m[2] = Tpw.at(2,0); - glTpw.m[3] = 0.0; - - glTpw.m[4] = Tpw.at(0,1); - glTpw.m[5] = Tpw.at(1,1); - glTpw.m[6] = Tpw.at(2,1); - glTpw.m[7] = 0.0; - - glTpw.m[8] = Tpw.at(0,2); - glTpw.m[9] = Tpw.at(1,2); - glTpw.m[10] = Tpw.at(2,2); - glTpw.m[11] = 0.0; - - glTpw.m[12] = Tpw.at(0,3); - glTpw.m[13] = Tpw.at(1,3); - glTpw.m[14] = Tpw.at(2,3); - glTpw.m[15] = 1.0; -} - -} diff --git a/ROS2/ORB_SLAM3/src/AR/ViewerAR.h b/ROS2/ORB_SLAM3/src/AR/ViewerAR.h deleted file mode 100644 index ef4c578d46..0000000000 --- a/ROS2/ORB_SLAM3/src/AR/ViewerAR.h +++ /dev/null @@ -1,118 +0,0 @@ -/** -* This file is part of ORB-SLAM3 -* -* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. -* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. -* -* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public -* License as published by the Free Software Foundation, either version 3 of the License, or -* (at your option) any later version. -* -* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even -* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -* GNU General Public License for more details. -* -* You should have received a copy of the GNU General Public License along with ORB-SLAM3. -* If not, see . -*/ - - -#ifndef VIEWERAR_H -#define VIEWERAR_H - -#include -#include -#include -#include -#include"../../../include/System.h" - -namespace ORB_SLAM3 -{ - -class Plane -{ -public: - Plane(const std::vector &vMPs, const cv::Mat &Tcw); - Plane(const float &nx, const float &ny, const float &nz, const float &ox, const float &oy, const float &oz); - - void Recompute(); - - //normal - cv::Mat n; - //origin - cv::Mat o; - //arbitrary orientation along normal - float rang; - //transformation from world to the plane - cv::Mat Tpw; - pangolin::OpenGlMatrix glTpw; - //MapPoints that define the plane - std::vector mvMPs; - //camera pose when the plane was first observed (to compute normal direction) - cv::Mat mTcw, XC; -}; - -class ViewerAR -{ -public: - ViewerAR(); - - void SetFPS(const float fps){ - mFPS = fps; - mT=1e3/fps; - } - - void SetSLAM(ORB_SLAM3::System* pSystem){ - mpSystem = pSystem; - } - - // Main thread function. - void Run(); - - void SetCameraCalibration(const float &fx_, const float &fy_, const float &cx_, const float &cy_){ - fx = fx_; fy = fy_; cx = cx_; cy = cy_; - } - - void SetImagePose(const cv::Mat &im, const cv::Mat &Tcw, const int &status, - const std::vector &vKeys, const std::vector &vMPs); - - void GetImagePose(cv::Mat &im, cv::Mat &Tcw, int &status, - std::vector &vKeys, std::vector &vMPs); - -private: - - //SLAM - ORB_SLAM3::System* mpSystem; - - void PrintStatus(const int &status, const bool &bLocMode, cv::Mat &im); - void AddTextToImage(const std::string &s, cv::Mat &im, const int r=0, const int g=0, const int b=0); - void LoadCameraPose(const cv::Mat &Tcw); - void DrawImageTexture(pangolin::GlTexture &imageTexture, cv::Mat &im); - void DrawCube(const float &size, const float x=0, const float y=0, const float z=0); - void DrawPlane(int ndivs, float ndivsize); - void DrawPlane(Plane* pPlane, int ndivs, float ndivsize); - void DrawTrackedPoints(const std::vector &vKeys, const std::vector &vMPs, cv::Mat &im); - - Plane* DetectPlane(const cv::Mat Tcw, const std::vector &vMPs, const int iterations=50); - - // frame rate - float mFPS, mT; - float fx,fy,cx,cy; - - // Last processed image and computed pose by the SLAM - std::mutex mMutexPoseImage; - cv::Mat mTcw; - cv::Mat mImage; - int mStatus; - std::vector mvKeys; - std::vector mvMPs; - -}; - - -} - - -#endif // VIEWERAR_H - - diff --git a/ROS2/ORB_SLAM3/src/AR/ros_mono_ar.cc b/ROS2/ORB_SLAM3/src/AR/ros_mono_ar.cc deleted file mode 100644 index e26fbca66a..0000000000 --- a/ROS2/ORB_SLAM3/src/AR/ros_mono_ar.cc +++ /dev/null @@ -1,167 +0,0 @@ -/** -* This file is part of ORB-SLAM3 -* -* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. -* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. -* -* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public -* License as published by the Free Software Foundation, either version 3 of the License, or -* (at your option) any later version. -* -* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even -* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -* GNU General Public License for more details. -* -* You should have received a copy of the GNU General Public License along with ORB-SLAM3. -* If not, see . -*/ - - -#include -#include -#include -#include - -#include -#include - -#include -#include - -#include"../../../include/System.h" - -#include"ViewerAR.h" - -using namespace std; - - -ORB_SLAM3::ViewerAR viewerAR; -bool bRGB = true; - -cv::Mat K; -cv::Mat DistCoef; - - -class ImageGrabber -{ -public: - ImageGrabber(ORB_SLAM3::System* pSLAM):mpSLAM(pSLAM){} - - void GrabImage(const sensor_msgs::ImageConstPtr& msg); - - ORB_SLAM3::System* mpSLAM; -}; - -int main(int argc, char **argv) -{ - ros::init(argc, argv, "Mono"); - ros::start(); - - if(argc != 3) - { - cerr << endl << "Usage: rosrun ORB_SLAM3 Mono path_to_vocabulary path_to_settings" << endl; - ros::shutdown(); - return 1; - } - - // Create SLAM system. It initializes all system threads and gets ready to process frames. - ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR,false); - - - cout << endl << endl; - cout << "-----------------------" << endl; - cout << "Augmented Reality Demo" << endl; - cout << "1) Translate the camera to initialize SLAM." << endl; - cout << "2) Look at a planar region and translate the camera." << endl; - cout << "3) Press Insert Cube to place a virtual cube in the plane. " << endl; - cout << endl; - cout << "You can place several cubes in different planes." << endl; - cout << "-----------------------" << endl; - cout << endl; - - - viewerAR.SetSLAM(&SLAM); - - ImageGrabber igb(&SLAM); - - ros::NodeHandle nodeHandler; - ros::Subscriber sub = nodeHandler.subscribe("/camera/image_raw", 1, &ImageGrabber::GrabImage,&igb); - - - cv::FileStorage fSettings(argv[2], cv::FileStorage::READ); - bRGB = static_cast((int)fSettings["Camera.RGB"]); - float fps = fSettings["Camera.fps"]; - viewerAR.SetFPS(fps); - - float fx = fSettings["Camera.fx"]; - float fy = fSettings["Camera.fy"]; - float cx = fSettings["Camera.cx"]; - float cy = fSettings["Camera.cy"]; - - viewerAR.SetCameraCalibration(fx,fy,cx,cy); - - K = cv::Mat::eye(3,3,CV_32F); - K.at(0,0) = fx; - K.at(1,1) = fy; - K.at(0,2) = cx; - K.at(1,2) = cy; - - DistCoef = cv::Mat::zeros(4,1,CV_32F); - DistCoef.at(0) = fSettings["Camera.k1"]; - DistCoef.at(1) = fSettings["Camera.k2"]; - DistCoef.at(2) = fSettings["Camera.p1"]; - DistCoef.at(3) = fSettings["Camera.p2"]; - const float k3 = fSettings["Camera.k3"]; - if(k3!=0) - { - DistCoef.resize(5); - DistCoef.at(4) = k3; - } - - thread tViewer = thread(&ORB_SLAM3::ViewerAR::Run,&viewerAR); - - ros::spin(); - - // Stop all threads - SLAM.Shutdown(); - - // Save camera trajectory - SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt"); - - ros::shutdown(); - - return 0; -} - -void ImageGrabber::GrabImage(const sensor_msgs::ImageConstPtr& msg) -{ - // Copy the ros image message to cv::Mat. - cv_bridge::CvImageConstPtr cv_ptr; - try - { - cv_ptr = cv_bridge::toCvShare(msg); - } - catch (cv_bridge::Exception& e) - { - ROS_ERROR("cv_bridge exception: %s", e.what()); - return; - } - cv::Mat im = cv_ptr->image.clone(); - cv::Mat imu; - cv::Mat Tcw = mpSLAM->TrackMonocular(cv_ptr->image,cv_ptr->header.stamp.toSec()); - int state = mpSLAM->GetTrackingState(); - vector vMPs = mpSLAM->GetTrackedMapPoints(); - vector vKeys = mpSLAM->GetTrackedKeyPointsUn(); - - cv::undistort(im,imu,K,DistCoef); - - if(bRGB) - viewerAR.SetImagePose(imu,Tcw,state,vKeys,vMPs); - else - { - cv::cvtColor(imu,imu,CV_RGB2BGR); - viewerAR.SetImagePose(imu,Tcw,state,vKeys,vMPs); - } -} - - diff --git a/ROS2/ORB_SLAM3/src/ros_mono.cc b/ROS2/ORB_SLAM3/src/ros_mono.cc index 7e1adb3009..7b22d54eaa 100644 --- a/ROS2/ORB_SLAM3/src/ros_mono.cc +++ b/ROS2/ORB_SLAM3/src/ros_mono.cc @@ -22,46 +22,47 @@ #include #include -#include +#include #include - -#include - +#include #include"../../../include/System.h" -using namespace std; +#include -class ImageGrabber +class ImageGrabber: public rclcpp::Node { -public: - ImageGrabber(ORB_SLAM3::System* pSLAM):mpSLAM(pSLAM){} - - void GrabImage(const sensor_msgs::ImageConstPtr& msg); - - ORB_SLAM3::System* mpSLAM; + public: + ImageGrabber(ORB_SLAM3::System* pSLAM): + Node("Mono"), + mpSLAM(pSLAM) + { + sub_ = this->create_subscription("/camera/image_raw", 1, std::bind(&ImageGrabber::GrabImage, this, std::placeholders::_1)); + } + + void GrabImage(const sensor_msgs::msg::Image::ConstPtr& msg); + ORB_SLAM3::System* mpSLAM; + + private: + rclcpp::Subscription::SharedPtr sub_; }; + int main(int argc, char **argv) { - ros::init(argc, argv, "Mono"); - ros::start(); - + rclcpp::init(argc, argv); + // rclcpp::start(); + //rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("Mono"); if(argc != 3) { cerr << endl << "Usage: rosrun ORB_SLAM3 Mono path_to_vocabulary path_to_settings" << endl; - ros::shutdown(); + rclcpp::shutdown(); return 1; } // Create SLAM system. It initializes all system threads and gets ready to process frames. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR,true); - ImageGrabber igb(&SLAM); - - ros::NodeHandle nodeHandler; - ros::Subscriber sub = nodeHandler.subscribe("/camera/image_raw", 1, &ImageGrabber::GrabImage,&igb); - - ros::spin(); + rclcpp::spin(std::make_shared(&SLAM)); // Stop all threads SLAM.Shutdown(); @@ -69,12 +70,12 @@ int main(int argc, char **argv) // Save camera trajectory SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt"); - ros::shutdown(); + rclcpp::shutdown(); return 0; } -void ImageGrabber::GrabImage(const sensor_msgs::ImageConstPtr& msg) +void ImageGrabber::GrabImage(const sensor_msgs::msg::Image::ConstPtr& msg) { // Copy the ros image message to cv::Mat. cv_bridge::CvImageConstPtr cv_ptr; @@ -84,11 +85,11 @@ void ImageGrabber::GrabImage(const sensor_msgs::ImageConstPtr& msg) } catch (cv_bridge::Exception& e) { - ROS_ERROR("cv_bridge exception: %s", e.what()); + RCLCPP_ERROR(this->get_logger(), "cv_bridge exception: %s", e.what()); return; } - mpSLAM->TrackMonocular(cv_ptr->image,cv_ptr->header.stamp.toSec()); + mpSLAM->TrackMonocular(cv_ptr->image,cv_ptr->header.stamp.sec); } diff --git a/ROS2/ORB_SLAM3/src/ros_mono_inertial.cc b/ROS2/ORB_SLAM3/src/ros_mono_inertial.cc index fa3630285c..3a0a2a558b 100644 --- a/ROS2/ORB_SLAM3/src/ros_mono_inertial.cc +++ b/ROS2/ORB_SLAM3/src/ros_mono_inertial.cc @@ -25,58 +25,67 @@ #include #include -#include -#include -#include +#include +#include +#include +#include -#include +#include -#include"../../../include/System.h" -#include"../include/ImuTypes.h" +#include "../../../include/System.h" +#include "../include/ImuTypes.h" -using namespace std; - -class ImuGrabber +class ImuGrabber: public rclcpp::Node { public: - ImuGrabber(){}; - void GrabImu(const sensor_msgs::ImuConstPtr &imu_msg); + ImuGrabber(): + Node("Mono_Inertial") + { + sub_imu_ = this->create_subscription("/imu", 1000, std::bind(&ImuGrabber::GrabImu, this, std::placeholders::_1)); + }; + void GrabImu(const sensor_msgs::msg::Imu::ConstPtr &imu_msg); + + queue imuBuf; + std::mutex ImuBufMutex; +private: + rclcpp::Subscription::SharedPtr sub_imu_; - queue imuBuf; - std::mutex mBufMutex; }; -class ImageGrabber +class ImageGrabber: public ImuGrabber { public: - ImageGrabber(ORB_SLAM3::System* pSLAM, ImuGrabber *pImuGb, const bool bClahe): mpSLAM(pSLAM), mpImuGb(pImuGb), mbClahe(bClahe){} + ImageGrabber(ORB_SLAM3::System* pSLAM, const bool bClahe): + mpSLAM(pSLAM), + mbClahe(bClahe) + { + sub_img_ = this->create_subscription("/camera/image_raw", 100, std::bind(&ImageGrabber::GrabImage, this, std::placeholders::_1)); + } - void GrabImage(const sensor_msgs::ImageConstPtr& msg); - cv::Mat GetImage(const sensor_msgs::ImageConstPtr &img_msg); + void GrabImage(const sensor_msgs::msg::Image::ConstPtr& msg); + cv::Mat GetImage(const sensor_msgs::msg::Image::ConstPtr &img_msg); void SyncWithImu(); - queue img0Buf; - std::mutex mBufMutex; + queue img0Buf; + std::mutex ImageBufMutex; ORB_SLAM3::System* mpSLAM; - ImuGrabber *mpImuGb; + ImuGrabber ImuGb; const bool mbClahe; cv::Ptr mClahe = cv::createCLAHE(3.0, cv::Size(8, 8)); +private: + rclcpp::Subscription::SharedPtr sub_img_; }; - - int main(int argc, char **argv) { - ros::init(argc, argv, "Mono_Inertial"); - ros::NodeHandle n("~"); - ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Info); + rclcpp::init(argc, argv); bool bEqual = false; if(argc < 3 || argc > 4) { cerr << endl << "Usage: rosrun ORB_SLAM3 Mono_Inertial path_to_vocabulary path_to_settings [do_equalize]" << endl; - ros::shutdown(); + rclcpp::shutdown(); return 1; } @@ -91,30 +100,24 @@ int main(int argc, char **argv) // Create SLAM system. It initializes all system threads and gets ready to process frames. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::IMU_MONOCULAR,true); - ImuGrabber imugb; - ImageGrabber igb(&SLAM,&imugb,bEqual); // TODO - + //ImageGrabber igb(&SLAM,bEqual); // TODO + auto node = std::make_shared(&SLAM, &bEqual); // Maximum delay, 5 seconds - ros::Subscriber sub_imu = n.subscribe("/imu", 1000, &ImuGrabber::GrabImu, &imugb); - ros::Subscriber sub_img0 = n.subscribe("/camera/image_raw", 100, &ImageGrabber::GrabImage,&igb); - - std::thread sync_thread(&ImageGrabber::SyncWithImu,&igb); - - ros::spin(); - + std::thread sync_thread(&ImageGrabber::SyncWithImu, node); + rclcpp::spin(node); return 0; } -void ImageGrabber::GrabImage(const sensor_msgs::ImageConstPtr &img_msg) +void ImageGrabber::GrabImage(const sensor_msgs::msg::Image::ConstPtr &img_msg) { - mBufMutex.lock(); + ImageBufMutex.lock(); if (!img0Buf.empty()) img0Buf.pop(); img0Buf.push(img_msg); - mBufMutex.unlock(); + ImageBufMutex.unlock(); } -cv::Mat ImageGrabber::GetImage(const sensor_msgs::ImageConstPtr &img_msg) +cv::Mat ImageGrabber::GetImage(const sensor_msgs::msg::Image::ConstPtr &img_msg) { // Copy the ros image message to cv::Mat. cv_bridge::CvImageConstPtr cv_ptr; @@ -124,7 +127,7 @@ cv::Mat ImageGrabber::GetImage(const sensor_msgs::ImageConstPtr &img_msg) } catch (cv_bridge::Exception& e) { - ROS_ERROR("cv_bridge exception: %s", e.what()); + RCLCPP_ERROR(this->get_logger(), "cv_bridge exception: %s", e.what()); } if(cv_ptr->image.type()==0) @@ -144,34 +147,34 @@ void ImageGrabber::SyncWithImu() { cv::Mat im; double tIm = 0; - if (!img0Buf.empty()&&!mpImuGb->imuBuf.empty()) + if (!img0Buf.empty()&&imuBuf.empty()) { - tIm = img0Buf.front()->header.stamp.toSec(); - if(tIm>mpImuGb->imuBuf.back()->header.stamp.toSec()) + tIm = img0Buf.front()->header.stamp.sec; + if(tIm > imuBuf.back()->header.stamp.sec) continue; { - this->mBufMutex.lock(); + ImageBufMutex.lock(); im = GetImage(img0Buf.front()); img0Buf.pop(); - this->mBufMutex.unlock(); + ImageBufMutex.unlock(); } vector vImuMeas; - mpImuGb->mBufMutex.lock(); - if(!mpImuGb->imuBuf.empty()) + ImuBufMutex.lock(); + if(!imuBuf.empty()) { // Load imu measurements from buffer vImuMeas.clear(); - while(!mpImuGb->imuBuf.empty() && mpImuGb->imuBuf.front()->header.stamp.toSec()<=tIm) + while(!imuBuf.empty() && imuBuf.front()->header.stamp.sec<=tIm) { - double t = mpImuGb->imuBuf.front()->header.stamp.toSec(); - cv::Point3f acc(mpImuGb->imuBuf.front()->linear_acceleration.x, mpImuGb->imuBuf.front()->linear_acceleration.y, mpImuGb->imuBuf.front()->linear_acceleration.z); - cv::Point3f gyr(mpImuGb->imuBuf.front()->angular_velocity.x, mpImuGb->imuBuf.front()->angular_velocity.y, mpImuGb->imuBuf.front()->angular_velocity.z); + double t = imuBuf.front()->header.stamp.sec; + cv::Point3f acc(imuBuf.front()->linear_acceleration.x, imuBuf.front()->linear_acceleration.y, imuBuf.front()->linear_acceleration.z); + cv::Point3f gyr(imuBuf.front()->angular_velocity.x, imuBuf.front()->angular_velocity.y, imuBuf.front()->angular_velocity.z); vImuMeas.push_back(ORB_SLAM3::IMU::Point(acc,gyr,t)); - mpImuGb->imuBuf.pop(); + imuBuf.pop(); } } - mpImuGb->mBufMutex.unlock(); + ImuBufMutex.unlock(); if(mbClahe) mClahe->apply(im,im); @@ -183,11 +186,11 @@ void ImageGrabber::SyncWithImu() } } -void ImuGrabber::GrabImu(const sensor_msgs::ImuConstPtr &imu_msg) +void ImuGrabber::GrabImu(const sensor_msgs::msg::Imu::ConstPtr &imu_msg) { - mBufMutex.lock(); + ImuBufMutex.lock(); imuBuf.push(imu_msg); - mBufMutex.unlock(); + ImuBufMutex.unlock(); return; } diff --git a/ROS2/ORB_SLAM3/src/ros_rgbd.cc b/ROS2/ORB_SLAM3/src/ros_rgbd.cc deleted file mode 100644 index faf6131541..0000000000 --- a/ROS2/ORB_SLAM3/src/ros_rgbd.cc +++ /dev/null @@ -1,112 +0,0 @@ -/** -* This file is part of ORB-SLAM3 -* -* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. -* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. -* -* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public -* License as published by the Free Software Foundation, either version 3 of the License, or -* (at your option) any later version. -* -* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even -* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -* GNU General Public License for more details. -* -* You should have received a copy of the GNU General Public License along with ORB-SLAM3. -* If not, see . -*/ - - -#include -#include -#include -#include - -#include -#include -#include -#include -#include - -#include - -#include"../../../include/System.h" - -using namespace std; - -class ImageGrabber -{ -public: - ImageGrabber(ORB_SLAM3::System* pSLAM):mpSLAM(pSLAM){} - - void GrabRGBD(const sensor_msgs::ImageConstPtr& msgRGB,const sensor_msgs::ImageConstPtr& msgD); - - ORB_SLAM3::System* mpSLAM; -}; - -int main(int argc, char **argv) -{ - ros::init(argc, argv, "RGBD"); - ros::start(); - - if(argc != 3) - { - cerr << endl << "Usage: rosrun ORB_SLAM3 RGBD path_to_vocabulary path_to_settings" << endl; - ros::shutdown(); - return 1; - } - - // Create SLAM system. It initializes all system threads and gets ready to process frames. - ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::RGBD,true); - - ImageGrabber igb(&SLAM); - - ros::NodeHandle nh; - - message_filters::Subscriber rgb_sub(nh, "/camera/rgb/image_raw", 100); - message_filters::Subscriber depth_sub(nh, "camera/depth_registered/image_raw", 100); - typedef message_filters::sync_policies::ApproximateTime sync_pol; - message_filters::Synchronizer sync(sync_pol(10), rgb_sub,depth_sub); - sync.registerCallback(boost::bind(&ImageGrabber::GrabRGBD,&igb,_1,_2)); - - ros::spin(); - - // Stop all threads - SLAM.Shutdown(); - - // Save camera trajectory - SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt"); - - ros::shutdown(); - - return 0; -} - -void ImageGrabber::GrabRGBD(const sensor_msgs::ImageConstPtr& msgRGB,const sensor_msgs::ImageConstPtr& msgD) -{ - // Copy the ros image message to cv::Mat. - cv_bridge::CvImageConstPtr cv_ptrRGB; - try - { - cv_ptrRGB = cv_bridge::toCvShare(msgRGB); - } - catch (cv_bridge::Exception& e) - { - ROS_ERROR("cv_bridge exception: %s", e.what()); - return; - } - - cv_bridge::CvImageConstPtr cv_ptrD; - try - { - cv_ptrD = cv_bridge::toCvShare(msgD); - } - catch (cv_bridge::Exception& e) - { - ROS_ERROR("cv_bridge exception: %s", e.what()); - return; - } - mpSLAM->TrackRGBD(cv_ptrRGB->image,cv_ptrD->image,cv_ptrRGB->header.stamp.toSec()); -} - - diff --git a/ROS2/ORB_SLAM3/src/ros_stereo.cc b/ROS2/ORB_SLAM3/src/ros_stereo.cc deleted file mode 100644 index 030fdb6af8..0000000000 --- a/ROS2/ORB_SLAM3/src/ros_stereo.cc +++ /dev/null @@ -1,170 +0,0 @@ -/** -* This file is part of ORB-SLAM3 -* -* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. -* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. -* -* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public -* License as published by the Free Software Foundation, either version 3 of the License, or -* (at your option) any later version. -* -* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even -* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -* GNU General Public License for more details. -* -* You should have received a copy of the GNU General Public License along with ORB-SLAM3. -* If not, see . -*/ - - -#include -#include -#include -#include - -#include -#include -#include -#include -#include - -#include - -#include"../../../include/System.h" - -using namespace std; - -class ImageGrabber -{ -public: - ImageGrabber(ORB_SLAM3::System* pSLAM):mpSLAM(pSLAM){} - - void GrabStereo(const sensor_msgs::ImageConstPtr& msgLeft,const sensor_msgs::ImageConstPtr& msgRight); - - ORB_SLAM3::System* mpSLAM; - bool do_rectify; - cv::Mat M1l,M2l,M1r,M2r; -}; - -int main(int argc, char **argv) -{ - ros::init(argc, argv, "RGBD"); - ros::start(); - - if(argc != 4) - { - cerr << endl << "Usage: rosrun ORB_SLAM3 Stereo path_to_vocabulary path_to_settings do_rectify" << endl; - ros::shutdown(); - return 1; - } - - // Create SLAM system. It initializes all system threads and gets ready to process frames. - ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::STEREO,true); - - ImageGrabber igb(&SLAM); - - stringstream ss(argv[3]); - ss >> boolalpha >> igb.do_rectify; - - if(igb.do_rectify) - { - // Load settings related to stereo calibration - cv::FileStorage fsSettings(argv[2], cv::FileStorage::READ); - if(!fsSettings.isOpened()) - { - cerr << "ERROR: Wrong path to settings" << endl; - return -1; - } - - cv::Mat K_l, K_r, P_l, P_r, R_l, R_r, D_l, D_r; - fsSettings["LEFT.K"] >> K_l; - fsSettings["RIGHT.K"] >> K_r; - - fsSettings["LEFT.P"] >> P_l; - fsSettings["RIGHT.P"] >> P_r; - - fsSettings["LEFT.R"] >> R_l; - fsSettings["RIGHT.R"] >> R_r; - - fsSettings["LEFT.D"] >> D_l; - fsSettings["RIGHT.D"] >> D_r; - - int rows_l = fsSettings["LEFT.height"]; - int cols_l = fsSettings["LEFT.width"]; - int rows_r = fsSettings["RIGHT.height"]; - int cols_r = fsSettings["RIGHT.width"]; - - if(K_l.empty() || K_r.empty() || P_l.empty() || P_r.empty() || R_l.empty() || R_r.empty() || D_l.empty() || D_r.empty() || - rows_l==0 || rows_r==0 || cols_l==0 || cols_r==0) - { - cerr << "ERROR: Calibration parameters to rectify stereo are missing!" << endl; - return -1; - } - - cv::initUndistortRectifyMap(K_l,D_l,R_l,P_l.rowRange(0,3).colRange(0,3),cv::Size(cols_l,rows_l),CV_32F,igb.M1l,igb.M2l); - cv::initUndistortRectifyMap(K_r,D_r,R_r,P_r.rowRange(0,3).colRange(0,3),cv::Size(cols_r,rows_r),CV_32F,igb.M1r,igb.M2r); - } - - ros::NodeHandle nh; - - message_filters::Subscriber left_sub(nh, "/camera/left/image_raw", 1); - message_filters::Subscriber right_sub(nh, "/camera/right/image_raw", 1); - typedef message_filters::sync_policies::ApproximateTime sync_pol; - message_filters::Synchronizer sync(sync_pol(10), left_sub,right_sub); - sync.registerCallback(boost::bind(&ImageGrabber::GrabStereo,&igb,_1,_2)); - - ros::spin(); - - // Stop all threads - SLAM.Shutdown(); - - // Save camera trajectory - SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory_TUM_Format.txt"); - SLAM.SaveTrajectoryTUM("FrameTrajectory_TUM_Format.txt"); - SLAM.SaveTrajectoryKITTI("FrameTrajectory_KITTI_Format.txt"); - - ros::shutdown(); - - return 0; -} - -void ImageGrabber::GrabStereo(const sensor_msgs::ImageConstPtr& msgLeft,const sensor_msgs::ImageConstPtr& msgRight) -{ - // Copy the ros image message to cv::Mat. - cv_bridge::CvImageConstPtr cv_ptrLeft; - try - { - cv_ptrLeft = cv_bridge::toCvShare(msgLeft); - } - catch (cv_bridge::Exception& e) - { - ROS_ERROR("cv_bridge exception: %s", e.what()); - return; - } - - cv_bridge::CvImageConstPtr cv_ptrRight; - try - { - cv_ptrRight = cv_bridge::toCvShare(msgRight); - } - catch (cv_bridge::Exception& e) - { - ROS_ERROR("cv_bridge exception: %s", e.what()); - return; - } - - if(do_rectify) - { - cv::Mat imLeft, imRight; - cv::remap(cv_ptrLeft->image,imLeft,M1l,M2l,cv::INTER_LINEAR); - cv::remap(cv_ptrRight->image,imRight,M1r,M2r,cv::INTER_LINEAR); - mpSLAM->TrackStereo(imLeft,imRight,cv_ptrLeft->header.stamp.toSec()); - } - else - { - mpSLAM->TrackStereo(cv_ptrLeft->image,cv_ptrRight->image,cv_ptrLeft->header.stamp.toSec()); - } - -} - - diff --git a/ROS2/ORB_SLAM3/src/ros_stereo_inertial.cc b/ROS2/ORB_SLAM3/src/ros_stereo_inertial.cc deleted file mode 100644 index 231ad72c07..0000000000 --- a/ROS2/ORB_SLAM3/src/ros_stereo_inertial.cc +++ /dev/null @@ -1,286 +0,0 @@ -/** -* This file is part of ORB-SLAM3 -* -* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. -* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. -* -* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public -* License as published by the Free Software Foundation, either version 3 of the License, or -* (at your option) any later version. -* -* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even -* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -* GNU General Public License for more details. -* -* You should have received a copy of the GNU General Public License along with ORB-SLAM3. -* If not, see . -*/ - -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include - -#include - -#include"../../../include/System.h" -#include"../include/ImuTypes.h" - -using namespace std; - -class ImuGrabber -{ -public: - ImuGrabber(){}; - void GrabImu(const sensor_msgs::ImuConstPtr &imu_msg); - - queue imuBuf; - std::mutex mBufMutex; -}; - -class ImageGrabber -{ -public: - ImageGrabber(ORB_SLAM3::System* pSLAM, ImuGrabber *pImuGb, const bool bRect, const bool bClahe): mpSLAM(pSLAM), mpImuGb(pImuGb), do_rectify(bRect), mbClahe(bClahe){} - - void GrabImageLeft(const sensor_msgs::ImageConstPtr& msg); - void GrabImageRight(const sensor_msgs::ImageConstPtr& msg); - cv::Mat GetImage(const sensor_msgs::ImageConstPtr &img_msg); - void SyncWithImu(); - - queue imgLeftBuf, imgRightBuf; - std::mutex mBufMutexLeft,mBufMutexRight; - - ORB_SLAM3::System* mpSLAM; - ImuGrabber *mpImuGb; - - const bool do_rectify; - cv::Mat M1l,M2l,M1r,M2r; - - const bool mbClahe; - cv::Ptr mClahe = cv::createCLAHE(3.0, cv::Size(8, 8)); -}; - - - -int main(int argc, char **argv) -{ - ros::init(argc, argv, "Stereo_Inertial"); - ros::NodeHandle n("~"); - ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Info); - bool bEqual = false; - if(argc < 4 || argc > 5) - { - cerr << endl << "Usage: rosrun ORB_SLAM3 Stereo_Inertial path_to_vocabulary path_to_settings do_rectify [do_equalize]" << endl; - ros::shutdown(); - return 1; - } - - std::string sbRect(argv[3]); - if(argc==5) - { - std::string sbEqual(argv[4]); - if(sbEqual == "true") - bEqual = true; - } - - // Create SLAM system. It initializes all system threads and gets ready to process frames. - ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::IMU_STEREO,true); - - ImuGrabber imugb; - ImageGrabber igb(&SLAM,&imugb,sbRect == "true",bEqual); - - if(igb.do_rectify) - { - // Load settings related to stereo calibration - cv::FileStorage fsSettings(argv[2], cv::FileStorage::READ); - if(!fsSettings.isOpened()) - { - cerr << "ERROR: Wrong path to settings" << endl; - return -1; - } - - cv::Mat K_l, K_r, P_l, P_r, R_l, R_r, D_l, D_r; - fsSettings["LEFT.K"] >> K_l; - fsSettings["RIGHT.K"] >> K_r; - - fsSettings["LEFT.P"] >> P_l; - fsSettings["RIGHT.P"] >> P_r; - - fsSettings["LEFT.R"] >> R_l; - fsSettings["RIGHT.R"] >> R_r; - - fsSettings["LEFT.D"] >> D_l; - fsSettings["RIGHT.D"] >> D_r; - - int rows_l = fsSettings["LEFT.height"]; - int cols_l = fsSettings["LEFT.width"]; - int rows_r = fsSettings["RIGHT.height"]; - int cols_r = fsSettings["RIGHT.width"]; - - if(K_l.empty() || K_r.empty() || P_l.empty() || P_r.empty() || R_l.empty() || R_r.empty() || D_l.empty() || D_r.empty() || - rows_l==0 || rows_r==0 || cols_l==0 || cols_r==0) - { - cerr << "ERROR: Calibration parameters to rectify stereo are missing!" << endl; - return -1; - } - - cv::initUndistortRectifyMap(K_l,D_l,R_l,P_l.rowRange(0,3).colRange(0,3),cv::Size(cols_l,rows_l),CV_32F,igb.M1l,igb.M2l); - cv::initUndistortRectifyMap(K_r,D_r,R_r,P_r.rowRange(0,3).colRange(0,3),cv::Size(cols_r,rows_r),CV_32F,igb.M1r,igb.M2r); - } - - // Maximum delay, 5 seconds - ros::Subscriber sub_imu = n.subscribe("/imu", 1000, &ImuGrabber::GrabImu, &imugb); - ros::Subscriber sub_img_left = n.subscribe("/camera/left/image_raw", 100, &ImageGrabber::GrabImageLeft,&igb); - ros::Subscriber sub_img_right = n.subscribe("/camera/right/image_raw", 100, &ImageGrabber::GrabImageRight,&igb); - - std::thread sync_thread(&ImageGrabber::SyncWithImu,&igb); - - ros::spin(); - - return 0; -} - - - -void ImageGrabber::GrabImageLeft(const sensor_msgs::ImageConstPtr &img_msg) -{ - mBufMutexLeft.lock(); - if (!imgLeftBuf.empty()) - imgLeftBuf.pop(); - imgLeftBuf.push(img_msg); - mBufMutexLeft.unlock(); -} - -void ImageGrabber::GrabImageRight(const sensor_msgs::ImageConstPtr &img_msg) -{ - mBufMutexRight.lock(); - if (!imgRightBuf.empty()) - imgRightBuf.pop(); - imgRightBuf.push(img_msg); - mBufMutexRight.unlock(); -} - -cv::Mat ImageGrabber::GetImage(const sensor_msgs::ImageConstPtr &img_msg) -{ - // Copy the ros image message to cv::Mat. - cv_bridge::CvImageConstPtr cv_ptr; - try - { - cv_ptr = cv_bridge::toCvShare(img_msg, sensor_msgs::image_encodings::MONO8); - } - catch (cv_bridge::Exception& e) - { - ROS_ERROR("cv_bridge exception: %s", e.what()); - } - - if(cv_ptr->image.type()==0) - { - return cv_ptr->image.clone(); - } - else - { - std::cout << "Error type" << std::endl; - return cv_ptr->image.clone(); - } -} - -void ImageGrabber::SyncWithImu() -{ - const double maxTimeDiff = 0.01; - while(1) - { - cv::Mat imLeft, imRight; - double tImLeft = 0, tImRight = 0; - if (!imgLeftBuf.empty()&&!imgRightBuf.empty()&&!mpImuGb->imuBuf.empty()) - { - tImLeft = imgLeftBuf.front()->header.stamp.toSec(); - tImRight = imgRightBuf.front()->header.stamp.toSec(); - - this->mBufMutexRight.lock(); - while((tImLeft-tImRight)>maxTimeDiff && imgRightBuf.size()>1) - { - imgRightBuf.pop(); - tImRight = imgRightBuf.front()->header.stamp.toSec(); - } - this->mBufMutexRight.unlock(); - - this->mBufMutexLeft.lock(); - while((tImRight-tImLeft)>maxTimeDiff && imgLeftBuf.size()>1) - { - imgLeftBuf.pop(); - tImLeft = imgLeftBuf.front()->header.stamp.toSec(); - } - this->mBufMutexLeft.unlock(); - - if((tImLeft-tImRight)>maxTimeDiff || (tImRight-tImLeft)>maxTimeDiff) - { - // std::cout << "big time difference" << std::endl; - continue; - } - if(tImLeft>mpImuGb->imuBuf.back()->header.stamp.toSec()) - continue; - - this->mBufMutexLeft.lock(); - imLeft = GetImage(imgLeftBuf.front()); - imgLeftBuf.pop(); - this->mBufMutexLeft.unlock(); - - this->mBufMutexRight.lock(); - imRight = GetImage(imgRightBuf.front()); - imgRightBuf.pop(); - this->mBufMutexRight.unlock(); - - vector vImuMeas; - mpImuGb->mBufMutex.lock(); - if(!mpImuGb->imuBuf.empty()) - { - // Load imu measurements from buffer - vImuMeas.clear(); - while(!mpImuGb->imuBuf.empty() && mpImuGb->imuBuf.front()->header.stamp.toSec()<=tImLeft) - { - double t = mpImuGb->imuBuf.front()->header.stamp.toSec(); - cv::Point3f acc(mpImuGb->imuBuf.front()->linear_acceleration.x, mpImuGb->imuBuf.front()->linear_acceleration.y, mpImuGb->imuBuf.front()->linear_acceleration.z); - cv::Point3f gyr(mpImuGb->imuBuf.front()->angular_velocity.x, mpImuGb->imuBuf.front()->angular_velocity.y, mpImuGb->imuBuf.front()->angular_velocity.z); - vImuMeas.push_back(ORB_SLAM3::IMU::Point(acc,gyr,t)); - mpImuGb->imuBuf.pop(); - } - } - mpImuGb->mBufMutex.unlock(); - if(mbClahe) - { - mClahe->apply(imLeft,imLeft); - mClahe->apply(imRight,imRight); - } - - if(do_rectify) - { - cv::remap(imLeft,imLeft,M1l,M2l,cv::INTER_LINEAR); - cv::remap(imRight,imRight,M1r,M2r,cv::INTER_LINEAR); - } - - mpSLAM->TrackStereo(imLeft,imRight,tImLeft,vImuMeas); - - std::chrono::milliseconds tSleep(1); - std::this_thread::sleep_for(tSleep); - } - } -} - -void ImuGrabber::GrabImu(const sensor_msgs::ImuConstPtr &imu_msg) -{ - mBufMutex.lock(); - imuBuf.push(imu_msg); - mBufMutex.unlock(); - return; -} - - diff --git a/ROS2/log/build_2023-06-19_20-42-56/ORB_SLAM3/command.log b/ROS2/log/build_2023-06-19_20-42-56/ORB_SLAM3/command.log deleted file mode 100644 index b36f616684..0000000000 --- a/ROS2/log/build_2023-06-19_20-42-56/ORB_SLAM3/command.log +++ /dev/null @@ -1,4 +0,0 @@ -Invoking command in '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3': /usr/bin/cmake /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3 -DCMAKE_INSTALL_PREFIX=/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/install/ORB_SLAM3 -Invoked command in '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3' returned '0': /usr/bin/cmake /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3 -DCMAKE_INSTALL_PREFIX=/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/install/ORB_SLAM3 -Invoking command in '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3': /usr/bin/cmake --build /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3 -- -j8 -l8 -Invoked command in '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3' returned '2': /usr/bin/cmake --build /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3 -- -j8 -l8 diff --git a/ROS2/log/build_2023-06-19_20-42-56/ORB_SLAM3/stderr.log b/ROS2/log/build_2023-06-19_20-42-56/ORB_SLAM3/stderr.log deleted file mode 100644 index a9ee4effc5..0000000000 --- a/ROS2/log/build_2023-06-19_20-42-56/ORB_SLAM3/stderr.log +++ /dev/null @@ -1,81 +0,0 @@ -CMake Deprecation Warning at CMakeLists.txt:1 (cmake_minimum_required): - Compatibility with CMake < 2.8.12 will be removed from a future version of - CMake. - - Update the VERSION argument value or use a ... suffix to tell - CMake that the project does not need compatibility with older versions. - - -CMake Warning (dev) at CMakeLists.txt:57 (add_executable): - Policy CMP0003 should be set before this line. Add code such as - - if(COMMAND cmake_policy) - cmake_policy(SET CMP0003 NEW) - endif(COMMAND cmake_policy) - - as early as possible but after the most recent call to - cmake_minimum_required or cmake_policy(VERSION). This warning appears - because target "Mono" links to some libraries for which the linker must - search: - - -lboost_system - - and other libraries with known full path: - - /usr/lib/x86_64-linux-gnu/libopencv_stitching.so.4.5.4d - /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/../../Thirdparty/DBoW2/lib/libDBoW2.so - /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/../../Thirdparty/g2o/lib/libg2o.so - /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/../../lib/libORB_SLAM3.so - - CMake is adding directories in the second list to the linker search path in - case they are needed to find libraries from the first list (for backwards - compatibility with CMake 2.4). Set policy CMP0003 to OLD or NEW to enable - or disable this behavior explicitly. Run "cmake --help-policy CMP0003" for - more information. -This warning is for project developers. Use -Wno-dev to suppress it. - -/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/ros_rgbd.cc:25:9: fatal error: ros/ros.h: No such file or directory - 25 | #include - | ^~~~~~~~~~~ -compilation terminated. -gmake[2]: *** [CMakeFiles/RGBD.dir/build.make:76: CMakeFiles/RGBD.dir/src/ros_rgbd.o] Error 1 -gmake[1]: *** [CMakeFiles/Makefile2:171: CMakeFiles/RGBD.dir/all] Error 2 -gmake[1]: *** Waiting for unfinished jobs.... -/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/AR/ros_mono_ar.cc:25:9: fatal error: ros/ros.h: No such file or directory - 25 | #include - | ^~~~~~~~~~~ -compilation terminated. -/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/ros_mono.cc:25:9: fatal error: ros/ros.h: No such file or directory - 25 | #include - | ^~~~~~~~~~~ -compilation terminated. -/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/ros_stereo.cc:25:9: fatal error: ros/ros.h: No such file or directory - 25 | #include - | ^~~~~~~~~~~ -compilation terminated. -gmake[2]: *** [CMakeFiles/MonoAR.dir/build.make:76: CMakeFiles/MonoAR.dir/src/AR/ros_mono_ar.o] Error 1 -gmake[2]: *** [CMakeFiles/Mono.dir/build.make:76: CMakeFiles/Mono.dir/src/ros_mono.o] Error 1 -gmake[2]: *** Waiting for unfinished jobs.... -gmake[1]: *** [CMakeFiles/Makefile2:93: CMakeFiles/Mono.dir/all] Error 2 -gmake[2]: *** [CMakeFiles/Stereo.dir/build.make:76: CMakeFiles/Stereo.dir/src/ros_stereo.o] Error 1 -gmake[1]: *** [CMakeFiles/Makefile2:145: CMakeFiles/Stereo.dir/all] Error 2 -/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/ros_mono_inertial.cc:28:9: fatal error: ros/ros.h: No such file or directory - 28 | #include - | ^~~~~~~~~~~ -compilation terminated. -/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/ros_stereo_inertial.cc:28:9: fatal error: ros/ros.h: No such file or directory - 28 | #include - | ^~~~~~~~~~~ -compilation terminated. -gmake[2]: *** [CMakeFiles/Mono_Inertial.dir/build.make:76: CMakeFiles/Mono_Inertial.dir/src/ros_mono_inertial.o] Error 1 -gmake[1]: *** [CMakeFiles/Makefile2:197: CMakeFiles/Mono_Inertial.dir/all] Error 2 -gmake[2]: *** [CMakeFiles/Stereo_Inertial.dir/build.make:76: CMakeFiles/Stereo_Inertial.dir/src/ros_stereo_inertial.o] Error 1 -gmake[1]: *** [CMakeFiles/Makefile2:223: CMakeFiles/Stereo_Inertial.dir/all] Error 2 -In file included from /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/AR/ViewerAR.cc:19: -/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/AR/ViewerAR.h:25:10: fatal error: pangolin/pangolin.h: No such file or directory - 25 | #include  - | ^~~~~~~~~~~~~~~~~~~~~ -compilation terminated. -gmake[2]: *** [CMakeFiles/MonoAR.dir/build.make:90: CMakeFiles/MonoAR.dir/src/AR/ViewerAR.o] Error 1 -gmake[1]: *** [CMakeFiles/Makefile2:119: CMakeFiles/MonoAR.dir/all] Error 2 -gmake: *** [Makefile:91: all] Error 2 diff --git a/ROS2/log/build_2023-06-19_20-42-56/ORB_SLAM3/stdout.log b/ROS2/log/build_2023-06-19_20-42-56/ORB_SLAM3/stdout.log deleted file mode 100644 index c983293df4..0000000000 --- a/ROS2/log/build_2023-06-19_20-42-56/ORB_SLAM3/stdout.log +++ /dev/null @@ -1,27 +0,0 @@ --- The C compiler identification is GNU 11.3.0 --- The CXX compiler identification is GNU 11.3.0 --- Detecting C compiler ABI info --- Detecting C compiler ABI info - done --- Check for working C compiler: /usr/bin/cc - skipped --- Detecting C compile features --- Detecting C compile features - done --- Detecting CXX compiler ABI info --- Detecting CXX compiler ABI info - done --- Check for working CXX compiler: /usr/bin/c++ - skipped --- Detecting CXX compile features --- Detecting CXX compile features - done --- Performing Test COMPILER_SUPPORTS_CXX11 --- Performing Test COMPILER_SUPPORTS_CXX11 - Success --- Performing Test COMPILER_SUPPORTS_CXX0X --- Performing Test COMPILER_SUPPORTS_CXX0X - Success --- Using flag -std=c++11. --- Configuring done --- Generating done --- Build files have been written to: /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3 -[ 23%] Building CXX object CMakeFiles/Mono.dir/src/ros_mono.o -[ 23%] Building CXX object CMakeFiles/MonoAR.dir/src/AR/ViewerAR.o -[ 23%] Building CXX object CMakeFiles/MonoAR.dir/src/AR/ros_mono_ar.o -[ 30%] Building CXX object CMakeFiles/Mono_Inertial.dir/src/ros_mono_inertial.o -[ 38%] Building CXX object CMakeFiles/Stereo.dir/src/ros_stereo.o -[ 53%] Building CXX object CMakeFiles/Stereo_Inertial.dir/src/ros_stereo_inertial.o -[ 53%] Building CXX object CMakeFiles/RGBD.dir/src/ros_rgbd.o diff --git a/ROS2/log/build_2023-06-19_20-42-56/ORB_SLAM3/stdout_stderr.log b/ROS2/log/build_2023-06-19_20-42-56/ORB_SLAM3/stdout_stderr.log deleted file mode 100644 index 04e439a119..0000000000 --- a/ROS2/log/build_2023-06-19_20-42-56/ORB_SLAM3/stdout_stderr.log +++ /dev/null @@ -1,108 +0,0 @@ -CMake Deprecation Warning at CMakeLists.txt:1 (cmake_minimum_required): - Compatibility with CMake < 2.8.12 will be removed from a future version of - CMake. - - Update the VERSION argument value or use a ... suffix to tell - CMake that the project does not need compatibility with older versions. - - --- The C compiler identification is GNU 11.3.0 --- The CXX compiler identification is GNU 11.3.0 --- Detecting C compiler ABI info --- Detecting C compiler ABI info - done --- Check for working C compiler: /usr/bin/cc - skipped --- Detecting C compile features --- Detecting C compile features - done --- Detecting CXX compiler ABI info --- Detecting CXX compiler ABI info - done --- Check for working CXX compiler: /usr/bin/c++ - skipped --- Detecting CXX compile features --- Detecting CXX compile features - done --- Performing Test COMPILER_SUPPORTS_CXX11 --- Performing Test COMPILER_SUPPORTS_CXX11 - Success --- Performing Test COMPILER_SUPPORTS_CXX0X --- Performing Test COMPILER_SUPPORTS_CXX0X - Success --- Using flag -std=c++11. --- Configuring done -CMake Warning (dev) at CMakeLists.txt:57 (add_executable): - Policy CMP0003 should be set before this line. Add code such as - - if(COMMAND cmake_policy) - cmake_policy(SET CMP0003 NEW) - endif(COMMAND cmake_policy) - - as early as possible but after the most recent call to - cmake_minimum_required or cmake_policy(VERSION). This warning appears - because target "Mono" links to some libraries for which the linker must - search: - - -lboost_system - - and other libraries with known full path: - - /usr/lib/x86_64-linux-gnu/libopencv_stitching.so.4.5.4d - /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/../../Thirdparty/DBoW2/lib/libDBoW2.so - /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/../../Thirdparty/g2o/lib/libg2o.so - /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/../../lib/libORB_SLAM3.so - - CMake is adding directories in the second list to the linker search path in - case they are needed to find libraries from the first list (for backwards - compatibility with CMake 2.4). Set policy CMP0003 to OLD or NEW to enable - or disable this behavior explicitly. Run "cmake --help-policy CMP0003" for - more information. -This warning is for project developers. Use -Wno-dev to suppress it. - --- Generating done --- Build files have been written to: /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3 -[ 23%] Building CXX object CMakeFiles/Mono.dir/src/ros_mono.o -[ 23%] Building CXX object CMakeFiles/MonoAR.dir/src/AR/ViewerAR.o -[ 23%] Building CXX object CMakeFiles/MonoAR.dir/src/AR/ros_mono_ar.o -[ 30%] Building CXX object CMakeFiles/Mono_Inertial.dir/src/ros_mono_inertial.o -[ 38%] Building CXX object CMakeFiles/Stereo.dir/src/ros_stereo.o -[ 53%] Building CXX object CMakeFiles/Stereo_Inertial.dir/src/ros_stereo_inertial.o -[ 53%] Building CXX object CMakeFiles/RGBD.dir/src/ros_rgbd.o -/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/ros_rgbd.cc:25:9: fatal error: ros/ros.h: No such file or directory - 25 | #include - | ^~~~~~~~~~~ -compilation terminated. -gmake[2]: *** [CMakeFiles/RGBD.dir/build.make:76: CMakeFiles/RGBD.dir/src/ros_rgbd.o] Error 1 -gmake[1]: *** [CMakeFiles/Makefile2:171: CMakeFiles/RGBD.dir/all] Error 2 -gmake[1]: *** Waiting for unfinished jobs.... -/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/AR/ros_mono_ar.cc:25:9: fatal error: ros/ros.h: No such file or directory - 25 | #include - | ^~~~~~~~~~~ -compilation terminated. -/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/ros_mono.cc:25:9: fatal error: ros/ros.h: No such file or directory - 25 | #include - | ^~~~~~~~~~~ -compilation terminated. -/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/ros_stereo.cc:25:9: fatal error: ros/ros.h: No such file or directory - 25 | #include - | ^~~~~~~~~~~ -compilation terminated. -gmake[2]: *** [CMakeFiles/MonoAR.dir/build.make:76: CMakeFiles/MonoAR.dir/src/AR/ros_mono_ar.o] Error 1 -gmake[2]: *** [CMakeFiles/Mono.dir/build.make:76: CMakeFiles/Mono.dir/src/ros_mono.o] Error 1 -gmake[2]: *** Waiting for unfinished jobs.... -gmake[1]: *** [CMakeFiles/Makefile2:93: CMakeFiles/Mono.dir/all] Error 2 -gmake[2]: *** [CMakeFiles/Stereo.dir/build.make:76: CMakeFiles/Stereo.dir/src/ros_stereo.o] Error 1 -gmake[1]: *** [CMakeFiles/Makefile2:145: CMakeFiles/Stereo.dir/all] Error 2 -/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/ros_mono_inertial.cc:28:9: fatal error: ros/ros.h: No such file or directory - 28 | #include - | ^~~~~~~~~~~ -compilation terminated. -/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/ros_stereo_inertial.cc:28:9: fatal error: ros/ros.h: No such file or directory - 28 | #include - | ^~~~~~~~~~~ -compilation terminated. -gmake[2]: *** [CMakeFiles/Mono_Inertial.dir/build.make:76: CMakeFiles/Mono_Inertial.dir/src/ros_mono_inertial.o] Error 1 -gmake[1]: *** [CMakeFiles/Makefile2:197: CMakeFiles/Mono_Inertial.dir/all] Error 2 -gmake[2]: *** [CMakeFiles/Stereo_Inertial.dir/build.make:76: CMakeFiles/Stereo_Inertial.dir/src/ros_stereo_inertial.o] Error 1 -gmake[1]: *** [CMakeFiles/Makefile2:223: CMakeFiles/Stereo_Inertial.dir/all] Error 2 -In file included from /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/AR/ViewerAR.cc:19: -/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/AR/ViewerAR.h:25:10: fatal error: pangolin/pangolin.h: No such file or directory - 25 | #include  - | ^~~~~~~~~~~~~~~~~~~~~ -compilation terminated. -gmake[2]: *** [CMakeFiles/MonoAR.dir/build.make:90: CMakeFiles/MonoAR.dir/src/AR/ViewerAR.o] Error 1 -gmake[1]: *** [CMakeFiles/Makefile2:119: CMakeFiles/MonoAR.dir/all] Error 2 -gmake: *** [Makefile:91: all] Error 2 diff --git a/ROS2/log/build_2023-06-19_20-42-56/ORB_SLAM3/streams.log b/ROS2/log/build_2023-06-19_20-42-56/ORB_SLAM3/streams.log deleted file mode 100644 index d969e2ec18..0000000000 --- a/ROS2/log/build_2023-06-19_20-42-56/ORB_SLAM3/streams.log +++ /dev/null @@ -1,112 +0,0 @@ -[0.007s] Invoking command in '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3': /usr/bin/cmake /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3 -DCMAKE_INSTALL_PREFIX=/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/install/ORB_SLAM3 -[0.013s] CMake Deprecation Warning at CMakeLists.txt:1 (cmake_minimum_required): -[0.013s] Compatibility with CMake < 2.8.12 will be removed from a future version of -[0.013s] CMake. -[0.013s] -[0.013s] Update the VERSION argument value or use a ... suffix to tell -[0.013s] CMake that the project does not need compatibility with older versions. -[0.013s] -[0.013s]  -[0.049s] -- The C compiler identification is GNU 11.3.0 -[0.091s] -- The CXX compiler identification is GNU 11.3.0 -[0.096s] -- Detecting C compiler ABI info -[0.151s] -- Detecting C compiler ABI info - done -[0.157s] -- Check for working C compiler: /usr/bin/cc - skipped -[0.157s] -- Detecting C compile features -[0.157s] -- Detecting C compile features - done -[0.160s] -- Detecting CXX compiler ABI info -[0.220s] -- Detecting CXX compiler ABI info - done -[0.225s] -- Check for working CXX compiler: /usr/bin/c++ - skipped -[0.225s] -- Detecting CXX compile features -[0.226s] -- Detecting CXX compile features - done -[0.227s] -- Performing Test COMPILER_SUPPORTS_CXX11 -[0.292s] -- Performing Test COMPILER_SUPPORTS_CXX11 - Success -[0.293s] -- Performing Test COMPILER_SUPPORTS_CXX0X -[0.349s] -- Performing Test COMPILER_SUPPORTS_CXX0X - Success -[0.350s] -- Using flag -std=c++11. -[0.361s] -- Configuring done -[0.365s] CMake Warning (dev) at CMakeLists.txt:57 (add_executable): -[0.365s] Policy CMP0003 should be set before this line. Add code such as -[0.365s] -[0.365s] if(COMMAND cmake_policy) -[0.365s] cmake_policy(SET CMP0003 NEW) -[0.366s] endif(COMMAND cmake_policy) -[0.366s] -[0.366s] as early as possible but after the most recent call to -[0.366s] cmake_minimum_required or cmake_policy(VERSION). This warning appears -[0.366s] because target "Mono" links to some libraries for which the linker must -[0.366s] search: -[0.366s] -[0.366s] -lboost_system -[0.366s] -[0.366s] and other libraries with known full path: -[0.366s] -[0.366s] /usr/lib/x86_64-linux-gnu/libopencv_stitching.so.4.5.4d -[0.366s] /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/../../Thirdparty/DBoW2/lib/libDBoW2.so -[0.366s] /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/../../Thirdparty/g2o/lib/libg2o.so -[0.366s] /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/../../lib/libORB_SLAM3.so -[0.366s] -[0.366s] CMake is adding directories in the second list to the linker search path in -[0.366s] case they are needed to find libraries from the first list (for backwards -[0.366s] compatibility with CMake 2.4). Set policy CMP0003 to OLD or NEW to enable -[0.366s] or disable this behavior explicitly. Run "cmake --help-policy CMP0003" for -[0.366s] more information. -[0.366s] This warning is for project developers. Use -Wno-dev to suppress it. -[0.366s]  -[0.392s] -- Generating done -[0.393s] -- Build files have been written to: /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3 -[0.396s] Invoked command in '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3' returned '0': /usr/bin/cmake /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3 -DCMAKE_INSTALL_PREFIX=/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/install/ORB_SLAM3 -[0.397s] Invoking command in '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3': /usr/bin/cmake --build /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3 -- -j8 -l8 -[0.432s] [ 23%] Building CXX object CMakeFiles/Mono.dir/src/ros_mono.o -[0.432s] [ 23%] Building CXX object CMakeFiles/MonoAR.dir/src/AR/ViewerAR.o -[0.432s] [ 23%] Building CXX object CMakeFiles/MonoAR.dir/src/AR/ros_mono_ar.o -[0.432s] [ 30%] Building CXX object CMakeFiles/Mono_Inertial.dir/src/ros_mono_inertial.o -[0.434s] [ 38%] Building CXX object CMakeFiles/Stereo.dir/src/ros_stereo.o -[0.434s] [ 53%] Building CXX object CMakeFiles/Stereo_Inertial.dir/src/ros_stereo_inertial.o -[0.434s] [ 53%] Building CXX object CMakeFiles/RGBD.dir/src/ros_rgbd.o -[0.470s] /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/ros_rgbd.cc:25:9: fatal error: ros/ros.h: No such file or directory -[0.470s] 25 | #include -[0.470s] | ^~~~~~~~~~~ -[0.470s] compilation terminated. -[0.471s] gmake[2]: *** [CMakeFiles/RGBD.dir/build.make:76: CMakeFiles/RGBD.dir/src/ros_rgbd.o] Error 1 -[0.471s] gmake[1]: *** [CMakeFiles/Makefile2:171: CMakeFiles/RGBD.dir/all] Error 2 -[0.472s] gmake[1]: *** Waiting for unfinished jobs.... -[0.492s] /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/AR/ros_mono_ar.cc:25:9: fatal error: ros/ros.h: No such file or directory -[0.492s] 25 | #include -[0.492s] | ^~~~~~~~~~~ -[0.492s] compilation terminated. -[0.492s] /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/ros_mono.cc:25:9: fatal error: ros/ros.h: No such file or directory -[0.492s] 25 | #include -[0.492s] | ^~~~~~~~~~~ -[0.492s] compilation terminated. -[0.493s] /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/ros_stereo.cc:25:9: fatal error: ros/ros.h: No such file or directory -[0.493s] 25 | #include -[0.493s] | ^~~~~~~~~~~ -[0.493s] compilation terminated. -[0.493s] gmake[2]: *** [CMakeFiles/MonoAR.dir/build.make:76: CMakeFiles/MonoAR.dir/src/AR/ros_mono_ar.o] Error 1 -[0.493s] gmake[2]: *** [CMakeFiles/Mono.dir/build.make:76: CMakeFiles/Mono.dir/src/ros_mono.o] Error 1 -[0.493s] gmake[2]: *** Waiting for unfinished jobs.... -[0.493s] gmake[1]: *** [CMakeFiles/Makefile2:93: CMakeFiles/Mono.dir/all] Error 2 -[0.494s] gmake[2]: *** [CMakeFiles/Stereo.dir/build.make:76: CMakeFiles/Stereo.dir/src/ros_stereo.o] Error 1 -[0.494s] gmake[1]: *** [CMakeFiles/Makefile2:145: CMakeFiles/Stereo.dir/all] Error 2 -[0.498s] /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/ros_mono_inertial.cc:28:9: fatal error: ros/ros.h: No such file or directory -[0.498s] 28 | #include -[0.498s] | ^~~~~~~~~~~ -[0.498s] compilation terminated. -[0.498s] /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/ros_stereo_inertial.cc:28:9: fatal error: ros/ros.h: No such file or directory -[0.498s] 28 | #include -[0.498s] | ^~~~~~~~~~~ -[0.498s] compilation terminated. -[0.499s] gmake[2]: *** [CMakeFiles/Mono_Inertial.dir/build.make:76: CMakeFiles/Mono_Inertial.dir/src/ros_mono_inertial.o] Error 1 -[0.499s] gmake[1]: *** [CMakeFiles/Makefile2:197: CMakeFiles/Mono_Inertial.dir/all] Error 2 -[0.499s] gmake[2]: *** [CMakeFiles/Stereo_Inertial.dir/build.make:76: CMakeFiles/Stereo_Inertial.dir/src/ros_stereo_inertial.o] Error 1 -[0.500s] gmake[1]: *** [CMakeFiles/Makefile2:223: CMakeFiles/Stereo_Inertial.dir/all] Error 2 -[0.546s] In file included from /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/AR/ViewerAR.cc:19: -[0.547s] /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/AR/ViewerAR.h:25:10: fatal error: pangolin/pangolin.h: No such file or directory -[0.547s] 25 | #include  -[0.547s] | ^~~~~~~~~~~~~~~~~~~~~ -[0.547s] compilation terminated. -[0.549s] gmake[2]: *** [CMakeFiles/MonoAR.dir/build.make:90: CMakeFiles/MonoAR.dir/src/AR/ViewerAR.o] Error 1 -[0.549s] gmake[1]: *** [CMakeFiles/Makefile2:119: CMakeFiles/MonoAR.dir/all] Error 2 -[0.549s] gmake: *** [Makefile:91: all] Error 2 -[0.550s] Invoked command in '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3' returned '2': /usr/bin/cmake --build /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3 -- -j8 -l8 diff --git a/ROS2/log/build_2023-06-19_20-42-56/events.log b/ROS2/log/build_2023-06-19_20-42-56/events.log deleted file mode 100644 index fe51981d58..0000000000 --- a/ROS2/log/build_2023-06-19_20-42-56/events.log +++ /dev/null @@ -1,124 +0,0 @@ -[0.000000] (-) TimerEvent: {} -[0.000210] (ORB_SLAM3) JobQueued: {'identifier': 'ORB_SLAM3', 'dependencies': OrderedDict()} -[0.000247] (ORB_SLAM3) JobStarted: {'identifier': 'ORB_SLAM3'} -[0.006466] (ORB_SLAM3) JobProgress: {'identifier': 'ORB_SLAM3', 'progress': 'cmake'} -[0.006565] (ORB_SLAM3) Command: {'cmd': ['/usr/bin/cmake', '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3', '-DCMAKE_INSTALL_PREFIX=/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/install/ORB_SLAM3'], 'cwd': '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3', 'env': OrderedDict([('LESSOPEN', '| /usr/bin/lesspipe %s'), ('USER', 'hvk'), ('LC_TIME', 'en_GB.UTF-8'), ('XDG_SESSION_TYPE', 'x11'), ('SHLVL', '1'), ('LD_LIBRARY_PATH', '/usr/lib/x86_64-linux-gnu/gazebo-11/plugins:/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib:/usr/lib/x86_64-linux-gnu/gazebo-11/plugins:'), ('HOME', '/home/hvk'), ('OLDPWD', '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3'), ('DESKTOP_SESSION', 'ubuntu-xorg'), ('GAZEBO_MASTER_URI', 'http://localhost:11345'), ('ROS_PYTHON_VERSION', '3'), ('GNOME_SHELL_SESSION_MODE', 'ubuntu'), ('GTK_MODULES', 'gail:atk-bridge'), ('LC_MONETARY', 'en_GB.UTF-8'), ('SYSTEMD_EXEC_PID', '2902'), ('DBUS_SESSION_BUS_ADDRESS', 'unix:path=/run/user/1000/bus'), ('COLORTERM', 'truecolor'), ('MANDATORY_PATH', '/usr/share/gconf/ubuntu-xorg.mandatory.path'), ('IM_CONFIG_PHASE', '1'), ('ROS_DISTRO', 'humble'), ('GTK_IM_MODULE', 'ibus'), ('LOGNAME', 'hvk'), ('_', '/usr/bin/colcon'), ('ROS_VERSION', '2'), ('XDG_SESSION_CLASS', 'user'), ('DEFAULTS_PATH', '/usr/share/gconf/ubuntu-xorg.default.path'), ('USERNAME', 'hvk'), ('TERM', 'xterm-256color'), ('GAZEBO_MODEL_PATH', '/usr/share/gazebo-11/models:'), ('GNOME_DESKTOP_SESSION_ID', 'this-is-deprecated'), ('ROS_LOCALHOST_ONLY', '0'), ('WINDOWPATH', '2'), ('OGRE_RESOURCE_PATH', '/usr/lib/x86_64-linux-gnu/OGRE-1.9.0'), ('PATH', '/opt/ros/humble/bin:/home/hvk/.cargo/bin:/home/hvk/.local/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin:/usr/local/go/bin'), ('SESSION_MANAGER', 'local/uss-voyager:@/tmp/.ICE-unix/2882,unix/uss-voyager:/tmp/.ICE-unix/2882'), ('PAPERSIZE', 'a4'), ('XDG_MENU_PREFIX', 'gnome-'), ('LC_ADDRESS', 'en_GB.UTF-8'), ('GNOME_TERMINAL_SCREEN', '/org/gnome/Terminal/screen/93682980_76cf_41e2_a9d2_098012e3dc66'), ('XDG_RUNTIME_DIR', '/run/user/1000'), ('DISPLAY', ':0'), ('LANG', 'en_US.UTF-8'), ('XDG_CURRENT_DESKTOP', 'ubuntu:GNOME'), ('LC_TELEPHONE', 'en_GB.UTF-8'), ('XMODIFIERS', '@im=ibus'), ('XDG_SESSION_DESKTOP', 'ubuntu-xorg'), ('XAUTHORITY', '/run/user/1000/gdm/Xauthority'), ('LS_COLORS', 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=30;41:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:'), ('GNOME_TERMINAL_SERVICE', ':1.446'), ('SSH_AGENT_LAUNCHER', 'gnome-keyring'), ('SSH_AUTH_SOCK', '/run/user/1000/keyring/ssh'), ('AMENT_PREFIX_PATH', '/opt/ros/humble'), ('SHELL', '/bin/bash'), ('LC_NAME', 'en_GB.UTF-8'), ('QT_ACCESSIBILITY', '1'), ('GDMSESSION', 'ubuntu-xorg'), ('LESSCLOSE', '/usr/bin/lesspipe %s %s'), ('LC_MEASUREMENT', 'en_GB.UTF-8'), ('GPG_AGENT_INFO', '/run/user/1000/gnupg/S.gpg-agent:0:1'), ('GAZEBO_RESOURCE_PATH', '/usr/share/gazebo-11:'), ('LC_IDENTIFICATION', 'en_GB.UTF-8'), ('GAZEBO_MODEL_DATABASE_URI', 'http://models.gazebosim.org'), ('QT_IM_MODULE', 'ibus'), ('PWD', '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3'), ('XDG_CONFIG_DIRS', '/etc/xdg/xdg-ubuntu-xorg:/etc/xdg'), ('GAZEBO_PLUGIN_PATH', '/usr/lib/x86_64-linux-gnu/gazebo-11/plugins:'), ('XDG_DATA_DIRS', '/usr/share/ubuntu-xorg:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop'), ('PYTHONPATH', '/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages'), ('LC_NUMERIC', 'en_GB.UTF-8'), ('LC_PAPER', 'en_GB.UTF-8'), ('COLCON', '1'), ('VTE_VERSION', '6800')]), 'shell': False} -[0.013200] (ORB_SLAM3) StderrLine: {'line': b'\x1b[0mCMake Deprecation Warning at CMakeLists.txt:1 (cmake_minimum_required):\n'} -[0.013310] (ORB_SLAM3) StderrLine: {'line': b' Compatibility with CMake < 2.8.12 will be removed from a future version of\n'} -[0.013351] (ORB_SLAM3) StderrLine: {'line': b' CMake.\n'} -[0.013389] (ORB_SLAM3) StderrLine: {'line': b'\n'} -[0.013427] (ORB_SLAM3) StderrLine: {'line': b' Update the VERSION argument value or use a ... suffix to tell\n'} -[0.013464] (ORB_SLAM3) StderrLine: {'line': b' CMake that the project does not need compatibility with older versions.\n'} -[0.013502] (ORB_SLAM3) StderrLine: {'line': b'\n'} -[0.013539] (ORB_SLAM3) StderrLine: {'line': b'\x1b[0m\n'} -[0.048703] (ORB_SLAM3) StdoutLine: {'line': b'-- The C compiler identification is GNU 11.3.0\n'} -[0.090781] (ORB_SLAM3) StdoutLine: {'line': b'-- The CXX compiler identification is GNU 11.3.0\n'} -[0.096453] (ORB_SLAM3) StdoutLine: {'line': b'-- Detecting C compiler ABI info\n'} -[0.098830] (-) TimerEvent: {} -[0.150740] (ORB_SLAM3) StdoutLine: {'line': b'-- Detecting C compiler ABI info - done\n'} -[0.157036] (ORB_SLAM3) StdoutLine: {'line': b'-- Check for working C compiler: /usr/bin/cc - skipped\n'} -[0.157238] (ORB_SLAM3) StdoutLine: {'line': b'-- Detecting C compile features\n'} -[0.157489] (ORB_SLAM3) StdoutLine: {'line': b'-- Detecting C compile features - done\n'} -[0.160038] (ORB_SLAM3) StdoutLine: {'line': b'-- Detecting CXX compiler ABI info\n'} -[0.199013] (-) TimerEvent: {} -[0.219906] (ORB_SLAM3) StdoutLine: {'line': b'-- Detecting CXX compiler ABI info - done\n'} -[0.225406] (ORB_SLAM3) StdoutLine: {'line': b'-- Check for working CXX compiler: /usr/bin/c++ - skipped\n'} -[0.225536] (ORB_SLAM3) StdoutLine: {'line': b'-- Detecting CXX compile features\n'} -[0.225999] (ORB_SLAM3) StdoutLine: {'line': b'-- Detecting CXX compile features - done\n'} -[0.227560] (ORB_SLAM3) StdoutLine: {'line': b'-- Performing Test COMPILER_SUPPORTS_CXX11\n'} -[0.292534] (ORB_SLAM3) StdoutLine: {'line': b'-- Performing Test COMPILER_SUPPORTS_CXX11 - Success\n'} -[0.293171] (ORB_SLAM3) StdoutLine: {'line': b'-- Performing Test COMPILER_SUPPORTS_CXX0X\n'} -[0.299114] (-) TimerEvent: {} -[0.349610] (ORB_SLAM3) StdoutLine: {'line': b'-- Performing Test COMPILER_SUPPORTS_CXX0X - Success\n'} -[0.349747] (ORB_SLAM3) StdoutLine: {'line': b'-- Using flag -std=c++11.\n'} -[0.361310] (ORB_SLAM3) StdoutLine: {'line': b'-- Configuring done\n'} -[0.365489] (ORB_SLAM3) StderrLine: {'line': b'\x1b[33mCMake Warning (dev) at CMakeLists.txt:57 (add_executable):\n'} -[0.365578] (ORB_SLAM3) StderrLine: {'line': b' Policy CMP0003 should be set before this line. Add code such as\n'} -[0.365624] (ORB_SLAM3) StderrLine: {'line': b'\n'} -[0.365670] (ORB_SLAM3) StderrLine: {'line': b' if(COMMAND cmake_policy)\n'} -[0.365710] (ORB_SLAM3) StderrLine: {'line': b' cmake_policy(SET CMP0003 NEW)\n'} -[0.365749] (ORB_SLAM3) StderrLine: {'line': b' endif(COMMAND cmake_policy)\n'} -[0.365787] (ORB_SLAM3) StderrLine: {'line': b'\n'} -[0.365825] (ORB_SLAM3) StderrLine: {'line': b' as early as possible but after the most recent call to\n'} -[0.365863] (ORB_SLAM3) StderrLine: {'line': b' cmake_minimum_required or cmake_policy(VERSION). This warning appears\n'} -[0.365902] (ORB_SLAM3) StderrLine: {'line': b' because target "Mono" links to some libraries for which the linker must\n'} -[0.365940] (ORB_SLAM3) StderrLine: {'line': b' search:\n'} -[0.365978] (ORB_SLAM3) StderrLine: {'line': b'\n'} -[0.366015] (ORB_SLAM3) StderrLine: {'line': b' -lboost_system\n'} -[0.366052] (ORB_SLAM3) StderrLine: {'line': b'\n'} -[0.366090] (ORB_SLAM3) StderrLine: {'line': b' and other libraries with known full path:\n'} -[0.366127] (ORB_SLAM3) StderrLine: {'line': b'\n'} -[0.366165] (ORB_SLAM3) StderrLine: {'line': b' /usr/lib/x86_64-linux-gnu/libopencv_stitching.so.4.5.4d\n'} -[0.366203] (ORB_SLAM3) StderrLine: {'line': b' /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/../../Thirdparty/DBoW2/lib/libDBoW2.so\n'} -[0.366242] (ORB_SLAM3) StderrLine: {'line': b' /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/../../Thirdparty/g2o/lib/libg2o.so\n'} -[0.366281] (ORB_SLAM3) StderrLine: {'line': b' /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/../../lib/libORB_SLAM3.so\n'} -[0.366319] (ORB_SLAM3) StderrLine: {'line': b'\n'} -[0.366357] (ORB_SLAM3) StderrLine: {'line': b' CMake is adding directories in the second list to the linker search path in\n'} -[0.366395] (ORB_SLAM3) StderrLine: {'line': b' case they are needed to find libraries from the first list (for backwards\n'} -[0.366433] (ORB_SLAM3) StderrLine: {'line': b' compatibility with CMake 2.4). Set policy CMP0003 to OLD or NEW to enable\n'} -[0.366469] (ORB_SLAM3) StderrLine: {'line': b' or disable this behavior explicitly. Run "cmake --help-policy CMP0003" for\n'} -[0.366506] (ORB_SLAM3) StderrLine: {'line': b' more information.\n'} -[0.366544] (ORB_SLAM3) StderrLine: {'line': b'This warning is for project developers. Use -Wno-dev to suppress it.\n'} -[0.366582] (ORB_SLAM3) StderrLine: {'line': b'\x1b[0m\n'} -[0.392219] (ORB_SLAM3) StdoutLine: {'line': b'-- Generating done\n'} -[0.392980] (ORB_SLAM3) StdoutLine: {'line': b'-- Build files have been written to: /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3\n'} -[0.395947] (ORB_SLAM3) CommandEnded: {'returncode': 0} -[0.396355] (ORB_SLAM3) JobProgress: {'identifier': 'ORB_SLAM3', 'progress': 'build'} -[0.396909] (ORB_SLAM3) Command: {'cmd': ['/usr/bin/cmake', '--build', '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3', '--', '-j8', '-l8'], 'cwd': '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3', 'env': OrderedDict([('LESSOPEN', '| /usr/bin/lesspipe %s'), ('USER', 'hvk'), ('LC_TIME', 'en_GB.UTF-8'), ('XDG_SESSION_TYPE', 'x11'), ('SHLVL', '1'), ('LD_LIBRARY_PATH', '/usr/lib/x86_64-linux-gnu/gazebo-11/plugins:/opt/ros/humble/opt/rviz_ogre_vendor/lib:/opt/ros/humble/lib/x86_64-linux-gnu:/opt/ros/humble/lib:/usr/lib/x86_64-linux-gnu/gazebo-11/plugins:'), ('HOME', '/home/hvk'), ('OLDPWD', '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3'), ('DESKTOP_SESSION', 'ubuntu-xorg'), ('GAZEBO_MASTER_URI', 'http://localhost:11345'), ('ROS_PYTHON_VERSION', '3'), ('GNOME_SHELL_SESSION_MODE', 'ubuntu'), ('GTK_MODULES', 'gail:atk-bridge'), ('LC_MONETARY', 'en_GB.UTF-8'), ('SYSTEMD_EXEC_PID', '2902'), ('DBUS_SESSION_BUS_ADDRESS', 'unix:path=/run/user/1000/bus'), ('COLORTERM', 'truecolor'), ('MANDATORY_PATH', '/usr/share/gconf/ubuntu-xorg.mandatory.path'), ('IM_CONFIG_PHASE', '1'), ('ROS_DISTRO', 'humble'), ('GTK_IM_MODULE', 'ibus'), ('LOGNAME', 'hvk'), ('_', '/usr/bin/colcon'), ('ROS_VERSION', '2'), ('XDG_SESSION_CLASS', 'user'), ('DEFAULTS_PATH', '/usr/share/gconf/ubuntu-xorg.default.path'), ('USERNAME', 'hvk'), ('TERM', 'xterm-256color'), ('GAZEBO_MODEL_PATH', '/usr/share/gazebo-11/models:'), ('GNOME_DESKTOP_SESSION_ID', 'this-is-deprecated'), ('ROS_LOCALHOST_ONLY', '0'), ('WINDOWPATH', '2'), ('OGRE_RESOURCE_PATH', '/usr/lib/x86_64-linux-gnu/OGRE-1.9.0'), ('PATH', '/opt/ros/humble/bin:/home/hvk/.cargo/bin:/home/hvk/.local/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin:/usr/local/go/bin'), ('SESSION_MANAGER', 'local/uss-voyager:@/tmp/.ICE-unix/2882,unix/uss-voyager:/tmp/.ICE-unix/2882'), ('PAPERSIZE', 'a4'), ('XDG_MENU_PREFIX', 'gnome-'), ('LC_ADDRESS', 'en_GB.UTF-8'), ('GNOME_TERMINAL_SCREEN', '/org/gnome/Terminal/screen/93682980_76cf_41e2_a9d2_098012e3dc66'), ('XDG_RUNTIME_DIR', '/run/user/1000'), ('DISPLAY', ':0'), ('LANG', 'en_US.UTF-8'), ('XDG_CURRENT_DESKTOP', 'ubuntu:GNOME'), ('LC_TELEPHONE', 'en_GB.UTF-8'), ('XMODIFIERS', '@im=ibus'), ('XDG_SESSION_DESKTOP', 'ubuntu-xorg'), ('XAUTHORITY', '/run/user/1000/gdm/Xauthority'), ('LS_COLORS', 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=30;41:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:'), ('GNOME_TERMINAL_SERVICE', ':1.446'), ('SSH_AGENT_LAUNCHER', 'gnome-keyring'), ('SSH_AUTH_SOCK', '/run/user/1000/keyring/ssh'), ('AMENT_PREFIX_PATH', '/opt/ros/humble'), ('SHELL', '/bin/bash'), ('LC_NAME', 'en_GB.UTF-8'), ('QT_ACCESSIBILITY', '1'), ('GDMSESSION', 'ubuntu-xorg'), ('LESSCLOSE', '/usr/bin/lesspipe %s %s'), ('LC_MEASUREMENT', 'en_GB.UTF-8'), ('GPG_AGENT_INFO', '/run/user/1000/gnupg/S.gpg-agent:0:1'), ('GAZEBO_RESOURCE_PATH', '/usr/share/gazebo-11:'), ('LC_IDENTIFICATION', 'en_GB.UTF-8'), ('GAZEBO_MODEL_DATABASE_URI', 'http://models.gazebosim.org'), ('QT_IM_MODULE', 'ibus'), ('PWD', '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3'), ('XDG_CONFIG_DIRS', '/etc/xdg/xdg-ubuntu-xorg:/etc/xdg'), ('GAZEBO_PLUGIN_PATH', '/usr/lib/x86_64-linux-gnu/gazebo-11/plugins:'), ('XDG_DATA_DIRS', '/usr/share/ubuntu-xorg:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop'), ('PYTHONPATH', '/opt/ros/humble/lib/python3.10/site-packages:/opt/ros/humble/local/lib/python3.10/dist-packages'), ('LC_NUMERIC', 'en_GB.UTF-8'), ('LC_PAPER', 'en_GB.UTF-8'), ('COLCON', '1'), ('VTE_VERSION', '6800')]), 'shell': False} -[0.399198] (-) TimerEvent: {} -[0.432016] (ORB_SLAM3) StdoutLine: {'line': b'[ 23%] \x1b[32mBuilding CXX object CMakeFiles/Mono.dir/src/ros_mono.o\x1b[0m\n'} -[0.432304] (ORB_SLAM3) StdoutLine: {'line': b'[ 23%] \x1b[32mBuilding CXX object CMakeFiles/MonoAR.dir/src/AR/ViewerAR.o\x1b[0m\n'} -[0.432399] (ORB_SLAM3) StdoutLine: {'line': b'[ 23%] \x1b[32mBuilding CXX object CMakeFiles/MonoAR.dir/src/AR/ros_mono_ar.o\x1b[0m\n'} -[0.432529] (ORB_SLAM3) StdoutLine: {'line': b'[ 30%] \x1b[32mBuilding CXX object CMakeFiles/Mono_Inertial.dir/src/ros_mono_inertial.o\x1b[0m\n'} -[0.433981] (ORB_SLAM3) StdoutLine: {'line': b'[ 38%] \x1b[32mBuilding CXX object CMakeFiles/Stereo.dir/src/ros_stereo.o\x1b[0m\n'} -[0.434157] (ORB_SLAM3) StdoutLine: {'line': b'[ 53%] \x1b[32mBuilding CXX object CMakeFiles/Stereo_Inertial.dir/src/ros_stereo_inertial.o\x1b[0m\n'} -[0.434227] (ORB_SLAM3) StdoutLine: {'line': b'[ 53%] \x1b[32mBuilding CXX object CMakeFiles/RGBD.dir/src/ros_rgbd.o\x1b[0m\n'} -[0.470239] (ORB_SLAM3) StderrLine: {'line': b'\x1b[01m\x1b[K/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/ros_rgbd.cc:25:9:\x1b[m\x1b[K \x1b[01;31m\x1b[Kfatal error: \x1b[m\x1b[Kros/ros.h: No such file or directory\n'} -[0.470426] (ORB_SLAM3) StderrLine: {'line': b' 25 | #include\x1b[01;31m\x1b[K\x1b[m\x1b[K\n'} -[0.470485] (ORB_SLAM3) StderrLine: {'line': b' | \x1b[01;31m\x1b[K^~~~~~~~~~~\x1b[m\x1b[K\n'} -[0.470539] (ORB_SLAM3) StderrLine: {'line': b'compilation terminated.\n'} -[0.471456] (ORB_SLAM3) StderrLine: {'line': b'gmake[2]: *** [CMakeFiles/RGBD.dir/build.make:76: CMakeFiles/RGBD.dir/src/ros_rgbd.o] Error 1\n'} -[0.471649] (ORB_SLAM3) StderrLine: {'line': b'gmake[1]: *** [CMakeFiles/Makefile2:171: CMakeFiles/RGBD.dir/all] Error 2\n'} -[0.471736] (ORB_SLAM3) StderrLine: {'line': b'gmake[1]: *** Waiting for unfinished jobs....\n'} -[0.491662] (ORB_SLAM3) StderrLine: {'line': b'\x1b[01m\x1b[K/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/AR/ros_mono_ar.cc:25:9:\x1b[m\x1b[K \x1b[01;31m\x1b[Kfatal error: \x1b[m\x1b[Kros/ros.h: No such file or directory\n'} -[0.491865] (ORB_SLAM3) StderrLine: {'line': b' 25 | #include\x1b[01;31m\x1b[K\x1b[m\x1b[K\n'} -[0.491929] (ORB_SLAM3) StderrLine: {'line': b' | \x1b[01;31m\x1b[K^~~~~~~~~~~\x1b[m\x1b[K\n'} -[0.491987] (ORB_SLAM3) StderrLine: {'line': b'compilation terminated.\n'} -[0.492043] (ORB_SLAM3) StderrLine: {'line': b'\x1b[01m\x1b[K/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/ros_mono.cc:25:9:\x1b[m\x1b[K \x1b[01;31m\x1b[Kfatal error: \x1b[m\x1b[Kros/ros.h: No such file or directory\n'} -[0.492101] (ORB_SLAM3) StderrLine: {'line': b' 25 | #include\x1b[01;31m\x1b[K\x1b[m\x1b[K\n'} -[0.492157] (ORB_SLAM3) StderrLine: {'line': b' | \x1b[01;31m\x1b[K^~~~~~~~~~~\x1b[m\x1b[K\n'} -[0.492224] (ORB_SLAM3) StderrLine: {'line': b'compilation terminated.\n'} -[0.492715] (ORB_SLAM3) StderrLine: {'line': b'\x1b[01m\x1b[K/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/ros_stereo.cc:25:9:\x1b[m\x1b[K \x1b[01;31m\x1b[Kfatal error: \x1b[m\x1b[Kros/ros.h: No such file or directory\n'} -[0.492800] (ORB_SLAM3) StderrLine: {'line': b' 25 | #include\x1b[01;31m\x1b[K\x1b[m\x1b[K\n'} -[0.492860] (ORB_SLAM3) StderrLine: {'line': b' | \x1b[01;31m\x1b[K^~~~~~~~~~~\x1b[m\x1b[K\n'} -[0.492917] (ORB_SLAM3) StderrLine: {'line': b'compilation terminated.\n'} -[0.493365] (ORB_SLAM3) StderrLine: {'line': b'gmake[2]: *** [CMakeFiles/MonoAR.dir/build.make:76: CMakeFiles/MonoAR.dir/src/AR/ros_mono_ar.o] Error 1\n'} -[0.493459] (ORB_SLAM3) StderrLine: {'line': b'gmake[2]: *** [CMakeFiles/Mono.dir/build.make:76: CMakeFiles/Mono.dir/src/ros_mono.o] Error 1\n'} -[0.493503] (ORB_SLAM3) StderrLine: {'line': b'gmake[2]: *** Waiting for unfinished jobs....\n'} -[0.493556] (ORB_SLAM3) StderrLine: {'line': b'gmake[1]: *** [CMakeFiles/Makefile2:93: CMakeFiles/Mono.dir/all] Error 2\n'} -[0.493974] (ORB_SLAM3) StderrLine: {'line': b'gmake[2]: *** [CMakeFiles/Stereo.dir/build.make:76: CMakeFiles/Stereo.dir/src/ros_stereo.o] Error 1\n'} -[0.494079] (ORB_SLAM3) StderrLine: {'line': b'gmake[1]: *** [CMakeFiles/Makefile2:145: CMakeFiles/Stereo.dir/all] Error 2\n'} -[0.497722] (ORB_SLAM3) StderrLine: {'line': b'\x1b[01m\x1b[K/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/ros_mono_inertial.cc:28:9:\x1b[m\x1b[K \x1b[01;31m\x1b[Kfatal error: \x1b[m\x1b[Kros/ros.h: No such file or directory\n'} -[0.497785] (ORB_SLAM3) StderrLine: {'line': b' 28 | #include\x1b[01;31m\x1b[K\x1b[m\x1b[K\n'} -[0.497827] (ORB_SLAM3) StderrLine: {'line': b' | \x1b[01;31m\x1b[K^~~~~~~~~~~\x1b[m\x1b[K\n'} -[0.497869] (ORB_SLAM3) StderrLine: {'line': b'compilation terminated.\n'} -[0.498523] (ORB_SLAM3) StderrLine: {'line': b'\x1b[01m\x1b[K/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/ros_stereo_inertial.cc:28:9:\x1b[m\x1b[K \x1b[01;31m\x1b[Kfatal error: \x1b[m\x1b[Kros/ros.h: No such file or directory\n'} -[0.498600] (ORB_SLAM3) StderrLine: {'line': b' 28 | #include\x1b[01;31m\x1b[K\x1b[m\x1b[K\n'} -[0.498655] (ORB_SLAM3) StderrLine: {'line': b' | \x1b[01;31m\x1b[K^~~~~~~~~~~\x1b[m\x1b[K\n'} -[0.498707] (ORB_SLAM3) StderrLine: {'line': b'compilation terminated.\n'} -[0.498987] (ORB_SLAM3) StderrLine: {'line': b'gmake[2]: *** [CMakeFiles/Mono_Inertial.dir/build.make:76: CMakeFiles/Mono_Inertial.dir/src/ros_mono_inertial.o] Error 1\n'} -[0.499035] (ORB_SLAM3) StderrLine: {'line': b'gmake[1]: *** [CMakeFiles/Makefile2:197: CMakeFiles/Mono_Inertial.dir/all] Error 2\n'} -[0.499257] (-) TimerEvent: {} -[0.499628] (ORB_SLAM3) StderrLine: {'line': b'gmake[2]: *** [CMakeFiles/Stereo_Inertial.dir/build.make:76: CMakeFiles/Stereo_Inertial.dir/src/ros_stereo_inertial.o] Error 1\n'} -[0.499759] (ORB_SLAM3) StderrLine: {'line': b'gmake[1]: *** [CMakeFiles/Makefile2:223: CMakeFiles/Stereo_Inertial.dir/all] Error 2\n'} -[0.546603] (ORB_SLAM3) StderrLine: {'line': b'In file included from \x1b[01m\x1b[K/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/AR/ViewerAR.cc:19\x1b[m\x1b[K:\n'} -[0.546768] (ORB_SLAM3) StderrLine: {'line': b'\x1b[01m\x1b[K/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3/src/AR/ViewerAR.h:25:10:\x1b[m\x1b[K \x1b[01;31m\x1b[Kfatal error: \x1b[m\x1b[Kpangolin/pangolin.h: No such file or directory\n'} -[0.546821] (ORB_SLAM3) StderrLine: {'line': b' 25 | #include \x1b[01;31m\x1b[K\x1b[m\x1b[K\n'} -[0.546868] (ORB_SLAM3) StderrLine: {'line': b' | \x1b[01;31m\x1b[K^~~~~~~~~~~~~~~~~~~~~\x1b[m\x1b[K\n'} -[0.546941] (ORB_SLAM3) StderrLine: {'line': b'compilation terminated.\n'} -[0.548906] (ORB_SLAM3) StderrLine: {'line': b'gmake[2]: *** [CMakeFiles/MonoAR.dir/build.make:90: CMakeFiles/MonoAR.dir/src/AR/ViewerAR.o] Error 1\n'} -[0.549032] (ORB_SLAM3) StderrLine: {'line': b'gmake[1]: *** [CMakeFiles/Makefile2:119: CMakeFiles/MonoAR.dir/all] Error 2\n'} -[0.549116] (ORB_SLAM3) StderrLine: {'line': b'gmake: *** [Makefile:91: all] Error 2\n'} -[0.550534] (ORB_SLAM3) CommandEnded: {'returncode': 2} -[0.550821] (ORB_SLAM3) JobEnded: {'identifier': 'ORB_SLAM3', 'rc': 2} -[0.561212] (-) EventReactorShutdown: {} diff --git a/ROS2/log/build_2023-06-19_20-42-56/logger_all.log b/ROS2/log/build_2023-06-19_20-42-56/logger_all.log deleted file mode 100644 index 8e2337eb07..0000000000 --- a/ROS2/log/build_2023-06-19_20-42-56/logger_all.log +++ /dev/null @@ -1,94 +0,0 @@ -[0.218s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build', '--parallel-workers', '4'] -[0.218s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, verb_parser=, verb_extension=, main=>) -[0.235s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters -[0.235s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters -[0.235s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters -[0.235s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters -[0.235s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover -[0.235s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover -[0.235s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2' -[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install'] -[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore' -[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install' -[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg'] -[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg' -[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta'] -[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta' -[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros'] -[0.235s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros' -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python'] -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake' -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python' -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py'] -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py' -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(ORB_SLAM3) by extensions ['ignore', 'ignore_ament_install'] -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(ORB_SLAM3) by extension 'ignore' -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(ORB_SLAM3) by extension 'ignore_ament_install' -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(ORB_SLAM3) by extensions ['colcon_pkg'] -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(ORB_SLAM3) by extension 'colcon_pkg' -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(ORB_SLAM3) by extensions ['colcon_meta'] -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(ORB_SLAM3) by extension 'colcon_meta' -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(ORB_SLAM3) by extensions ['ros'] -[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(ORB_SLAM3) by extension 'ros' -[0.245s] DEBUG:colcon.colcon_core.package_identification:Failed to parse potential ROS package manifest in'ORB_SLAM3': Error(s) in package 'ORB_SLAM3/package.xml': -The manifest must contain exactly one "description" tag -[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(ORB_SLAM3) by extensions ['cmake', 'python'] -[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(ORB_SLAM3) by extension 'cmake' -[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(ORB_SLAM3) by extension 'python' -[0.246s] DEBUG:colcon.colcon_core.package_identification:Package 'ORB_SLAM3' with type 'cmake' and name 'ORB_SLAM3' -[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install'] -[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore' -[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored -[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install'] -[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore' -[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored -[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install'] -[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore' -[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored -[0.246s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults -[0.246s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover -[0.246s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults -[0.246s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover -[0.246s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults -[0.261s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters -[0.261s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover -[0.264s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 372 installed packages in /opt/ros/humble -[0.265s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults -[0.308s] Level 5:colcon.colcon_core.verb:set package 'ORB_SLAM3' build argument 'cmake_args' from command line to 'None' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'ORB_SLAM3' build argument 'cmake_target' from command line to 'None' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'ORB_SLAM3' build argument 'cmake_target_skip_unavailable' from command line to 'False' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'ORB_SLAM3' build argument 'cmake_clean_cache' from command line to 'False' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'ORB_SLAM3' build argument 'cmake_clean_first' from command line to 'False' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'ORB_SLAM3' build argument 'cmake_force_configure' from command line to 'False' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'ORB_SLAM3' build argument 'ament_cmake_args' from command line to 'None' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'ORB_SLAM3' build argument 'catkin_cmake_args' from command line to 'None' -[0.308s] Level 5:colcon.colcon_core.verb:set package 'ORB_SLAM3' build argument 'catkin_skip_building_tests' from command line to 'False' -[0.308s] DEBUG:colcon.colcon_core.verb:Building package 'ORB_SLAM3' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/install/ORB_SLAM3', 'merge_install': False, 'path': '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3', 'symlink_install': False, 'test_result_base': None} -[0.308s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor -[0.311s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete -[0.311s] INFO:colcon.colcon_cmake.task.cmake.build:Building CMake package in '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3' -[0.313s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems -[0.314s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell -[0.314s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment -[0.319s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3': /usr/bin/cmake /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3 -DCMAKE_INSTALL_PREFIX=/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/install/ORB_SLAM3 -[0.708s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3' returned '0': /usr/bin/cmake /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/ORB_SLAM3 -DCMAKE_INSTALL_PREFIX=/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/install/ORB_SLAM3 -[0.709s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3': /usr/bin/cmake --build /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3 -- -j8 -l8 -[0.862s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3' returned '2': /usr/bin/cmake --build /home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/build/ORB_SLAM3 -- -j8 -l8 -[0.872s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop -[0.872s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed -[0.872s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '2' -[0.873s] DEBUG:colcon.colcon_core.event_reactor:joining thread -[0.876s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems -[0.876s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems -[0.876s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2' -[0.885s] DEBUG:colcon.colcon_core.event_reactor:joined thread -[0.886s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/install/local_setup.ps1' -[0.887s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/install/_local_setup_util_ps1.py' -[0.888s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/install/setup.ps1' -[0.889s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/install/local_setup.sh' -[0.889s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/install/_local_setup_util_sh.py' -[0.889s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/install/setup.sh' -[0.890s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/install/local_setup.bash' -[0.890s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/install/setup.bash' -[0.891s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/install/local_setup.zsh' -[0.891s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/hvk/Developments/projects_ws/ORB_SLAM3_ROS2_REALSENSE/ROS2/install/setup.zsh' diff --git a/build_ros2.sh b/build_ros2.sh index 09117329de..e23ec65b4a 100755 --- a/build_ros2.sh +++ b/build_ros2.sh @@ -44,7 +44,7 @@ cd .. echo "Configuring and building ORB_SLAM3 ..." mkdir build -cd buil +cd build cmake .. -DCMAKE_BUILD_TYPE=Release make -j2 cd .. @@ -52,4 +52,4 @@ echo $PWD echo "Building ROS nodes" cd ROS2 -colcon build --parallel-workers 4 \ No newline at end of file +colcon build --parallel-workers 2