diff --git a/CMakeLists.txt b/CMakeLists.txt index c18bc813..3a3ba20d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,398 +1,131 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.8) project(opencv_apps) -## https://stackoverflow.com/questions/10984442/how-to-detect-c11-support-of-a-compiler-with-cmake -if(CMAKE_COMPILER_IS_GNUCXX AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS "7") - execute_process(COMMAND ${CMAKE_C_COMPILER} -dumpversion OUTPUT_VARIABLE GCC_VERSION) - if (GCC_VERSION VERSION_GREATER 4.7 OR GCC_VERSION VERSION_EQUAL 4.7) - message(STATUS "C++11 activated.") - add_definitions("-std=gnu++11") - elseif(GCC_VERSION VERSION_GREATER 4.3 OR GCC_VERSION VERSION_EQUAL 4.3) - message(WARNING "C++0x activated. If you get any errors update to a compiler which fully supports C++11") - add_definitions("-std=gnu++0x") - else () - message(FATAL_ERROR "C++11 needed. Therefore a gcc compiler with a version higher than 4.3 is needed.") - endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) endif() -find_package(catkin REQUIRED COMPONENTS cv_bridge dynamic_reconfigure message_generation image_transport nodelet roscpp sensor_msgs std_msgs std_srvs class_loader) - +# C++14 for ROS2 +set(CMAKE_CXX_STANDARD 14) +set(CMAKE_CXX_STANDARD_REQUIRED ON) + +# Find dependencies +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rclcpp_components REQUIRED) +find_package(sensor_msgs REQUIRED) +find_package(std_msgs REQUIRED) +find_package(std_srvs REQUIRED) +find_package(cv_bridge REQUIRED) +find_package(image_transport REQUIRED) +find_package(rosidl_default_generators REQUIRED) find_package(OpenCV REQUIRED) -message(STATUS "OpenCV VERSION: ${OpenCV_VERSION}") -message(STATUS "OpenCV Components: ${OpenCV_LIB_COMPONENTS}") -if(OpenCV_VERSION VERSION_LESS "3.0" OR TARGET opencv_optflow) - set(OPENCV_HAVE_OPTFLOW TRUE) -endif() -# Supporting CompressedImage in cv_bridge has been started from 1.11.9 (2015-11-29) -# note : hydro 1.10.18, indigo : 1.11.13 ... -# https://github.com/ros-perception/vision_opencv/pull/70 -if(cv_bridge_VERSION VERSION_LESS "1.11.9") - add_definitions("-DCV_BRIDGE_COMPRESSED_IMAGE_IS_NOT_SUPPORTED") -endif() -# Supporting CvtColorForDisplay in cv_bridge has been started from 1.11.9 (2015-11-29) -if(cv_bridge_VERSION VERSION_LESS "1.11.9") - add_definitions("-DCV_BRIDGE_CVT_COLOR_FOR_DISPLAY_IS_NOT_SUPPORTED") -endif() -# Supporting CvtColorForDisplayOptions in cv_bridge has been started from 1.11.13 (2016-07-11) -if(cv_bridge_VERSION VERSION_LESS "1.11.13") - add_definitions("-DCV_BRIDGE_CVT_COLOR_FOR_DISPLAY_OPTION_IS_NOT_SUPPORTED") -endif() -if(class_loader_VERSION VERSION_LESS "0.4.0") - add_definitions("-DUSE_PLUGINLIB_CLASS_LIST_MACROS_H") -endif() -# generate the dynamic_reconfigure config file -generate_dynamic_reconfigure_options( - cfg/DiscreteFourierTransform.cfg - cfg/AddingImages.cfg - cfg/Smoothing.cfg - cfg/Morphology.cfg - cfg/Pyramids.cfg - cfg/EdgeDetection.cfg cfg/HoughLines.cfg cfg/HoughCircles.cfg - cfg/FindContours.cfg cfg/ConvexHull.cfg cfg/GeneralContours.cfg cfg/ContourMoments.cfg - cfg/FaceDetection.cfg - cfg/FaceRecognition.cfg - cfg/GoodfeatureTrack.cfg - cfg/CornerHarris.cfg - # - cfg/EqualizeHistogram.cfg - cfg/CamShift.cfg - cfg/FBackFlow.cfg - cfg/LKFlow.cfg - cfg/PeopleDetect.cfg - cfg/PhaseCorr.cfg - cfg/SegmentObjects.cfg - cfg/SimpleFlow.cfg - cfg/Threshold.cfg - cfg/RGBColorFilter.cfg - cfg/HLSColorFilter.cfg - cfg/HSVColorFilter.cfg - cfg/LabColorFilter.cfg - cfg/WatershedSegmentation.cfg - ) +message(STATUS "OpenCV VERSION: ${OpenCV_VERSION}") -## Generate messages in the 'msg' folder -add_message_files( - FILES - Point2D.msg - Point2DStamped.msg - Point2DArray.msg - Point2DArrayStamped.msg - Rect.msg - RectArray.msg - RectArrayStamped.msg - Flow.msg - FlowStamped.msg - FlowArray.msg - FlowArrayStamped.msg - Size.msg - Face.msg - FaceArray.msg - FaceArrayStamped.msg - Line.msg - LineArray.msg - LineArrayStamped.msg - RotatedRect.msg - RotatedRectStamped.msg - RotatedRectArray.msg - RotatedRectArrayStamped.msg - Circle.msg - CircleArray.msg - CircleArrayStamped.msg - Moment.msg - MomentArray.msg - MomentArrayStamped.msg - Contour.msg - ContourArray.msg - ContourArrayStamped.msg +# Generate messages and services +set(msg_files + "msg/Point2D.msg" + "msg/Point2DStamped.msg" + "msg/Point2DArray.msg" + "msg/Point2DArrayStamped.msg" + "msg/Rect.msg" + "msg/RectArray.msg" + "msg/RectArrayStamped.msg" + "msg/Flow.msg" + "msg/FlowStamped.msg" + "msg/FlowArray.msg" + "msg/FlowArrayStamped.msg" + "msg/Size.msg" + "msg/Face.msg" + "msg/FaceArray.msg" + "msg/FaceArrayStamped.msg" + "msg/Line.msg" + "msg/LineArray.msg" + "msg/LineArrayStamped.msg" + "msg/RotatedRect.msg" + "msg/RotatedRectStamped.msg" + "msg/RotatedRectArray.msg" + "msg/RotatedRectArrayStamped.msg" + "msg/Circle.msg" + "msg/CircleArray.msg" + "msg/CircleArrayStamped.msg" + "msg/Moment.msg" + "msg/MomentArray.msg" + "msg/MomentArrayStamped.msg" + "msg/Contour.msg" + "msg/ContourArray.msg" + "msg/ContourArrayStamped.msg" ) -add_service_files( - FILES - FaceRecognitionTrain.srv +set(srv_files + "srv/FaceRecognitionTrain.srv" ) -## Generate added messages and services with any dependencies listed here -generate_messages( - DEPENDENCIES - sensor_msgs - std_msgs +rosidl_generate_interfaces(${PROJECT_NAME} + ${msg_files} + ${srv_files} + DEPENDENCIES sensor_msgs std_msgs ) -catkin_package(CATKIN_DEPENDS dynamic_reconfigure message_runtime nodelet roscpp sensor_msgs std_msgs std_srvs -# DEPENDS OpenCV - INCLUDE_DIRS include - LIBRARIES ${PROJECT_NAME} +ament_export_dependencies(rosidl_default_runtime) + +# Include directories +include_directories( + include + ${OpenCV_INCLUDE_DIRS} ) -include_directories(include ${catkin_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS}) +# Create a list of dependencies +set(dependencies + rclcpp + rclcpp_components + sensor_msgs + std_msgs + std_srvs + cv_bridge + image_transport +) -## Macro to add nodelets -macro(opencv_apps_add_nodelet node_name nodelet_cppfile) - set(NODE_NAME ${node_name}) - set(NODELET_NAME opencv_apps/${node_name}) - configure_file(src/node/standalone_nodelet_exec.cpp.in ${node_name}.cpp @ONLY) - add_executable(${node_name}_exe ${node_name}.cpp) - SET_TARGET_PROPERTIES(${node_name}_exe PROPERTIES OUTPUT_NAME ${node_name}) - target_link_libraries(${node_name}_exe ${catkin_LIBRARIES} ${OpenCV_LIBRARIES}) - list(APPEND _opencv_apps_nodelet_cppfiles ${nodelet_cppfile}) - list(APPEND _opencv_apps_nodelet_targets ${node_name}_exe) +# Macro to add nodes +macro(opencv_apps_add_node node_name nodelet_cppfile) + add_executable(${node_name}_exe ${nodelet_cppfile} src/nodelet/nodelet.cpp) + ament_target_dependencies(${node_name}_exe ${dependencies}) + target_link_libraries(${node_name}_exe ${OpenCV_LIBRARIES}) + rosidl_get_typesupport_target(cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp") + target_link_libraries(${node_name}_exe "${cpp_typesupport_target}") + set_target_properties(${node_name}_exe PROPERTIES OUTPUT_NAME ${node_name}) + + install(TARGETS ${node_name}_exe + DESTINATION lib/${PROJECT_NAME}) endmacro() -# https://github.com/Itseez/opencv/blob/2.4/samples/cpp/ - -# calib3d - # ./tutorial_code/calib3d/camera_calibration/camera_calibration.cpp - # ./tutorial_code/calib3d/real_time_pose_estimation/src/main_detection.cpp - # ./tutorial_code/calib3d/real_time_pose_estimation/src/main_registration.cpp - # ./tutorial_code/calib3d/stereoBM/SBM_Sample.cpp - -# core -opencv_apps_add_nodelet(adding_images src/nodelet/adding_images_nodelet.cpp) # ./tutorial_code/core/AddingImages/AddingImages.cpp -opencv_apps_add_nodelet(discrete_fourier_transform src/nodelet/discrete_fourier_transform_nodelet.cpp) # ./tutorial_code/core/discrete_fourier_transform/discrete_fourier_transform.cpp - # ./tutorial_code/core/file_input_output/file_input_output.cpp - # ./tutorial_code/core/how_to_scan_images/how_to_scan_images.cpp - # ./tutorial_code/core/interoperability_with_OpenCV_1/interoperability_with_OpenCV_1.cpp - # ./tutorial_code/core/ippasync/ippasync_sample.cpp - # ./tutorial_code/core/mat_mask_operations/mat_mask_operations.cpp - # ./tutorial_code/core/Matrix/Drawing_1.cpp - # ./tutorial_code/core/Matrix/Drawing_2.cpp - # ./tutorial_code/core/mat_the_basic_image_container/mat_the_basic_image_container.cpp - -# features2D - # ./tutorial_code/features2D/AKAZE_match.cpp - # ./tutorial_code/features2D/AKAZE_tracking/planar_tracking.cpp - # ./tutorial_code/gpu/gpu-basics-similarity/gpu-basics-similarity.cpp - -# highGUi - # ./tutorial_code/HighGUI/AddingImagesTrackbar.cpp - # ./tutorial_code/HighGUI/BasicLinearTransformsTrackbar.cpp - -# Histograms_Matching - # ./tutorial_code/Histograms_Matching/calcBackProject_Demo1.cpp - # ./tutorial_code/Histograms_Matching/calcBackProject_Demo2.cpp - # ./tutorial_code/Histograms_Matching/calcHist_Demo.cpp - # ./tutorial_code/Histograms_Matching/compareHist_Demo.cpp - opencv_apps_add_nodelet(equalize_histogram src/nodelet/equalize_histogram_nodelet.cpp) # ./tutorial_code/Histograms_Matching/EqualizeHist_Demo.cpp - # ./tutorial_code/Histograms_Matching/MatchTemplate_Demo.cpp - -# imagecodecs - # ./tutorial_code/imgcodecs/GDAL_IO/gdal-image.cpp - -# ImgProc - # ./tutorial_code/ImgProc/BasicLinearTransforms.cpp - # ./tutorial_code/ImgProc/Morphology_1.cpp - # ./tutorial_code/ImgProc/Morphology_2.cpp -opencv_apps_add_nodelet(morphology src/nodelet/morphology_nodelet.cpp) # ./tutorial_code/ImgProc/Morphology_3.cpp -opencv_apps_add_nodelet(pyramids src/nodelet/pyramids_nodelet.cpp) # ./tutorial_code/ImgProc/Pyramids.cpp -opencv_apps_add_nodelet(smoothing src/nodelet/smoothing_nodelet.cpp) # ./tutorial_code/ImgProc/Smoothing.cpp -opencv_apps_add_nodelet(threshold src/nodelet/threshold_nodelet.cpp) # ./tutorial_code/ImgProc/Threshold.cpp -opencv_apps_add_nodelet(rgb_color_filter src/nodelet/color_filter_nodelet.cpp) # ./tutorial_code/ImgProc/Threshold_inRange.cpp -opencv_apps_add_nodelet(hls_color_filter src/nodelet/color_filter_nodelet.cpp) # ./tutorial_code/ImgProc/Threshold_inRange.cpp -opencv_apps_add_nodelet(hsv_color_filter src/nodelet/color_filter_nodelet.cpp) # ./tutorial_code/ImgProc/Threshold_inRange.cpp -opencv_apps_add_nodelet(lab_color_filter src/nodelet/color_filter_nodelet.cpp) - -# ImgTrans -opencv_apps_add_nodelet(edge_detection src/nodelet/edge_detection_nodelet.cpp) # ./tutorial_code/ImgTrans/CannyDetector_Demo.cpp - # ./tutorial_code/ImgTrans/Laplace_Demo.cpp - # ./tutorial_code/ImgTrans/Sobel_Demo.cpp -opencv_apps_add_nodelet(hough_lines src/nodelet/hough_lines_nodelet.cpp) # ./tutorial_code/ImgTrans/HoughLines_Demo.cpp -opencv_apps_add_nodelet(hough_circles src/nodelet/hough_circles_nodelet.cpp) # ./tutorial_code/ImgTrans/HoughCircle_Demo.cpp - # ./tutorial_code/ImgTrans/copyMakeBorder_demo.cpp - # ./tutorial_code/ImgTrans/filter2D_demo.cpp - # ./tutorial_code/ImgTrans/Geometric_Transforms_Demo.cpp - # ./tutorial_code/ImgTrans/imageSegmentation.cpp - # ./tutorial_code/ImgTrans/Remap_Demo.cpp - -# introduction - # ./tutorial_code/introduction/display_image/display_image.cpp - # ./tutorial_code/introduction/windows_visual_studio_Opencv/introduction_windows_vs.cpp - -# ml - # ./tutorial_code/ml/introduction_to_pca/introduction_to_pca.cpp - # ./tutorial_code/ml/introduction_to_svm/introduction_to_svm.cpp - # ./tutorial_code/ml/non_linear_svms/non_linear_svms.cpp - -# objectDetection - # ./tutorial_code/objectDetection/objectDetection2.cpp - # ./tutorial_code/objectDetection/objectDetection.cpp - -# photo - # ./tutorial_code/photo/decolorization/decolor.cpp - # ./tutorial_code/photo/hdr_imaging/hdr_imaging.cpp - # ./tutorial_code/photo/non_photorealistic_rendering/npr_demo.cpp - # ./tutorial_code/photo/seamless_cloning/cloning_demo.cpp - # ./tutorial_code/photo/seamless_cloning/cloning_gui.cpp - -# ShapeDescriptors -opencv_apps_add_nodelet(find_contours src/nodelet/find_contours_nodelet.cpp) # ./tutorial_code/ShapeDescriptors/findContours_demo.cpp -opencv_apps_add_nodelet(convex_hull src/nodelet/convex_hull_nodelet.cpp) # ./tutorial_code/ShapeDescriptors/hull_demo.cpp -opencv_apps_add_nodelet(general_contours src/nodelet/general_contours_nodelet.cpp) # ./tutorial_code/ShapeDescriptors/generalContours_demo2.cpp -opencv_apps_add_nodelet(contour_moments src/nodelet/contour_moments_nodelet.cpp) # ./tutorial_code/ShapeDescriptors/moments_demo.cpp - # ./tutorial_code/ShapeDescriptors/generalContours_demo1.cpp - # ./tutorial_code/ShapeDescriptors/pointPolygonTest_demo.cpp - -# TrackingMotion -opencv_apps_add_nodelet(goodfeature_track src/nodelet/goodfeature_track_nodelet.cpp) # ./tutorial_code/TrackingMotion/goodFeaturesToTrack_Demo.cpp - # ./tutorial_code/TrackingMotion/cornerDetector_Demo.cpp -opencv_apps_add_nodelet(corner_harris src/nodelet/corner_harris_nodelet.cpp) # ./tutorial_code/TrackingMotion/cornerHarris_Demo.cpp - # ./tutorial_code/TrackingMotion/cornerSubPix_Demo.cpp - -# videoio - # ./tutorial_code/video/bg_sub.cpp - # ./tutorial_code/videoio/video-input-psnr-ssim/video-input-psnr-ssim.cpp - # ./tutorial_code/videoio/video-write/video-write.cpp - -# viz - # ./tutorial_code/viz/creating_widgets.cpp - # ./tutorial_code/viz/launching_viz.cpp - # ./tutorial_code/viz/transformations.cpp - # ./tutorial_code/viz/widget_pose.cpp - -# xfeature - # ./tutorial_code/xfeatures2D/LATCH_match.cpp - -# ./3calibration.cpp -# ./autofocus.cpp -# ./bgfg_segm.cpp -# ./calibration.cpp -opencv_apps_add_nodelet(camshift src/nodelet/camshift_nodelet.cpp) # ./camshiftdemo.cpp -# ./cloning_demo.cpp -# ./cloning_gui.cpp -# ./connected_components.cpp -# ./contours2.cpp -# ./convexhull.cpp -# ./cout_mat.cpp -# ./create_mask.cpp -# ./dbt_face_detection.cpp -# ./delaunay2.cpp -# ./demhist.cpp -# ./detect_blob.cpp -# ./detect_mser.cpp -# ./dft.cpp -# ./distrans.cpp -# ./drawing.cpp -# ./edge.cpp -# ./em.cpp -# ./example_cmake/example.cpp -opencv_apps_add_nodelet(face_detection src/nodelet/face_detection_nodelet.cpp) # ./facedetect.cpp -opencv_apps_add_nodelet(face_recognition src/nodelet/face_recognition_nodelet.cpp) -# ./facial_features.cpp -opencv_apps_add_nodelet(fback_flow src/nodelet/fback_flow_nodelet.cpp) # ./fback.cpp -# ./ffilldemo.cpp -# ./filestorage_base64.cpp -# ./filestorage.cpp -# ./fitellipse.cpp -# ./grabcut.cpp -# ./houghcircles.cpp -# ./houghlines.cpp -# ./image_alignment.cpp -# ./image.cpp -# ./imagelist_creator.cpp -# ./image_sequence.cpp -# ./inpaint.cpp -# ./intelperc_capture.cpp -# ./kalman.cpp -# ./kmeans.cpp -# ./laplace.cpp -# ./letter_recog.cpp -opencv_apps_add_nodelet(lk_flow src/nodelet/lk_flow_nodelet.cpp) # ./lkdemo.cpp -# ./logistic_regression.cpp -# ./lsd_lines.cpp -# ./mask_tmpl.cpp -# ./matchmethod_orb_akaze_brisk.cpp -# ./minarea.cpp -# ./morphology2.cpp -# ./neural_network.cpp -# ./npr_demo.cpp -# ./opencv_version.cpp -# ./openni_capture.cpp -# ./pca.cpp -opencv_apps_add_nodelet(people_detect src/nodelet/people_detect_nodelet.cpp) # ./peopledetect.cpp -opencv_apps_add_nodelet(phase_corr src/nodelet/phase_corr_nodelet.cpp) # ./phase_corr.cpp -# ./points_classifier.cpp -# ./polar_transforms.cpp -opencv_apps_add_nodelet(segment_objects src/nodelet/segment_objects_nodelet.cpp) # ./segment_objects.cpp -# ./select3dobj.cpp -# ./shape_example.cpp -# ./smiledetect.cpp -# ./squares.cpp -# ./starter_imagelist.cpp -# ./starter_video.cpp -# ./stereo_calib.cpp -# ./stereo_match.cpp -# ./stitching.cpp -# ./stitching_detailed.cpp -# ./train_HOG.cpp -# ./train_svmsgd.cpp -# ./tree_engine.cpp -# ./tvl1_optical_flow.cpp -# ./videostab.cpp -opencv_apps_add_nodelet(watershed_segmentation src/nodelet/watershed_segmentation_nodelet.cpp) # ./watershed.cpp - -# ros examples -opencv_apps_add_nodelet(simple_example src/nodelet/simple_example_nodelet.cpp) -opencv_apps_add_nodelet(simple_compressed_example src/nodelet/simple_compressed_example_nodelet.cpp) - - -# TApi -# ./tapi/bgfg_segm.cpp -# ./tapi/camshift.cpp -# opencv_apps_add_nodelet(equalize_histogram src/nodelet/equalize_histogram_nodelet.cpp) ./tapi/clahe.cpp -# ./tapi/dense_optical_flow.cpp -# ./tapi/hog.cpp -# ./tapi/opencl_custom_kernel.cpp -# ./tapi/pyrlk_optical_flow.cpp -# ./tapi/squares.cpp -# ./tapi/ufacedetect.cpp - -# https://github.com/Itseez/opencv/blob/2.4/samples/cpp/simpleflow_demo.cpp -# simple flow requires opencv-contrib https://github.com/ros-perception/vision_opencv/issues/108 -if(OPENCV_HAVE_OPTFLOW) - opencv_apps_add_nodelet(simple_flow src/nodelet/simple_flow_nodelet.cpp) -endif() -# https://github.com/opencv/opencv/blob/2.4/samples/cpp/bgfg_gmg.cpp -# https://github.com/opencv/opencv/blob/2.4/samples/cpp/hybridtrackingsample.cpp -# https://github.com/opencv/opencv/blob/2.4/samples/cpp/linemod.cpp -# https://github.com/opencv/opencv/blob/2.4/samples/cpp/retinaDemo.cpp -# https://github.com/opencv/opencv/blob/2.4/samples/cpp/video_dmtx.cpp -# https://github.com/opencv/opencv/blob/2.4/samples/cpp/video_homography.cpp -# https://github.com/opencv/opencv/blob/2.4/samples/cpp/videocapture_pvapi.cpp - -add_library(${PROJECT_NAME} SHARED - src/nodelet/nodelet.cpp - ${_opencv_apps_nodelet_cppfiles} +# Add nodes +opencv_apps_add_node(edge_detection src/nodelet/edge_detection_nodelet.cpp) +opencv_apps_add_node(camshift src/nodelet/camshift_nodelet.cpp) +# opencv_apps_add_node(face_detection src/nodelet/face_detection_nodelet.cpp) +# opencv_apps_add_node(hough_lines src/nodelet/hough_lines_nodelet.cpp) +# opencv_apps_add_node(hough_circles src/nodelet/hough_circles_nodelet.cpp) +# opencv_apps_add_node(find_contours src/nodelet/find_contours_nodelet.cpp) +# opencv_apps_add_node(convex_hull src/nodelet/convex_hull_nodelet.cpp) +# opencv_apps_add_node(goodfeature_track src/nodelet/goodfeature_track_nodelet.cpp) +# opencv_apps_add_node(corner_harris src/nodelet/corner_harris_nodelet.cpp) +# opencv_apps_add_node(fback_flow src/nodelet/fback_flow_nodelet.cpp) +# opencv_apps_add_node(lk_flow src/nodelet/lk_flow_nodelet.cpp) + +# Install launch files +install(DIRECTORY launch/ + DESTINATION share/${PROJECT_NAME}/launch ) -target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${OpenCV_LIBRARIES}) -add_dependencies(${PROJECT_NAME} ${PROJECT_NAME}_gencfg ${PROJECT_NAME}_generate_messages_cpp) -install(TARGETS ${PROJECT_NAME} - DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# Install include directory +install(DIRECTORY include/ + DESTINATION include ) -install(DIRECTORY include/${PROJECT_NAME}/ - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) -install(TARGETS ${_opencv_apps_nodelet_targets} - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) -install(FILES nodelet_plugins.xml - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) -install(DIRECTORY launch test scripts - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} - USE_SOURCE_PERMISSIONS) - -## test -if(CATKIN_ENABLE_TESTING) - find_package(rostest REQUIRED) - find_package(roslaunch REQUIRED) - if(roslaunch_VERSION VERSION_LESS "1.11.1") - message(WARNING "roslaunch_add_file check fails with unsupported doc attributes ${roslaunch_VERSION}") - else() - file(GLOB LAUNCH_FILES launch/*.launch) - foreach(LAUNCH_FILE ${LAUNCH_FILES}) - roslaunch_add_file_check(${LAUNCH_FILE}) - endforeach() - endif() - add_subdirectory(test) +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() endif() + +ament_package() diff --git a/include/opencv_apps/nodelet.h b/include/opencv_apps/nodelet.h index a9977c8e..b12d211b 100644 --- a/include/opencv_apps/nodelet.h +++ b/include/opencv_apps/nodelet.h @@ -35,41 +35,14 @@ #ifndef OPENCV_APPS_NODELET_H_ #define OPENCV_APPS_NODELET_H_ -#include -#include -#include -#include -#if BOOST_VERSION < 106000 // since 1.60.0, boost uses placeholders namesapce for _1,_2... -#ifndef BOOST_PLAEHOLDERS -#define BOOST_PLAEHOLDERS -namespace boost -{ -namespace placeholders -{ -extern boost::arg<1> _1; -extern boost::arg<2> _2; -extern boost::arg<3> _3; -extern boost::arg<4> _4; -extern boost::arg<5> _5; -extern boost::arg<6> _6; -extern boost::arg<7> _7; -extern boost::arg<8> _8; -extern boost::arg<9> _9; -} // namespace placeholders -} // namespace boost -#endif // BOOST_PLAEHOLDERS -#endif // BOOST_VERSION < 106000 - -// https://stackoverflow.com/questions/10496824/how-to-define-nullptr-for-supporting-both-c03-and-c11 -#if !defined(nullptr) -#define nullptr NULL -#endif +#include +#include +#include +#include namespace opencv_apps { -/** @brief - * Enum to represent connection status. - */ + enum ConnectionStatus { NOT_INITIALIZED, @@ -77,240 +50,63 @@ enum ConnectionStatus SUBSCRIBED }; -/** @brief - * Nodelet to automatically subscribe/unsubscribe - * topics according to subscription of advertised topics. - * - * It's important not to subscribe topic if no output is required. - * - * In order to watch advertised topics, need to use advertise template method. - * And create subscribers in subscribe() and shutdown them in unsubscribed(). - * - */ -class Nodelet : public nodelet::Nodelet +class Nodelet : public rclcpp::Node { public: - Nodelet() : subscribed_(false) + explicit Nodelet(const std::string& node_name, const rclcpp::NodeOptions& options = rclcpp::NodeOptions()) + : rclcpp::Node(node_name, options), subscribed_(false), ever_subscribed_(false), + always_subscribe_(false), verbose_connection_(false), connection_status_(NOT_INITIALIZED) { } + virtual ~Nodelet() = default; + protected: - /** @brief - * Initialize nodehandles nh_ and pnh_. Subclass should call - * this method in its onInit method - */ virtual void onInit(); - - /** @brief - * Post processing of initialization of nodelet. - * You need to call this method in order to use always_subscribe - * feature. - */ virtual void onInitPostProcess(); - - /** @brief - * callback function which is called when new subscriber come - */ - virtual void connectionCallback(const ros::SingleSubscriberPublisher& pub); - - /** @brief - * callback function which is called when new subscriber come for image - * publisher - */ - virtual void imageConnectionCallback(const image_transport::SingleSubscriberPublisher& pub); - - /** @brief - * callback function which is called when new subscriber come for camera - * image publisher - */ - virtual void cameraConnectionCallback(const image_transport::SingleSubscriberPublisher& pub); - - /** @brief - * callback function which is called when new subscriber come for - * camera info publisher - */ - virtual void cameraInfoConnectionCallback(const ros::SingleSubscriberPublisher& pub); - - /** @brief - * callback function which is called when new subscriber come for camera - * image publisher or camera info publisher. - * This function is called from cameraConnectionCallback - * or cameraInfoConnectionCallback. - */ - virtual void cameraConnectionBaseCallback(); - - /** @brief - * callback function which is called when walltimer - * duration run out. - */ - virtual void warnNeverSubscribedCallback(const ros::WallTimerEvent& event); - - /** @brief - * This method is called when publisher is subscribed by other - * nodes. - * Set up subscribers in this method. - */ virtual void subscribe() = 0; - - /** @brief - * This method is called when publisher is unsubscribed by other - * nodes. - * Shut down subscribers in this method. - */ virtual void unsubscribe() = 0; - /** @brief - * Advertise a topic and watch the publisher. Publishers which are - * created by this method. - * It automatically reads latch boolean parameter from nh and - * publish topic with appropriate latch parameter. - * - * @param nh NodeHandle. - * @param topic topic name to advertise. - * @param queue_size queue size for publisher. - * @param latch set true if latch topic publication. - * @return Publisher for the advertised topic. - */ template - ros::Publisher advertise(ros::NodeHandle& nh, std::string topic, int queue_size) + typename rclcpp::Publisher::SharedPtr advertise(const std::string& topic, int queue_size) { - boost::mutex::scoped_lock lock(connection_mutex_); - ros::SubscriberStatusCallback connect_cb = boost::bind(&Nodelet::connectionCallback, this, boost::placeholders::_1); - ros::SubscriberStatusCallback disconnect_cb = - boost::bind(&Nodelet::connectionCallback, this, boost::placeholders::_1); - bool latch; - nh.param("latch", latch, false); - ros::Publisher ret = nh.advertise(topic, queue_size, connect_cb, disconnect_cb, ros::VoidConstPtr(), latch); - publishers_.push_back(ret); - - return ret; + std::lock_guard lock(connection_mutex_); + auto pub = this->create_publisher(topic, queue_size); + // In ROS2, we don't have simple connection callbacks, so we'll just subscribe immediately if always_subscribe_ is true + return pub; } - /** @brief - * Advertise an image topic and watch the publisher. Publishers which are - * created by this method. - * It automatically reads latch boolean parameter from nh and it and - * publish topic with appropriate latch parameter. - * - * @param nh NodeHandle. - * @param topic topic name to advertise. - * @param queue_size queue size for publisher. - * @param latch set true if latch topic publication. - * @return Publisher for the advertised topic. - */ - image_transport::Publisher advertiseImage(ros::NodeHandle& nh, const std::string& topic, int queue_size) + std::shared_ptr advertiseImage(const std::string& topic, int queue_size) { - boost::mutex::scoped_lock lock(connection_mutex_); - image_transport::SubscriberStatusCallback connect_cb = - boost::bind(&Nodelet::imageConnectionCallback, this, boost::placeholders::_1); - image_transport::SubscriberStatusCallback disconnect_cb = - boost::bind(&Nodelet::imageConnectionCallback, this, boost::placeholders::_1); - bool latch; - nh.param("latch", latch, false); - image_transport::Publisher pub = - image_transport::ImageTransport(nh).advertise(topic, 1, connect_cb, disconnect_cb, ros::VoidPtr(), latch); + std::lock_guard lock(connection_mutex_); + auto pub = std::make_shared( + image_transport::create_publisher(this, topic)); image_publishers_.push_back(pub); return pub; } - /** @brief - * Advertise an image topic camera info topic and watch the publisher. - * Publishers which are - * created by this method. - * It automatically reads latch boolean parameter from nh and it and - * publish topic with appropriate latch parameter. - * - * @param nh NodeHandle. - * @param topic topic name to advertise. - * @param queue_size queue size for publisher. - * @param latch set true if latch topic publication. - * @return Publisher for the advertised topic. - */ - image_transport::CameraPublisher advertiseCamera(ros::NodeHandle& nh, const std::string& topic, int queue_size) + std::shared_ptr advertiseCamera(const std::string& topic, int queue_size) { - boost::mutex::scoped_lock lock(connection_mutex_); - image_transport::SubscriberStatusCallback connect_cb = - boost::bind(&Nodelet::cameraConnectionCallback, this, boost::placeholders::_1); - image_transport::SubscriberStatusCallback disconnect_cb = - boost::bind(&Nodelet::cameraConnectionCallback, this, boost::placeholders::_1); - ros::SubscriberStatusCallback info_connect_cb = - boost::bind(&Nodelet::cameraInfoConnectionCallback, this, boost::placeholders::_1); - ros::SubscriberStatusCallback info_disconnect_cb = - boost::bind(&Nodelet::cameraInfoConnectionCallback, this, boost::placeholders::_1); - bool latch; - nh.param("latch", latch, false); - image_transport::CameraPublisher pub = image_transport::ImageTransport(nh).advertiseCamera( - topic, 1, connect_cb, disconnect_cb, info_connect_cb, info_disconnect_cb, ros::VoidPtr(), latch); + std::lock_guard lock(connection_mutex_); + auto pub = std::make_shared( + image_transport::create_camera_publisher(this, topic)); camera_publishers_.push_back(pub); return pub; } - /** @brief - * mutex to call subscribe() and unsubscribe() in - * critical section. - */ - boost::mutex connection_mutex_; - - /** @brief - * List of watching publishers - */ - std::vector publishers_; - - /** @brief - * List of watching image publishers - */ - std::vector image_publishers_; - - /** @brief - * List of watching camera publishers - */ - std::vector camera_publishers_; - - /** @brief - * Shared pointer to nodehandle. - */ - boost::shared_ptr nh_; - - /** @brief - * Shared pointer to private nodehandle. - */ - boost::shared_ptr pnh_; - - /** @brief - * WallTimer instance for warning about no connection. - */ - ros::WallTimer timer_; + std::mutex connection_mutex_; + std::vector> image_publishers_; + std::vector> camera_publishers_; - /** @brief - * A flag to check if any publisher is already subscribed - * or not. - */ bool subscribed_; - - /** @brief - * A flag to check if the node has been ever subscribed - * or not. - */ bool ever_subscribed_; - - /** @brief - * A flag to disable watching mechanism and always subscribe input - * topics. It can be specified via ~always_subscribe parameter. - */ bool always_subscribe_; - - /** @brief - * Status of connection - */ - ConnectionStatus connection_status_; - - /** @brief - * true if `~verbose_connection` or `verbose_connection` parameter is true. - */ bool verbose_connection_; + ConnectionStatus connection_status_; private: }; + } // namespace opencv_apps #endif diff --git a/launch/camshift.launch.py b/launch/camshift.launch.py new file mode 100644 index 00000000..0ddee670 --- /dev/null +++ b/launch/camshift.launch.py @@ -0,0 +1,114 @@ +#!/usr/bin/env python3 + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node + + +def generate_launch_description(): + # Declare launch arguments + node_name_arg = DeclareLaunchArgument( + 'node_name', + default_value='camshift_node', + description='Name of the node' + ) + + namespace_arg = DeclareLaunchArgument( + 'namespace', + default_value='camshift', + description='Namespace for the node' + ) + + image_arg = DeclareLaunchArgument( + 'image', + default_value='image', + description='The image topic. Should be remapped to the name of the real image topic.' + ) + + use_camera_info_arg = DeclareLaunchArgument( + 'use_camera_info', + default_value='false', + description='Indicates that the camera_info topic should be subscribed to' + ) + + debug_view_arg = DeclareLaunchArgument( + 'debug_view', + default_value='true', + description='Specify whether the node displays a window to show edge image' + ) + + queue_size_arg = DeclareLaunchArgument( + 'queue_size', + default_value='3', + description='Specify queue_size of input image subscribers' + ) + + histogram_arg = DeclareLaunchArgument( + 'histogram', + default_value='[]', + description='Histogram of tracked color object' + ) + + vmin_arg = DeclareLaunchArgument( + 'vmin', + default_value='10', + description='Min threshold of lightness' + ) + + vmax_arg = DeclareLaunchArgument( + 'vmax', + default_value='256', + description='Max threshold of lightness' + ) + + smin_arg = DeclareLaunchArgument( + 'smin', + default_value='30', + description='Min value of saturation' + ) + + always_subscribe_arg = DeclareLaunchArgument( + 'always_subscribe', + default_value='false', + description='Always subscribe to input topics regardless of output subscribers' + ) + + # Create the node + camshift_node = Node( + package='opencv_apps', + executable='camshift', + name=LaunchConfiguration('node_name'), + namespace=LaunchConfiguration('namespace'), + remappings=[ + ('image', LaunchConfiguration('image')), + ('track_box', '/camshift/track_box'), + ('image_out', '/camshift/image_out'), + ('back_project', '/camshift/back_project'), + ], + parameters=[{ + 'use_camera_info': LaunchConfiguration('use_camera_info'), + 'debug_view': LaunchConfiguration('debug_view'), + 'queue_size': LaunchConfiguration('queue_size'), + 'vmin': LaunchConfiguration('vmin'), + 'vmax': LaunchConfiguration('vmax'), + 'smin': LaunchConfiguration('smin'), + 'always_subscribe': LaunchConfiguration('always_subscribe'), + }], + output='screen', + ) + + return LaunchDescription([ + node_name_arg, + namespace_arg, + image_arg, + use_camera_info_arg, + debug_view_arg, + queue_size_arg, + histogram_arg, + vmin_arg, + vmax_arg, + smin_arg, + always_subscribe_arg, + camshift_node, + ]) diff --git a/launch/edge_detection.launch.py b/launch/edge_detection.launch.py new file mode 100644 index 00000000..3a9244bb --- /dev/null +++ b/launch/edge_detection.launch.py @@ -0,0 +1,104 @@ +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node + + +def generate_launch_description(): + return LaunchDescription([ + # Declare launch arguments + DeclareLaunchArgument( + 'node_name', + default_value='edge_detection', + description='Name of the node' + ), + DeclareLaunchArgument( + 'image', + default_value='image', + description='The image topic. Should be remapped to the name of the real image topic.' + ), + DeclareLaunchArgument( + 'use_camera_info', + default_value='false', + description='Indicates that the camera_info topic should be subscribed to get the default input_frame_id' + ), + DeclareLaunchArgument( + 'debug_view', + default_value='true', + description='Specify whether the node displays a window to show edge image' + ), + DeclareLaunchArgument( + 'queue_size', + default_value='3', + description='Specify queue_size of input image subscribers' + ), + DeclareLaunchArgument( + 'edge_type', + default_value='0', + description='Specify edge detection methods. 0: Sobel Derivatives, 1: Laplace Operator, 2: Canny Edge Detector' + ), + DeclareLaunchArgument( + 'canny_threshold1', + default_value='100', + description='Specify second canny threshold value' + ), + DeclareLaunchArgument( + 'canny_threshold2', + default_value='200', + description='Specify first canny threshold value' + ), + DeclareLaunchArgument( + 'apertureSize', + default_value='3', + description='Aperture size for the Sobel() operator' + ), + DeclareLaunchArgument( + 'apply_blur_pre', + default_value='true', + description='Flag, applying Blur() to input image' + ), + DeclareLaunchArgument( + 'postBlurSize', + default_value='13', + description='Aperture size for the Blur() to input image' + ), + DeclareLaunchArgument( + 'postBlurSigma', + default_value='3.2', + description='Sigma for the GaussianBlur() to input image' + ), + DeclareLaunchArgument( + 'apply_blur_post', + default_value='false', + description='Flag, applying GaussianBlur() to output(edge) image' + ), + DeclareLaunchArgument( + 'L2gradient', + default_value='false', + description='Flag, L2Gradient' + ), + + # Node + Node( + package='opencv_apps', + executable='edge_detection', + name=LaunchConfiguration('node_name'), + remappings=[ + ('image', LaunchConfiguration('image')), + ], + parameters=[{ + 'use_camera_info': LaunchConfiguration('use_camera_info'), + 'debug_view': LaunchConfiguration('debug_view'), + 'queue_size': LaunchConfiguration('queue_size'), + 'edge_type': LaunchConfiguration('edge_type'), + 'canny_threshold1': LaunchConfiguration('canny_threshold1'), + 'canny_threshold2': LaunchConfiguration('canny_threshold2'), + 'apertureSize': LaunchConfiguration('apertureSize'), + 'apply_blur_pre': LaunchConfiguration('apply_blur_pre'), + 'postBlurSize': LaunchConfiguration('postBlurSize'), + 'postBlurSigma': LaunchConfiguration('postBlurSigma'), + 'apply_blur_post': LaunchConfiguration('apply_blur_post'), + 'L2gradient': LaunchConfiguration('L2gradient'), + }] + ), + ]) diff --git a/launch/face_detection.launch.py b/launch/face_detection.launch.py new file mode 100644 index 00000000..57a75402 --- /dev/null +++ b/launch/face_detection.launch.py @@ -0,0 +1,62 @@ +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node + + +def generate_launch_description(): + return LaunchDescription([ + # Declare launch arguments + DeclareLaunchArgument( + 'node_name', + default_value='face_detection', + description='Name of the node' + ), + DeclareLaunchArgument( + 'image', + default_value='image', + description='The image topic. Should be remapped to the name of the real image topic.' + ), + DeclareLaunchArgument( + 'use_camera_info', + default_value='false', + description='Indicates that the camera_info topic should be subscribed to get the default input_frame_id' + ), + DeclareLaunchArgument( + 'debug_view', + default_value='true', + description='Specify whether the node displays a window to show edge image' + ), + DeclareLaunchArgument( + 'queue_size', + default_value='3', + description='Specify queue_size of input image subscribers' + ), + DeclareLaunchArgument( + 'face_cascade_name', + default_value='/usr/share/opencv4/haarcascades/haarcascade_frontalface_alt.xml', + description='Face detection cascade filename' + ), + DeclareLaunchArgument( + 'eyes_cascade_name', + default_value='/usr/share/opencv4/haarcascades/haarcascade_eye_tree_eyeglasses.xml', + description='Eye detection cascade filename' + ), + + # Node + Node( + package='opencv_apps', + executable='face_detection', + name=LaunchConfiguration('node_name'), + remappings=[ + ('image', LaunchConfiguration('image')), + ], + parameters=[{ + 'use_camera_info': LaunchConfiguration('use_camera_info'), + 'debug_view': LaunchConfiguration('debug_view'), + 'queue_size': LaunchConfiguration('queue_size'), + 'face_cascade_name': LaunchConfiguration('face_cascade_name'), + 'eyes_cascade_name': LaunchConfiguration('eyes_cascade_name'), + }] + ), + ]) diff --git a/launch/hough_circles.launch.py b/launch/hough_circles.launch.py new file mode 100644 index 00000000..6fced6ae --- /dev/null +++ b/launch/hough_circles.launch.py @@ -0,0 +1,98 @@ +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node + + +def generate_launch_description(): + return LaunchDescription([ + # Declare launch arguments + DeclareLaunchArgument( + 'node_name', + default_value='hough_circles', + description='Name of the node' + ), + DeclareLaunchArgument( + 'image', + default_value='image', + description='The image topic. Should be remapped to the name of the real image topic.' + ), + DeclareLaunchArgument( + 'use_camera_info', + default_value='false', + description='Indicates that the camera_info topic should be subscribed to get the default input_frame_id' + ), + DeclareLaunchArgument( + 'debug_view', + default_value='true', + description='Specify whether the node displays a window to show edge image' + ), + DeclareLaunchArgument( + 'queue_size', + default_value='3', + description='Specify queue_size of input image subscribers' + ), + DeclareLaunchArgument( + 'canny_threshold', + default_value='200', + description='Upper threshold for the internal Canny edge detector' + ), + DeclareLaunchArgument( + 'accumulator_threshold', + default_value='50', + description='Threshold for center detection' + ), + DeclareLaunchArgument( + 'gaussian_blur_size', + default_value='9', + description='The size of gaussian blur (should be odd number)' + ), + DeclareLaunchArgument( + 'gaussian_sigma_x', + default_value='2', + description='Sigma x of gaussian kernel' + ), + DeclareLaunchArgument( + 'gaussian_sigma_y', + default_value='2', + description='Sigma y of gaussian kernel' + ), + DeclareLaunchArgument( + 'dp', + default_value='2', + description='The inverse ratio of resolution' + ), + DeclareLaunchArgument( + 'min_circle_radius', + default_value='0', + description='The minimum size of the circle, If unknown, put zero as default' + ), + DeclareLaunchArgument( + 'max_circle_radius', + default_value='0', + description='The maximum size of the circle, If unknown, put zero as default' + ), + + # Node + Node( + package='opencv_apps', + executable='hough_circles', + name=LaunchConfiguration('node_name'), + remappings=[ + ('image', LaunchConfiguration('image')), + ], + parameters=[{ + 'use_camera_info': LaunchConfiguration('use_camera_info'), + 'debug_view': LaunchConfiguration('debug_view'), + 'queue_size': LaunchConfiguration('queue_size'), + 'canny_threshold': LaunchConfiguration('canny_threshold'), + 'accumulator_threshold': LaunchConfiguration('accumulator_threshold'), + 'gaussian_blur_size': LaunchConfiguration('gaussian_blur_size'), + 'gaussian_sigma_x': LaunchConfiguration('gaussian_sigma_x'), + 'gaussian_sigma_y': LaunchConfiguration('gaussian_sigma_y'), + 'dp': LaunchConfiguration('dp'), + 'min_circle_radius': LaunchConfiguration('min_circle_radius'), + 'max_circle_radius': LaunchConfiguration('max_circle_radius'), + }] + ), + ]) diff --git a/msg/CircleArrayStamped.msg b/msg/CircleArrayStamped.msg index a3302340..3535f6b9 100644 --- a/msg/CircleArrayStamped.msg +++ b/msg/CircleArrayStamped.msg @@ -1,3 +1,3 @@ -Header header +std_msgs/Header header Circle[] circles diff --git a/msg/ContourArrayStamped.msg b/msg/ContourArrayStamped.msg index f9479f67..19538a09 100644 --- a/msg/ContourArrayStamped.msg +++ b/msg/ContourArrayStamped.msg @@ -1,3 +1,3 @@ -Header header +std_msgs/Header header Contour[] contours diff --git a/msg/FaceArrayStamped.msg b/msg/FaceArrayStamped.msg index 44396828..a3620005 100644 --- a/msg/FaceArrayStamped.msg +++ b/msg/FaceArrayStamped.msg @@ -1,3 +1,3 @@ -Header header +std_msgs/Header header Face[] faces diff --git a/msg/FlowArrayStamped.msg b/msg/FlowArrayStamped.msg index d88f34fe..79d1edca 100644 --- a/msg/FlowArrayStamped.msg +++ b/msg/FlowArrayStamped.msg @@ -1,3 +1,3 @@ -Header header +std_msgs/Header header Flow[] flow bool[] status diff --git a/msg/FlowStamped.msg b/msg/FlowStamped.msg index 14676463..599f1d34 100644 --- a/msg/FlowStamped.msg +++ b/msg/FlowStamped.msg @@ -1,2 +1,2 @@ -Header header +std_msgs/Header header Flow flow diff --git a/msg/LineArrayStamped.msg b/msg/LineArrayStamped.msg index d72ff618..a8d0da2e 100644 --- a/msg/LineArrayStamped.msg +++ b/msg/LineArrayStamped.msg @@ -1,2 +1,2 @@ -Header header +std_msgs/Header header Line[] lines diff --git a/msg/MomentArrayStamped.msg b/msg/MomentArrayStamped.msg index 0b6b6b9a..d8224a92 100644 --- a/msg/MomentArrayStamped.msg +++ b/msg/MomentArrayStamped.msg @@ -1,2 +1,2 @@ -Header header +std_msgs/Header header Moment[] moments diff --git a/msg/Point2DArrayStamped.msg b/msg/Point2DArrayStamped.msg index e52a8c58..abe6e1be 100644 --- a/msg/Point2DArrayStamped.msg +++ b/msg/Point2DArrayStamped.msg @@ -1,2 +1,2 @@ -Header header +std_msgs/Header header Point2D[] points diff --git a/msg/Point2DStamped.msg b/msg/Point2DStamped.msg index 89f3a0e0..4fc2d050 100644 --- a/msg/Point2DStamped.msg +++ b/msg/Point2DStamped.msg @@ -1,3 +1,3 @@ -Header header +std_msgs/Header header Point2D point diff --git a/msg/RectArrayStamped.msg b/msg/RectArrayStamped.msg index e238d668..fcb61038 100644 --- a/msg/RectArrayStamped.msg +++ b/msg/RectArrayStamped.msg @@ -1,4 +1,4 @@ -Header header +std_msgs/Header header Rect[] rects diff --git a/msg/RotatedRectArrayStamped.msg b/msg/RotatedRectArrayStamped.msg index b10aa7dc..e96a0cb3 100644 --- a/msg/RotatedRectArrayStamped.msg +++ b/msg/RotatedRectArrayStamped.msg @@ -1,3 +1,3 @@ -Header header +std_msgs/Header header RotatedRect[] rects diff --git a/msg/RotatedRectStamped.msg b/msg/RotatedRectStamped.msg index 4c03ddad..e85b6386 100644 --- a/msg/RotatedRectStamped.msg +++ b/msg/RotatedRectStamped.msg @@ -1,4 +1,4 @@ -Header header +std_msgs/Header header RotatedRect rect diff --git a/package.xml b/package.xml index 7f5029db..cb954a7c 100644 --- a/package.xml +++ b/package.xml @@ -1,14 +1,11 @@ - + + opencv_apps 2.0.3 -

opencv_apps provides various nodes that run internally OpenCV's functionalities and publish the result as ROS topics. With opencv_apps, you can skip writing OpenCV application codes for a lot of its functionalities by simply running a launch file that corresponds to OpenCV's functionality you want.

-
    -
  • You can have a look at all launch files provided here (be sure to choose the correct branch. As of Sept. 2016 indigo branch is used for ROS Indigo, Jade, and Kinetic distros).
  • -
  • Some of the features covered by opencv_apps are explained in the wiki.
  • -
-

The most of code is originally taken from https://github.com/Itseez/opencv/tree/master/samples/cpp

+ opencv_apps provides various nodes that run internally OpenCV's functionalities and publish the result as ROS topics. With opencv_apps, you can skip writing OpenCV application codes for a lot of its functionalities by simply running a launch file that corresponds to OpenCV's functionality you want. + The most of code is originally taken from https://github.com/Itseez/opencv/tree/master/samples/cpp
Kei Okada @@ -16,42 +13,32 @@ BSD - catkin + ament_cmake + rosidl_default_generators cv_bridge - dynamic_reconfigure - g++-static image_transport - message_generation - nodelet - roscpp + rclcpp + rclcpp_components sensor_msgs std_msgs std_srvs - class_loader - - cv_bridge - dynamic_reconfigure - image_transport - image_view - message_runtime - nodelet - roscpp - sensor_msgs - std_msgs - std_srvs - class_loader - - roslaunch - rostest - rosbag - rosservice - rostopic - image_proc - topic_tools - compressed_image_transport + + cv_bridge + image_transport + rclcpp + rclcpp_components + sensor_msgs + std_msgs + std_srvs + rosidl_default_runtime + + ament_lint_auto + ament_lint_common + + rosidl_interface_packages - + ament_cmake
diff --git a/src/nodelet/camshift_nodelet.cpp b/src/nodelet/camshift_nodelet.cpp index 5d139642..a88f20cc 100644 --- a/src/nodelet/camshift_nodelet.cpp +++ b/src/nodelet/camshift_nodelet.cpp @@ -32,19 +32,12 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -// https://github.com/Itseez/opencv/blob/2.4/samples/cpp/camshiftdemo.cpp -/** - * This is a demo that shows mean-shift based tracking - * You select a color objects such as your face and it tracks it. - * This reads from video camera (0 by default, or the camera number the user enters - */ - -#include +#include #include "opencv_apps/nodelet.h" -#include -#include -#include -#include +#include +#include +#include +#include #include #include @@ -52,32 +45,22 @@ #include #include -#include -#include "opencv_apps/CamShiftConfig.h" -#include "opencv_apps/RotatedRectStamped.h" +#include "opencv_apps/msg/rotated_rect_stamped.hpp" namespace opencv_apps { class CamShiftNodelet : public opencv_apps::Nodelet { - image_transport::Publisher img_pub_, bproj_pub_; - image_transport::Subscriber img_sub_; - image_transport::CameraSubscriber cam_sub_; - ros::Publisher msg_pub_; - - boost::shared_ptr it_; - - typedef opencv_apps::CamShiftConfig Config; - typedef dynamic_reconfigure::Server ReconfigureServer; - Config config_; - boost::shared_ptr reconfigure_server_; + std::shared_ptr img_pub_, bproj_pub_; + std::shared_ptr img_sub_; + std::shared_ptr cam_sub_; + rclcpp::Publisher::SharedPtr msg_pub_; int queue_size_; bool debug_view_; - ros::Time prev_stamp_; + rclcpp::Time prev_stamp_; std::string window_name_, histogram_name_; - static bool need_config_update_; static bool on_mouse_update_; static int on_mouse_event_; static int on_mouse_x_; @@ -91,13 +74,14 @@ class CamShiftNodelet : public opencv_apps::Nodelet cv::Point origin; cv::Rect selection; bool paused; + bool use_camera_info_; cv::Rect trackWindow; int hsize; float hranges[2]; const float* phranges; cv::Mat hist, histimg; - // cv::Mat hsv; + rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr param_callback_handle_; static void onMouse(int event, int x, int y, int /*unused*/, void* /*unused*/) { @@ -107,70 +91,60 @@ class CamShiftNodelet : public opencv_apps::Nodelet on_mouse_y_ = y; } - void reconfigureCallback(Config& new_config, uint32_t level) + rcl_interfaces::msg::SetParametersResult parameterCallback(const std::vector& parameters) { - config_ = new_config; - vmin_ = config_.vmin; - vmax_ = config_.vmax; - smin_ = config_.smin; - } + rcl_interfaces::msg::SetParametersResult result; + result.successful = true; - const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame) - { - if (frame.empty()) - return image_frame; - return frame; + for (const auto& param : parameters) + { + if (param.get_name() == "vmin") + { + vmin_ = param.as_int(); + RCLCPP_INFO(this->get_logger(), "Updated vmin to %d", vmin_); + } + else if (param.get_name() == "vmax") + { + vmax_ = param.as_int(); + RCLCPP_INFO(this->get_logger(), "Updated vmax to %d", vmax_); + } + else if (param.get_name() == "smin") + { + smin_ = param.as_int(); + RCLCPP_INFO(this->get_logger(), "Updated smin to %d", smin_); + } + } + return result; } - void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) + void imageCallbackWithInfo(const sensor_msgs::msg::Image::ConstSharedPtr& msg, + const sensor_msgs::msg::CameraInfo::ConstSharedPtr& cam_info) { doWork(msg, cam_info->header.frame_id); } - void imageCallback(const sensor_msgs::ImageConstPtr& msg) + void imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr& msg) { doWork(msg, msg->header.frame_id); } - static void trackbarCallback(int /*unused*/, void* /*unused*/) + void doWork(const sensor_msgs::msg::Image::ConstSharedPtr& msg, const std::string& input_frame_from_msg) { - need_config_update_ = true; - } - - void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg) - { - // Work on the image. try { - // Convert the image into something opencv can handle. cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image; cv::Mat backproj; - // Messages - opencv_apps::RotatedRectStamped rect_msg; + opencv_apps::msg::RotatedRectStamped rect_msg; rect_msg.header = msg->header; - // Do the work - if (debug_view_) { - /// Create Trackbars for Thresholds - cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE); - cv::setMouseCallback(window_name_, onMouse, nullptr); - cv::createTrackbar("Vmin", window_name_, &vmin_, 256, trackbarCallback); - cv::createTrackbar("Vmax", window_name_, &vmax_, 256, trackbarCallback); - cv::createTrackbar("Smin", window_name_, &smin_, 256, trackbarCallback); - - if (need_config_update_) - { - config_.vmin = vmin_; - config_.vmax = vmax_; - config_.smin = smin_; - reconfigure_server_->updateConfig(config_); - need_config_update_ = false; - } + cv::createTrackbar("Vmin", window_name_, &vmin_, 256, nullptr); + cv::createTrackbar("Vmax", window_name_, &vmax_, 256, nullptr); + cv::createTrackbar("Smin", window_name_, &smin_, 256, nullptr); } if (on_mouse_update_) @@ -185,7 +159,6 @@ class CamShiftNodelet : public opencv_apps::Nodelet selection.y = MIN(y, origin.y); selection.width = std::abs(x - origin.x); selection.height = std::abs(y - origin.y); - selection &= cv::Rect(0, 0, frame.cols, frame.rows); } @@ -224,13 +197,14 @@ class CamShiftNodelet : public opencv_apps::Nodelet cv::Mat roi(hue, selection), maskroi(mask, selection); cv::calcHist(&roi, 1, nullptr, maskroi, hist, 1, &hsize, &phranges); cv::normalize(hist, hist, 0, 255, cv::NORM_MINMAX); - std::vector hist_value; + + std::vector hist_value; hist_value.resize(hsize); for (int i = 0; i < hsize; i++) { hist_value[i] = hist.at(i); } - pnh_->setParam("histogram", hist_value); + this->set_parameter(rclcpp::Parameter("histogram", hist_value)); trackWindow = selection; trackObject = 1; @@ -254,11 +228,10 @@ class CamShiftNodelet : public opencv_apps::Nodelet backproj &= mask; cv::RotatedRect track_box = cv::CamShift( backproj, trackWindow, cv::TermCriteria(cv::TermCriteria::EPS + cv::TermCriteria::MAX_ITER, 10, 1)); + if (trackWindow.area() <= 1) { int cols = backproj.cols, rows = backproj.rows, r = (MIN(cols, rows) + 5) / 6; - // trackWindow = cv::Rect(trackWindow.x - r, trackWindow.y - r, - // trackWindow.x + r, trackWindow.y + r) & trackWindow = cv::Rect(cols / 2 - r, rows / 2 - r, cols / 2 + r, rows / 2 + r) & cv::Rect(0, 0, cols, rows); } @@ -271,8 +244,8 @@ class CamShiftNodelet : public opencv_apps::Nodelet #endif rect_msg.rect.angle = track_box.angle; - opencv_apps::Point2D point_msg; - opencv_apps::Size size_msg; + opencv_apps::msg::Point2D point_msg; + opencv_apps::msg::Size size_msg; point_msg.x = track_box.center.x; point_msg.y = track_box.center.y; size_msg.width = track_box.size.width; @@ -293,11 +266,10 @@ class CamShiftNodelet : public opencv_apps::Nodelet if (debug_view_) { cv::imshow(window_name_, frame); - cv::imshow(histogram_name_, histimg); + if (showHist) + cv::imshow(histogram_name_, histimg); char c = (char)cv::waitKey(1); - // if( c == 27 ) - // break; switch (c) { case 'b': @@ -321,59 +293,89 @@ class CamShiftNodelet : public opencv_apps::Nodelet } } - // Publish the image. - sensor_msgs::Image::Ptr out_img1 = cv_bridge::CvImage(msg->header, msg->encoding, frame).toImageMsg(); - sensor_msgs::Image::Ptr out_img2 = + sensor_msgs::msg::Image::SharedPtr out_img1 = cv_bridge::CvImage(msg->header, msg->encoding, frame).toImageMsg(); + sensor_msgs::msg::Image::SharedPtr out_img2 = cv_bridge::CvImage(msg->header, sensor_msgs::image_encodings::MONO8, backproj).toImageMsg(); - img_pub_.publish(out_img1); - bproj_pub_.publish(out_img2); + img_pub_->publish(*out_img1); + bproj_pub_->publish(*out_img2); if (trackObject) - msg_pub_.publish(rect_msg); + msg_pub_->publish(rect_msg); } catch (cv::Exception& e) { - NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line); + RCLCPP_ERROR(this->get_logger(), "Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), + e.file.c_str(), e.line); } prev_stamp_ = msg->header.stamp; } - void subscribe() // NOLINT(modernize-use-override) + void subscribe() { - NODELET_DEBUG("Subscribing to image topic."); - if (config_.use_camera_info) - cam_sub_ = it_->subscribeCamera("image", queue_size_, &CamShiftNodelet::imageCallbackWithInfo, this); + RCLCPP_DEBUG(this->get_logger(), "Subscribing to image topic."); + if (use_camera_info_) + { + cam_sub_ = std::make_shared( + image_transport::create_camera_subscription( + this, "image", + std::bind(&CamShiftNodelet::imageCallbackWithInfo, this, + std::placeholders::_1, std::placeholders::_2), + "raw")); + } else - img_sub_ = it_->subscribe("image", queue_size_, &CamShiftNodelet::imageCallback, this); + { + img_sub_ = std::make_shared( + image_transport::create_subscription( + this, "image", + std::bind(&CamShiftNodelet::imageCallback, this, std::placeholders::_1), + "raw")); + } } - void unsubscribe() // NOLINT(modernize-use-override) + void unsubscribe() { - NODELET_DEBUG("Unsubscribing from image topic."); - img_sub_.shutdown(); - cam_sub_.shutdown(); + RCLCPP_DEBUG(this->get_logger(), "Unsubscribing from image topic."); + img_sub_.reset(); + cam_sub_.reset(); } public: - virtual void onInit() // NOLINT(modernize-use-override) + CamShiftNodelet(const rclcpp::NodeOptions& options = rclcpp::NodeOptions()) + : Nodelet("camshift", options) + { + } + + void onInit() override { Nodelet::onInit(); - it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); - pnh_->param("queue_size", queue_size_, 3); - pnh_->param("debug_view", debug_view_, false); + this->declare_parameter("queue_size", 3); + this->declare_parameter("debug_view", false); + this->declare_parameter("use_camera_info", false); + this->declare_parameter("vmin", 10); + this->declare_parameter("vmax", 256); + this->declare_parameter("smin", 30); + this->declare_parameter("histogram", std::vector()); + + this->get_parameter("queue_size", queue_size_); + this->get_parameter("debug_view", debug_view_); + this->get_parameter("use_camera_info", use_camera_info_); + this->get_parameter("vmin", vmin_); + this->get_parameter("vmax", vmax_); + this->get_parameter("smin", smin_); + if (debug_view_) { + RCLCPP_INFO(this->get_logger(), "debug_view: %s", debug_view_ ? "true" : "false"); + RCLCPP_INFO(this->get_logger(), "debug_view is enabled, setting always_subscribe to true"); always_subscribe_ = true; + RCLCPP_INFO(this->get_logger(), "always_subscribe: %s", always_subscribe_ ? "true" : "false"); } - prev_stamp_ = ros::Time(0, 0); + prev_stamp_ = rclcpp::Time(0); window_name_ = "CamShift Demo"; histogram_name_ = "Histogram"; - vmin_ = 10; - vmax_ = 256; - smin_ = 30; backprojMode = false; selectObject = false; trackObject = 0; @@ -386,26 +388,24 @@ class CamShiftNodelet : public opencv_apps::Nodelet phranges = hranges; histimg = cv::Mat::zeros(200, 320, CV_8UC3); - reconfigure_server_ = boost::make_shared >(*pnh_); - dynamic_reconfigure::Server::CallbackType f = - boost::bind(&CamShiftNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2); - reconfigure_server_->setCallback(f); - - img_pub_ = advertiseImage(*pnh_, "image", 1); - bproj_pub_ = advertiseImage(*pnh_, "back_project", 1); - msg_pub_ = advertise(*pnh_, "track_box", 1); - - NODELET_INFO("Hot keys: "); - NODELET_INFO("\tESC - quit the program"); - NODELET_INFO("\tc - stop the tracking"); - NODELET_INFO("\tb - switch to/from backprojection view"); - NODELET_INFO("\th - show/hide object histogram"); - NODELET_INFO("\tp - pause video"); - NODELET_INFO("To initialize tracking, select the object with mouse"); - - std::vector hist_value; - pnh_->getParam("histogram", hist_value); - if (hist_value.size() == hsize) + param_callback_handle_ = this->add_on_set_parameters_callback( + std::bind(&CamShiftNodelet::parameterCallback, this, std::placeholders::_1)); + + img_pub_ = advertiseImage("image_out", 1); + bproj_pub_ = advertiseImage("back_project", 1); + msg_pub_ = this->create_publisher("track_box", 1); + + RCLCPP_INFO(this->get_logger(), "Hot keys:"); + RCLCPP_INFO(this->get_logger(), " ESC - quit the program"); + RCLCPP_INFO(this->get_logger(), " c - stop the tracking"); + RCLCPP_INFO(this->get_logger(), " b - switch to/from backprojection view"); + RCLCPP_INFO(this->get_logger(), " h - show/hide object histogram"); + RCLCPP_INFO(this->get_logger(), " p - pause video"); + RCLCPP_INFO(this->get_logger(), "To initialize tracking, select the object with mouse"); + + std::vector hist_value; + this->get_parameter("histogram", hist_value); + if (hist_value.size() == static_cast(hsize)) { hist.create(hsize, 1, CV_32F); for (int i = 0; i < hsize; i++) @@ -413,7 +413,7 @@ class CamShiftNodelet : public opencv_apps::Nodelet hist.at(i) = hist_value[i]; } trackObject = 1; - trackWindow = cv::Rect(0, 0, 640, 480); // + trackWindow = cv::Rect(0, 0, 640, 480); histimg = cv::Scalar::all(0); int bin_w = histimg.cols / hsize; @@ -429,34 +429,27 @@ class CamShiftNodelet : public opencv_apps::Nodelet cv::Scalar(buf.at(i)), -1, 8); } } + onInitPostProcess(); } }; -bool CamShiftNodelet::need_config_update_ = false; + bool CamShiftNodelet::on_mouse_update_ = false; int CamShiftNodelet::on_mouse_event_ = 0; int CamShiftNodelet::on_mouse_x_ = 0; int CamShiftNodelet::on_mouse_y_ = 0; + } // namespace opencv_apps -namespace camshift -{ -class CamShiftNodelet : public opencv_apps::CamShiftNodelet -{ -public: - virtual void onInit() // NOLINT(modernize-use-override) - { - ROS_WARN("DeprecationWarning: Nodelet camshift/camshift is deprecated, " - "and renamed to opencv_apps/camshift."); - opencv_apps::CamShiftNodelet::onInit(); - } -}; -} // namespace camshift +#include +RCLCPP_COMPONENTS_REGISTER_NODE(opencv_apps::CamShiftNodelet) -#ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H -#include -#else -#include -#endif -PLUGINLIB_EXPORT_CLASS(opencv_apps::CamShiftNodelet, nodelet::Nodelet); -PLUGINLIB_EXPORT_CLASS(camshift::CamShiftNodelet, nodelet::Nodelet); +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + auto node = std::make_shared(); + node->onInit(); + rclcpp::spin(node); + rclcpp::shutdown(); + return 0; +} diff --git a/src/nodelet/edge_detection_nodelet.cpp b/src/nodelet/edge_detection_nodelet.cpp index e9048793..88f43cd3 100644 --- a/src/nodelet/edge_detection_nodelet.cpp +++ b/src/nodelet/edge_detection_nodelet.cpp @@ -33,55 +33,29 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -// https://github.com/Itseez/opencv/blob/2.4/samples/cpp/tutorial_code/ImgTrans/ -/** - * @file Sobel_Demo.cpp - * @brief Sample code using Sobel and/orScharr OpenCV functions to make a simple Edge Detector - * @author OpenCV team - */ -/** - * @file Laplace_Demo.cpp - * @brief Sample code showing how to detect edges using the Laplace operator - * @author OpenCV team - */ -/** - * @file CannyDetector_Demo.cpp - * @brief Sample code showing how to detect edges using the Canny Detector - * @author OpenCV team - */ - -#include +#include #include "opencv_apps/nodelet.h" -#include -#include -#include +#include +#include +#include +#include #include #include -#include -#include "opencv_apps/EdgeDetectionConfig.h" - namespace opencv_apps { class EdgeDetectionNodelet : public opencv_apps::Nodelet { - image_transport::Publisher img_pub_; - image_transport::Subscriber img_sub_; - image_transport::CameraSubscriber cam_sub_; - ros::Publisher msg_pub_; - - boost::shared_ptr it_; - - typedef opencv_apps::EdgeDetectionConfig Config; - typedef dynamic_reconfigure::Server ReconfigureServer; - Config config_; - boost::shared_ptr reconfigure_server_; + std::shared_ptr img_pub_; + std::shared_ptr img_sub_; + std::shared_ptr cam_sub_; int queue_size_; bool debug_view_; - ros::Time prev_stamp_; + rclcpp::Time prev_stamp_; + int edge_type_; int canny_threshold1_; int canny_threshold2_; int apertureSize_; @@ -90,59 +64,93 @@ class EdgeDetectionNodelet : public opencv_apps::Nodelet bool apply_blur_post_; int postBlurSize_; double postBlurSigma_; + bool use_camera_info_; std::string window_name_; - static bool need_config_update_; + rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr param_callback_handle_; - void reconfigureCallback(Config& new_config, uint32_t level) + rcl_interfaces::msg::SetParametersResult parameterCallback(const std::vector& parameters) { - config_ = new_config; - canny_threshold1_ = config_.canny_threshold1; - canny_threshold2_ = config_.canny_threshold2; - apertureSize_ = 2 * ((config_.apertureSize / 2)) + 1; - L2gradient_ = config_.L2gradient; - - apply_blur_pre_ = config_.apply_blur_pre; - apply_blur_post_ = config_.apply_blur_post; - postBlurSize_ = 2 * ((config_.postBlurSize) / 2) + 1; - postBlurSigma_ = config_.postBlurSigma; - } + rcl_interfaces::msg::SetParametersResult result; + result.successful = true; - const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame) - { - if (frame.empty()) - return image_frame; - return frame; + for (const auto& param : parameters) + { + if (param.get_name() == "edge_type") + { + edge_type_ = param.as_int(); + RCLCPP_INFO(this->get_logger(), "Updated edge_type to %d", edge_type_); + } + else if (param.get_name() == "canny_threshold1") + { + canny_threshold1_ = param.as_int(); + RCLCPP_INFO(this->get_logger(), "Updated canny_threshold1 to %d", canny_threshold1_); + } + else if (param.get_name() == "canny_threshold2") + { + canny_threshold2_ = param.as_int(); + RCLCPP_INFO(this->get_logger(), "Updated canny_threshold2 to %d", canny_threshold2_); + } + else if (param.get_name() == "apertureSize") + { + apertureSize_ = param.as_int(); + RCLCPP_INFO(this->get_logger(), "Updated apertureSize to %d", apertureSize_); + } + else if (param.get_name() == "L2gradient") + { + L2gradient_ = param.as_bool(); + RCLCPP_INFO(this->get_logger(), "Updated L2gradient to %s", L2gradient_ ? "true" : "false"); + } + else if (param.get_name() == "apply_blur_pre") + { + apply_blur_pre_ = param.as_bool(); + RCLCPP_INFO(this->get_logger(), "Updated apply_blur_pre to %s", apply_blur_pre_ ? "true" : "false"); + } + else if (param.get_name() == "apply_blur_post") + { + apply_blur_post_ = param.as_bool(); + RCLCPP_INFO(this->get_logger(), "Updated apply_blur_post to %s", apply_blur_post_ ? "true" : "false"); + } + else if (param.get_name() == "postBlurSize") + { + postBlurSize_ = param.as_int(); + RCLCPP_INFO(this->get_logger(), "Updated postBlurSize to %d", postBlurSize_); + } + else if (param.get_name() == "postBlurSigma") + { + postBlurSigma_ = param.as_double(); + RCLCPP_INFO(this->get_logger(), "Updated postBlurSigma to %.2f", postBlurSigma_); + } + else if (param.get_name() == "debug_view") + { + debug_view_ = param.as_bool(); + RCLCPP_INFO(this->get_logger(), "Updated debug_view to %s", debug_view_ ? "true" : "false"); + } + } + + return result; } - void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) + void imageCallbackWithInfo(const sensor_msgs::msg::Image::ConstSharedPtr& msg, + const sensor_msgs::msg::CameraInfo::ConstSharedPtr& cam_info) { doWork(msg, cam_info->header.frame_id); } - void imageCallback(const sensor_msgs::ImageConstPtr& msg) + void imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr& msg) { doWork(msg, msg->header.frame_id); } - static void trackbarCallback(int /*unused*/, void* /*unused*/) + void doWork(const sensor_msgs::msg::Image::ConstSharedPtr& msg, const std::string& input_frame_from_msg) { - need_config_update_ = true; - } - - void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg) - { - // Work on the image. try { - // Convert the image into something opencv can handle. cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image; - // Do the work cv::Mat src_gray; cv::GaussianBlur(frame, frame, cv::Size(3, 3), 0, 0, cv::BORDER_DEFAULT); - /// Convert it to gray if (frame.channels() > 1) { cv::cvtColor(frame, src_gray, cv::COLOR_RGB2GRAY); @@ -152,98 +160,55 @@ class EdgeDetectionNodelet : public opencv_apps::Nodelet src_gray = frame; } - /// Create window if (debug_view_) { cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE); } - std::string new_window_name; cv::Mat grad; - switch (config_.edge_type) + switch (edge_type_) { - case opencv_apps::EdgeDetection_Sobel: + case 0: // Sobel { - /// Generate grad_x and grad_y cv::Mat grad_x, grad_y; cv::Mat abs_grad_x, abs_grad_y; - int scale = 1; int delta = 0; int ddepth = CV_16S; - /// Gradient X - // Scharr( src_gray, grad_x, ddepth, 1, 0, scale, delta, BORDER_DEFAULT ); cv::Sobel(src_gray, grad_x, ddepth, 1, 0, 3, scale, delta, cv::BORDER_DEFAULT); cv::convertScaleAbs(grad_x, abs_grad_x); - /// Gradient Y - // Scharr( src_gray, grad_y, ddepth, 0, 1, scale, delta, BORDER_DEFAULT ); cv::Sobel(src_gray, grad_y, ddepth, 0, 1, 3, scale, delta, cv::BORDER_DEFAULT); cv::convertScaleAbs(grad_y, abs_grad_y); - /// Total Gradient (approximate) cv::addWeighted(abs_grad_x, 0.5, abs_grad_y, 0.5, 0, grad); - - new_window_name = "Sobel Edge Detection Demo"; break; } - case opencv_apps::EdgeDetection_Laplace: + case 1: // Laplace { cv::Mat dst; int kernel_size = 3; int scale = 1; int delta = 0; int ddepth = CV_16S; - /// Apply Laplace function cv::Laplacian(src_gray, dst, ddepth, kernel_size, scale, delta, cv::BORDER_DEFAULT); convertScaleAbs(dst, grad); - - new_window_name = "Laplace Edge Detection Demo"; break; } - case opencv_apps::EdgeDetection_Canny: + case 2: // Canny { - int edge_thresh = 1; - int kernel_size = 3; - int const max_canny_threshold1 = 500; - int const max_canny_threshold2 = 500; - cv::Mat detected_edges; - - /// Reduce noise with a kernel 3x3 if (apply_blur_pre_) { cv::blur(src_gray, src_gray, cv::Size(apertureSize_, apertureSize_)); } - /// Canny detector - cv::Canny(src_gray, grad, canny_threshold1_, canny_threshold2_, kernel_size, L2gradient_); - if (apply_blur_post_) - { - cv::GaussianBlur(grad, grad, cv::Size(postBlurSize_, postBlurSize_), postBlurSigma_, - postBlurSigma_); // 0.3*(ksize/2 - 1) + 0.8 - } - - new_window_name = "Canny Edge Detection Demo"; + cv::Canny(src_gray, grad, canny_threshold1_, canny_threshold2_, 3, L2gradient_); - /// Create a Trackbar for user to enter threshold - if (debug_view_) + if (apply_blur_post_) { - if (need_config_update_) - { - config_.canny_threshold1 = canny_threshold1_; - config_.canny_threshold2 = canny_threshold2_; - reconfigure_server_->updateConfig(config_); - need_config_update_ = false; - } - if (window_name_ == new_window_name) - { - cv::createTrackbar("Min CannyThreshold1:", window_name_, &canny_threshold1_, max_canny_threshold1, - trackbarCallback); - cv::createTrackbar("Min CannyThreshold2:", window_name_, &canny_threshold2_, max_canny_threshold2, - trackbarCallback); - } + cv::GaussianBlur(grad, grad, cv::Size(postBlurSize_, postBlurSize_), postBlurSigma_, postBlurSigma_); } break; } @@ -251,95 +216,117 @@ class EdgeDetectionNodelet : public opencv_apps::Nodelet if (debug_view_) { - if (window_name_ != new_window_name) - { - cv::destroyWindow(window_name_); - window_name_ = new_window_name; - } cv::imshow(window_name_, grad); int c = cv::waitKey(1); } - // Publish the image. - sensor_msgs::Image::Ptr out_img = + sensor_msgs::msg::Image::SharedPtr out_img = cv_bridge::CvImage(msg->header, sensor_msgs::image_encodings::MONO8, grad).toImageMsg(); - img_pub_.publish(out_img); + img_pub_->publish(*out_img); } catch (cv::Exception& e) { - NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line); + RCLCPP_ERROR(this->get_logger(), "Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), + e.file.c_str(), e.line); } prev_stamp_ = msg->header.stamp; } - void subscribe() // NOLINT(modernize-use-override) + void subscribe() { - NODELET_DEBUG("Subscribing to image topic."); - if (config_.use_camera_info) - cam_sub_ = it_->subscribeCamera("image", queue_size_, &EdgeDetectionNodelet::imageCallbackWithInfo, this); + RCLCPP_DEBUG(this->get_logger(), "Subscribing to image topic."); + if (use_camera_info_) + { + cam_sub_ = std::make_shared( + image_transport::create_camera_subscription( + this, "image", + std::bind(&EdgeDetectionNodelet::imageCallbackWithInfo, this, + std::placeholders::_1, std::placeholders::_2), + "raw")); + } else - img_sub_ = it_->subscribe("image", queue_size_, &EdgeDetectionNodelet::imageCallback, this); + { + img_sub_ = std::make_shared( + image_transport::create_subscription( + this, "image", + std::bind(&EdgeDetectionNodelet::imageCallback, this, std::placeholders::_1), + "raw")); + } } - void unsubscribe() // NOLINT(modernize-use-override) + void unsubscribe() { - NODELET_DEBUG("Unsubscribing from image topic."); - img_sub_.shutdown(); - cam_sub_.shutdown(); + RCLCPP_DEBUG(this->get_logger(), "Unsubscribing from image topic."); + img_sub_.reset(); + cam_sub_.reset(); } public: - virtual void onInit() // NOLINT(modernize-use-override) + EdgeDetectionNodelet(const rclcpp::NodeOptions& options = rclcpp::NodeOptions()) + : Nodelet("edge_detection", options) + { + } + + void onInit() override { Nodelet::onInit(); - it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); - pnh_->param("queue_size", queue_size_, 3); - pnh_->param("debug_view", debug_view_, false); + this->declare_parameter("queue_size", 3); + this->declare_parameter("debug_view", false); + this->declare_parameter("use_camera_info", false); + this->declare_parameter("edge_type", 0); + this->declare_parameter("canny_threshold1", 100); + this->declare_parameter("canny_threshold2", 200); + this->declare_parameter("apertureSize", 3); + this->declare_parameter("L2gradient", false); + this->declare_parameter("apply_blur_pre", true); + this->declare_parameter("apply_blur_post", false); + this->declare_parameter("postBlurSize", 13); + this->declare_parameter("postBlurSigma", 3.2); + + this->get_parameter("queue_size", queue_size_); + this->get_parameter("debug_view", debug_view_); + this->get_parameter("use_camera_info", use_camera_info_); + this->get_parameter("edge_type", edge_type_); + this->get_parameter("canny_threshold1", canny_threshold1_); + this->get_parameter("canny_threshold2", canny_threshold2_); + this->get_parameter("apertureSize", apertureSize_); + this->get_parameter("L2gradient", L2gradient_); + this->get_parameter("apply_blur_pre", apply_blur_pre_); + this->get_parameter("apply_blur_post", apply_blur_post_); + this->get_parameter("postBlurSize", postBlurSize_); + this->get_parameter("postBlurSigma", postBlurSigma_); if (debug_view_) { always_subscribe_ = true; } - prev_stamp_ = ros::Time(0, 0); + prev_stamp_ = rclcpp::Time(0); window_name_ = "Edge Detection Demo"; - canny_threshold1_ = 100; // only for canny - canny_threshold2_ = 200; // only for canny - reconfigure_server_ = boost::make_shared >(*pnh_); - dynamic_reconfigure::Server::CallbackType f = - boost::bind(&EdgeDetectionNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2); - reconfigure_server_->setCallback(f); + img_pub_ = advertiseImage("image", 1); - img_pub_ = advertiseImage(*pnh_, "image", 1); - // msg_pub_ = local_nh_.advertise("lines", 1, msg_connect_cb, msg_disconnect_cb); + // Register parameter callback for runtime parameter changes + param_callback_handle_ = this->add_on_set_parameters_callback( + std::bind(&EdgeDetectionNodelet::parameterCallback, this, std::placeholders::_1)); onInitPostProcess(); } }; -bool EdgeDetectionNodelet::need_config_update_ = false; + } // namespace opencv_apps -namespace edge_detection -{ -class EdgeDetectionNodelet : public opencv_apps::EdgeDetectionNodelet +#include +RCLCPP_COMPONENTS_REGISTER_NODE(opencv_apps::EdgeDetectionNodelet) + +int main(int argc, char** argv) { -public: - virtual void onInit() // NOLINT(modernize-use-override) - { - ROS_WARN("DeprecationWarning: Nodelet edge_detection/edge_detection is deprecated, " - "and renamed to opencv_apps/edge_detection."); - opencv_apps::EdgeDetectionNodelet::onInit(); - } -}; -} // namespace edge_detection - -#ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H -#include -#else -#include -#endif -PLUGINLIB_EXPORT_CLASS(opencv_apps::EdgeDetectionNodelet, nodelet::Nodelet); -PLUGINLIB_EXPORT_CLASS(edge_detection::EdgeDetectionNodelet, nodelet::Nodelet); + rclcpp::init(argc, argv); + auto node = std::make_shared(); + node->onInit(); + rclcpp::spin(node); + rclcpp::shutdown(); + return 0; +} diff --git a/src/nodelet/nodelet.cpp b/src/nodelet/nodelet.cpp index 6725f310..3b98fd64 100644 --- a/src/nodelet/nodelet.cpp +++ b/src/nodelet/nodelet.cpp @@ -13,7 +13,7 @@ * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/o2r other materials provided + * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the JSK Lab nor the names of its * contributors may be used to endorse or promote products derived @@ -34,192 +34,37 @@ *********************************************************************/ #include "opencv_apps/nodelet.h" -#if BOOST_VERSION < 106000 // since 1.60.0, boost uses placeholders namesapce for _1,_2... -#ifndef BOOST_PLAEHOLDERS -#define BOOST_PLAEHOLDERS -namespace boost -{ -namespace placeholders -{ -boost::arg<1> _1; -boost::arg<2> _2; -boost::arg<3> _3; -boost::arg<4> _4; -boost::arg<5> _5; -boost::arg<6> _6; -boost::arg<7> _7; -boost::arg<8> _8; -boost::arg<9> _9; -} // namespace placeholders -} // namespace boost -#endif // BOOST_PLAEHOLDERS -#endif // BOOST_VERSION < 106000 namespace opencv_apps { void Nodelet::onInit() { connection_status_ = NOT_SUBSCRIBED; - nh_.reset(new ros::NodeHandle(getMTNodeHandle())); - pnh_.reset(new ros::NodeHandle(getMTPrivateNodeHandle())); - pnh_->param("always_subscribe", always_subscribe_, false); - pnh_->param("verbose_connection", verbose_connection_, false); - if (!verbose_connection_) - { - nh_->param("verbose_connection", verbose_connection_, false); - } - // timer to warn when no connection in a few seconds + + this->declare_parameter("always_subscribe", false); + this->declare_parameter("verbose_connection", false); + + this->get_parameter("always_subscribe", always_subscribe_); + this->get_parameter("verbose_connection", verbose_connection_); + ever_subscribed_ = false; - timer_ = nh_->createWallTimer(ros::WallDuration(5), &Nodelet::warnNeverSubscribedCallback, this, - /*oneshot=*/true); } void Nodelet::onInitPostProcess() { + // In ROS2, we typically always subscribe since connection callbacks are more complex if (always_subscribe_) { subscribe(); + connection_status_ = SUBSCRIBED; } -} - -void Nodelet::warnNeverSubscribedCallback(const ros::WallTimerEvent& event) -{ - if (!ever_subscribed_) + else { - NODELET_WARN("'%s' subscribes topics only with child subscribers.", nodelet::Nodelet::getName().c_str()); - } -} - -void Nodelet::connectionCallback(const ros::SingleSubscriberPublisher& pub) -{ - if (verbose_connection_) - { - NODELET_INFO("New connection or disconnection is detected"); - } - if (!always_subscribe_) - { - boost::mutex::scoped_lock lock(connection_mutex_); - for (const ros::Publisher& pub : publishers_) - { - if (pub.getNumSubscribers() > 0) - { - if (!ever_subscribed_) - { - ever_subscribed_ = true; - } - if (connection_status_ != SUBSCRIBED) - { - if (verbose_connection_) - { - NODELET_INFO("Subscribe input topics"); - } - subscribe(); - connection_status_ = SUBSCRIBED; - } - return; - } - } - if (connection_status_ == SUBSCRIBED) - { - if (verbose_connection_) - { - NODELET_INFO("Unsubscribe input topics"); - } - unsubscribe(); - connection_status_ = NOT_SUBSCRIBED; - } - } -} - -void Nodelet::imageConnectionCallback(const image_transport::SingleSubscriberPublisher& pub) -{ - if (verbose_connection_) - { - NODELET_INFO("New image connection or disconnection is detected"); - } - if (!always_subscribe_) - { - boost::mutex::scoped_lock lock(connection_mutex_); - for (const image_transport::Publisher& pub : image_publishers_) - { - if (pub.getNumSubscribers() > 0) - { - if (!ever_subscribed_) - { - ever_subscribed_ = true; - } - if (connection_status_ != SUBSCRIBED) - { - if (verbose_connection_) - { - NODELET_INFO("Subscribe input topics"); - } - subscribe(); - connection_status_ = SUBSCRIBED; - } - return; - } - } - if (connection_status_ == SUBSCRIBED) - { - if (verbose_connection_) - { - NODELET_INFO("Unsubscribe input topics"); - } - unsubscribe(); - connection_status_ = NOT_SUBSCRIBED; - } + // For simplicity in ROS2, we'll just always subscribe + RCLCPP_INFO(this->get_logger(), "Subscribing to input topics"); + subscribe(); + connection_status_ = SUBSCRIBED; } } -void Nodelet::cameraConnectionCallback(const image_transport::SingleSubscriberPublisher& pub) -{ - cameraConnectionBaseCallback(); -} - -void Nodelet::cameraInfoConnectionCallback(const ros::SingleSubscriberPublisher& pub) -{ - cameraConnectionBaseCallback(); -} - -void Nodelet::cameraConnectionBaseCallback() -{ - if (verbose_connection_) - { - NODELET_INFO("New image connection or disconnection is detected"); - } - if (!always_subscribe_) - { - boost::mutex::scoped_lock lock(connection_mutex_); - for (const image_transport::CameraPublisher& pub : camera_publishers_) - { - if (pub.getNumSubscribers() > 0) - { - if (!ever_subscribed_) - { - ever_subscribed_ = true; - } - if (connection_status_ != SUBSCRIBED) - { - if (verbose_connection_) - { - NODELET_INFO("Subscribe input topics"); - } - subscribe(); - connection_status_ = SUBSCRIBED; - } - return; - } - } - if (connection_status_ == SUBSCRIBED) - { - if (verbose_connection_) - { - NODELET_INFO("Unsubscribe input topics"); - } - unsubscribe(); - connection_status_ = NOT_SUBSCRIBED; - } - } -} } // namespace opencv_apps