ORB_SLAM_iOS icon indicating copy to clipboard operation
ORB_SLAM_iOS copied to clipboard

Optimizer.cpp & map.cpp some erros

Open umutboz opened this issue 7 years ago • 4 comments

macOS Mojave

Xcode 10.1

I get some errors when building on the device.

Showing Recent Messages /Applications/Xcode.app/Contents/Developer/Toolchains/XcodeDefault.xctoolchain/usr/include/c++/v1/map:818:5: Static_assert failed due to requirement 'is_same<typename allocator_type::value_type, value_type>::value' "Allocator::value_type must be same type as value_type"

ORB_SLAM/Optimizer.cpp:581:43: No viable overloaded operator[] for type 'LoopClosing::KeyFrameAndPose' (aka 'map<ORB_SLAM::KeyFrame *, g2o::Sim3, std::less<KeyFrame *>, Eigen::aligned_allocator<std::pair<const KeyFrame *, g2o::Sim3> > >')

ORB_SLAM/Optimizer.cpp:582:49: No viable overloaded operator[] for type 'LoopClosing::KeyFrameAndPose' (aka 'map<ORB_SLAM::KeyFrame *, g2o::Sim3, std::less<KeyFrame *>, Eigen::aligned_allocator<std::pair<const KeyFrame *, g2o::Sim3> > >')

ORB_SLAM/Optimizer.cpp:648:33: No member named 'count' in 'std::__1::map<ORB_SLAM::KeyFrame *, g2o::Sim3, std::__1::less<ORB_SLAM::KeyFrame *>, Eigen::aligned_allocator<std::__1::pair<const ORB_SLAM::KeyFrame *, g2o::Sim3> > >'

ORB_SLAM/Optimizer.cpp:649:39: No viable overloaded operator[] for type 'LoopClosing::KeyFrameAndPose' (aka 'map<ORB_SLAM::KeyFrame *, g2o::Sim3, std::less<KeyFrame *>, Eigen::aligned_allocator<std::pair<const KeyFrame *, g2o::Sim3> > >')

SLAM/ORB_SLAM/Optimizer.cpp:662:37: No member named 'count' in 'std::__1::map<ORB_SLAM::KeyFrame *, g2o::Sim3, std::__1::less<ORB_SLAM::KeyFrame *>, Eigen::aligned_allocator<std::__1::pair<const ORB_SLAM::KeyFrame *, g2o::Sim3> > >'

SLAM/ORB_SLAM/Optimizer.cpp:663:43: No viable overloaded operator[] for type 'LoopClosing::KeyFrameAndPose' (aka 'map<ORB_SLAM::KeyFrame *, g2o::Sim3, std::less<KeyFrame *>, Eigen::aligned_allocator<std::pair<const KeyFrame *, g2o::Sim3> > >')

ORB_SLAM/Optimizer.cpp:686:41: No member named 'count' in 'std::__1::map<ORB_SLAM::KeyFrame *, g2o::Sim3, std::__1::less<ORB_SLAM::KeyFrame *>, Eigen::aligned_allocator<std::__1::pair<const ORB_SLAM::KeyFrame *, g2o::Sim3> > >'

SLAM/ORB_SLAM/Optimizer.cpp:687:47: No viable overloaded operator[] for type 'LoopClosing::KeyFrameAndPose' (aka 'map<ORB_SLAM::KeyFrame *, g2o::Sim3, std::less<KeyFrame *>, Eigen::aligned_allocator<std::pair<const KeyFrame *, g2o::Sim3> > >')

SLAM/ORB_SLAM/Optimizer.cpp:714:45: No member named 'count' in 'std::__1::map<ORB_SLAM::KeyFrame *, g2o::Sim3, std::__1::less<ORB_SLAM::KeyFrame *>, Eigen::aligned_allocator<std::__1::pair<const ORB_SLAM::KeyFrame *, g2o::Sim3> > >'

SLAM/ORB_SLAM/Optimizer.cpp:715:51: No viable overloaded operator[] for type 'LoopClosing::KeyFrameAndPose' (aka 'map<ORB_SLAM::KeyFrame *, g2o::Sim3, std::less<KeyFrame *>, Eigen::aligned_allocator<std::pair<const KeyFrame *, g2o::Sim3> > >')

umutboz avatar Feb 09 '19 14:02 umutboz

Same problem,Have you solved it?

month612 avatar Apr 16 '19 02:04 month612

@umutboz @month612 did you guys able to solve this compilation issue? Please share if you able to solve it

ftahir999 avatar May 28 '19 07:05 ftahir999

I am able run this project on older Xcode (8.2.1) and on OS High Sierra

ftahir999 avatar May 31 '19 07:05 ftahir999

The correct way is to change LoopClosing.h map definition from

typedef map<KeyFrame*, g2o::Sim3, std::less<KeyFrame*>,
        Eigen::aligned_allocator<std::pair<const KeyFrame*, g2o::Sim3> > > KeyFrameAndPose;

to

typedef map<KeyFrame*, g2o::Sim3, std::less<KeyFrame*>,
        Eigen::aligned_allocator<std::pair<KeyFrame* const, g2o::Sim3> > > KeyFrameAndPose;

see

https://lists.freebsd.org/pipermail/freebsd-hackers/2016-June/049595.html

Patch:

diff --git a/include/LoopClosing.h b/include/LoopClosing.h
index 7eb0416..c3adf13 100644
--- a/include/LoopClosing.h
+++ b/include/LoopClosing.h
@@ -47,7 +47,7 @@ public:
 
     typedef pair<set<KeyFrame*>,int> ConsistentGroup;    
     typedef map<KeyFrame*,g2o::Sim3,std::less<KeyFrame*>,
-        Eigen::aligned_allocator<std::pair<const KeyFrame*, g2o::Sim3> > > KeyFrameAndPose;
+        Eigen::aligned_allocator<std::pair<KeyFrame* const, g2o::Sim3> > > KeyFrameAndPose;
 
 public:

quimnuss avatar Sep 20 '19 15:09 quimnuss