Skip to content

Commit

Permalink
update submodules
Browse files Browse the repository at this point in the history
  • Loading branch information
JzHuai0108 committed Mar 14, 2018
1 parent 9e91042 commit e50e374
Show file tree
Hide file tree
Showing 28 changed files with 753 additions and 149 deletions.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ The Boost library is used to launch different threads of the SLAM system.
```
sudo apt-get install libboost-all-dev
```
## 2.2 OpenCV 2.4.x
## 2.2 OpenCV (>=3.0)

OpenCV is mainly used for feature extraction, and matching. It can be installed via:
```
Expand Down
1 change: 1 addition & 0 deletions Thirdparty/DBoW2/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -37,3 +37,4 @@ set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
include_directories(${OpenCV_INCLUDE_DIRS})
add_library(DBoW2 SHARED ${SRCS_DBOW2} ${SRCS_DUTILS})
target_link_libraries(DBoW2 ${OpenCV_LIBS})

2 changes: 1 addition & 1 deletion Thirdparty/DBoW2/DBoW2/FClass.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
#ifndef __D_T_FCLASS__
#define __D_T_FCLASS__

#include <opencv/cv.h>
#include <opencv2/core/core.hpp>
#include <vector>
#include <string>

Expand Down
2 changes: 1 addition & 1 deletion Thirdparty/DBoW2/DBoW2/FORB.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
#ifndef __D_T_F_ORB__
#define __D_T_F_ORB__

#include <opencv/cv.h>
#include <opencv2/core/core.hpp>
#include <vector>
#include <string>

Expand Down
52 changes: 0 additions & 52 deletions Thirdparty/DBoW2/DBoW2/LICENSE.txt

This file was deleted.

4 changes: 3 additions & 1 deletion Thirdparty/DBoW2/DBoW2/ScoringObject.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,9 @@ class GeneralScoring
static const double LOG_EPS;
// If you change the type of WordValue, make sure you change also the
// epsilon value (this is needed by the KL method)
virtual ~GeneralScoring(){}

virtual ~GeneralScoring() {} //!< Required for virtual base classes

};

/**
Expand Down
7 changes: 4 additions & 3 deletions Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include <fstream>
#include <string>
#include <algorithm>
#include <opencv/cv.h>
#include <opencv2/core/core.hpp>
#include <limits>

#include "FeatureVector.h"
Expand Down Expand Up @@ -1384,7 +1384,8 @@ bool TemplatedVocabulary<TDescriptor,F>::loadFromTextFile(const std::string &fil

int nid = m_nodes.size();
m_nodes.resize(m_nodes.size()+1);
m_nodes[nid].id = nid;
m_nodes[nid].id = nid;

int pid ;
ssnode >> pid;
m_nodes[nid].parent = pid;
Expand All @@ -1399,7 +1400,7 @@ bool TemplatedVocabulary<TDescriptor,F>::loadFromTextFile(const std::string &fil
string sElement;
ssnode >> sElement;
ssd << sElement << " ";
}
}
F::fromString(m_nodes[nid].descriptor, ssd.str());

ssnode >> m_nodes[nid].weight;
Expand Down
34 changes: 0 additions & 34 deletions Thirdparty/DBoW2/DUtils/LICENSE.txt

This file was deleted.

12 changes: 2 additions & 10 deletions Thirdparty/DBoW2/LICENSE.txt
Original file line number Diff line number Diff line change
@@ -1,14 +1,8 @@
This is a modified version of:

DBoW2: bag-of-words library for C++ with generic descriptors

Copyright (c) 2015 Dorian Galvez-Lopez. http://doriangalvez.com
Copyright (c) 2015 Dorian Galvez-Lopez <http://doriangalvez.com> (Universidad de Zaragoza)
All rights reserved.

This version contains only a subset of the original components of the library
and DBoW2/FORB.cpp has been modified (see the file for details).


Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions
are met:
Expand All @@ -17,9 +11,7 @@ are met:
2. Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
3. The original author of the work must be notified of any
redistribution of source code or in binary form.
4. Neither the name of copyright holders nor the names of its
3. Neither the name of copyright holders nor the names of its
contributors may be used to endorse or promote products derived
from this software without specific prior written permission.

Expand Down
7 changes: 7 additions & 0 deletions Thirdparty/DBoW2/README.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
You should have received this DBoW2 version along with ORB-SLAM2 (https://github.com/raulmur/ORB_SLAM2).
See the original DBoW2 library at: https://github.com/dorian3d/DBoW2
All files included in this version are BSD, see LICENSE.txt

We also use Random.h, Random.cpp, Timestamp.pp and Timestamp.h from DLib/DUtils.
See the original DLib library at: https://github.com/dorian3d/DLib
All files included in this version are BSD, see LICENSE.txt
46 changes: 34 additions & 12 deletions Thirdparty/vio_common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,19 +24,20 @@ ENDIF()
SET(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS} -O3 -fsee -fomit-frame-pointer -fno-signed-zeros -fno-math-errno -funroll-loops")

# Add plain cmake packages
FIND_PACKAGE(OpenCV REQUIRED)
find_package(OpenCV REQUIRED)
message ("opencv include dir " ${OpenCV_INCLUDE_DIRS})
FIND_PACKAGE(Eigen REQUIRED)

# Include dirs
INCLUDE_DIRECTORIES(
include
LIST(APPEND vio_common_INCLUDE_DIR
${CMAKE_CURRENT_SOURCE_DIR}/include
${Eigen_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
)

IF(USE_ROS)
FIND_PACKAGE(catkin REQUIRED COMPONENTS roscpp cmake_modules)
LIST(APPEND INCLUDE_DIRECTORIES ${catkin_INCLUDE_DIRS})
LIST(APPEND vio_common_INCLUDE_DIR ${catkin_INCLUDE_DIRS})
catkin_package(
DEPENDS Eigen OpenCV
CATKIN_DEPENDS roscpp
Expand All @@ -62,17 +63,17 @@ src/FrameGrabber.cpp
src/eigen_utils.cpp
include/vio/PointStatistics.h
include/vio/IMUErrorModel.h
include/vio/IMUErrorModel.cpp
)

IF(USE_GPSTK)
ADD_DEFINITIONS(-DHAVE_GPSTK)
SET(GPSTK_INCLUDE_DIRS $ENV{HOME}/ScaViSLAM/svslocal/include)
INCLUDE_DIRECTORIES(${GPSTK_INCLUDE_DIRS})
SET(GPSTK_LIB $ENV{HOME}/ScaViSLAM/svslocal/lib/libgpstk.so)
SET(GPSTK_INCLUDE_DIRS $ENV{HOME}/workspace/local_install/gpstk/include)
LIST(APPEND vio_common_INCLUDE_DIR ${GPSTK_INCLUDE_DIRS})
SET(GPSTK_LIB $ENV{HOME}/workspace/local_install/gpstk/lib/libgpstk.so)
ENDIF()

# Create library
INCLUDE_DIRECTORIES(${vio_common_INCLUDE_DIR})
ADD_LIBRARY(${PROJECT_NAME} SHARED ${SOURCEFILES})
TARGET_LINK_LIBRARIES(${PROJECT_NAME}
${OpenCV_LIBS})
Expand Down Expand Up @@ -104,12 +105,33 @@ TARGET_LINK_LIBRARIES(testeigeninverse ${PROJECT_NAME})
################################################################################
# Create the vio_commonConfig.cmake file for other cmake projects.
IF(NOT USE_ROS)
SET(vio_common_LIBRARIES ${PROJECT_SOURCE_DIR}/lib/libvio_common.so)
# Export package for use from the build tree
EXPORT( PACKAGE vio_common )

# Create the vio_commonConfig.cmake file for other cmake projects.
# ... for the build tree
SET( CONFIG_SOURCE_DIR ${CMAKE_CURRENT_SOURCE_DIR})
SET( CONFIG_DIR ${CMAKE_CURRENT_BINARY_DIR})
SET(vio_common_LIBRARY ${PROJECT_SOURCE_DIR}/lib/libvio_common.so)
SET(vio_common_LIBRARY_DIR ${PROJECT_SOURCE_DIR}/lib)
SET(vio_common_INCLUDE_DIR "${PROJECT_SOURCE_DIR}/include")
CONFIGURE_FILE( ${CMAKE_CURRENT_SOURCE_DIR}/vio_commonConfig.cmake.in
${CMAKE_CURRENT_BINARY_DIR}/vio_commonConfig.cmake @ONLY IMMEDIATE )
export( PACKAGE vio_common )

# ... for the install tree
SET( CMAKECONFIG_INSTALL_DIR lib/cmake/vio_common )
FILE( RELATIVE_PATH REL_INCLUDE_DIR
"${CMAKE_INSTALL_PREFIX}/${CMAKECONFIG_INSTALL_DIR}"
"${CMAKE_INSTALL_PREFIX}/include" )

SET( vio_common_INCLUDE_DIR "\${vio_common_CMAKE_DIR}/${REL_INCLUDE_DIR}" )
SET( vio_common_LIBRARY_DIR "\${vio_common_CMAKE_DIR}/../.." )
SET( vio_common_LIBRARY "\${vio_common_CMAKE_DIR}/../../libvio_common.so" )
SET( CONFIG_SOURCE_DIR )
SET( CONFIG_DIR )
CONFIGURE_FILE( ${CMAKE_CURRENT_SOURCE_DIR}/vio_commonConfig.cmake.in
${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/vio_commonConfig.cmake @ONLY )
INSTALL(FILES "${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/vio_commonConfig.cmake"
DESTINATION ${CMAKECONFIG_INSTALL_DIR} )

INSTALL(DIRECTORY include/vio DESTINATION ${CMAKE_INSTALL_PREFIX}/include FILES_MATCHING PATTERN "*.h" )
INSTALL(TARGETS ${PROJECT_NAME} DESTINATION ${CMAKE_INSTALL_PREFIX}/lib )
Expand Down
27 changes: 27 additions & 0 deletions Thirdparty/vio_common/README.md
Original file line number Diff line number Diff line change
@@ -1 +1,28 @@
vio_common

# Build instructions

1. Install opencv 2.4 and eigen 3.3

```
#e.g.,
sudo apt-get install libopencv-dev libeigen3-dev
```

If you want to install a specific version of these libraries or install to a specific path(note -DCMAKE\_INSTALL\_PREFIX), you may build them from source.

2. Build vio_common

```
cd
cd workspace
git clone https://github.com/JzHuai0108/vio_common.git vio_common
mkdir build && cd build
#cmake .. -DOpenCV_DIR=/folder/of/OpenCVConfig.cmake -DEIGEN_INCLUDE_DIR=/folder/of/Eigen -DCMAKE_INSTALL_PREFIX=$HOME/workspace/local_install/vio_common
#e.g.,
cmake .. -DOpenCV_DIR=$HOME/workspace/local_install/opencv/share/OpenCV -DEIGEN_INCLUDE_DIR=$HOME/workspace/local_install/eigen -DCMAKE_INSTALL_PREFIX=$HOME/workspace/local_install/vio_common
make
make install
```


6 changes: 4 additions & 2 deletions Thirdparty/vio_common/include/vio/CsvReader.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,8 @@
namespace vio{
enum OUTPUT_FILE_TYPE{OKVIS_OUTPUT_FILE=0};
class CsvReader:DataGrabber{
public:
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
class LinePattern{
virtual std::ostream& print(std::ostream &) const=0;
virtual std::istream& read(std::istream &)=0;
Expand All @@ -29,7 +30,7 @@ class CsvReader:DataGrabber{
virtual double getTime()=0;
};

class OkvisOutputPattern: public LinePattern{
class OkvisOutputPattern: public LinePattern{

virtual std::ostream& print(std::ostream &) const;
virtual std::istream& read(std::istream &);
Expand Down Expand Up @@ -70,6 +71,7 @@ void loadCsvData(std::string csvFile, std::vector<Eigen::Matrix<double, 19, 1> >

class ViclamOutputReader:vio::DataGrabber{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
class ViclamOutputPattern{

virtual std::ostream& print(std::ostream &) const;
Expand Down
1 change: 0 additions & 1 deletion Thirdparty/vio_common/include/vio/DataGrabber.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@

#include <iostream>
#include <fstream>
#include <Eigen/Dense>

namespace vio{

Expand Down
2 changes: 2 additions & 0 deletions Thirdparty/vio_common/include/vio/FrameGrabber.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,8 @@ class FrameGrabber{
*/
bool grabFrame(cv::Mat & frame, double & tk);
int getCurrentId(){return mnCurrentId - 1;} //because it's incremented once a frame is obtained
//queryIndex is zero based, currently only supports video not image sequences
bool grabFrameByIndex(const int queryIndex, cv::Mat & left_img, double & tk);
protected:
bool is_measurement_good; //does the measurement fit our requirements?
std::string mVideoFile;
Expand Down
1 change: 1 addition & 0 deletions Thirdparty/vio_common/include/vio/GPSGrabber.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ namespace vio{
enum GPSSolutionType{TOW_ECEF=0, TOW_NED, UTC_ECEF, UTC_NED};
class GPSGrabber:vio::DataGrabber{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
// GPS TOW
class RtklibPosPattern{
virtual std::ostream& print(std::ostream &) const;
Expand Down
2 changes: 2 additions & 0 deletions Thirdparty/vio_common/include/vio/IMUErrorModel.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ template <class Scalar>
class IMUErrorModel
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
//a volatile class to estimate linear acceleration and angular rate given measurements, or predict measurements given estimated values
Eigen::Matrix<Scalar, 3,1> b_g;
Eigen::Matrix<Scalar, 3, 1> b_a;
Expand Down Expand Up @@ -60,4 +61,5 @@ class IMUErrorModel
void dwa_B_dbgbaSTS(Eigen::Matrix<Scalar, 6, 27+6> & output);
};

#include "implementation/IMUErrorModel.h"
#endif
Loading

0 comments on commit e50e374

Please sign in to comment.