From 706c020528b66e772e3f86ff5acc88191b415419 Mon Sep 17 00:00:00 2001 From: Markus Vieth <39675748+mvieth@users.noreply.github.com> Date: Sat, 22 Aug 2020 20:04:21 +0200 Subject: [PATCH] Deprecate use_polynomial_fit (#305) The pcl function setPolynomialFit is deprecated, setPolynomialOrder should be used instead --- pcl_ros/src/pcl_ros/surface/moving_least_squares.cpp | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/pcl_ros/src/pcl_ros/surface/moving_least_squares.cpp b/pcl_ros/src/pcl_ros/surface/moving_least_squares.cpp index f48391d4..c05cbbb6 100644 --- a/pcl_ros/src/pcl_ros/surface/moving_least_squares.cpp +++ b/pcl_ros/src/pcl_ros/surface/moving_least_squares.cpp @@ -244,7 +244,19 @@ pcl_ros::MovingLeastSquares::config_callback(MLSConfig & config, uint32_t level) NODELET_DEBUG( "[config_callback] Setting the use_polynomial_fit flag to: %d.", use_polynomial_fit_); +#if PCL_VERSION_COMPARE(<, 1, 9, 0) impl_.setPolynomialFit(use_polynomial_fit_); +#else + if (use_polynomial_fit_) { + NODELET_WARN( + "[config_callback] use_polynomial_fit is deprecated, use polynomial_order instead!"); + if (impl_.getPolynomialOrder() < 2) { + impl_.setPolynomialOrder(2); + } + } else { + impl_.setPolynomialOrder(0); + } +#endif } if (polynomial_order_ != config.polynomial_order) { polynomial_order_ = config.polynomial_order;