From a279fc4be8c2ac005636be41cc605ed59c02b309 Mon Sep 17 00:00:00 2001 From: John Date: Wed, 10 Feb 2016 01:02:20 +0900 Subject: [PATCH 1/3] Fixed compile errors on Clang, MacOSX Yosemite. --- lsd_slam_core/src/DataStructures/Frame.cpp | 64 +++++++++---------- lsd_slam_core/src/DataStructures/Frame.h | 58 +++++++++-------- .../src/GlobalMapping/KeyFrameGraph.h | 22 +++---- lsd_slam_core/src/IOWrapper/Timestamp.h | 16 ++--- lsd_slam_core/src/util/SophusUtil.cpp | 14 ++-- lsd_slam_core/src/util/SophusUtil.h | 5 +- 6 files changed, 88 insertions(+), 91 deletions(-) diff --git a/lsd_slam_core/src/DataStructures/Frame.cpp b/lsd_slam_core/src/DataStructures/Frame.cpp index 04ec0498..a3dbb3c3 100644 --- a/lsd_slam_core/src/DataStructures/Frame.cpp +++ b/lsd_slam_core/src/DataStructures/Frame.cpp @@ -2,7 +2,7 @@ * This file is part of LSD-SLAM. * * Copyright 2013 Jakob Engel (Technical University of Munich) -* For more information see +* For more information see * * LSD-SLAM is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -35,7 +35,7 @@ int privateFrameAllocCount = 0; Frame::Frame(int id, int width, int height, const Eigen::Matrix3f& K, double timestamp, const unsigned char* image) { initialize(id, width, height, K, timestamp); - + data.image[0] = FrameMemory::getInstance().getFloatBuffer(data.width[0]*data.height[0]); float* maxPt = data.image[0] + data.width[0]*data.height[0]; @@ -56,7 +56,7 @@ Frame::Frame(int id, int width, int height, const Eigen::Matrix3f& K, double tim Frame::Frame(int id, int width, int height, const Eigen::Matrix3f& K, double timestamp, const float* image) { initialize(id, width, height, K, timestamp); - + data.image[0] = FrameMemory::getInstance().getFloatBuffer(data.width[0]*data.height[0]); memcpy(data.image[0], image, data.width[0]*data.height[0] * sizeof(float)); data.imageValid[0] = true; @@ -67,7 +67,7 @@ Frame::Frame(int id, int width, int height, const Eigen::Matrix3f& K, double tim printf("ALLOCATED frame %d, now there are %d\n", this->id(), privateFrameAllocCount); } -Frame::~Frame() +Frame::~Frame() throw() { if(enablePrintDebugInfo && printMemoryDebugInfo) @@ -210,7 +210,7 @@ void Frame::setDepth(const DepthMapPixelHypothesis* newDepth) float* pyrIDepth = data.idepth[0]; float* pyrIDepthVar = data.idepthVar[0]; float* pyrIDepthMax = pyrIDepth + (data.width[0]*data.height[0]); - + float sumIdepth=0; int numIdepth=0; @@ -230,7 +230,7 @@ void Frame::setDepth(const DepthMapPixelHypothesis* newDepth) *pyrIDepthVar = -1; } } - + meanIdepth = sumIdepth / numIdepth; numPoints = numIdepth; @@ -283,7 +283,7 @@ void Frame::setDepthFromGroundTruth(const float* depth, float cov_scale) ++ pyrIDepthVar; } } - + data.idepthValid[0] = true; data.idepthVarValid[0] = true; // data.refIDValid[0] = true; @@ -397,7 +397,7 @@ bool Frame::minimizeInMemory() void Frame::initialize(int id, int width, int height, const Eigen::Matrix3f& K, double timestamp) { data.id = id; - + pose = new FramePoseStruct(this); data.K[0] = K; @@ -405,21 +405,21 @@ void Frame::initialize(int id, int width, int height, const Eigen::Matrix3f& K, data.fy[0] = K(1,1); data.cx[0] = K(0,2); data.cy[0] = K(1,2); - + data.KInv[0] = K.inverse(); data.fxInv[0] = data.KInv[0](0,0); data.fyInv[0] = data.KInv[0](1,1); data.cxInv[0] = data.KInv[0](0,2); data.cyInv[0] = data.KInv[0](1,2); - + data.timestamp = timestamp; data.hasIDepthBeenSet = false; depthHasBeenUpdatedFlag = false; - + referenceID = -1; referenceLevel = -1; - + numMappablePixels = -1; for (int level = 0; level < PYRAMID_LEVELS; ++ level) @@ -441,7 +441,7 @@ void Frame::initialize(int id, int width, int height, const Eigen::Matrix3f& K, data.reActivationDataValid = false; // data.refIDValid[level] = false; - + if (level > 0) { data.fx[level] = data.fx[level-1] * 0.5; @@ -495,7 +495,7 @@ void Frame::buildImage(int level) printf("Frame::buildImage(0): Loading image from disk is not implemented yet! No-op.\n"); return; } - + require(IMAGE, level - 1); boost::unique_lock lock2(buildMutex); @@ -562,36 +562,36 @@ void Frame::buildImage(int level) int height_iteration_count = height / 2; const float* cur_px = source; const float* next_row_px = source + width; - + __asm__ __volatile__ ( "vldmia %[p025], {q10} \n\t" // p025(q10) - + ".height_loop: \n\t" - + "mov r5, %[width_iteration_count] \n\t" // store width_iteration_count ".width_loop: \n\t" - + "vldmia %[cur_px]!, {q0-q1} \n\t" // top_left(q0), top_right(q1) "vldmia %[next_row_px]!, {q2-q3} \n\t" // bottom_left(q2), bottom_right(q3) - + "vadd.f32 q0, q0, q2 \n\t" // left(q0) "vadd.f32 q1, q1, q3 \n\t" // right(q1) - + "vpadd.f32 d0, d0, d1 \n\t" // pairwise add into sum(q0) "vpadd.f32 d1, d2, d3 \n\t" "vmul.f32 q0, q0, q10 \n\t" // multiply with 0.25 to get average - + "vstmia %[dest]!, {q0} \n\t" - + "subs %[width_iteration_count], %[width_iteration_count], #1 \n\t" "bne .width_loop \n\t" "mov %[width_iteration_count], r5 \n\t" // restore width_iteration_count - + // Advance one more line "add %[cur_px], %[cur_px], %[rowSize] \n\t" "add %[next_row_px], %[next_row_px], %[rowSize] \n\t" - + "subs %[height_iteration_count], %[height_iteration_count], #1 \n\t" "bne .height_loop \n\t" @@ -658,7 +658,7 @@ void Frame::buildGradients(int level) const float* img_pt = data.image[level] + width; const float* img_pt_max = data.image[level] + width*(height-1); Eigen::Vector4f* gradxyii_pt = data.gradients[level] + width; - + // in each iteration i need -1,0,p1,mw,pw float val_m1 = *(img_pt-1); float val_00 = *img_pt; @@ -701,7 +701,7 @@ void Frame::buildMaxGradients(int level) int height = data.height[level]; if (data.maxGradients[level] == 0) data.maxGradients[level] = FrameMemory::getInstance().getFloatBuffer(width * height); - + float* maxGradTemp = FrameMemory::getInstance().getFloatBuffer(width * height); @@ -787,16 +787,16 @@ void Frame::buildIDepthAndIDepthVar(int level) require(IDEPTH, level - 1); boost::unique_lock lock2(buildMutex); - + if(data.idepthValid[level] && data.idepthVarValid[level]) return; if(enablePrintDebugInfo && printFrameBuildDebugInfo) printf("CREATE IDepth lvl %d for frame %d\n", level, id()); - + int width = data.width[level]; int height = data.height[level]; - + if (data.idepth[level] == 0) data.idepth[level] = FrameMemory::getInstance().getFloatBuffer(width * height); if (data.idepthVar[level] == 0) @@ -808,7 +808,7 @@ void Frame::buildIDepthAndIDepthVar(int level) const float* idepthVarSource = data.idepthVar[level - 1]; float* idepthDest = data.idepth[level]; float* idepthVarDest = data.idepthVar[level]; - + for(int y=0;y 0) { float depth = ivarSumsSum / idepthSumsSum; @@ -883,7 +883,7 @@ void Frame::releaseIDepth(int level) printf("Frame::releaseIDepth(0): Storing depth on disk is not supported yet! No-op.\n"); return; } - + FrameMemory::getInstance().returnBuffer(data.idepth[level]); data.idepth[level] = 0; } diff --git a/lsd_slam_core/src/DataStructures/Frame.h b/lsd_slam_core/src/DataStructures/Frame.h index 1ff2f530..4fbded2e 100644 --- a/lsd_slam_core/src/DataStructures/Frame.h +++ b/lsd_slam_core/src/DataStructures/Frame.h @@ -2,7 +2,7 @@ * This file is part of LSD-SLAM. * * Copyright 2013 Jakob Engel (Technical University of Munich) -* For more information see +* For more information see * * LSD-SLAM is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -28,6 +28,10 @@ #include "unordered_set" #include "util/settings.h" +#ifdef __clang__ +#define isnanf(x) isnan(x) +#endif + namespace lsd_slam { @@ -49,32 +53,32 @@ class Frame Frame(int id, int width, int height, const Eigen::Matrix3f& K, double timestamp, const float* image); - ~Frame(); - - + ~Frame() throw(); + + /** Sets or updates idepth and idepthVar on level zero. Invalidates higher levels. */ void setDepth(const DepthMapPixelHypothesis* newDepth); /** Calculates mean information for statistical purposes. */ void calculateMeanInformation(); - + /** Sets ground truth depth (real, not inverse!) from a float array on level zero. Invalidates higher levels. */ void setDepthFromGroundTruth(const float* depth, float cov_scale = 1.0f); - + /** Prepares this frame for stereo comparisons with the other frame (computes some intermediate values that will be needed) */ void prepareForStereoWith(Frame* other, Sim3 thisToOther, const Eigen::Matrix3f& K, const int level); - + // Accessors /** Returns the unique frame id. */ inline int id() const; - + /** Returns the frame's image width. */ inline int width(int level = 0) const; /** Returns the frame's image height. */ inline int height(int level = 0) const; - + /** Returns the frame's intrinsics matrix. */ inline const Eigen::Matrix3f& K(int level = 0) const; /** Returns the frame's inverse intrinsics matrix. */ @@ -95,10 +99,10 @@ class Frame inline float cxInv(int level = 0) const; /** Returns KInv(1, 2). */ inline float cyInv(int level = 0) const; - + /** Returns the frame's recording timestamp. */ inline double timestamp() const; - + inline float* image(int level = 0); inline const Eigen::Vector4f* gradients(int level = 0); inline const float* maxGradients(int level = 0); @@ -123,10 +127,10 @@ class Frame IDEPTH = 1<<3, IDEPTH_VAR = 1<<4, REF_ID = 1<<5, - + ALL = IMAGE | GRADIENTS | MAX_GRADIENTS | IDEPTH | IDEPTH_VAR | REF_ID }; - + void setPermaRef(TrackingReference* reference); void takeReActivationData(DepthMapPixelHypothesis* depthMap); @@ -161,7 +165,7 @@ class Frame /** Multi-Map indicating for which other keyframes with which initialization tracking failed.*/ std::unordered_multimap< Frame*, Sim3, std::hash, std::equal_to, - Eigen::aligned_allocator< std::pair > > trackingFailed; + Eigen::aligned_allocator< std::pair > > trackingFailed; // flag set when depth is updated. @@ -212,44 +216,44 @@ class Frame void initialize(int id, int width, int height, const Eigen::Matrix3f& K, double timestamp); void setDepth_Allocate(); - + void buildImage(int level); void releaseImage(int level); - + void buildGradients(int level); void releaseGradients(int level); - + void buildMaxGradients(int level); void releaseMaxGradients(int level); - + void buildIDepthAndIDepthVar(int level); void releaseIDepth(int level); void releaseIDepthVar(int level); - + void printfAssert(const char* message) const; - + struct Data { int id; - + int width[PYRAMID_LEVELS], height[PYRAMID_LEVELS]; Eigen::Matrix3f K[PYRAMID_LEVELS], KInv[PYRAMID_LEVELS]; float fx[PYRAMID_LEVELS], fy[PYRAMID_LEVELS], cx[PYRAMID_LEVELS], cy[PYRAMID_LEVELS]; float fxInv[PYRAMID_LEVELS], fyInv[PYRAMID_LEVELS], cxInv[PYRAMID_LEVELS], cyInv[PYRAMID_LEVELS]; - + double timestamp; - + float* image[PYRAMID_LEVELS]; bool imageValid[PYRAMID_LEVELS]; - + Eigen::Vector4f* gradients[PYRAMID_LEVELS]; bool gradientsValid[PYRAMID_LEVELS]; - + float* maxGradients[PYRAMID_LEVELS]; bool maxGradientsValid[PYRAMID_LEVELS]; - + bool hasIDepthBeenSet; @@ -257,7 +261,7 @@ class Frame // a pixel is valid iff idepthVar[i] > 0. float* idepth[PYRAMID_LEVELS]; bool idepthValid[PYRAMID_LEVELS]; - + // MUST contain -1 for invalid pixel (that dont have depth)!! float* idepthVar[PYRAMID_LEVELS]; bool idepthVarValid[PYRAMID_LEVELS]; diff --git a/lsd_slam_core/src/GlobalMapping/KeyFrameGraph.h b/lsd_slam_core/src/GlobalMapping/KeyFrameGraph.h index 15d1ea21..dc159650 100644 --- a/lsd_slam_core/src/GlobalMapping/KeyFrameGraph.h +++ b/lsd_slam_core/src/GlobalMapping/KeyFrameGraph.h @@ -2,7 +2,7 @@ * This file is part of LSD-SLAM. * * Copyright 2013 Jakob Engel (Technical University of Munich) -* For more information see +* For more information see * * LSD-SLAM is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -93,13 +93,13 @@ friend class IntegrationTest; /** Constructs an empty pose graph. */ KeyFrameGraph(); - + /** Deletes the g2o graph. */ ~KeyFrameGraph(); - + /** Adds a new KeyFrame to the graph. */ void addKeyFrame(Frame* frame); - + /** Adds a new Frame to the graph. Doesnt actually keep the frame, but only it's pose-struct. */ void addFrame(Frame* frame); @@ -107,27 +107,27 @@ friend class IntegrationTest; /** * Adds a new constraint to the graph. - * + * * The transformation must map world points such that they move as if * attached to a frame which moves from firstFrame to secondFrame: * second->camToWorld * first->worldToCam * point - * + * * If isOdometryConstraint is set, scaleInformation is ignored. */ void insertConstraint(KFConstraintStruct* constraint); - + /** Optimizes the graph. Does not update the keyframe poses, * only the vertex poses. You must call updateKeyFramePoses() afterwards. */ int optimize(int num_iterations); bool addElementsFromBuffer(); - + /** * Creates a hash map of keyframe -> distance to given frame. */ void calculateGraphDistancesToFrame(Frame* frame, std::unordered_map* distanceMap); - + int totalPoints; @@ -178,9 +178,9 @@ friend class IntegrationTest; /** Pose graph representation in g2o */ g2o::SparseOptimizer graph; - + std::vector< Frame*, Eigen::aligned_allocator > newKeyframesBuffer; - std::vector< KFConstraintStruct*, Eigen::aligned_allocator > newEdgeBuffer; + std::vector< KFConstraintStruct*, Eigen::aligned_allocator > newEdgeBuffer; int nextEdgeId; diff --git a/lsd_slam_core/src/IOWrapper/Timestamp.h b/lsd_slam_core/src/IOWrapper/Timestamp.h index bc59d0fc..885d3de3 100644 --- a/lsd_slam_core/src/IOWrapper/Timestamp.h +++ b/lsd_slam_core/src/IOWrapper/Timestamp.h @@ -2,7 +2,7 @@ * This file is part of LSD-SLAM. * * Copyright 2013 Jakob Engel (Technical University of Munich) -* For more information see +* For more information see * * LSD-SLAM is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -30,7 +30,7 @@ // TODO: remove this hack namespace std { namespace chrono { - #if (__GNUC__ > 4) || (__GNUC_MINOR__ >= 8) + #if (__GNUC__ > 4) || (__GNUC_MINOR__ >= 8) || __clang__ #define monotonic_clock steady_clock #endif } @@ -52,32 +52,32 @@ class Timestamp */ Timestamp(); Timestamp(double seconds); - + /** * Returns the timestamp as the time in seconds which has passed since the * start of the program until the timestamp was taken. */ double toSec() const; - + /** * Returns the timestamp as a date string with format TODO. */ std::string toDateStr(const char* format) const; - + /** * Returns the seconds from this timestamp to the other. */ double secondsUntil(const Timestamp& other) const; - + /** * Returns a timestamp representing the current point in time. */ static Timestamp now(); - + private: std::chrono::monotonic_clock::time_point timePoint; std::chrono::system_clock::time_point systemTimePoint; - + static const std::chrono::monotonic_clock::time_point startupTimePoint; static boost::mutex localtimeMutex; diff --git a/lsd_slam_core/src/util/SophusUtil.cpp b/lsd_slam_core/src/util/SophusUtil.cpp index e67f3318..1840e6a2 100644 --- a/lsd_slam_core/src/util/SophusUtil.cpp +++ b/lsd_slam_core/src/util/SophusUtil.cpp @@ -2,7 +2,7 @@ * This file is part of LSD-SLAM. * * Copyright 2013 Jakob Engel (Technical University of Munich) -* For more information see +* For more information see * * LSD-SLAM is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -23,18 +23,14 @@ // Compile the templates here once so they don't need to be compiled in every // other file using them. -// +// // Other files then include SophusUtil.h which contains extern template // declarations to prevent compiling them there again. (For this reason, // this header must not be included here). -// -// Eigen::Matrix seemingly cannot be instantiated this way, as it tries to -// compile a constructor variant for 4-component vectors, resulting in a -// static assertion failure. - -template class Eigen::Quaternion; -template class Eigen::Quaternion; +// This section used to contain Eigen::Quaternion and +// Eigen::Quaternion template instantiations, but these were causing +// static assert falures on Clang. template class Sophus::SE3Group; template class Sophus::SE3Group; diff --git a/lsd_slam_core/src/util/SophusUtil.h b/lsd_slam_core/src/util/SophusUtil.h index 46e74eba..bf0220c8 100644 --- a/lsd_slam_core/src/util/SophusUtil.h +++ b/lsd_slam_core/src/util/SophusUtil.h @@ -2,7 +2,7 @@ * This file is part of LSD-SLAM. * * Copyright 2013 Jakob Engel (Technical University of Munich) -* For more information see +* For more information see * * LSD-SLAM is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -66,9 +66,6 @@ inline SE3 se3FromSim3(const Sim3& sim3) } // Extern templates (see SophusUtil.cpp) -extern template class Eigen::Quaternion; -extern template class Eigen::Quaternion; - extern template class Sophus::SE3Group; extern template class Sophus::SE3Group; From cd152f32e58214e0dde8b70f8b945951111cc1ef Mon Sep 17 00:00:00 2001 From: John Date: Wed, 10 Feb 2016 01:15:04 +0900 Subject: [PATCH 2/3] Made a pathway to build without ROS, and wrote instructions. --- README.md | 32 ++++++++++- lsd_slam_core/CMakeLists.txt | 100 +++++++++++++++++++++++------------ 2 files changed, 95 insertions(+), 37 deletions(-) diff --git a/README.md b/README.md index 35cb8a19..d404bc96 100644 --- a/README.md +++ b/README.md @@ -43,7 +43,8 @@ and one window showing the 3D map (from viewer). If for some reason the initiali # 2. Installation -We tested LSD-SLAM on two different system configurations, using Ubuntu 12.04 (Precise) and ROS fuerte, or Ubuntu 14.04 (trusty) and ROS indigo. Note that building without ROS is not supported, however ROS is only used for input and output, facilitating easy portability to other platforms. +We tested LSD-SLAM on three different system configurations, using Ubuntu 12.04 (Precise) and ROS fuerte, Ubuntu 14.04 (trusty) and ROS indigo, +and MacOSX Yosemite. Since ROS is used for input and output, the stand-alone build does not install any front-end executable programs. ## 2.1 ROS fuerte + Ubuntu 12.04 @@ -91,9 +92,36 @@ Compile the two package by typing: +## 2.3 Stand-alone CMake build +Install system-wide dependencies through your package manager (brew, apt-get - as above, but omitting ros-related packages) or manually. + brew install eigen suite-sparse opencv cmake -## 2.3 openFabMap for large loop-closure detection [optional] +Clone and build g2o in the directory of your choice. + + git clone https://github.com/RainerKuemmerle/g2o + cd g2o + mkdir build + cd build + cmake -DCMAKE_INSTALL_PATH=../install + make -j8 + make install + +Continue as you would for any other cmake build. The only difference is that you will only build lsd_slam_core, and that you will +probably have to provide the BUILD_WITHOUT_ROS, EXTRA_LIB_DIRS, and EXTRA_INCLUDE_DIRS variables to cmake. + + git clone https://github.com/tum-vision/lsd_slam.git lsd_slam + cd lsd_slam/lsd_slam_core + mkdir build + cd build + cmake -DEXTRA_LIB_DIRS=/path/to/g2o/lib/ -DEXTRA_INCLUDE_DIRS=/path/to/g2o/include -DBUILD_WITHOUT_ROS=ON ../ + make -j8 + +Please note that this process only builds the lsd_slam library, and no programs with which you can test it. This build method could be +useful in integrating lsd_slam with other projects. + + +## 2.4 openFabMap for large loop-closure detection [optional] If you want to use openFABMAP for large loop closure detection, uncomment the following lines in `lsd_slam_core/CMakeLists.txt` : #add_subdirectory(${PROJECT_SOURCE_DIR}/thirdparty/openFabMap) diff --git a/lsd_slam_core/CMakeLists.txt b/lsd_slam_core/CMakeLists.txt index 758ce0ba..fee8ecbb 100644 --- a/lsd_slam_core/CMakeLists.txt +++ b/lsd_slam_core/CMakeLists.txt @@ -1,16 +1,18 @@ cmake_minimum_required(VERSION 2.8.7) project(lsd_slam_core) -include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) +if(NOT BUILD_WITHOUT_ROS) + include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) -# Set the build type. Options are: -# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage -# Debug : w/ debug symbols, w/o optimization -# Release : w/o debug symbols, w/ optimization -# RelWithDebInfo : w/ debug symbols, w/ optimization -# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries -set(ROS_BUILD_TYPE Release) + # Set the build type. Options are: + # Coverage : w/ debug symbols, w/o optimization, w/ code-coverage + # Debug : w/ debug symbols, w/o optimization + # Release : w/o debug symbols, w/ optimization + # RelWithDebInfo : w/ debug symbols, w/ optimization + # MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries + set(ROS_BUILD_TYPE Release) -rosbuild_init() + rosbuild_init() +endif() set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin) set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) @@ -27,20 +29,25 @@ find_package(X11 REQUIRED) #add_definitions("-DHAVE_FABMAP") #set(FABMAP_LIB openFABMAP ) -# Dynamic Reconfigure Services -rosbuild_find_ros_package(dynamic_reconfigure) -include(${dynamic_reconfigure_PACKAGE_PATH}/cmake/cfgbuild.cmake) -gencfg() - -# SSE flags -rosbuild_check_for_sse() -add_definitions("-DUSE_ROS") +if(NOT BUILD_WITHOUT_ROS) + # Dynamic Reconfigure Services + rosbuild_find_ros_package(dynamic_reconfigure) + include(${dynamic_reconfigure_PACKAGE_PATH}/cmake/cfgbuild.cmake) + gencfg() + + # SSE flags + rosbuild_check_for_sse() + add_definitions("-DUSE_ROS") +else() + find_package(Boost REQUIRED COMPONENTS thread system) + find_package(OpenCV REQUIRED) +endif() add_definitions("-DENABLE_SSE") # Also add some useful compiler flag set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${SSE_FLAGS} -march=native -std=c++0x" -) +) # Set source files set(lsd_SOURCE_FILES @@ -65,34 +72,57 @@ set(lsd_SOURCE_FILES ${PROJECT_SOURCE_DIR}/src/GlobalMapping/g2oTypeSim3Sophus.cpp ${PROJECT_SOURCE_DIR}/src/GlobalMapping/TrackableKeyFrameSearch.cpp ) + +if(NOT BUILD_WITHOUT_ROS) + set(ADDITIONAL_ROS_SOURCES + ${PROJECT_SOURCE_DIR}/src/IOWrapper/ROS/ROSImageStreamThread.cpp + ${PROJECT_SOURCE_DIR}/src/IOWrapper/ROS/ROSOutput3DWrapper.cpp + ) +endif() set(SOURCE_FILES ${lsd_SOURCE_FILES} - ${PROJECT_SOURCE_DIR}/src/IOWrapper/ROS/ROSImageStreamThread.cpp - ${PROJECT_SOURCE_DIR}/src/IOWrapper/ROS/ROSOutput3DWrapper.cpp ${PROJECT_SOURCE_DIR}/src/IOWrapper/OpenCV/ImageDisplay_OpenCV.cpp + ${ADDITIONAL_ROS_SOURCES} ) - +# The variables EXTRA_INCLUDE_DIRS and EXTRA_LIB_DIRS can be used to +# inject non-standard library paths for local builds of libraries that +# aren't in system directories - for example, g2o include_directories( ${EIGEN3_INCLUDE_DIR} ${PROJECT_SOURCE_DIR}/src ${PROJECT_SOURCE_DIR}/thirdparty/Sophus ${CSPARSE_INCLUDE_DIR} #Has been set by SuiteParse ${CHOLMOD_INCLUDE_DIR} #Has been set by SuiteParse + ${EXTRA_INCLUDE_DIRS} ) +link_directories(${EXTRA_LIB_DIRS}) -# build shared library. -rosbuild_add_library(lsdslam SHARED ${SOURCE_FILES}) -target_link_libraries(lsdslam ${FABMAP_LIB} g2o_core g2o_stuff csparse cxsparse g2o_solver_csparse g2o_csparse_extension g2o_types_sim3 g2o_types_sba X11) -rosbuild_link_boost(lsdslam thread) - - -# build live ros node -rosbuild_add_executable(live_slam src/main_live_odometry.cpp) -target_link_libraries(live_slam lsdslam) - - -# build image node -rosbuild_add_executable(dataset_slam src/main_on_images.cpp) -target_link_libraries(dataset_slam lsdslam) +# build shared library. +if (BUILD_WITHOUT_ROS) + set(PLATFORM_SPECIFIC_LIBRARIES ${Boost_LIBRARIES} + ${OpenCV_LIBS} + ) + add_library(lsdslam SHARED ${SOURCE_FILES}) +else() + set(PLATFORM_SPECIFIC_LIBRARIES X11) + rosbuild_add_library(lsdslam SHARED ${SOURCE_FILES}) + rosbuild_link_boost(lsdslam thread) +endif() + +target_link_libraries(lsdslam ${FABMAP_LIB} g2o_core g2o_stuff cxsparse g2o_solver_csparse g2o_csparse_extension g2o_types_sim3 g2o_types_sba + ${PLATFORM_SPECIFIC_LIBRARIES} + ) + + +if(NOT BUILD_WITHOUT_ROS) + # build live ros node + rosbuild_add_executable(live_slam src/main_live_odometry.cpp) + target_link_libraries(live_slam lsdslam) + + + # build image node + rosbuild_add_executable(dataset_slam src/main_on_images.cpp) + target_link_libraries(dataset_slam lsdslam) +endif() From af0c5d0650a8ef98da1392717106787ff754dadd Mon Sep 17 00:00:00 2001 From: indianajohn Date: Wed, 10 Feb 2016 10:40:57 +0900 Subject: [PATCH 3/3] Updated README.md for Ubuntu build test. --- README.md | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index d404bc96..7795e7c2 100644 --- a/README.md +++ b/README.md @@ -43,8 +43,9 @@ and one window showing the 3D map (from viewer). If for some reason the initiali # 2. Installation -We tested LSD-SLAM on three different system configurations, using Ubuntu 12.04 (Precise) and ROS fuerte, Ubuntu 14.04 (trusty) and ROS indigo, -and MacOSX Yosemite. Since ROS is used for input and output, the stand-alone build does not install any front-end executable programs. +We tested LSD-SLAM on four different system configurations, using Ubuntu 12.04 (Precise) and ROS fuerte, Ubuntu 14.04 (trusty) and ROS indigo, +Ubuntu 14.04 stand-alone, and MacOSX Yosemite stand-alone. Since ROS is used for input and output, the stand-alone builds do not install any +front-end executable programs. ## 2.1 ROS fuerte + Ubuntu 12.04 @@ -93,7 +94,8 @@ Compile the two package by typing: ## 2.3 Stand-alone CMake build -Install system-wide dependencies through your package manager (brew, apt-get - as above, but omitting ros-related packages) or manually. +Install system-wide dependencies through your package manager (brew, apt-get - as above, but omitting ros-related packages) or +manually. The command to install dependencies with Homebrew (http://brew.sh) is given below. brew install eigen suite-sparse opencv cmake @@ -103,7 +105,7 @@ Clone and build g2o in the directory of your choice. cd g2o mkdir build cd build - cmake -DCMAKE_INSTALL_PATH=../install + cmake -DCMAKE_INSTALL_PREFIX=../install make -j8 make install