From 4b734ae9353c177f0908022d6682ad6839908fed Mon Sep 17 00:00:00 2001 From: Stephanie Eng Date: Wed, 24 Apr 2024 12:32:31 -0400 Subject: [PATCH] Update deprecated include of boost/progress.hpp to boost/timer/progress_display.hpp --- moveit_ros/benchmarks/src/BenchmarkExecutor.cpp | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp index cd0033d368..50760073fd 100644 --- a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp +++ b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp @@ -43,13 +43,10 @@ #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 -#include #undef BOOST_ALLOW_DEPRECATED_HEADERS +#include #include #include #include @@ -776,7 +773,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::timer::progress_display progress(num_planners * options.runs, std::cout); // Iterate through all planning pipelines auto planning_pipelines = moveit_cpp_->getPlanningPipelines();