diff --git a/vins_estimator/CMakeLists.txt b/vins_estimator/CMakeLists.txt index b428271..75cfc5e 100644 --- a/vins_estimator/CMakeLists.txt +++ b/vins_estimator/CMakeLists.txt @@ -1,8 +1,11 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.3) project(vins_estimator) -set(CMAKE_CXX_FLAGS "-std=c++11") -#-DEIGEN_USE_MKL_ALL") +# Enable compile optimizations +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -O3 -fsee -fomit-frame-pointer -fno-signed-zeros -fno-math-errno -funroll-loops") + +# Enable debug flags (use if you want to debug in gdb) +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -g3 -Wall -Wuninitialized -Wmaybe-uninitialized -fno-omit-frame-pointer") find_package(catkin REQUIRED COMPONENTS roscpp @@ -15,20 +18,22 @@ find_package(catkin REQUIRED COMPONENTS find_package(OpenCV REQUIRED) -# message(WARNING "OpenCV_VERSION: ${OpenCV_VERSION}") - find_package(Ceres REQUIRED) -include_directories(${catkin_INCLUDE_DIRS} ${CERES_INCLUDE_DIRS}) - set(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake) find_package(Eigen3) + include_directories( + include ${catkin_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIR} + ${CERES_INCLUDE_DIRS} ) -catkin_package() +catkin_package( + INCLUDE_DIRS include + CATKIN_DEPENDS ${CATKIN_DEPENDENCIES} +) add_executable(vins_estimator src/estimator_node.cpp @@ -48,7 +53,23 @@ add_executable(vins_estimator src/initial/initial_ex_rotation.cpp ) +add_dependencies(vins_estimator + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} + ) target_link_libraries(vins_estimator ${catkin_LIBRARIES} ${OpenCV_LIBS} ${CERES_LIBRARIES}) +## -------------------------------------------------------------- +## | Install | +## -------------------------------------------------------------- + +install(TARGETS vins_estimator + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} + ) +install(DIRECTORY include + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + ) diff --git a/vins_estimator/src/estimator.h b/vins_estimator/include/vins_estimator/estimator.h similarity index 83% rename from vins_estimator/src/estimator.h rename to vins_estimator/include/vins_estimator/estimator.h index 2390aa0..10cf799 100644 --- a/vins_estimator/src/estimator.h +++ b/vins_estimator/include/vins_estimator/estimator.h @@ -1,27 +1,27 @@ #pragma once -#include "parameters.h" -#include "feature_manager.h" -#include "utility/utility.h" -#include "utility/tic_toc.h" -#include "initial/solve_5pts.h" -#include "initial/initial_sfm.h" -#include "initial/initial_alignment.h" -#include "initial/initial_ex_rotation.h" #include #include #include -#include "factor/imu_factor.h" -#include "factor/pose_local_parameterization.h" -#include "factor/projection_factor.h" -#include "factor/projection_td_factor.h" -#include "factor/marginalization_factor.h" #include #include #include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include class Estimator { diff --git a/vins_estimator/src/factor/imu_factor.h b/vins_estimator/include/vins_estimator/factor/imu_factor.h similarity index 98% rename from vins_estimator/src/factor/imu_factor.h rename to vins_estimator/include/vins_estimator/factor/imu_factor.h index 3552643..dfe1277 100644 --- a/vins_estimator/src/factor/imu_factor.h +++ b/vins_estimator/include/vins_estimator/factor/imu_factor.h @@ -3,9 +3,9 @@ #include #include -#include "../utility/utility.h" -#include "../parameters.h" -#include "integration_base.h" +#include +#include +#include #include diff --git a/vins_estimator/src/factor/integration_base.h b/vins_estimator/include/vins_estimator/factor/integration_base.h similarity index 99% rename from vins_estimator/src/factor/integration_base.h rename to vins_estimator/include/vins_estimator/factor/integration_base.h index 9794534..387f5fe 100644 --- a/vins_estimator/src/factor/integration_base.h +++ b/vins_estimator/include/vins_estimator/factor/integration_base.h @@ -1,7 +1,7 @@ #pragma once -#include "../utility/utility.h" -#include "../parameters.h" +#include +#include #include using namespace Eigen; @@ -443,4 +443,4 @@ class IntegrationBase cout << "bg diff " << (turb_linearized_bg - result_linearized_bg).transpose() << endl; cout << "bg jacob diff" << (step_V.block<3, 3>(12, 9) * turb).transpose() << endl; } - */ \ No newline at end of file + */ diff --git a/vins_estimator/src/factor/marginalization_factor.h b/vins_estimator/include/vins_estimator/factor/marginalization_factor.h similarity index 96% rename from vins_estimator/src/factor/marginalization_factor.h rename to vins_estimator/include/vins_estimator/factor/marginalization_factor.h index 1edcef6..9ba41e0 100644 --- a/vins_estimator/src/factor/marginalization_factor.h +++ b/vins_estimator/include/vins_estimator/factor/marginalization_factor.h @@ -7,8 +7,8 @@ #include #include -#include "../utility/utility.h" -#include "../utility/tic_toc.h" +#include +#include const int NUM_THREADS = 4; diff --git a/vins_estimator/src/factor/pose_local_parameterization.h b/vins_estimator/include/vins_estimator/factor/pose_local_parameterization.h similarity index 90% rename from vins_estimator/src/factor/pose_local_parameterization.h rename to vins_estimator/include/vins_estimator/factor/pose_local_parameterization.h index b9d856c..7dd4912 100644 --- a/vins_estimator/src/factor/pose_local_parameterization.h +++ b/vins_estimator/include/vins_estimator/factor/pose_local_parameterization.h @@ -2,7 +2,8 @@ #include #include -#include "../utility/utility.h" + +#include class PoseLocalParameterization : public ceres::LocalParameterization { diff --git a/vins_estimator/src/factor/projection_factor.h b/vins_estimator/include/vins_estimator/factor/projection_factor.h similarity index 80% rename from vins_estimator/src/factor/projection_factor.h rename to vins_estimator/include/vins_estimator/factor/projection_factor.h index 92de6ed..0536b01 100644 --- a/vins_estimator/src/factor/projection_factor.h +++ b/vins_estimator/include/vins_estimator/factor/projection_factor.h @@ -3,9 +3,10 @@ #include #include #include -#include "../utility/utility.h" -#include "../utility/tic_toc.h" -#include "../parameters.h" + +#include +#include +#include class ProjectionFactor : public ceres::SizedCostFunction<2, 7, 7, 7, 1> { diff --git a/vins_estimator/src/factor/projection_td_factor.h b/vins_estimator/include/vins_estimator/factor/projection_td_factor.h similarity index 86% rename from vins_estimator/src/factor/projection_td_factor.h rename to vins_estimator/include/vins_estimator/factor/projection_td_factor.h index d797d26..9214f06 100644 --- a/vins_estimator/src/factor/projection_td_factor.h +++ b/vins_estimator/include/vins_estimator/factor/projection_td_factor.h @@ -3,9 +3,10 @@ #include #include #include -#include "../utility/utility.h" -#include "../utility/tic_toc.h" -#include "../parameters.h" + +#include +#include +#include class ProjectionTdFactor : public ceres::SizedCostFunction<2, 7, 7, 7, 1, 1> { diff --git a/vins_estimator/src/feature_manager.h b/vins_estimator/include/vins_estimator/feature_manager.h similarity index 98% rename from vins_estimator/src/feature_manager.h rename to vins_estimator/include/vins_estimator/feature_manager.h index 4e5d3ce..2fa5e04 100644 --- a/vins_estimator/src/feature_manager.h +++ b/vins_estimator/include/vins_estimator/feature_manager.h @@ -5,15 +5,16 @@ #include #include #include -using namespace std; #include -using namespace Eigen; #include #include -#include "parameters.h" +#include + +using namespace std; +using namespace Eigen; class FeaturePerFrame { @@ -99,4 +100,4 @@ class FeatureManager Matrix3d ric[NUM_OF_CAM]; }; -#endif \ No newline at end of file +#endif diff --git a/vins_estimator/src/initial/initial_alignment.h b/vins_estimator/include/vins_estimator/initial/initial_alignment.h similarity index 78% rename from vins_estimator/src/initial/initial_alignment.h rename to vins_estimator/include/vins_estimator/initial/initial_alignment.h index 49bc466..3c51095 100644 --- a/vins_estimator/src/initial/initial_alignment.h +++ b/vins_estimator/include/vins_estimator/initial/initial_alignment.h @@ -1,11 +1,13 @@ #pragma once #include #include -#include "../factor/imu_factor.h" -#include "../utility/utility.h" + #include #include -#include "../feature_manager.h" + +#include +#include +#include using namespace Eigen; using namespace std; @@ -26,4 +28,4 @@ class ImageFrame bool is_key_frame; }; -bool VisualIMUAlignment(map &all_image_frame, Vector3d* Bgs, Vector3d &g, VectorXd &x); \ No newline at end of file +bool VisualIMUAlignment(map &all_image_frame, Vector3d* Bgs, Vector3d &g, VectorXd &x); diff --git a/vins_estimator/src/initial/initial_ex_rotation.h b/vins_estimator/include/vins_estimator/initial/initial_ex_rotation.h similarity index 96% rename from vins_estimator/src/initial/initial_ex_rotation.h rename to vins_estimator/include/vins_estimator/initial/initial_ex_rotation.h index 902b6fa..6bf8e6e 100644 --- a/vins_estimator/src/initial/initial_ex_rotation.h +++ b/vins_estimator/include/vins_estimator/initial/initial_ex_rotation.h @@ -1,15 +1,17 @@ #pragma once #include -#include "../parameters.h" -using namespace std; #include #include -using namespace Eigen; #include +#include + +using namespace std; +using namespace Eigen; + /* This class help you to calibrate extrinsic rotation between imu and camera when your totally don't konw the extrinsic parameter */ class InitialEXRotation { diff --git a/vins_estimator/src/initial/initial_sfm.h b/vins_estimator/include/vins_estimator/initial/initial_sfm.h similarity index 99% rename from vins_estimator/src/initial/initial_sfm.h rename to vins_estimator/include/vins_estimator/initial/initial_sfm.h index f70432d..29d58e7 100644 --- a/vins_estimator/src/initial/initial_sfm.h +++ b/vins_estimator/include/vins_estimator/initial/initial_sfm.h @@ -8,11 +8,10 @@ #include #include #include + using namespace Eigen; using namespace std; - - struct SFMFeature { bool state; @@ -71,4 +70,4 @@ class GlobalSFM vector &sfm_f); int feature_num; -}; \ No newline at end of file +}; diff --git a/vins_estimator/src/initial/solve_5pts.h b/vins_estimator/include/vins_estimator/initial/solve_5pts.h similarity index 94% rename from vins_estimator/src/initial/solve_5pts.h rename to vins_estimator/include/vins_estimator/initial/solve_5pts.h index 5a807a9..bbd7b6a 100644 --- a/vins_estimator/src/initial/solve_5pts.h +++ b/vins_estimator/include/vins_estimator/initial/solve_5pts.h @@ -1,15 +1,16 @@ #pragma once #include -using namespace std; #include -//#include + #include -using namespace Eigen; #include +using namespace std; +using namespace Eigen; + class MotionEstimator { public: diff --git a/vins_estimator/src/parameters.h b/vins_estimator/include/vins_estimator/parameters.h similarity index 96% rename from vins_estimator/src/parameters.h rename to vins_estimator/include/vins_estimator/parameters.h index 7d62731..3feb0f2 100644 --- a/vins_estimator/src/parameters.h +++ b/vins_estimator/include/vins_estimator/parameters.h @@ -3,11 +3,12 @@ #include #include #include -#include "utility/utility.h" #include #include #include +#include + const double FOCAL_LENGTH = 460.0; const int WINDOW_SIZE = 10; const int NUM_OF_CAM = 1; diff --git a/vins_estimator/src/utility/CameraPoseVisualization.h b/vins_estimator/include/vins_estimator/utility/CameraPoseVisualization.h similarity index 100% rename from vins_estimator/src/utility/CameraPoseVisualization.h rename to vins_estimator/include/vins_estimator/utility/CameraPoseVisualization.h diff --git a/vins_estimator/src/utility/tic_toc.h b/vins_estimator/include/vins_estimator/utility/tic_toc.h similarity index 100% rename from vins_estimator/src/utility/tic_toc.h rename to vins_estimator/include/vins_estimator/utility/tic_toc.h diff --git a/vins_estimator/src/utility/utility.h b/vins_estimator/include/vins_estimator/utility/utility.h similarity index 100% rename from vins_estimator/src/utility/utility.h rename to vins_estimator/include/vins_estimator/utility/utility.h diff --git a/vins_estimator/src/utility/visualization.h b/vins_estimator/include/vins_estimator/utility/visualization.h similarity index 89% rename from vins_estimator/src/utility/visualization.h rename to vins_estimator/include/vins_estimator/utility/visualization.h index bf7d1d1..3b18800 100644 --- a/vins_estimator/src/utility/visualization.h +++ b/vins_estimator/include/vins_estimator/utility/visualization.h @@ -13,12 +13,13 @@ #include #include #include -#include "CameraPoseVisualization.h" #include -#include "../estimator.h" -#include "../parameters.h" #include +#include +#include +#include + extern ros::Publisher pub_odometry; extern ros::Publisher pub_path, pub_pose; extern ros::Publisher pub_cloud, pub_map; @@ -49,4 +50,4 @@ void pubTF(const Estimator &estimator, const std_msgs::Header &header); void pubKeyframe(const Estimator &estimator); -void pubRelocalization(const Estimator &estimator); \ No newline at end of file +void pubRelocalization(const Estimator &estimator); diff --git a/vins_estimator/package.xml b/vins_estimator/package.xml index 08e6562..cca77d0 100644 --- a/vins_estimator/package.xml +++ b/vins_estimator/package.xml @@ -1,55 +1,18 @@ - + + vins_estimator - 0.0.0 + 1.0.0 The vins_estimator package - - - - qintong - - - - - - TODO - - - - - - + Matej Petrlik + MIT - - - - + qintong - - - - - - - - - - - - catkin - roscpp - roscpp - - - - - - - - + roscpp + libceres-dev - diff --git a/vins_estimator/src/estimator.cpp b/vins_estimator/src/estimator.cpp index cc19876..887bb64 100644 --- a/vins_estimator/src/estimator.cpp +++ b/vins_estimator/src/estimator.cpp @@ -1,4 +1,4 @@ -#include "estimator.h" +#include Estimator::Estimator(): f_manager{Rs} { diff --git a/vins_estimator/src/estimator_node.cpp b/vins_estimator/src/estimator_node.cpp index d217c63..582988f 100644 --- a/vins_estimator/src/estimator_node.cpp +++ b/vins_estimator/src/estimator_node.cpp @@ -8,9 +8,9 @@ #include #include -#include "estimator.h" -#include "parameters.h" -#include "utility/visualization.h" +#include +#include +#include Estimator estimator; diff --git a/vins_estimator/src/factor/marginalization_factor.cpp b/vins_estimator/src/factor/marginalization_factor.cpp index 7e073c0..4c14d9e 100644 --- a/vins_estimator/src/factor/marginalization_factor.cpp +++ b/vins_estimator/src/factor/marginalization_factor.cpp @@ -1,4 +1,4 @@ -#include "marginalization_factor.h" +#include void ResidualBlockInfo::Evaluate() { diff --git a/vins_estimator/src/factor/pose_local_parameterization.cpp b/vins_estimator/src/factor/pose_local_parameterization.cpp index cb6d944..b91cb24 100644 --- a/vins_estimator/src/factor/pose_local_parameterization.cpp +++ b/vins_estimator/src/factor/pose_local_parameterization.cpp @@ -1,4 +1,4 @@ -#include "pose_local_parameterization.h" +#include bool PoseLocalParameterization::Plus(const double *x, const double *delta, double *x_plus_delta) const { diff --git a/vins_estimator/src/factor/projection_factor.cpp b/vins_estimator/src/factor/projection_factor.cpp index 8653c32..7149fb2 100644 --- a/vins_estimator/src/factor/projection_factor.cpp +++ b/vins_estimator/src/factor/projection_factor.cpp @@ -1,4 +1,4 @@ -#include "projection_factor.h" +#include Eigen::Matrix2d ProjectionFactor::sqrt_info; double ProjectionFactor::sum_t; diff --git a/vins_estimator/src/factor/projection_td_factor.cpp b/vins_estimator/src/factor/projection_td_factor.cpp index 1b144f8..e0c797e 100644 --- a/vins_estimator/src/factor/projection_td_factor.cpp +++ b/vins_estimator/src/factor/projection_td_factor.cpp @@ -1,4 +1,4 @@ -#include "projection_td_factor.h" +#include Eigen::Matrix2d ProjectionTdFactor::sqrt_info; double ProjectionTdFactor::sum_t; diff --git a/vins_estimator/src/feature_manager.cpp b/vins_estimator/src/feature_manager.cpp index 7d5aed9..b813023 100644 --- a/vins_estimator/src/feature_manager.cpp +++ b/vins_estimator/src/feature_manager.cpp @@ -1,4 +1,4 @@ -#include "feature_manager.h" +#include int FeaturePerId::endFrame() { @@ -385,4 +385,4 @@ double FeatureManager::compensatedParallax2(const FeaturePerId &it_per_id, int f ans = max(ans, sqrt(min(du * du + dv * dv, du_comp * du_comp + dv_comp * dv_comp))); return ans; -} \ No newline at end of file +} diff --git a/vins_estimator/src/initial/initial_aligment.cpp b/vins_estimator/src/initial/initial_aligment.cpp index c2f287c..14f3a83 100644 --- a/vins_estimator/src/initial/initial_aligment.cpp +++ b/vins_estimator/src/initial/initial_aligment.cpp @@ -1,4 +1,4 @@ -#include "initial_alignment.h" +#include void solveGyroscopeBias(map &all_image_frame, Vector3d* Bgs) { diff --git a/vins_estimator/src/initial/initial_ex_rotation.cpp b/vins_estimator/src/initial/initial_ex_rotation.cpp index dc99d1c..a1e1538 100644 --- a/vins_estimator/src/initial/initial_ex_rotation.cpp +++ b/vins_estimator/src/initial/initial_ex_rotation.cpp @@ -1,4 +1,4 @@ -#include "initial_ex_rotation.h" +#include InitialEXRotation::InitialEXRotation(){ frame_count = 0; diff --git a/vins_estimator/src/initial/initial_sfm.cpp b/vins_estimator/src/initial/initial_sfm.cpp index 6fbcc17..34a75b0 100644 --- a/vins_estimator/src/initial/initial_sfm.cpp +++ b/vins_estimator/src/initial/initial_sfm.cpp @@ -1,4 +1,4 @@ -#include "initial_sfm.h" +#include GlobalSFM::GlobalSFM(){} diff --git a/vins_estimator/src/initial/solve_5pts.cpp b/vins_estimator/src/initial/solve_5pts.cpp index c37608d..b83c90e 100644 --- a/vins_estimator/src/initial/solve_5pts.cpp +++ b/vins_estimator/src/initial/solve_5pts.cpp @@ -1,4 +1,4 @@ -#include "solve_5pts.h" +#include namespace cv { diff --git a/vins_estimator/src/parameters.cpp b/vins_estimator/src/parameters.cpp index 7ea0d10..49a2e1b 100644 --- a/vins_estimator/src/parameters.cpp +++ b/vins_estimator/src/parameters.cpp @@ -1,4 +1,4 @@ -#include "parameters.h" +#include double INIT_DEPTH; double MIN_PARALLAX; diff --git a/vins_estimator/src/utility/CameraPoseVisualization.cpp b/vins_estimator/src/utility/CameraPoseVisualization.cpp index df97dba..e93d805 100644 --- a/vins_estimator/src/utility/CameraPoseVisualization.cpp +++ b/vins_estimator/src/utility/CameraPoseVisualization.cpp @@ -1,4 +1,4 @@ -#include "CameraPoseVisualization.h" +#include const Eigen::Vector3d CameraPoseVisualization::imlt = Eigen::Vector3d(-1.0, -0.5, 1.0); const Eigen::Vector3d CameraPoseVisualization::imrt = Eigen::Vector3d( 1.0, -0.5, 1.0); @@ -195,4 +195,4 @@ void CameraPoseVisualization::publish_by( ros::Publisher &pub, const std_msgs::H } pub.publish(markerArray_msg); -} \ No newline at end of file +} diff --git a/vins_estimator/src/utility/utility.cpp b/vins_estimator/src/utility/utility.cpp index d5bf029..9838516 100644 --- a/vins_estimator/src/utility/utility.cpp +++ b/vins_estimator/src/utility/utility.cpp @@ -1,4 +1,4 @@ -#include "utility.h" +#include Eigen::Matrix3d Utility::g2R(const Eigen::Vector3d &g) { diff --git a/vins_estimator/src/utility/visualization.cpp b/vins_estimator/src/utility/visualization.cpp index 840b176..f6649c0 100644 --- a/vins_estimator/src/utility/visualization.cpp +++ b/vins_estimator/src/utility/visualization.cpp @@ -1,4 +1,4 @@ -#include "visualization.h" +#include using namespace ros; using namespace Eigen;