Skip to content

Commit

Permalink
moved headers to include dir
Browse files Browse the repository at this point in the history
  • Loading branch information
petrlmat committed Dec 20, 2024
1 parent f81cbca commit 3e5776c
Show file tree
Hide file tree
Showing 34 changed files with 116 additions and 122 deletions.
37 changes: 29 additions & 8 deletions vins_estimator/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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
Expand All @@ -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
Expand All @@ -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}
)
Original file line number Diff line number Diff line change
@@ -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 <std_msgs/Header.h>
#include <std_msgs/Float32.h>

#include <ceres/ceres.h>
#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 <unordered_map>
#include <queue>
#include <opencv2/core/eigen.hpp>

#include <vins_estimator/parameters.h>
#include <vins_estimator/feature_manager.h>
#include <vins_estimator/utility/utility.h>
#include <vins_estimator/utility/tic_toc.h>
#include <vins_estimator/initial/solve_5pts.h>
#include <vins_estimator/initial/initial_sfm.h>
#include <vins_estimator/initial/initial_alignment.h>
#include <vins_estimator/initial/initial_ex_rotation.h>
#include <vins_estimator/factor/imu_factor.h>
#include <vins_estimator/factor/pose_local_parameterization.h>
#include <vins_estimator/factor/projection_factor.h>
#include <vins_estimator/factor/projection_td_factor.h>
#include <vins_estimator/factor/marginalization_factor.h>

class Estimator
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,9 @@
#include <iostream>
#include <eigen3/Eigen/Dense>

#include "../utility/utility.h"
#include "../parameters.h"
#include "integration_base.h"
#include <vins_estimator/utility/utility.h>
#include <vins_estimator/parameters.h>
#include <vins_estimator/factor/integration_base.h>

#include <ceres/ceres.h>

Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#pragma once

#include "../utility/utility.h"
#include "../parameters.h"
#include <vins_estimator/utility/utility.h>
#include <vins_estimator/parameters.h>

#include <ceres/ceres.h>
using namespace Eigen;
Expand Down Expand Up @@ -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;
}
*/
*/
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@
#include <ceres/ceres.h>
#include <unordered_map>

#include "../utility/utility.h"
#include "../utility/tic_toc.h"
#include <vins_estimator/utility/utility.h>
#include <vins_estimator/utility/tic_toc.h>

const int NUM_THREADS = 4;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,8 @@

#include <eigen3/Eigen/Dense>
#include <ceres/ceres.h>
#include "../utility/utility.h"

#include <vins_estimator/utility/utility.h>

class PoseLocalParameterization : public ceres::LocalParameterization
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,10 @@
#include <ros/assert.h>
#include <ceres/ceres.h>
#include <Eigen/Dense>
#include "../utility/utility.h"
#include "../utility/tic_toc.h"
#include "../parameters.h"

#include <vins_estimator/utility/utility.h>
#include <vins_estimator/utility/tic_toc.h>
#include <vins_estimator/parameters.h>

class ProjectionFactor : public ceres::SizedCostFunction<2, 7, 7, 7, 1>
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,10 @@
#include <ros/assert.h>
#include <ceres/ceres.h>
#include <Eigen/Dense>
#include "../utility/utility.h"
#include "../utility/tic_toc.h"
#include "../parameters.h"

#include <vins_estimator/utility/utility.h>
#include <vins_estimator/utility/tic_toc.h>
#include <vins_estimator//parameters.h>

class ProjectionTdFactor : public ceres::SizedCostFunction<2, 7, 7, 7, 1, 1>
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,15 +5,16 @@
#include <algorithm>
#include <vector>
#include <numeric>
using namespace std;

#include <eigen3/Eigen/Dense>
using namespace Eigen;

#include <ros/console.h>
#include <ros/assert.h>

#include "parameters.h"
#include <vins_estimator/parameters.h>

using namespace std;
using namespace Eigen;

class FeaturePerFrame
{
Expand Down Expand Up @@ -99,4 +100,4 @@ class FeatureManager
Matrix3d ric[NUM_OF_CAM];
};

#endif
#endif
Original file line number Diff line number Diff line change
@@ -1,11 +1,13 @@
#pragma once
#include <eigen3/Eigen/Dense>
#include <iostream>
#include "../factor/imu_factor.h"
#include "../utility/utility.h"

#include <ros/ros.h>
#include <map>
#include "../feature_manager.h"

#include <vins_estimator/factor/imu_factor.h>
#include <vins_estimator/utility/utility.h>
#include <vins_estimator/feature_manager.h>

using namespace Eigen;
using namespace std;
Expand All @@ -26,4 +28,4 @@ class ImageFrame
bool is_key_frame;
};

bool VisualIMUAlignment(map<double, ImageFrame> &all_image_frame, Vector3d* Bgs, Vector3d &g, VectorXd &x);
bool VisualIMUAlignment(map<double, ImageFrame> &all_image_frame, Vector3d* Bgs, Vector3d &g, VectorXd &x);
Original file line number Diff line number Diff line change
@@ -1,15 +1,17 @@
#pragma once

#include <vector>
#include "../parameters.h"
using namespace std;

#include <opencv2/opencv.hpp>

#include <eigen3/Eigen/Dense>
using namespace Eigen;
#include <ros/console.h>

#include <vins_estimator/parameters.h>

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
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,11 +8,10 @@
#include <map>
#include <opencv2/core/eigen.hpp>
#include <opencv2/opencv.hpp>

using namespace Eigen;
using namespace std;



struct SFMFeature
{
bool state;
Expand Down Expand Up @@ -71,4 +70,4 @@ class GlobalSFM
vector<SFMFeature> &sfm_f);

int feature_num;
};
};
Original file line number Diff line number Diff line change
@@ -1,15 +1,16 @@
#pragma once

#include <vector>
using namespace std;

#include <opencv2/opencv.hpp>
//#include <opencv2/core/eigen.hpp>

#include <eigen3/Eigen/Dense>
using namespace Eigen;

#include <ros/console.h>

using namespace std;
using namespace Eigen;

class MotionEstimator
{
public:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,11 +3,12 @@
#include <ros/ros.h>
#include <vector>
#include <eigen3/Eigen/Dense>
#include "utility/utility.h"
#include <opencv2/opencv.hpp>
#include <opencv2/core/eigen.hpp>
#include <fstream>

#include <vins_estimator/utility/utility.h>

const double FOCAL_LENGTH = 460.0;
const int WINDOW_SIZE = 10;
const int NUM_OF_CAM = 1;
Expand Down
File renamed without changes.
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -13,12 +13,13 @@
#include <geometry_msgs/PointStamped.h>
#include <visualization_msgs/Marker.h>
#include <tf/transform_broadcaster.h>
#include "CameraPoseVisualization.h"
#include <eigen3/Eigen/Dense>
#include "../estimator.h"
#include "../parameters.h"
#include <fstream>

#include <vins_estimator/utility/CameraPoseVisualization.h>
#include <vins_estimator/estimator.h>
#include <vins_estimator/parameters.h>

extern ros::Publisher pub_odometry;
extern ros::Publisher pub_path, pub_pose;
extern ros::Publisher pub_cloud, pub_map;
Expand Down Expand Up @@ -49,4 +50,4 @@ void pubTF(const Estimator &estimator, const std_msgs::Header &header);

void pubKeyframe(const Estimator &estimator);

void pubRelocalization(const Estimator &estimator);
void pubRelocalization(const Estimator &estimator);
Loading

0 comments on commit 3e5776c

Please sign in to comment.