From 93a9871fb521c95178ecbaf50566cefb64b544fe Mon Sep 17 00:00:00 2001 From: v4hn Date: Mon, 11 Nov 2024 15:13:36 +0100 Subject: [PATCH 01/10] Fixup 6ac62fef5caba52cbfa71c093b242a1f0b5a1b88 Drop unused catkin_python_setup(). The call and setup.py are only required when defining python modules, but jsk_recognition_msgs does not expose a python package (aside from the autogenerated package for the messages). This got noticed because Debian's python setuptools complains about missing package list in setup.py: --- error: Multiple top-level packages discovered in a flat-layout: ['srv', 'msg', 'debian', 'action', 'sample']. To avoid accidental inclusion of unwanted files or directories, setuptools will not proceed with this build. If you are trying to create a single distribution with multiple packages on purpose, you should not rely on automatic discovery. Instead, consider the following options: 1. set up custom discovery (`find` directive with `include` or `exclude`) 2. use a `src-layout` 3. explicitly set `py_modules` or `packages` with a list of names To find more information, look for "package discovery" on setuptools docs. CMake Error at catkin_generated/safe_execute_install.cmake:4 (message): execute_process(/<>package/.obj-x86_64-linux-gnu/catkin_generated/python_distutils_install.sh) returned error code Call Stack (most recent call first): cmake_install.cmake:46 (include) --- --- jsk_recognition_msgs/CMakeLists.txt | 3 --- jsk_recognition_msgs/setup.py | 17 ----------------- 2 files changed, 20 deletions(-) delete mode 100644 jsk_recognition_msgs/setup.py diff --git a/jsk_recognition_msgs/CMakeLists.txt b/jsk_recognition_msgs/CMakeLists.txt index 86e6164943..1fba71e003 100644 --- a/jsk_recognition_msgs/CMakeLists.txt +++ b/jsk_recognition_msgs/CMakeLists.txt @@ -2,9 +2,6 @@ cmake_minimum_required(VERSION 2.8.3) project(jsk_recognition_msgs) find_package(catkin REQUIRED std_msgs sensor_msgs geometry_msgs message_generation pcl_msgs jsk_footstep_msgs) -if(NOT $ENV{ROS_DISTRO} STREQUAL "indigo") # on noetic it needs catkin_install_python to support Python3 and it does not work on indigo for some reason... - catkin_python_setup() -endif() add_message_files( FILES Accuracy.msg diff --git a/jsk_recognition_msgs/setup.py b/jsk_recognition_msgs/setup.py deleted file mode 100644 index 90f8d8be68..0000000000 --- a/jsk_recognition_msgs/setup.py +++ /dev/null @@ -1,17 +0,0 @@ -#!/usr/bin/env python - -from setuptools import setup - -from setuptools import find_packages -from catkin_pkg.python_setup import generate_distutils_setup - -d = generate_distutils_setup( - # Uncomment until src/jsk_recognition_msgs - # error: package directory 'jsk_recognition_msgs' does not exist - # [jsk_recognition_msgs:install] - # packages=['jsk_recognition_msgs'], - # [jsk_recognition_msgs:install] error: package directory 'src/jsk_recognition_msgs' does not exist - # package_dir={'': 'src'}, -) - -setup(**d) From c394e94add20890c53e03f1478b25c83ea531682 Mon Sep 17 00:00:00 2001 From: v4hn Date: Mon, 18 Nov 2024 17:40:26 +0100 Subject: [PATCH 02/10] fix build with PCL 1.13 - PCL_LIBRARIES has to be added explicitly to pull in VTK, which is required in `pointcloud_to_stl_nodelet.cpp` by using `pcl::io::savePolygonFileSTL(ss.str(),triangles)`. (the respective header includes VTK headers) - define pcl_isfinite again which got removed from PCL for compatibility with old versions - ros::topic::waitForMessage still returns a boost::shared_ptr. --- jsk_pcl_ros_utils/CMakeLists.txt | 2 +- jsk_pcl_ros_utils/src/normal_flip_to_frame_nodelet.cpp | 5 +++++ jsk_pcl_ros_utils/src/pointcloud_to_pcd_nodelet.cpp | 2 +- 3 files changed, 7 insertions(+), 2 deletions(-) diff --git a/jsk_pcl_ros_utils/CMakeLists.txt b/jsk_pcl_ros_utils/CMakeLists.txt index 231dda1b06..e9eb0eff92 100644 --- a/jsk_pcl_ros_utils/CMakeLists.txt +++ b/jsk_pcl_ros_utils/CMakeLists.txt @@ -223,7 +223,7 @@ jsk_pcl_util_nodelet(src/marker_array_voxel_to_pointcloud_nodelet.cpp add_library(jsk_pcl_ros_utils SHARED ${jsk_pcl_util_nodelet_sources}) add_dependencies(jsk_pcl_ros_utils ${PROJECT_NAME}_gencfg) target_link_libraries(jsk_pcl_ros_utils - ${catkin_LIBRARIES} ${pcl_ros_LIBRARIES} ${OpenCV_LIBRARIES} yaml-cpp) + ${catkin_LIBRARIES} ${pcl_ros_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBRARIES} yaml-cpp) get_property(dirs DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} PROPERTY INCLUDE_DIRECTORIES) diff --git a/jsk_pcl_ros_utils/src/normal_flip_to_frame_nodelet.cpp b/jsk_pcl_ros_utils/src/normal_flip_to_frame_nodelet.cpp index 77309bb8cb..36a59b2f88 100644 --- a/jsk_pcl_ros_utils/src/normal_flip_to_frame_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/normal_flip_to_frame_nodelet.cpp @@ -64,6 +64,11 @@ namespace jsk_pcl_ros_utils sub_.shutdown(); } +// pcl removed the method by 1.13, no harm in defining it ourselves to use below +#if __cplusplus >= 201103L +#define pcl_isfinite(x) std::isfinite(x) +#endif + void NormalFlipToFrame::flip(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg) { vital_checker_->poke(); diff --git a/jsk_pcl_ros_utils/src/pointcloud_to_pcd_nodelet.cpp b/jsk_pcl_ros_utils/src/pointcloud_to_pcd_nodelet.cpp index fe9be68586..e123b5057c 100644 --- a/jsk_pcl_ros_utils/src/pointcloud_to_pcd_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/pointcloud_to_pcd_nodelet.cpp @@ -60,7 +60,7 @@ namespace jsk_pcl_ros_utils void PointCloudToPCD::savePCD() { - pcl::PCLPointCloud2::ConstPtr cloud; + boost::shared_ptr cloud; cloud = ros::topic::waitForMessage("input", *pnh_); if ((cloud->width * cloud->height) == 0) { From ed1b5293ac209aa04294ef6730f56e10b7c4cccb Mon Sep 17 00:00:00 2001 From: Shun Hasegawa Date: Thu, 12 Dec 2024 16:23:04 +0900 Subject: [PATCH 03/10] [audio_to_spectrogram] Fix when to use catkin_install_python Conditional branch introduced by https://github.com/jsk-ros-pkg/jsk_recognition/pull/2743 is wrong --- audio_to_spectrogram/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/audio_to_spectrogram/CMakeLists.txt b/audio_to_spectrogram/CMakeLists.txt index f3828e9d70..a20760df5f 100644 --- a/audio_to_spectrogram/CMakeLists.txt +++ b/audio_to_spectrogram/CMakeLists.txt @@ -17,7 +17,7 @@ install(DIRECTORY launch sample test DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} USE_SOURCE_PERMISSIONS ) -if(NOT $ENV{ROS_DISTRO} STREQUAL "indigo") # on noetic it needs catkin_install_python to support Python3 and it does not work on indigo for some reason... +if($ENV{ROS_DISTRO} STREQUAL "indigo") # on noetic it needs catkin_install_python to support Python3 and it does not work on indigo for some reason... install(DIRECTORY scripts DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} USE_SOURCE_PERMISSIONS From 63fc581a0b3d0d9da6cd4014d5caaf9e27520f09 Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Thu, 26 Dec 2024 11:06:25 +0000 Subject: [PATCH 04/10] [ros-o] use std::isfinite,std::isnan instead of pcl_isfinite, pcl_isnan pcl removed the method by 1.13, no harm in defining it as '#define pcl_isfinite(x) std::isfinite(x)' --- jsk_pcl_ros/include/jsk_pcl_ros/organized_pass_through.h | 5 +++++ jsk_pcl_ros/src/attention_clipper_nodelet.cpp | 5 +++++ .../src/cluster_point_indices_decomposer_nodelet.cpp | 5 +++++ jsk_pcl_ros/src/colorize_random_points_RF_nodelet.cpp | 7 ++++++- jsk_pcl_ros/src/colorize_segmented_RF_nodelet.cpp | 5 +++++ jsk_pcl_ros/src/edgebased_cube_finder_nodelet.cpp | 7 ++++++- jsk_pcl_ros/src/geometric_consistency_grouping_nodelet.cpp | 5 +++++ jsk_pcl_ros/src/linemod_nodelet.cpp | 5 +++++ .../src/organized_statistical_outlier_removal_nodelet.cpp | 5 +++++ 9 files changed, 47 insertions(+), 2 deletions(-) diff --git a/jsk_pcl_ros/include/jsk_pcl_ros/organized_pass_through.h b/jsk_pcl_ros/include/jsk_pcl_ros/organized_pass_through.h index 26c372489e..0f96df5e76 100644 --- a/jsk_pcl_ros/include/jsk_pcl_ros/organized_pass_through.h +++ b/jsk_pcl_ros/include/jsk_pcl_ros/organized_pass_through.h @@ -70,6 +70,11 @@ namespace jsk_pcl_ros virtual void updateDiagnostic( diagnostic_updater::DiagnosticStatusWrapper &stat); + // pcl removed the method by 1.13, no harm in defining it ourselves to use below +#if __cplusplus >= 201103L +#define pcl_isfinite(x) std::isfinite(x) +#endif + bool isPointNaN(const PointT& p) { return (!pcl_isfinite(p.x) || !pcl_isfinite(p.y) || !pcl_isfinite(p.z)); } diff --git a/jsk_pcl_ros/src/attention_clipper_nodelet.cpp b/jsk_pcl_ros/src/attention_clipper_nodelet.cpp index b58d170b40..620788914e 100644 --- a/jsk_pcl_ros/src/attention_clipper_nodelet.cpp +++ b/jsk_pcl_ros/src/attention_clipper_nodelet.cpp @@ -378,6 +378,11 @@ namespace jsk_pcl_ros cv::rectangle(mask, roi_rect, white, CV_FILLED); } + // pcl removed the method by 1.13, no harm in defining it ourselves to use below +#if __cplusplus >= 201103L +#define pcl_isfinite(x) std::isfinite(x) +#endif + void AttentionClipper::clipPointcloud( const sensor_msgs::PointCloud2::ConstPtr& msg) { diff --git a/jsk_pcl_ros/src/cluster_point_indices_decomposer_nodelet.cpp b/jsk_pcl_ros/src/cluster_point_indices_decomposer_nodelet.cpp index dbdeb3850e..9d88f498a5 100644 --- a/jsk_pcl_ros/src/cluster_point_indices_decomposer_nodelet.cpp +++ b/jsk_pcl_ros/src/cluster_point_indices_decomposer_nodelet.cpp @@ -432,6 +432,11 @@ namespace jsk_pcl_ros return true; } + // pcl removed the method by 1.13, no harm in defining it ourselves to use below +#if __cplusplus >= 201103L +#define pcl_isfinite(x) std::isfinite(x) +#endif + bool ClusterPointIndicesDecomposer::computeCenterAndBoundingBox (const pcl::PointCloud::Ptr segmented_cloud, const std_msgs::Header header, diff --git a/jsk_pcl_ros/src/colorize_random_points_RF_nodelet.cpp b/jsk_pcl_ros/src/colorize_random_points_RF_nodelet.cpp index abdf66d379..5dabfc77ee 100644 --- a/jsk_pcl_ros/src/colorize_random_points_RF_nodelet.cpp +++ b/jsk_pcl_ros/src/colorize_random_points_RF_nodelet.cpp @@ -86,7 +86,12 @@ namespace jsk_pcl_ros { sub_input_.shutdown(); } - + + // pcl removed the method by 1.13, no harm in defining it ourselves to use below +#if __cplusplus >= 201103L +#define pcl_isnan(x) std::isnan(x) +#endif + void ColorizeMapRandomForest::extract(const sensor_msgs::PointCloud2 pc) { pcl::PointCloud::Ptr cloud (new pcl::PointCloud ()); diff --git a/jsk_pcl_ros/src/colorize_segmented_RF_nodelet.cpp b/jsk_pcl_ros/src/colorize_segmented_RF_nodelet.cpp index ffe0f68d09..68e61568d5 100644 --- a/jsk_pcl_ros/src/colorize_segmented_RF_nodelet.cpp +++ b/jsk_pcl_ros/src/colorize_segmented_RF_nodelet.cpp @@ -72,6 +72,11 @@ namespace jsk_pcl_ros pass_offset2_ = tmp_pass2; } + // pcl removed the method by 1.13, no harm in defining it ourselves to use below +#if __cplusplus >= 201103L +#define pcl_isnan(x) std::isnan(x) +#endif + void ColorizeRandomForest::extract(const sensor_msgs::PointCloud2 pc) { pcl::PointCloud::Ptr cloud (new pcl::PointCloud ()); diff --git a/jsk_pcl_ros/src/edgebased_cube_finder_nodelet.cpp b/jsk_pcl_ros/src/edgebased_cube_finder_nodelet.cpp index be851a0ff7..fba7929ed7 100644 --- a/jsk_pcl_ros/src/edgebased_cube_finder_nodelet.cpp +++ b/jsk_pcl_ros/src/edgebased_cube_finder_nodelet.cpp @@ -115,7 +115,12 @@ namespace jsk_pcl_ros jsk_recognition_utils::ConvexPolygon::Ptr convex (new jsk_recognition_utils::ConvexPolygon(vertices)); return convex; } - + + // pcl removed the method by 1.13, no harm in defining it ourselves to use below +#if __cplusplus >= 201103L +#define pcl_isfinite(x) std::isfinite(x) +#endif + double CubeHypothesis::evaluatePointOnPlanes( const pcl::PointCloud& cloud, jsk_recognition_utils::ConvexPolygon& polygon_a, diff --git a/jsk_pcl_ros/src/geometric_consistency_grouping_nodelet.cpp b/jsk_pcl_ros/src/geometric_consistency_grouping_nodelet.cpp index a86ee8918f..7989dde276 100644 --- a/jsk_pcl_ros/src/geometric_consistency_grouping_nodelet.cpp +++ b/jsk_pcl_ros/src/geometric_consistency_grouping_nodelet.cpp @@ -110,6 +110,11 @@ namespace jsk_pcl_ros pcl::fromROSMsg(*model_feature_msg, *reference_feature_); } + // pcl removed the method by 1.13, no harm in defining it ourselves to use below +#if __cplusplus >= 201103L +#define pcl_isfinite(x) std::isfinite(x) +#endif + void GeometricConsistencyGrouping::recognize( const sensor_msgs::PointCloud2::ConstPtr& scene_cloud_msg, const sensor_msgs::PointCloud2::ConstPtr& scene_feature_msg) diff --git a/jsk_pcl_ros/src/linemod_nodelet.cpp b/jsk_pcl_ros/src/linemod_nodelet.cpp index 90115a3807..b9e924b918 100644 --- a/jsk_pcl_ros/src/linemod_nodelet.cpp +++ b/jsk_pcl_ros/src/linemod_nodelet.cpp @@ -646,6 +646,11 @@ namespace jsk_pcl_ros linemod_in.close(); } + // pcl removed the method by 1.13, no harm in defining it ourselves to use below +#if __cplusplus >= 201103L +#define pcl_isfinite(x) std::isfinite(x) +#endif + void LINEMODDetector::computeCenterOfTemplate( pcl::PointCloud::Ptr cloud, const pcl::SparseQuantizedMultiModTemplate& linemod_template, diff --git a/jsk_pcl_ros/src/organized_statistical_outlier_removal_nodelet.cpp b/jsk_pcl_ros/src/organized_statistical_outlier_removal_nodelet.cpp index 2c9cea7014..5fa2aa7722 100644 --- a/jsk_pcl_ros/src/organized_statistical_outlier_removal_nodelet.cpp +++ b/jsk_pcl_ros/src/organized_statistical_outlier_removal_nodelet.cpp @@ -79,6 +79,11 @@ namespace jsk_pcl_ros std_mul_ = config.stddev; } + // pcl removed the method by 1.13, no harm in defining it ourselves to use below +#if __cplusplus >= 201103L +#define pcl_isfinite(x) std::isfinite(x) +#endif + void OrganizedStatisticalOutlierRemoval::filter(const sensor_msgs::PointCloud2::ConstPtr& msg) { boost::mutex::scoped_lock lock(mutex_); From 6d7fc063069a184c07a5cfc3e171f3a90fdec378 Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Thu, 26 Dec 2024 11:09:06 +0000 Subject: [PATCH 05/10] [ros-o][colorize_random_points_RF_nodelet.cpp] add #include --- jsk_pcl_ros/src/colorize_random_points_RF_nodelet.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_pcl_ros/src/colorize_random_points_RF_nodelet.cpp b/jsk_pcl_ros/src/colorize_random_points_RF_nodelet.cpp index 5dabfc77ee..fb6b674334 100644 --- a/jsk_pcl_ros/src/colorize_random_points_RF_nodelet.cpp +++ b/jsk_pcl_ros/src/colorize_random_points_RF_nodelet.cpp @@ -34,6 +34,7 @@ #include "jsk_pcl_ros/colorize_random_points_RF.h" #include #include +#include namespace jsk_pcl_ros { From 93e11f882ea3dcda89a757aa9305f370a82c3105 Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Thu, 26 Dec 2024 13:28:30 +0000 Subject: [PATCH 06/10] [ros-o] jsk_pcl_ros/CMakeLists.txt, support c++17, skip src/extract_cuboid_particles_top_n_nodelet.cpp, due to undefined reference to 'pcl::FilterIndices::applyFilter(pcl::PointCloud&)' --- jsk_pcl_ros/CMakeLists.txt | 14 ++++++++++++-- 1 file changed, 12 insertions(+), 2 deletions(-) diff --git a/jsk_pcl_ros/CMakeLists.txt b/jsk_pcl_ros/CMakeLists.txt index 985b04abf5..46833c0a7c 100644 --- a/jsk_pcl_ros/CMakeLists.txt +++ b/jsk_pcl_ros/CMakeLists.txt @@ -11,10 +11,13 @@ endif() # check c++11 / c++0x include(CheckCXXCompilerFlag) +check_cxx_compiler_flag("-std=c++17" COMPILER_SUPPORTS_CXX17) check_cxx_compiler_flag("-std=c++14" COMPILER_SUPPORTS_CXX14) check_cxx_compiler_flag("-std=c++11" COMPILER_SUPPORTS_CXX11) check_cxx_compiler_flag("-std=c++0x" COMPILER_SUPPORTS_CXX0X) -if(COMPILER_SUPPORTS_CXX14) +if(COMPILER_SUPPORTS_CXX17) + set(CMAKE_CXX_FLAGS "-std=c++17") +elseif(COMPILER_SUPPORTS_CXX14) set(CMAKE_CXX_FLAGS "-std=c++14") elseif(COMPILER_SUPPORTS_CXX11) set(CMAKE_CXX_FLAGS "-std=c++11") @@ -57,6 +60,7 @@ find_package(PkgConfig) pkg_check_modules(ml_classifiers ml_classifiers QUIET) # only run in hydro find_package(PCL REQUIRED) +message(STATUS "PCL_VERSION : ${PCL_VERSION}") find_package(OpenMP) set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}") set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") @@ -180,8 +184,12 @@ jsk_pcl_nodelet(src/moving_least_square_smoothing_nodelet.cpp "jsk_pcl/MovingLea jsk_pcl_nodelet(src/fisheye_sphere_publisher_nodelet.cpp "jsk_pcl/FisheyeSpherePublisher" "fisheye_sphere_publisher") jsk_pcl_nodelet(src/plane_supported_cuboid_estimator_nodelet.cpp "jsk_pcl/PlaneSupportedCuboidEstimator" "plane_supported_cuboid_estimator") +if(${PCL_VERSION} VERSION_LESS "1.12.0") + # Could not compile on PCL-1.12.0 + # undefined reference to `pcl::FilterIndices::applyFilter(pcl::PointCloud&)' jsk_pcl_nodelet(src/extract_cuboid_particles_top_n_nodelet.cpp "jsk_pcl/ExtractCuboidParticlesTopN" "extract_cuboid_particles_top_n") +endif() jsk_pcl_nodelet(src/interactive_cuboid_likelihood_nodelet.cpp "jsk_pcl/InteractiveCuboidLikelihood" "interactive_cuboid_likelihood") jsk_pcl_nodelet(src/image_rotate_nodelet.cpp @@ -577,7 +585,9 @@ if (CATKIN_ENABLE_TESTING) add_rostest(test/test_edgebased_cube_finder.test) add_rostest(test/test_environment_plane_modeling.test) add_rostest(test/test_euclidean_segmentation.test) - add_rostest(test/test_extract_cuboid_particles_top_n.test) + if(${PCL_VERSION} VERSION_LESS "1.12.0") + add_rostest(test/test_extract_cuboid_particles_top_n.test) + endif() add_rostest(test/test_extract_top_polygon_likelihood.test) add_rostest(test/test_feature_registration.test) add_rostest(test/test_find_object_on_plane.test) From f9dc100c0890d3090c9c4e2e5ee9e601c9228b77 Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Thu, 26 Dec 2024 13:29:52 +0000 Subject: [PATCH 07/10] [ros-o] boost::make_shared -> std::make_shared, use .makeShared() --- .../container_occupancy_detector.h | 7 +++++ .../jsk_pcl_ros/particle_filter_tracking.h | 2 +- .../jsk_pcl_ros/target_adaptive_tracking.h | 1 + .../src/edgebased_cube_finder_nodelet.cpp | 4 +++ .../euclidean_cluster_extraction_nodelet.cpp | 15 ++++++++-- jsk_pcl_ros/src/icp_registration_nodelet.cpp | 14 ++++++++++ .../moving_least_square_smoothing_nodelet.cpp | 3 ++ ...nized_multi_plane_segmentation_nodelet.cpp | 28 +++++++++++++++++++ .../src/particle_filter_tracking_nodelet.cpp | 9 ++---- .../pointcloud_database_server_nodelet.cpp | 1 + .../src/pointcloud_screenpoint_nodelet.cpp | 7 ++--- ...ng_multiple_plane_segmentation_nodelet.cpp | 4 +++ .../region_growing_segmentation_nodelet.cpp | 4 +++ .../src/resize_points_publisher_nodelet.cpp | 4 +++ .../src/supervoxel_segmentation_nodelet.cpp | 8 ++++-- .../src/target_adaptive_tracking_nodelet.cpp | 16 ++++++++--- 16 files changed, 108 insertions(+), 19 deletions(-) diff --git a/jsk_pcl_ros/include/jsk_pcl_ros/container_occupancy_detector.h b/jsk_pcl_ros/include/jsk_pcl_ros/container_occupancy_detector.h index d05afe36cb..6d1e2b15a3 100644 --- a/jsk_pcl_ros/include/jsk_pcl_ros/container_occupancy_detector.h +++ b/jsk_pcl_ros/include/jsk_pcl_ros/container_occupancy_detector.h @@ -107,10 +107,17 @@ namespace jsk_pcl_ros{ tf2_ros::TransformListener* tf_listener_; sensor_msgs::PointCloud2::Ptr transformed_points_msg_ = boost::shared_ptr(new sensor_msgs::PointCloud2); +#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) + pcl::PCLPointCloud2Ptr pcl_pc2_ptr_ = + std::shared_ptr(new pcl::PCLPointCloud2); + pcl::PointCloud::Ptr pcl_xyz_ptr_ = + std::shared_ptr>(new pcl::PointCloud); +#else pcl::PCLPointCloud2Ptr pcl_pc2_ptr_ = boost::shared_ptr(new pcl::PCLPointCloud2); pcl::PointCloud::Ptr pcl_xyz_ptr_ = boost::shared_ptr>(new pcl::PointCloud); +#endif //////////////////////////////////////////////////////// // Diagnostics Variables diff --git a/jsk_pcl_ros/include/jsk_pcl_ros/particle_filter_tracking.h b/jsk_pcl_ros/include/jsk_pcl_ros/particle_filter_tracking.h index f4c85d0476..b92be9bcfd 100644 --- a/jsk_pcl_ros/include/jsk_pcl_ros/particle_filter_tracking.h +++ b/jsk_pcl_ros/include/jsk_pcl_ros/particle_filter_tracking.h @@ -186,7 +186,7 @@ namespace pcl // } if (!change_detector_) - change_detector_ = boost::shared_ptr >(new pcl::octree::OctreePointCloudChangeDetector (change_detector_resolution_)); + pcl::octree::OctreePointCloudChangeDetector *change_detector_ = new pcl::octree::OctreePointCloudChangeDetector (change_detector_resolution_); if (!particles_ || particles_->points.empty ()) initParticles (true); diff --git a/jsk_pcl_ros/include/jsk_pcl_ros/target_adaptive_tracking.h b/jsk_pcl_ros/include/jsk_pcl_ros/target_adaptive_tracking.h index 73bde4f7e5..c85c0469a9 100644 --- a/jsk_pcl_ros/include/jsk_pcl_ros/target_adaptive_tracking.h +++ b/jsk_pcl_ros/include/jsk_pcl_ros/target_adaptive_tracking.h @@ -42,6 +42,7 @@ #include #include #include +#include // for computePairFeatures #include #include #include diff --git a/jsk_pcl_ros/src/edgebased_cube_finder_nodelet.cpp b/jsk_pcl_ros/src/edgebased_cube_finder_nodelet.cpp index fba7929ed7..c66f3789d0 100644 --- a/jsk_pcl_ros/src/edgebased_cube_finder_nodelet.cpp +++ b/jsk_pcl_ros/src/edgebased_cube_finder_nodelet.cpp @@ -756,7 +756,11 @@ namespace jsk_pcl_ros *points_on_edges = *points_on_edges + *points_on_edge; cubes.push_back(cube); } +#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) + pub_debug_filtered_cloud_.publish(*points_on_edges); +#else pub_debug_filtered_cloud_.publish(points_on_edges); +#endif } } diff --git a/jsk_pcl_ros/src/euclidean_cluster_extraction_nodelet.cpp b/jsk_pcl_ros/src/euclidean_cluster_extraction_nodelet.cpp index e1cac93e4d..a655d0a236 100644 --- a/jsk_pcl_ros/src/euclidean_cluster_extraction_nodelet.cpp +++ b/jsk_pcl_ros/src/euclidean_cluster_extraction_nodelet.cpp @@ -140,7 +140,9 @@ namespace jsk_pcl_ros EuclideanClusterExtraction impl; if (filtered_cloud->points.size() > 0) { jsk_topic_tools::ScopedTimer timer = kdtree_acc_.scopedTimer(); -#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 ) +#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) + pcl::search::KdTree::Ptr tree (new pcl::search::KdTree()); +#elif ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 ) pcl::search::KdTree::Ptr tree (new pcl::search::KdTree); tree = boost::make_shared< pcl::search::KdTree > (); #else @@ -332,7 +334,9 @@ namespace jsk_pcl_ros pcl::PointCloud::Ptr cloud (new pcl::PointCloud); pcl::fromROSMsg(req.input, *cloud); -#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 ) +#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) + pcl::search::KdTree::Ptr tree (new pcl::search::KdTree ()); +#elif ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 ) pcl::search::KdTree::Ptr tree (new pcl::search::KdTree); tree = boost::make_shared< pcl::search::KdTree > (); #else @@ -361,12 +365,19 @@ namespace jsk_pcl_ros pcl_conversions::toPCL(req.input, *pcl_cloud); pcl::ExtractIndices ex; ex.setInputCloud(pcl_cloud); +#elif ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) + pcl::ExtractIndices ex; + ex.setInputCloud ( req.input.makeShared() ); #else pcl::ExtractIndices ex; ex.setInputCloud ( boost::make_shared< sensor_msgs::PointCloud2 > (req.input) ); #endif for ( size_t i = 0; i < cluster_indices.size(); i++ ) { +#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) + ex.setIndices ( std::make_shared< pcl::PointIndices > (cluster_indices[i]) ); +#else ex.setIndices ( boost::make_shared< pcl::PointIndices > (cluster_indices[i]) ); +#endif ex.setNegative ( false ); #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 7 ) pcl::PCLPointCloud2 output_cloud; diff --git a/jsk_pcl_ros/src/icp_registration_nodelet.cpp b/jsk_pcl_ros/src/icp_registration_nodelet.cpp index 016a862326..3fb2195122 100644 --- a/jsk_pcl_ros/src/icp_registration_nodelet.cpp +++ b/jsk_pcl_ros/src/icp_registration_nodelet.cpp @@ -592,6 +592,12 @@ namespace jsk_pcl_ros pcl::PointCloud::Ptr& output_cloud, Eigen::Affine3d& output_transform) { +#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) + pcl::GeneralizedIterativeClosestPoint icp; + icp.setRotationEpsilon(rotation_epsilon_); + icp.setCorrespondenceRandomness(correspondence_randomness_); + icp.setMaximumOptimizerIterations(maximum_optimizer_iterations_); +#else pcl::IterativeClosestPoint icp; if (use_normal_) { pcl::IterativeClosestPointWithNormals icp_with_normal; @@ -606,6 +612,7 @@ namespace jsk_pcl_ros gicp.setMaximumOptimizerIterations(maximum_optimizer_iterations_); icp = gicp; } +#endif if (correspondence_algorithm_ == 1) { // Projective if (!camera_info_msg_) { NODELET_ERROR("no camera info is available yet"); @@ -636,10 +643,17 @@ namespace jsk_pcl_ros icp.setInputTarget(cloud); if (transform_3dof_) { +#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) + pcl::registration::WarpPointRigid3D::Ptr warp_func + (new pcl::registration::WarpPointRigid3D); + pcl::registration::TransformationEstimationLM::Ptr te + (new pcl::registration::TransformationEstimationLM); +#else boost::shared_ptr > warp_func (new pcl::registration::WarpPointRigid3D); boost::shared_ptr > te (new pcl::registration::TransformationEstimationLM); +#endif te->setWarpFunction(warp_func); icp.setTransformationEstimation(te); } diff --git a/jsk_pcl_ros/src/moving_least_square_smoothing_nodelet.cpp b/jsk_pcl_ros/src/moving_least_square_smoothing_nodelet.cpp index e01ea5ae4d..93d41a7299 100644 --- a/jsk_pcl_ros/src/moving_least_square_smoothing_nodelet.cpp +++ b/jsk_pcl_ros/src/moving_least_square_smoothing_nodelet.cpp @@ -39,6 +39,7 @@ #include #include "jsk_recognition_utils/pcl_conversion_util.h" +#include // for KdTree namespace jsk_pcl_ros { @@ -56,7 +57,9 @@ namespace jsk_pcl_ros pcl::MovingLeastSquares smoother; smoother.setSearchRadius (search_radius_); if (gauss_param_set_) smoother.setSqrGaussParam (gauss_param_set_); +#if PCL_VERSION_COMPARE (<, 1, 9, 0) // https://github.com/PointCloudLibrary/pcl/blob/cc08f815a9a5f2a1d3f897fb2bc9d541635792c9/CHANGES.md?plain=1#L1633 smoother.setPolynomialFit (use_polynomial_fit_); +#endif smoother.setPolynomialOrder (polynomial_order_); smoother.setComputeNormals (calc_normal_); diff --git a/jsk_pcl_ros/src/organized_multi_plane_segmentation_nodelet.cpp b/jsk_pcl_ros/src/organized_multi_plane_segmentation_nodelet.cpp index d04bd9b521..3a7841b922 100644 --- a/jsk_pcl_ros/src/organized_multi_plane_segmentation_nodelet.cpp +++ b/jsk_pcl_ros/src/organized_multi_plane_segmentation_nodelet.cpp @@ -246,10 +246,17 @@ namespace jsk_pcl_ros // compute the distance between two boundaries. // if they are near enough, we can regard these two map should connect +#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) + pcl::PointIndices::Ptr a_indices + = std::make_shared(boundary_indices[i]); + pcl::PointIndices::Ptr b_indices + = std::make_shared(boundary_indices[j]); +#else pcl::PointIndices::Ptr a_indices = boost::make_shared(boundary_indices[i]); pcl::PointIndices::Ptr b_indices = boost::make_shared(boundary_indices[j]); +#endif pcl::PointCloud a_cloud, b_cloud; extract.setIndices(a_indices); extract.filter(a_cloud); @@ -364,10 +371,17 @@ namespace jsk_pcl_ros pcl::ModelCoefficients pcl_new_coefficients; pcl_new_coefficients.values = new_coefficients; // estimate concave hull +#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) + pcl::PointIndices::Ptr indices_ptr + = std::make_shared(one_boundaries); + pcl::ModelCoefficients::Ptr coefficients_ptr + = std::make_shared(pcl_new_coefficients); +#else pcl::PointIndices::Ptr indices_ptr = boost::make_shared(one_boundaries); pcl::ModelCoefficients::Ptr coefficients_ptr = boost::make_shared(pcl_new_coefficients); +#endif jsk_recognition_utils::ConvexPolygon::Ptr convex = jsk_recognition_utils::convexFromCoefficientsAndInliers( input, indices_ptr, coefficients_ptr); @@ -478,7 +492,11 @@ namespace jsk_pcl_ros for (size_t i = 0; i < boundary_indices.size(); i++) { pcl::PointCloud boundary_cloud; pcl::PointIndices boundary_one_indices = boundary_indices[i]; +#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) + pcl::PointIndices::Ptr indices_ptr = std::make_shared(boundary_indices[i]); +#else pcl::PointIndices::Ptr indices_ptr = boost::make_shared(boundary_indices[i]); +#endif extract.setIndices(indices_ptr); extract.filter(boundary_cloud); boundaries.push_back(boundary_cloud); @@ -510,8 +528,13 @@ namespace jsk_pcl_ros //////////////////////////////////////////////////////// jsk_recognition_utils::Vertices centroids; for (size_t i = 0; i < inliers.size(); i++) { +#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) + pcl::PointIndices::Ptr target_inliers + = std::make_shared(inliers[i]); +#else pcl::PointIndices::Ptr target_inliers = boost::make_shared(inliers[i]); +#endif pcl::PointCloud::Ptr target_cloud (new pcl::PointCloud); Eigen::Vector4f centroid; pcl::ExtractIndices ex; @@ -640,8 +663,13 @@ namespace jsk_pcl_ros jsk_topic_tools::ScopedTimer timer = ransac_refinement_time_acc_.scopedTimer(); for (size_t i = 0; i < input_indices.size(); i++) { +#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) + pcl::PointIndices::Ptr input_indices_ptr + = std::make_shared(input_indices[i]); +#else pcl::PointIndices::Ptr input_indices_ptr = boost::make_shared(input_indices[i]); +#endif Eigen::Vector3f normal(input_coefficients[i].values[0], input_coefficients[i].values[1], input_coefficients[i].values[2]); diff --git a/jsk_pcl_ros/src/particle_filter_tracking_nodelet.cpp b/jsk_pcl_ros/src/particle_filter_tracking_nodelet.cpp index 9c55c45728..43b27ade27 100644 --- a/jsk_pcl_ros/src/particle_filter_tracking_nodelet.cpp +++ b/jsk_pcl_ros/src/particle_filter_tracking_nodelet.cpp @@ -145,19 +145,16 @@ namespace jsk_pcl_ros } - boost::shared_ptr > - distance_coherence(new DistanceCoherence); + DistanceCoherence::Ptr distance_coherence(new DistanceCoherence); coherence->addPointCoherence(distance_coherence); //add HSV coherence if (use_hsv) { - boost::shared_ptr > hsv_color_coherence - = boost::shared_ptr >(new HSVColorCoherence()); + HSVColorCoherence::Ptr hsv_color_coherence(new HSVColorCoherence()); coherence->addPointCoherence(hsv_color_coherence); } - boost::shared_ptr > search - (new pcl::search::Octree(octree_resolution)); + pcl::search::Octree::Ptr search(new pcl::search::Octree(octree_resolution)); //boost::shared_ptr > search(new pcl::search::KdTree()); coherence->setSearchMethod(search); double max_distance; diff --git a/jsk_pcl_ros/src/pointcloud_database_server_nodelet.cpp b/jsk_pcl_ros/src/pointcloud_database_server_nodelet.cpp index fa7ae6acf0..4eb3dcdc72 100644 --- a/jsk_pcl_ros/src/pointcloud_database_server_nodelet.cpp +++ b/jsk_pcl_ros/src/pointcloud_database_server_nodelet.cpp @@ -39,6 +39,7 @@ #include #include #include "jsk_recognition_utils/pcl_conversion_util.h" +#include namespace jsk_pcl_ros { diff --git a/jsk_pcl_ros/src/pointcloud_screenpoint_nodelet.cpp b/jsk_pcl_ros/src/pointcloud_screenpoint_nodelet.cpp index 4f1a334924..c27bb84c83 100644 --- a/jsk_pcl_ros/src/pointcloud_screenpoint_nodelet.cpp +++ b/jsk_pcl_ros/src/pointcloud_screenpoint_nodelet.cpp @@ -49,7 +49,7 @@ void PointcloudScreenpoint::onInit() ConnectionBasedNodelet::onInit(); - normals_tree_ = boost::make_shared< pcl::search::KdTree< pcl::PointXYZ > > (); + pcl::search::KdTree::Ptr normals_tree_(new pcl::search::KdTree); n3d_.setSearchMethod (normals_tree_); dyn_srv_ = boost::make_shared< dynamic_reconfigure::Server< Config > >(*pnh_); @@ -257,8 +257,7 @@ bool PointcloudScreenpoint::screenpoint_cb ( } // search normal - n3d_.setSearchSurface( - boost::make_shared > (latest_cloud_)); + n3d_.setSearchSurface(latest_cloud_.makeShared()); pcl::PointCloud cloud_; pcl::PointXYZ pt; @@ -268,7 +267,7 @@ bool PointcloudScreenpoint::screenpoint_cb ( cloud_.points.resize(0); cloud_.points.push_back(pt); - n3d_.setInputCloud (boost::make_shared > (cloud_)); + n3d_.setInputCloud (cloud_.makeShared()); pcl::PointCloud cloud_normals; n3d_.compute (cloud_normals); diff --git a/jsk_pcl_ros/src/region_growing_multiple_plane_segmentation_nodelet.cpp b/jsk_pcl_ros/src/region_growing_multiple_plane_segmentation_nodelet.cpp index 05381374b5..be966a4ed5 100644 --- a/jsk_pcl_ros/src/region_growing_multiple_plane_segmentation_nodelet.cpp +++ b/jsk_pcl_ros/src/region_growing_multiple_plane_segmentation_nodelet.cpp @@ -204,7 +204,11 @@ namespace jsk_pcl_ros for (size_t i = 0; i < clusters->size(); i++) { pcl::PointIndices::Ptr plane_inliers(new pcl::PointIndices); pcl::ModelCoefficients::Ptr plane_coefficients(new pcl::ModelCoefficients); +#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) + pcl::PointIndices::Ptr cluster = std::make_shared((*clusters)[i]); +#else pcl::PointIndices::Ptr cluster = boost::make_shared((*clusters)[i]); +#endif ransacEstimation(cloud, cluster, *plane_inliers, *plane_coefficients); if (plane_inliers->indices.size() > 0) { diff --git a/jsk_pcl_ros/src/region_growing_segmentation_nodelet.cpp b/jsk_pcl_ros/src/region_growing_segmentation_nodelet.cpp index c373f2d7c4..de6850bce1 100644 --- a/jsk_pcl_ros/src/region_growing_segmentation_nodelet.cpp +++ b/jsk_pcl_ros/src/region_growing_segmentation_nodelet.cpp @@ -89,7 +89,11 @@ namespace jsk_pcl_ros void RegionGrowingSegmentation::segment(const sensor_msgs::PointCloud2::ConstPtr& msg) { boost::mutex::scoped_lock lock(mutex_); +#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) + pcl::search::Search::Ptr tree(new pcl::search::KdTree()); +#else pcl::search::Search::Ptr tree = boost::shared_ptr > (new pcl::search::KdTree); +#endif pcl::PointCloud cloud; pcl::fromROSMsg(*msg, cloud); diff --git a/jsk_pcl_ros/src/resize_points_publisher_nodelet.cpp b/jsk_pcl_ros/src/resize_points_publisher_nodelet.cpp index 9eeb105a89..ebb35d45ec 100644 --- a/jsk_pcl_ros/src/resize_points_publisher_nodelet.cpp +++ b/jsk_pcl_ros/src/resize_points_publisher_nodelet.cpp @@ -184,7 +184,11 @@ namespace jsk_pcl_ros } pcl::ExtractIndices extract; extract.setInputCloud (pcl_input_cloud.makeShared()); +#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) + extract.setIndices (std::make_shared > (ex_indices)); +#else extract.setIndices (boost::make_shared > (ex_indices)); +#endif extract.setNegative (false); extract.filter (output); diff --git a/jsk_pcl_ros/src/supervoxel_segmentation_nodelet.cpp b/jsk_pcl_ros/src/supervoxel_segmentation_nodelet.cpp index 3eba32ee8c..2c0eb57b19 100644 --- a/jsk_pcl_ros/src/supervoxel_segmentation_nodelet.cpp +++ b/jsk_pcl_ros/src/supervoxel_segmentation_nodelet.cpp @@ -72,8 +72,12 @@ namespace jsk_pcl_ros pcl::PointCloud::Ptr cloud (new pcl::PointCloud); pcl::fromROSMsg(*cloud_msg, *cloud); pcl::SupervoxelClustering super(voxel_resolution_, - seed_resolution_, - use_transform_); + seed_resolution_ +#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) + ); +#else + , use_transform_); +#endif super.setInputCloud(cloud); super.setColorImportance(color_importance_); super.setSpatialImportance(spatial_importance_); diff --git a/jsk_pcl_ros/src/target_adaptive_tracking_nodelet.cpp b/jsk_pcl_ros/src/target_adaptive_tracking_nodelet.cpp index 3f0126b080..8ddca9f8bb 100644 --- a/jsk_pcl_ros/src/target_adaptive_tracking_nodelet.cpp +++ b/jsk_pcl_ros/src/target_adaptive_tracking_nodelet.cpp @@ -1782,8 +1782,12 @@ namespace jsk_pcl_ros boost::mutex::scoped_lock lock(mutex_); pcl::SupervoxelClustering super( voxel_resolution_, - static_cast(seed_resolution), - use_transform_); + static_cast(seed_resolution) +#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) + ); +#else + , use_transform_); +#endif super.setInputCloud(cloud); super.setColorImportance(color_importance_); super.setSpatialImportance(spatial_importance_); @@ -1804,8 +1808,12 @@ namespace jsk_pcl_ros } boost::mutex::scoped_lock lock(mutex_); pcl::SupervoxelClustering super(voxel_resolution_, - seed_resolution_, - use_transform_); + seed_resolution_ +#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) + ); +#else + , use_transform_); +#endif super.setInputCloud(cloud); super.setColorImportance(color_importance_); super.setSpatialImportance(spatial_importance_); From 335addd77aabd67819c337cd130fc1c589f22959 Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Thu, 26 Dec 2024 13:30:36 +0000 Subject: [PATCH 08/10] [ros-o] sound_classification: use Python3 and requirements.in.obase --- sound_classification/CMakeLists.txt | 9 +++++++++ sound_classification/requirements.in.obase | 3 +++ 2 files changed, 12 insertions(+) create mode 100644 sound_classification/requirements.in.obase diff --git a/sound_classification/CMakeLists.txt b/sound_classification/CMakeLists.txt index 3dafdddebd..816dacd072 100644 --- a/sound_classification/CMakeLists.txt +++ b/sound_classification/CMakeLists.txt @@ -29,10 +29,19 @@ catkin_package( message_runtime ) +if("$ENV{ROS_DISTRO}" STREQUAL "indigo" OR "$ENV{ROS_DISTRO}" STREQUAL "kinetic" OR + "$ENV{ROS_DISTRO}" STREQUAL "melodic" OR "$ENV{ROS_DISTRO}" STREQUAL "noetic") catkin_generate_virtualenv( PYTHON_INTERPRETER python2 INPUT_REQUIREMENTS requirements.in ) +else() +execute_process(COMMAND cmake -E remove ${PROJECT_SOURCE_DIR}/requirements.txt) +catkin_generate_virtualenv( + PYTHON_INTERPRETER python3 + INPUT_REQUIREMENTS requirements.in.obase + ) +endif() file(GLOB SCRIPTS_FILES scripts/*.py) catkin_install_python( diff --git a/sound_classification/requirements.in.obase b/sound_classification/requirements.in.obase new file mode 100644 index 0000000000..6aab3c2c1a --- /dev/null +++ b/sound_classification/requirements.in.obase @@ -0,0 +1,3 @@ +chainer # For Python 2.x, chainer 5.x.x is needed, 7.0.0 will not work on Python2 +numpy<2.0 +cv_bridge From 8e2df18af1bc789b119b31343942e27b491c059a Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Fri, 27 Dec 2024 11:01:41 +0000 Subject: [PATCH 09/10] [ros-o] .github/workflows/config.yml add 22.04 check --- .github/workflows/config.yml | 59 ++++++++++++++++++++++++++++++++++++ 1 file changed, 59 insertions(+) diff --git a/.github/workflows/config.yml b/.github/workflows/config.yml index 3a9120b1dc..9838b0a103 100644 --- a/.github/workflows/config.yml +++ b/.github/workflows/config.yml @@ -141,3 +141,62 @@ jobs: USE_JENKINS : ${{ matrix.USE_JENKINS }} DOCKER_IMAGE_JENKINS : ${{ matrix.DOCKER_IMAGE_JENKINS }} TIMEOUT_JENKINS : 180 + +# ROS-O setup https://github.com/v4hn/ros-o-builder/blob/jammy-one/README.md#install-instructions + ros-o: + runs-on: ubuntu-latest + + strategy: + fail-fast: false + matrix: + include: + - DISTRO: ubuntu:22.04 + ROS_REPOSITORY_URL: https://raw.githubusercontent.com/v4hn/ros-o-builder/jammy-one/repository + + container: ${{ matrix.DISTRO }} + + env: + DEBIAN_FRONTEND : noninteractive + + steps: + - name: Chcekout Source + uses: actions/checkout@v3.0.2 + + - name: Setup ROS-O deb repository + run: | + set -x + apt update && apt install -qq -y ca-certificates + echo "deb [trusted=yes] ${{ matrix.ROS_REPOSITORY_URL }}/ ./" | tee /etc/apt/sources.list.d/ros-o-builder.list + apt update + apt install -qq -y python3-rosdep2 + echo "yaml ${{ matrix.ROS_REPOSITORY_URL }}/local.yaml debian" | tee /etc/ros/rosdep/sources.list.d/1-ros-o-builder.list + rosdep update + + - name: Setup catkin-tools + run: | + set -x + # setup catkin tools + apt install -qq -y python3-pip + pip3 install catkin-tools + # setup build tools + apt install -qq -y cmake build-essential catkin ros-one-rosbash + + - name: Setup Workspace + run: | + source /opt/ros/one/setup.bash + set -x + # setup workspace + mkdir -p ~/ws/src + cd ~/ws/src + ln -sf $GITHUB_WORKSPACE . + rosdep install -qq -r -y --from-path . --ignore-src || echo "OK" + shell: bash + + - name: Compile Packages + run: | + source /opt/ros/one/setup.bash + set -x + cd ~/ws/ + catkin build --no-status -sv ${{ matrix.CATKIN_OPTIONS }} --cmake-args -DCATKIN_ENABLE_TESTING=OFF -DCMAKE_VERBOSE_MAKEFILE:BOOL=ON ${{ matrix.CMAKE_OPTIONS }} + shell: bash + From 9822d35c95b2a436f961db45a07dad35dc2718c9 Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Sat, 28 Dec 2024 03:26:33 +0000 Subject: [PATCH 10/10] [ros-o] .github/workflows/config.yml download unreleased files --- .github/workflows/config.yml | 23 +++++++++++++++++++++++ 1 file changed, 23 insertions(+) diff --git a/.github/workflows/config.yml b/.github/workflows/config.yml index 9838b0a103..fa16ca55a9 100644 --- a/.github/workflows/config.yml +++ b/.github/workflows/config.yml @@ -159,8 +159,14 @@ jobs: DEBIAN_FRONTEND : noninteractive steps: + - name: Install git on container + run: | + apt update && apt install -y -q -qq git + - name: Chcekout Source uses: actions/checkout@v3.0.2 + with: + submodules: recursive - name: Setup ROS-O deb repository run: | @@ -181,6 +187,23 @@ jobs: # setup build tools apt install -qq -y cmake build-essential catkin ros-one-rosbash + - name: Download unreleased files + run: | + source /opt/ros/one/setup.bash + set -x + apt install -qq -y git wget + mkdir -p ~/ws/src + cd ~/ws/src + # rosinstall_generator libsiftfast --rosdistro noetic + git clone https://github.com/tork-a/jsk_3rdparty-release.git -b release/noetic/libsiftfast/2.1.28-1 + wget https://github.com/jsk-ros-pkg/jsk_3rdparty/commit/cafbff6dd2bd7869eb4f989bedd0a322a7c35d50.diff -O 1.patch + wget https://github.com/jsk-ros-pkg/jsk_3rdparty/commit/c8eb21e211d1a8f803cd55549a5b2bdc87e6ff9f.diff -O 2.patch + patch -d jsk_3rdparty-release -p3 < 1.patch + patch -d jsk_3rdparty-release -p3 < 2.patch + # rosinstall_generator jsk_topic_tools --rosdistro noetic + git clone https://github.com/tork-a/jsk_common-release.git -b release/noetic/jsk_topic_tools/2.2.15-4 + shell: bash + - name: Setup Workspace run: | source /opt/ros/one/setup.bash