diff --git a/apriltag_detector/CMakeLists.txt b/apriltag_detector/CMakeLists.txt index 20c1a06..59e48f6 100644 --- a/apriltag_detector/CMakeLists.txt +++ b/apriltag_detector/CMakeLists.txt @@ -31,10 +31,6 @@ find_package(rclcpp) find_package(rclcpp_components) find_package(sensor_msgs REQUIRED) -if(${cv_bridge_VERSION} VERSION_GREATER_EQUAL "4.0.0") - add_definitions(-DUSE_CV_BRIDGE_HPP) -endif() - if(${rclcpp_VERSION} VERSION_GREATER_EQUAL "28.0.0") add_definitions(-DUSE_MATCHED_EVENTS) endif() @@ -43,6 +39,10 @@ if(${image_transport_VERSION} VERSION_GREATER_EQUAL "6.3.0") add_definitions(-DIMAGE_TRANSPORT_USE_QOS) endif() +if(${image_transport_VERSION} VERSION_GREATER_EQUAL "6.4.0") + add_definitions(-DIMAGE_TRANSPORT_USE_NODEINTERFACE) +endif() + # # --------- header-only library # diff --git a/apriltag_detector/src/detector_component.cpp b/apriltag_detector/src/detector_component.cpp index cf3bbe7..291d9f8 100644 --- a/apriltag_detector/src/detector_component.cpp +++ b/apriltag_detector/src/detector_component.cpp @@ -14,7 +14,7 @@ // limitations under the License. #include -#ifdef USE_CV_BRIDGE_HPP +#if __has_include() #include #else #include @@ -109,7 +109,12 @@ void DetectorComponent::subscribe() const auto profile = string_to_profile(image_qos_profile_); image_sub_ = std::make_shared( image_transport::create_subscription( - this, "image", +#ifdef IMAGE_TRANSPORT_USE_NODEINTERFACE + *this, +#else + this, +#endif + "image", std::bind(&DetectorComponent::callback, this, std::placeholders::_1), in_transport_, convert_profile(profile))); is_subscribed_ = true; diff --git a/apriltag_draw/CMakeLists.txt b/apriltag_draw/CMakeLists.txt index 4ababd2..a0cd08c 100644 --- a/apriltag_draw/CMakeLists.txt +++ b/apriltag_draw/CMakeLists.txt @@ -39,10 +39,6 @@ set(ament_dependencies ${sensor_msgs_TARGETS} ${apriltag_msgs_TARGETS}) -if(${cv_bridge_VERSION} VERSION_GREATER_EQUAL "4.0.0") - add_definitions(-DUSE_CV_BRIDGE_HPP) -endif() - if(${rclcpp_VERSION} VERSION_GREATER_EQUAL "28.0.0") add_definitions(-DUSE_MATCHED_EVENTS) endif() @@ -50,6 +46,11 @@ endif() if(${image_transport_VERSION} VERSION_GREATER_EQUAL "6.3.0") add_definitions(-DIMAGE_TRANSPORT_USE_QOS) endif() + +if(${image_transport_VERSION} VERSION_GREATER_EQUAL "6.4.0") + add_definitions(-DIMAGE_TRANSPORT_USE_NODEINTERFACE) +endif() + # # --------- composable node library (public) # diff --git a/apriltag_draw/src/apriltag_draw.cpp b/apriltag_draw/src/apriltag_draw.cpp index ac20305..7b9c2ce 100644 --- a/apriltag_draw/src/apriltag_draw.cpp +++ b/apriltag_draw/src/apriltag_draw.cpp @@ -14,7 +14,7 @@ // limitations under the License. #include -#ifdef USE_CV_BRIDGE_HPP +#if __has_include() #include #else #include @@ -121,10 +121,20 @@ ApriltagDraw::ApriltagDraw(const rclcpp::NodeOptions & options) } }; image_pub_ = image_transport::create_publisher( - this, "image_tags", convert_profile(rmw_qos_profile_default), pub_options); +#ifdef IMAGE_TRANSPORT_USE_NODEINTERFACE + *this, +#else + this, +#endif + "image_tags", convert_profile(rmw_qos_profile_default), pub_options); #else image_pub_ = image_transport::create_publisher( - this, "image_tags", convert_profile(rmw_qos_profile_default)); +#ifdef IMAGE_TRANSPORT_USE_NODEINTERFACE + *this, +#else + this, +#endif + "image_tags", convert_profile(rmw_qos_profile_default)); // Since the early ROS2 image transport does not call back when // subscribers come and go: must check by polling @@ -149,7 +159,12 @@ void ApriltagDraw::subscribe() std::bind(&ApriltagDraw::tagCallback, this, std::placeholders::_1)); image_sub_ = std::make_shared( image_transport::create_subscription( - this, "image", +#ifdef IMAGE_TRANSPORT_USE_NODEINTERFACE + *this, +#else + this, +#endif + "image", std::bind(&ApriltagDraw::imageCallback, this, std::placeholders::_1), transport_, convert_profile(qos_profile_))); is_subscribed_ = true;