UZ-SLAMLab / ORB_SLAM3

ORB-SLAM3: An Accurate Open-Source Library for Visual, Visual-Inertial and Multi-Map SLAM
GNU General Public License v3.0
6.51k stars 2.55k forks source link

macOS Compilation Errors #247

Open Lincoln-Zhou opened 3 years ago

Lincoln-Zhou commented 3 years ago

When compiling ORB_SLAM3 on macOS Big Sur 11.2 (20D5042d), several errors happened after running ./build.sh command.

Terminal output:

In file included from /Users/langzhou/Project/ORB_SLAM3/src/LoopClosing.cc:20:
In file included from /Users/langzhou/Project/ORB_SLAM3/include/LoopClosing.h:23:
In file included from /Users/langzhou/Project/ORB_SLAM3/include/KeyFrame.h:23:
In file included from /Users/langzhou/Project/ORB_SLAM3/include/MapPoint.h:24:
In file included from /Users/langzhou/Project/ORB_SLAM3/include/Frame.h:27:
In file included from /Users/langzhou/Project/ORB_SLAM3/Thirdparty/DBoW2/DBoW2/BowVector.h:14:
/Library/Developer/CommandLineTools/usr/bin/../include/c++/v1/map:912:5: error: 
      static_assert failed due to requirement 'is_same<std::__1::pair<const
      ORB_SLAM3::KeyFrame *, g2o::Sim3>, std::__1::pair<ORB_SLAM3::KeyFrame *const,
      g2o::Sim3> >::value' "Allocator::value_type must be same type as value_type"
    static_assert((is_same<typename allocator_type::value_type, value_type>::value),
    ^              ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
/Users/langzhou/Project/ORB_SLAM3/src/LoopClosing.cc:1056:21: note: in instantiation of
      template class 'std::__1::map<ORB_SLAM3::KeyFrame *, g2o::Sim3,
      std::__1::less<ORB_SLAM3::KeyFrame *>, Eigen::aligned_allocator<std::__1::pair<const
      ORB_SLAM3::KeyFrame *, g2o::Sim3> > >' requested here
    KeyFrameAndPose CorrectedSim3, NonCorrectedSim3;
                    ^
/Users/langzhou/Project/ORB_SLAM3/src/LoopClosing.cc:1089:29: error: no viable overloaded
      operator[] for type 'ORB_SLAM3::LoopClosing::KeyFrameAndPose' (aka
      'map<ORB_SLAM3::KeyFrame *, g2o::Sim3, std::less<KeyFrame *>,
      Eigen::aligned_allocator<std::pair<const KeyFrame *, g2o::Sim3> > >')
            NonCorrectedSim3[pKFi]=g2oSiw;
            ~~~~~~~~~~~~~~~~^~~~~
1 warning generated.
[ 33%] Building CXX object Thirdparty/g2o/CMakeFiles/g2o.dir/g2o/core/robust_kernel.cpp.o
/Users/langzhou/Project/ORB_SLAM3/src/LoopClosing.cc:1095:39: error: use of undeclared
      identifier 'mit'; did you mean 'min'?
        for(KeyFrameAndPose::iterator mit=CorrectedSim3.begin(), mend=CorrectedSim3...
                                      ^~~
                                      min
/Library/Developer/CommandLineTools/usr/bin/../include/c++/v1/algorithm:2454:1: note: 
      'min' declared here
min(const _Tp& __a, const _Tp& __b, _Compare __comp)
^
/Users/langzhou/Project/ORB_SLAM3/src/LoopClosing.cc:1095:30: error: no member named
      'iterator' in 'std::__1::map<ORB_SLAM3::KeyFrame *, g2o::Sim3,
      std::__1::less<ORB_SLAM3::KeyFrame *>, Eigen::aligned_allocator<std::__1::pair<const
      ORB_SLAM3::KeyFrame *, g2o::Sim3> > >'
        for(KeyFrameAndPose::iterator mit=CorrectedSim3.begin(), mend=CorrectedSim3...
            ~~~~~~~~~~~~~~~~~^
/Users/langzhou/Project/ORB_SLAM3/src/LoopClosing.cc:1095:92: error: use of undeclared
      identifier 'mit'; did you mean 'min'?
  ...mit=CorrectedSim3.begin(), mend=CorrectedSim3.end(); mit!=mend; mit++)
                                                          ^~~
                                                          min
/Library/Developer/CommandLineTools/usr/bin/../include/c++/v1/algorithm:2454:1: note: 
      'min' declared here
min(const _Tp& __a, const _Tp& __b, _Compare __comp)
^
/Users/langzhou/Project/ORB_SLAM3/src/LoopClosing.cc:1095:97: error: use of undeclared
      identifier 'mend'
  ...mit=CorrectedSim3.begin(), mend=CorrectedSim3.end(); mit!=mend; mit++)
                                                               ^
/Users/langzhou/Project/ORB_SLAM3/src/LoopClosing.cc:1095:103: error: use of undeclared
      identifier 'mit'
  ...mit=CorrectedSim3.begin(), mend=CorrectedSim3.end(); mit!=mend; mit++)
                                                                     ^
/Users/langzhou/Project/ORB_SLAM3/src/LoopClosing.cc:1097:30: error: use of undeclared
      identifier 'mit'
            KeyFrame* pKFi = mit->first;
                             ^
/Users/langzhou/Project/ORB_SLAM3/src/LoopClosing.cc:1098:41: error: use of undeclared
      identifier 'mit'
            g2o::Sim3 g2oCorrectedSiw = mit->second;
                                        ^
/Users/langzhou/Project/ORB_SLAM3/src/LoopClosing.cc:1276:20: warning: incrementing
      expression of type bool is deprecated and incompatible with C++17
      [-Wdeprecated-increment-bool]
        mnFullBAIdx++;
        ~~~~~~~~~~~^
/Users/langzhou/Project/ORB_SLAM3/src/LoopClosing.cc:1454:19: error: no viable overloaded
      operator[] for type 'ORB_SLAM3::LoopClosing::KeyFrameAndPose' (aka
      'map<ORB_SLAM3::KeyFrame *, g2o::Sim3, std::less<KeyFrame *>,
      Eigen::aligned_allocator<std::pair<const KeyFrame *, g2o::Sim3> > >')
    vCorrectedSim3[mpCurrentKF]=g2oCorrectedScw;
    ~~~~~~~~~~~~~~^~~~~~~~~~~~
/Users/langzhou/Project/ORB_SLAM3/src/LoopClosing.cc:1455:22: error: no viable overloaded
      operator[] for type 'ORB_SLAM3::LoopClosing::KeyFrameAndPose' (aka
      'map<ORB_SLAM3::KeyFrame *, g2o::Sim3, std::less<KeyFrame *>,
      Eigen::aligned_allocator<std::pair<const KeyFrame *, g2o::Sim3> > >')
    vNonCorrectedSim3[mpCurrentKF]=g2oNonCorrectedScw;
    ~~~~~~~~~~~~~~~~~^~~~~~~~~~~~
/Users/langzhou/Project/ORB_SLAM3/src/LoopClosing.cc:1484:30: error: no viable overloaded
      operator[] for type 'ORB_SLAM3::LoopClosing::KeyFrameAndPose' (aka
      'map<ORB_SLAM3::KeyFrame *, g2o::Sim3, std::less<KeyFrame *>,
      Eigen::aligned_allocator<std::pair<const KeyFrame *, g2o::Sim3> > >')
            vNonCorrectedSim3[pKFi]=g2oSiw;
            ~~~~~~~~~~~~~~~~~^~~~~
/Users/langzhou/Project/ORB_SLAM3/src/LoopClosing.cc:1491:27: error: no viable overloaded
      operator[] for type 'ORB_SLAM3::LoopClosing::KeyFrameAndPose' (aka
      'map<ORB_SLAM3::KeyFrame *, g2o::Sim3, std::less<KeyFrame *>,
      Eigen::aligned_allocator<std::pair<const KeyFrame *, g2o::Sim3> > >')
            vCorrectedSim3[pKFi]=g2oCorrectedSiw;
            ~~~~~~~~~~~~~~^~~~~
/Users/langzhou/Project/ORB_SLAM3/src/LoopClosing.cc:1526:70: error: no viable overloaded
      operator[] for type 'ORB_SLAM3::LoopClosing::KeyFrameAndPose' (aka
      'map<ORB_SLAM3::KeyFrame *, g2o::Sim3, std::less<KeyFrame *>,
      Eigen::aligned_allocator<std::pair<const KeyFrame *, g2o::Sim3> > >')
            Eigen::Matrix3d Rcor = eigR.transpose()*vNonCorrectedSim3[pKFi].rotatio...
                                                    ~~~~~~~~~~~~~~~~~^~~~~
/Users/langzhou/Project/ORB_SLAM3/src/LoopClosing.cc:1541:51: error: no viable overloaded
      operator[] for type 'ORB_SLAM3::LoopClosing::KeyFrameAndPose' (aka
      'map<ORB_SLAM3::KeyFrame *, g2o::Sim3, std::less<KeyFrame *>,
      Eigen::aligned_allocator<std::pair<const KeyFrame *, g2o::Sim3> > >')
        g2o::Sim3 g2oCorrectedSwi = vCorrectedSim3[pKFref].inverse();
                                    ~~~~~~~~~~~~~~^~~~~~~
/Users/langzhou/Project/ORB_SLAM3/src/LoopClosing.cc:1542:57: error: no viable overloaded
      operator[] for type 'ORB_SLAM3::LoopClosing::KeyFrameAndPose' (aka
      'map<ORB_SLAM3::KeyFrame *, g2o::Sim3, std::less<KeyFrame *>,
      Eigen::aligned_allocator<std::pair<const KeyFrame *, g2o::Sim3> > >')
        g2o::Sim3 g2oNonCorrectedSiw = vNonCorrectedSim3[pKFref];
                                       ~~~~~~~~~~~~~~~~~^~~~~~~
/Users/langzhou/Project/ORB_SLAM3/src/LoopClosing.cc:1765:38: error: no viable overloaded
      operator[] for type 'ORB_SLAM3::LoopClosing::KeyFrameAndPose' (aka
      'map<ORB_SLAM3::KeyFrame *, g2o::Sim3, std::less<KeyFrame *>,
      Eigen::aligned_allocator<std::pair<const KeyFrame *, g2o::Sim3> > >')
                    vNonCorrectedSim3[pKFi]=g2oSiw;
                    ~~~~~~~~~~~~~~~~~^~~~~
/Users/langzhou/Project/ORB_SLAM3/src/LoopClosing.cc:1772:35: error: no viable overloaded
      operator[] for type 'ORB_SLAM3::LoopClosing::KeyFrameAndPose' (aka
      'map<ORB_SLAM3::KeyFrame *, g2o::Sim3, std::less<KeyFrame *>,
      Eigen::aligned_allocator<std::pair<const KeyFrame *, g2o::Sim3> > >')
                    vCorrectedSim3[pKFi]=g2oCorrectedSiw;
                    ~~~~~~~~~~~~~~^~~~~
/Users/langzhou/Project/ORB_SLAM3/src/LoopClosing.cc:1791:82: error: no viable overloaded
      operator[] for type 'ORB_SLAM3::LoopClosing::KeyFrameAndPose' (aka
      'map<ORB_SLAM3::KeyFrame *, g2o::Sim3, std::less<KeyFrame *>,
      Eigen::aligned_allocator<std::pair<const KeyFrame *, g2o::Sim3> > >')
  ...Eigen::Matrix3d Rcor = eigR.transpose()*vNonCorrectedSim3[pKFi].rotation().toRotati...
                                             ~~~~~~~~~~~~~~~~~^~~~~
fatal error: too many errors emitted, stopping now [-ferror-limit=]
16 warnings and 20 errors generated.

After doing some searching I found some similar issues, some dating back to ORB_SLAM2 and hasn't been solved yet.

For example: https://github.com/raulmur/ORB_SLAM2/issues/78#issuecomment-678144967 https://github.com/tum-vision/LDSO/issues/4 https://github.com/sunbingfeng/ORB-SLAM2-MAC/issues/1

I guess it may due to Apple clang compiler issues, so I changed to the compiler to gcc and g++ in build.sh by adding parameters -DCMAKE_CXX_COMPILER=/usr/bin/g++ and -DCMAKE_C_COMPILER=/usr/bin/gcc, not worked though. It seems that most errors are related to project file /src/LoopClosing.cc, but with my limited C++ knowledge it's hard to tell which part is wrong.

Could anyone review this issue and offer some help? Thanks in advance.

zhigangjiang commented 3 years ago

https://github.com/raulmur/ORB_SLAM2/issues/487#issuecomment-353747129

In include/LoopClosing.h, change lines 49 and 50 to:

typedef map<KeyFrame*,g2o::Sim3,std::less<KeyFrame*>,
        Eigen::aligned_allocator<std::pair<KeyFrame* const, g2o::Sim3> > > KeyFrameAndPose;
arjunskumar commented 3 years ago

@zhigangjiang This worked for me, Thanks