From 12353769d247772ceb79d0f9cfc69ba44512dbe7 Mon Sep 17 00:00:00 2001 From: cyy_mac Date: Thu, 26 Mar 2026 05:48:03 +0800 Subject: [PATCH] new camera calibraction fix --- src/camera_calibration/CMakeLists.txt | 21 ++++++++++++------- .../src/calibration_node.cpp | 11 +++++++--- 2 files changed, 22 insertions(+), 10 deletions(-) diff --git a/src/camera_calibration/CMakeLists.txt b/src/camera_calibration/CMakeLists.txt index c0ffdbe..86843d5 100644 --- a/src/camera_calibration/CMakeLists.txt +++ b/src/camera_calibration/CMakeLists.txt @@ -8,7 +8,6 @@ endif() # Find dependencies find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) -find_package(rclcpp_components REQUIRED) find_package(std_msgs REQUIRED) find_package(sensor_msgs REQUIRED) find_package(image_transport REQUIRED) @@ -23,7 +22,7 @@ include_directories( ${EIGEN3_INCLUDE_DIRS} ) -# Node library +# Node library - without rclcpp_components registration add_library(camera_calibration_lib SHARED src/calibration_node.cpp ) @@ -39,13 +38,21 @@ ament_target_dependencies(camera_calibration_lib rm_interfaces ) -# Component library for component container -rclcpp_components_register_node(camera_calibration_lib - PLUGIN "camera_calibration::CalibrationNode" - EXECUTABLE camera_calibration_node +# Create executable directly instead of using component registration +add_executable(camera_calibration_node src/calibration_node.cpp) +ament_target_dependencies(camera_calibration_node + rclcpp + std_msgs + sensor_msgs + image_transport + cv_bridge + OpenCV + Eigen3 + rm_interfaces ) +target_link_libraries(camera_calibration_node camera_calibration_lib) -install(TARGETS camera_calibration_lib +install(TARGETS camera_calibration_lib camera_calibration_node ARCHIVE DESTINATION lib LIBRARY DESTINATION lib RUNTIME DESTINATION lib diff --git a/src/camera_calibration/src/calibration_node.cpp b/src/camera_calibration/src/calibration_node.cpp index 86d891f..1674fe3 100644 --- a/src/camera_calibration/src/calibration_node.cpp +++ b/src/camera_calibration/src/calibration_node.cpp @@ -488,6 +488,11 @@ cv::Mat CalibrationNode::drawCalibrationResults(const cv::Mat& image, } // namespace camera_calibration -#include "rclcpp_components/register_node_macro.hpp" - -RCLCPP_COMPONENTS_REGISTER_NODE(camera_calibration::CalibrationNode) +int main(int argc, char** argv) { + rclcpp::init(argc, argv); + rclcpp::NodeOptions options; + auto node = std::make_shared(options); + rclcpp::spin(node->get_node_base_interface()); + rclcpp::shutdown(); + return 0; +}