Created
November 1, 2025 17:20
-
-
Save matlabbe/ebbb343cd744da9d6d6d6ded2e1557fd to your computer and use it in GitHub Desktop.
VINS-Fusion patch to use it as library from external project on ros2 Humble Ubuntu 22.04 (https://github.com/zinuok/VINS-Fusion-ROS2)
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
| diff --git a/camera_models/CMakeLists.txt b/camera_models/CMakeLists.txt | |
| index 723ff03..4867f90 100755 | |
| --- a/camera_models/CMakeLists.txt | |
| +++ b/camera_models/CMakeLists.txt | |
| @@ -67,6 +67,7 @@ add_library(camera_models | |
| target_link_libraries(Calibrations ${Boost_LIBRARIES} ${OpenCV_LIBS} ${CERES_LIBRARIES}) | |
| target_link_libraries(camera_models ${Boost_LIBRARIES} ${OpenCV_LIBS} ${CERES_LIBRARIES}) | |
| +set_target_properties(camera_models PROPERTIES POSITION_INDEPENDENT_CODE ON) | |
| # Install | |
| install(TARGETS | |
| diff --git a/loop_fusion/src/utility/CameraPoseVisualization.cpp b/loop_fusion/src/utility/CameraPoseVisualization.cpp | |
| index 5ffbd23..4b47d05 100755 | |
| --- a/loop_fusion/src/utility/CameraPoseVisualization.cpp | |
| +++ b/loop_fusion/src/utility/CameraPoseVisualization.cpp | |
| @@ -92,7 +92,7 @@ void CameraPoseVisualization::add_loopedge(const Eigen::Vector3d& p0, const Eige | |
| // tmp_loop_edge_num = 1; | |
| marker.type = visualization_msgs::msg::Marker::LINE_STRIP; | |
| marker.action = visualization_msgs::msg::Marker::ADD; | |
| - marker.lifetime = rclcpp::Duration(0); | |
| + marker.lifetime = rclcpp::Duration::from_seconds(0); | |
| //marker.scale.x = 0.4; | |
| marker.scale.x = 0.02; | |
| marker.color.r = 1.0f; | |
| diff --git a/vins/CMakeLists.txt b/vins/CMakeLists.txt | |
| index c58ff9b..d79fbb3 100755 | |
| --- a/vins/CMakeLists.txt | |
| +++ b/vins/CMakeLists.txt | |
| @@ -36,7 +36,7 @@ include_directories( | |
| ) | |
| -add_library(vins_lib | |
| +add_library(vins_lib SHARED | |
| src/estimator/parameters.cpp | |
| src/estimator/estimator.cpp | |
| src/estimator/feature_manager.cpp | |
| @@ -53,8 +53,12 @@ add_library(vins_lib | |
| src/initial/initial_sfm.cpp | |
| src/initial/initial_ex_rotation.cpp | |
| src/featureTracker/feature_tracker.cpp) | |
| -target_link_libraries(vins_lib ${OpenCV_LIBS} ${CERES_LIBRARIES}) | |
| - | |
| +target_link_libraries(vins_lib ${OpenCV_LIBS} ${CERES_LIBRARIES}) | |
| +target_include_directories(vins_lib | |
| + PUBLIC | |
| + $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src> | |
| + $<INSTALL_INTERFACE:include> | |
| +) | |
| ament_target_dependencies(vins_lib rclcpp rcpputils std_msgs visualization_msgs geometry_msgs nav_msgs tf2 tf2_ros cv_bridge camera_models image_transport) | |
| add_executable(vins_node src/rosNodeTest.cpp) | |
| @@ -100,5 +104,26 @@ install( | |
| # DESTINATION share/${PROJECT_NAME} | |
| # ) | |
| +############# | |
| +## Install ## | |
| +############# | |
| + | |
| +ament_export_dependencies(rclcpp rcpputils std_msgs visualization_msgs geometry_msgs nav_msgs tf2 tf2_ros cv_bridge camera_models image_transport) | |
| +ament_export_include_directories(include) | |
| +ament_export_targets(${PROJECT_NAME}) # To include downstream with targets | |
| +ament_export_libraries(vins_lib) # To include downstream without targets | |
| + | |
| +install(TARGETS | |
| + vins_lib | |
| + EXPORT ${PROJECT_NAME} | |
| + ARCHIVE DESTINATION lib | |
| + LIBRARY DESTINATION lib | |
| + RUNTIME DESTINATION bin | |
| +) | |
| + | |
| +install(DIRECTORY src/ | |
| + DESTINATION include | |
| + FILES_MATCHING PATTERN "*.h" PATTERN "*.hpp" | |
| +) | |
| ament_package() | |
| diff --git a/vins/src/estimator/estimator.cpp b/vins/src/estimator/estimator.cpp | |
| index 53ee2b8..a318db0 100755 | |
| --- a/vins/src/estimator/estimator.cpp | |
| +++ b/vins/src/estimator/estimator.cpp | |
| @@ -13,6 +13,12 @@ | |
| Estimator::Estimator(): f_manager{Rs} | |
| { | |
| ROS_INFO("init begins"); | |
| + for(int i=0; i<WINDOW_SIZE+1; ++i) | |
| + { | |
| + pre_integrations[i] = nullptr; | |
| + } | |
| + tmp_pre_integration = nullptr; | |
| + last_marginalization_info = nullptr; | |
| initThreadFlag = false; | |
| clearState(); | |
| } | |
| @@ -1168,7 +1174,7 @@ void Estimator::optimization() | |
| if (USE_GPU_CERES) | |
| // std::cout << "1" << endl; | |
| - options.dense_linear_algebra_library_type = ceres::CUDA; | |
| + options.linear_solver_type = ceres::DENSE_SCHUR; | |
| else | |
| // std::cout << "2" << endl; | |
| options.linear_solver_type = ceres::DENSE_SCHUR; | |
| diff --git a/vins/src/estimator/parameters.cpp b/vins/src/estimator/parameters.cpp | |
| index 82992e9..0d7c614 100755 | |
| --- a/vins/src/estimator/parameters.cpp | |
| +++ b/vins/src/estimator/parameters.cpp | |
| @@ -23,6 +23,7 @@ int USE_GPU; | |
| int USE_GPU_ACC_FLOW; | |
| int USE_GPU_CERES; | |
| +double FOCAL_LENGTH; | |
| double BIAS_ACC_THRESHOLD; | |
| double BIAS_GYR_THRESHOLD; | |
| double SOLVER_TIME; | |
| @@ -114,6 +115,7 @@ void readParameters(std::string config_file) | |
| SOLVER_TIME = fsSettings["max_solver_time"]; | |
| NUM_ITERATIONS = fsSettings["max_num_iterations"]; | |
| MIN_PARALLAX = fsSettings["keyframe_parallax"]; | |
| + FOCAL_LENGTH = 460; | |
| MIN_PARALLAX = MIN_PARALLAX / FOCAL_LENGTH; | |
| fsSettings["output_path"] >> OUTPUT_FOLDER; | |
| diff --git a/vins/src/estimator/parameters.h b/vins/src/estimator/parameters.h | |
| index 50ba1af..e3fdad2 100755 | |
| --- a/vins/src/estimator/parameters.h | |
| +++ b/vins/src/estimator/parameters.h | |
| @@ -24,7 +24,7 @@ using namespace std; | |
| #define ROS_WARN RCUTILS_LOG_WARN | |
| #define ROS_ERROR RCUTILS_LOG_ERROR | |
| -const double FOCAL_LENGTH = 460.0; | |
| +extern double FOCAL_LENGTH; | |
| const int WINDOW_SIZE = 10; | |
| const int NUM_OF_F = 1000; | |
| //#define UNIT_SPHERE_ERROR | |
| diff --git a/vins/src/featureTracker/feature_tracker.h b/vins/src/featureTracker/feature_tracker.h | |
| index 35ad72f..575af0c 100755 | |
| --- a/vins/src/featureTracker/feature_tracker.h | |
| +++ b/vins/src/featureTracker/feature_tracker.h | |
| @@ -11,9 +11,6 @@ | |
| #pragma once | |
| -#define GPU_MODE 1 | |
| - | |
| - | |
| #include <cstdio> | |
| #include <iostream> | |
| #include <queue> | |
| diff --git a/vins/src/utility/visualization.cpp b/vins/src/utility/visualization.cpp | |
| index 8efb3fd..861623d 100755 | |
| --- a/vins/src/utility/visualization.cpp | |
| +++ b/vins/src/utility/visualization.cpp | |
| @@ -198,7 +198,7 @@ void pubKeyPoses(const Estimator &estimator, const std_msgs::msg::Header &header | |
| key_poses.type = visualization_msgs::msg::Marker::SPHERE_LIST; | |
| key_poses.action = visualization_msgs::msg::Marker::ADD; | |
| key_poses.pose.orientation.w = 1.0; | |
| - key_poses.lifetime = rclcpp::Duration(0); | |
| + key_poses.lifetime = rclcpp::Duration::from_seconds(0); | |
| //static int key_poses_id = 0; | |
| key_poses.id = 0; //key_poses_id++; |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment