diff --git a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp index cd0033d368..252d2a98d6 100644 --- a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp +++ b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp @@ -43,13 +43,21 @@ #include #include -// TODO(henningkayser): Switch to boost/timer/progress_display.hpp with Boost 1.72 -// boost/progress.hpp is deprecated and will be replaced by boost/timer/progress_display.hpp in Boost 1.72. -// Until then we need to suppress the deprecation warning. -#define BOOST_ALLOW_DEPRECATED_HEADERS #include + +#if __has_include() +#include +using boost_progress_display = boost::timer::progress_display; +#else +// boost < 1.72 +#define BOOST_TIMER_ENABLE_DEPRECATED 1 #include -#undef BOOST_ALLOW_DEPRECATED_HEADERS +#undef BOOST_TIMER_ENABLE_DEPRECATED +using boost_progress_display = boost::progress_display; +#endif + +#include +#include #include #include #include @@ -776,7 +784,7 @@ void BenchmarkExecutor::runBenchmark(moveit_msgs::msg::MotionPlanRequest request } num_planners += options.parallel_planning_pipelines.size(); - boost::progress_display progress(num_planners * options.runs, std::cout); + boost_progress_display progress(num_planners * options.runs, std::cout); // Iterate through all planning pipelines auto planning_pipelines = moveit_cpp_->getPlanningPipelines();