Skip to content

Commit

Permalink
Simplify deprecation macros
Browse files Browse the repository at this point in the history
I simplified the code for the deprecation macro so that it easier to
understand and to use. There is now only one macro PCL_DEPRECATED which
you use the same way as you would use [[deprecated(message)]] i.e. it
always needs a message, although it can be an empty string.
To be able to remove the other macros we needed to ignore the
deprecation for Visual Studio 2013 and below because of a different
syntax when using __declspec(deprecated) in combination with the 'using'
keyword when creating a type alias.
  • Loading branch information
flowvision committed Feb 21, 2020
1 parent f971727 commit 6292eaa
Show file tree
Hide file tree
Showing 18 changed files with 62 additions and 78 deletions.
8 changes: 4 additions & 4 deletions common/include/pcl/common/io.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ namespace pcl
* \ingroup common
*/
template <typename PointT>
PCL_DEPRECATED_MESSAGE("use getFieldIndex<PointT> (field_name, fields) instead")
PCL_DEPRECATED("use getFieldIndex<PointT> (field_name, fields) instead")
inline int
getFieldIndex (const pcl::PointCloud<PointT> &cloud, const std::string &field_name,
std::vector<pcl::PCLPointField> &fields);
Expand Down Expand Up @@ -106,7 +106,7 @@ namespace pcl
* \ingroup common
*/
template <typename PointT>
PCL_DEPRECATED_MESSAGE("use getFields<PointT> () with return value instead")
PCL_DEPRECATED("use getFields<PointT> () with return value instead")
inline void
getFields (const pcl::PointCloud<PointT> &cloud, std::vector<pcl::PCLPointField> &fields);

Expand All @@ -116,7 +116,7 @@ namespace pcl
* \ingroup common
*/
template <typename PointT>
PCL_DEPRECATED_MESSAGE("use getFields<PointT> () with return value instead")
PCL_DEPRECATED("use getFields<PointT> () with return value instead")
inline void
getFields (std::vector<pcl::PCLPointField> &fields);

Expand Down Expand Up @@ -328,7 +328,7 @@ namespace pcl
* \return true if successful, false otherwise (e.g., name/number of fields differs)
* \ingroup common
*/
PCL_DEPRECATED_MESSAGE("use pcl::concatenate() instead, but beware of subtle difference in behavior (see documentation)")
PCL_DEPRECATED("use pcl::concatenate() instead, but beware of subtle difference in behavior (see documentation)")
PCL_EXPORTS bool
concatenatePointCloud (const pcl::PCLPointCloud2 &cloud1,
const pcl::PCLPointCloud2 &cloud2,
Expand Down
4 changes: 2 additions & 2 deletions common/include/pcl/impl/point_types.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -1155,11 +1155,11 @@ namespace pcl

inline PointWithViewpoint (): PointWithViewpoint (0.f, 0.f, 0.f) {}

PCL_DEPRECATED_MESSAGE("Use ctor accepting all position (x, y, z) data")
PCL_DEPRECATED("Use ctor accepting all position (x, y, z) data")
inline PointWithViewpoint (float _x, float _y = 0.f):
PointWithViewpoint (_x, _y, 0.f) {}

PCL_DEPRECATED_MESSAGE("Use ctor accepting all viewpoint (vp_x, vp_y, vp_z) data")
PCL_DEPRECATED("Use ctor accepting all viewpoint (vp_x, vp_y, vp_z) data")
inline PointWithViewpoint (float _x, float _y, float _z, float _vp_x, float _vp_y = 0.f):
PointWithViewpoint (_x, _y, _z, _vp_x, _vp_y, 0.f) {}

Expand Down
58 changes: 21 additions & 37 deletions common/include/pcl/pcl_macros.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,34 +76,18 @@

#include <pcl/pcl_config.h>

#define PCL_SINGLE_ARG(...) __VA_ARGS__

#if (defined(__CUDACC__) && defined(_MSC_VER))
// No version of the 'deprecated' attribute works when
// compiling with nvcc under Windows until atleast CUDA 10.2.
// When this is fixed we can correctly define the attribute.
#define PCL_DEPRECATED
#define PCL_DEPRECATED_MESSAGE(message)
#define PCL_DEPRECATED_USING(identifier, type, message) using identifier = type
#elif (__cplusplus >= 201402L || (defined(_MSC_VER) && (_MSC_VER >= 1900) && (_MSVC_LANG >= 201402L)))
#define PCL_DEPRECATED [[deprecated]]
#define PCL_DEPRECATED_MESSAGE(message) [[deprecated(message)]]
#define PCL_DEPRECATED_USING(identifier, type, message) using identifier [[deprecated(message)]] = type
#elif defined(__GNUC__)
#define PCL_DEPRECATED __attribute__((deprecated))
// TODO Is there some way to implement this?
#define PCL_DEPRECATED_MESSAGE(message) __attribute__((deprecated))
#define PCL_DEFINE_DEPRECATED_USING(identifier, type, message) using identifier __attribute__((deprecated(message))) = type
#if defined(__has_cpp_attribute) && __has_cpp_attribute(deprecated)
#define PCL_DEPRECATED(message) [[deprecated(message)]]
#elif defined(__GNUC__) || defined(__clang__)
#define PCL_DEPRECATED(message) __attribute__((deprecated(message)))
#elif defined(_MSC_VER)
#define PCL_DEPRECATED __declspec(deprecated)
#define PCL_DEPRECATED_MESSAGE(message) __declspec(deprecated(message))
// __declspec doesn't work with using keyword
#define PCL_DEPRECATED_USING(identifier, type, message) using identifier = type
// Until Visual Studio 2013 you had to use __declspec(deprecated).
// However, we decided to ignore the deprecation for these version because
// of simplicity reasons. See PR #3634 for the details.
#define PCL_DEPRECATED(message)
#else
#warning "You need to implement PCL_DEPRECATED for this compiler"
#define PCL_DEPRECATED
#define PCL_DEPRECATED_MESSAGE(message)
#define PCL_DEPRECATED_USING(identifier, type, message) using identifier = type
#define PCL_DEPRECATED(message)
#endif

namespace pcl
Expand All @@ -119,15 +103,15 @@ namespace pcl
template <typename T>
using shared_ptr = boost::shared_ptr<T>;

PCL_DEPRECATED_USING(uint8_t, std::uint8_t, "use std::uint8_t instead of pcl::uint8_t");
PCL_DEPRECATED_USING(int8_t, std::int8_t, "use std::int8_t instead of pcl::int8_t");
PCL_DEPRECATED_USING(uint16_t, std::uint16_t, "use std::uint16_t instead of pcl::uint16_t");
PCL_DEPRECATED_USING(int16_t, std::int16_t, "use std::uint16_t instead of pcl::int16_t");
PCL_DEPRECATED_USING(uint32_t, std::uint32_t, "use std::uint32_t instead of pcl::uint32_t");
PCL_DEPRECATED_USING(int32_t, std::int32_t, "use std::int32_t instead of pcl::int32_t");
PCL_DEPRECATED_USING(uint64_t, std::uint64_t, "use std::uint64_t instead of pcl::uint64_t");
PCL_DEPRECATED_USING(int64_t, std::int64_t, "use std::int64_t instead of pcl::int64_t");
PCL_DEPRECATED_USING(int_fast16_t, std::int_fast16_t, "use std::int_fast16_t instead of pcl::int_fast16_t");
using uint8_t PCL_DEPRECATED("use std::uint8_t instead of pcl::uint8_t") = std::uint8_t;
using int8_t PCL_DEPRECATED("use std::int8_t instead of pcl::int8_t") = std::int8_t;
using uint16_t PCL_DEPRECATED("use std::uint16_t instead of pcl::uint16_t") = std::uint16_t;
using int16_t PCL_DEPRECATED("use std::uint16_t instead of pcl::int16_t") = std::int16_t;
using uint32_t PCL_DEPRECATED("use std::uint32_t instead of pcl::uint32_t") = std::uint32_t;
using int32_t PCL_DEPRECATED("use std::int32_t instead of pcl::int32_t") = std::int32_t;
using uint64_t PCL_DEPRECATED("use std::uint64_t instead of pcl::uint64_t") = std::uint64_t;
using int64_t PCL_DEPRECATED("use std::int64_t instead of pcl::int64_t") = std::int64_t;
using int_fast16_t PCL_DEPRECATED("use std::int_fast16_t instead of pcl::int_fast16_t") = std::int_fast16_t;
}

#if defined _WIN32 && defined _MSC_VER
Expand Down Expand Up @@ -164,15 +148,15 @@ namespace pcl


template<typename T>
PCL_DEPRECATED_MESSAGE("use std::isnan instead of pcl_isnan")
PCL_DEPRECATED("use std::isnan instead of pcl_isnan")
bool pcl_isnan (T&& x) { return std::isnan (std::forward<T> (x)); }

template<typename T>
PCL_DEPRECATED_MESSAGE("use std::isfinite instead of pcl_isfinite")
PCL_DEPRECATED("use std::isfinite instead of pcl_isfinite")
bool pcl_isfinite (T&& x) { return std::isfinite (std::forward<T> (x)); }

template<typename T>
PCL_DEPRECATED_MESSAGE("use std::isinf instead of pcl_isinf")
PCL_DEPRECATED("use std::isinf instead of pcl_isinf")
bool pcl_isinf (T&& x) { return std::isinf (std::forward<T> (x)); }


Expand Down
4 changes: 2 additions & 2 deletions common/include/pcl/point_cloud.h
Original file line number Diff line number Diff line change
Expand Up @@ -138,7 +138,7 @@ namespace pcl
namespace detail
{
template <typename PointT>
PCL_DEPRECATED_MESSAGE("use createMapping() instead")
PCL_DEPRECATED("use createMapping() instead")
shared_ptr<pcl::MsgFieldMap>&
getMapping (pcl::PointCloud<PointT>& p);
} // namespace detail
Expand Down Expand Up @@ -606,7 +606,7 @@ namespace pcl

protected:
// This is motivated by ROS integration. Users should not need to access mapping_.
PCL_DEPRECATED_MESSAGE("rewrite your code to avoid using this protected field") shared_ptr<MsgFieldMap> mapping_;
PCL_DEPRECATED("rewrite your code to avoid using this protected field") shared_ptr<MsgFieldMap> mapping_;

friend shared_ptr<MsgFieldMap>& detail::getMapping<PointT>(pcl::PointCloud<PointT> &p);

Expand Down
4 changes: 2 additions & 2 deletions features/include/pcl/features/rsd.h
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ namespace pcl
int nr_subdiv, double plane_radius, PointOutT &radii, bool compute_histogram = false);

template <typename PointInT, typename PointNT, typename PointOutT>
PCL_DEPRECATED_MESSAGE("use computeRSD() overload that takes input point clouds by const reference")
PCL_DEPRECATED("use computeRSD() overload that takes input point clouds by const reference")
Eigen::MatrixXf
computeRSD (typename pcl::PointCloud<PointInT>::ConstPtr &surface, typename pcl::PointCloud<PointNT>::ConstPtr &normals,
const std::vector<int> &indices, double max_dist,
Expand All @@ -115,7 +115,7 @@ namespace pcl
int nr_subdiv, double plane_radius, PointOutT &radii, bool compute_histogram = false);

template <typename PointNT, typename PointOutT>
PCL_DEPRECATED_MESSAGE("use computeRSD() overload that takes input point cloud by const reference")
PCL_DEPRECATED("use computeRSD() overload that takes input point cloud by const reference")
Eigen::MatrixXf
computeRSD (typename pcl::PointCloud<PointNT>::ConstPtr &normals,
const std::vector<int> &indices, const std::vector<float> &sqr_dists, double max_dist,
Expand Down
6 changes: 3 additions & 3 deletions filters/include/pcl/filters/passthrough.h
Original file line number Diff line number Diff line change
Expand Up @@ -287,7 +287,7 @@ namespace pcl
* Default: false.
* \param[in] limit_negative return data inside the interval (false) or outside (true)
*/
PCL_DEPRECATED_MESSAGE("use inherited FilterIndices::setNegative() instead")
PCL_DEPRECATED("use inherited FilterIndices::setNegative() instead")
inline void
setFilterLimitsNegative (const bool limit_negative)
{
Expand All @@ -297,7 +297,7 @@ namespace pcl
/** \brief Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
* \param[out] limit_negative true if data \b outside the interval [min; max] is to be returned, false otherwise
*/
PCL_DEPRECATED_MESSAGE("use inherited FilterIndices::getNegative() instead")
PCL_DEPRECATED("use inherited FilterIndices::getNegative() instead")
inline void
getFilterLimitsNegative (bool &limit_negative) const
{
Expand All @@ -307,7 +307,7 @@ namespace pcl
/** \brief Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
* \return true if data \b outside the interval [min; max] is to be returned, false otherwise
*/
PCL_DEPRECATED_MESSAGE("use inherited FilterIndices::getNegative() instead")
PCL_DEPRECATED("use inherited FilterIndices::getNegative() instead")
inline bool
getFilterLimitsNegative () const
{
Expand Down
2 changes: 1 addition & 1 deletion io/include/pcl/compression/entropy_range_coder.h
Original file line number Diff line number Diff line change
Expand Up @@ -170,7 +170,7 @@ namespace pcl
* \param n_arg: some value
* \return binary logarithm (log2) of argument n_arg
*/
PCL_DEPRECATED_MESSAGE("use std::log2 instead")
PCL_DEPRECATED("use std::log2 instead")
inline double
Log2 (double n_arg)
{
Expand Down
2 changes: 1 addition & 1 deletion io/include/pcl/io/ascii_io.h
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,7 @@ namespace pcl
* \param[in] p a point type
*/
template<typename PointT>
PCL_DEPRECATED_MESSAGE("use parameterless setInputFields<PointT>() instead")
PCL_DEPRECATED("use parameterless setInputFields<PointT>() instead")
inline void setInputFields (const PointT p)
{
(void) p;
Expand Down
2 changes: 1 addition & 1 deletion io/include/pcl/io/grabber.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ namespace pcl
* \return Connection object, that can be used to disconnect the callback method from the signal again.
*/
template<typename T, template<typename> class FunctionT>
PCL_DEPRECATED_MESSAGE ("please assign the callback to a std::function.")
PCL_DEPRECATED ("please assign the callback to a std::function.")
boost::signals2::connection
registerCallback (const FunctionT<T>& callback)
{
Expand Down
8 changes: 4 additions & 4 deletions io/include/pcl/io/hdl_grabber.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,8 +71,8 @@ namespace pcl
*/
using sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba = void (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &, float, float);

PCL_DEPRECATED_USING(sig_cb_velodyne_hdl_scan_point_cloud_xyzrgb, sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba,
"use sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba instead");
using sig_cb_velodyne_hdl_scan_point_cloud_xyzrgb PCL_DEPRECATED("use sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba instead")
= sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba;

/** \brief Signal used for a single sector
* Represents 1 corrected packet from the HDL Velodyne with the returned intensity.
Expand All @@ -97,8 +97,8 @@ namespace pcl
*/
using sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba = void (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &);

PCL_DEPRECATED_USING(sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgb, sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba,
"use sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba instead");
using sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgb PCL_DEPRECATED("use sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba instead")
= sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba;

/** \brief Constructor taking an optional path to an HDL corrections file. The Grabber will listen on the default IP/port for data packets [192.168.3.255/2368]
* \param[in] correctionsFile Path to a file which contains the correction parameters for the HDL. This parameter is mandatory for the HDL-64, optional for the HDL-32
Expand Down
6 changes: 3 additions & 3 deletions octree/include/pcl/octree/octree2buf_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -252,13 +252,13 @@ namespace pcl
using LeafNodeIterator = OctreeLeafNodeDepthFirstIterator<OctreeT>;
using ConstLeafNodeIterator = const OctreeLeafNodeDepthFirstIterator<OctreeT>;

PCL_DEPRECATED_MESSAGE("use leaf_depth_begin() instead")
PCL_DEPRECATED("use leaf_depth_begin() instead")
LeafNodeIterator leaf_begin (unsigned int max_depth_arg = 0)
{
return LeafNodeIterator (this, max_depth_arg);
};

PCL_DEPRECATED_MESSAGE("use leaf_depth_end() instead")
PCL_DEPRECATED("use leaf_depth_end() instead")
const LeafNodeIterator leaf_end ()
{
return LeafNodeIterator ();
Expand Down Expand Up @@ -886,7 +886,7 @@ namespace pcl
* \param n_arg: some value
* \return binary logarithm (log2) of argument n_arg
*/
PCL_DEPRECATED_MESSAGE("use std::log2 instead")
PCL_DEPRECATED("use std::log2 instead")
inline double Log2 (double n_arg)
{
return std::log2 (n_arg);
Expand Down
6 changes: 3 additions & 3 deletions octree/include/pcl/octree/octree_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -129,13 +129,13 @@ namespace pcl
using LeafNodeIterator = OctreeLeafNodeDepthFirstIterator<OctreeT>;
using ConstLeafNodeIterator = const OctreeLeafNodeDepthFirstIterator<OctreeT>;

PCL_DEPRECATED_MESSAGE("use leaf_depth_begin() instead")
PCL_DEPRECATED("use leaf_depth_begin() instead")
LeafNodeIterator leaf_begin (unsigned int max_depth_arg = 0u)
{
return LeafNodeIterator (this, max_depth_arg? max_depth_arg : this->octree_depth_);
};

PCL_DEPRECATED_MESSAGE("use leaf_depth_end() instead")
PCL_DEPRECATED("use leaf_depth_end() instead")
const LeafNodeIterator leaf_end ()
{
return LeafNodeIterator (this, 0, nullptr);
Expand Down Expand Up @@ -655,7 +655,7 @@ namespace pcl
* \param n_arg: some value
* \return binary logarithm (log2) of argument n_arg
*/
PCL_DEPRECATED_MESSAGE("use std::log2 instead")
PCL_DEPRECATED("use std::log2 instead")
double
Log2 (double n_arg)
{
Expand Down
2 changes: 1 addition & 1 deletion recognition/include/pcl/recognition/mask_map.h
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ class PCL_EXPORTS MaskMap {
return (data_.data());
}

PCL_DEPRECATED_MESSAGE("Use new version diff getDifferenceMask(mask0, mask1)")
PCL_DEPRECATED("Use new version diff getDifferenceMask(mask0, mask1)")
static void
getDifferenceMask(const MaskMap& mask0, const MaskMap& mask1, MaskMap& diff_mask);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -211,7 +211,7 @@ namespace pcl
using experimental::EuclideanClusterComparator<PointT, PointLT>::setExcludeLabels;

/** \brief Default constructor for EuclideanClusterComparator. */
PCL_DEPRECATED_MESSAGE("remove PointNT from template parameters")
PCL_DEPRECATED("remove PointNT from template parameters")
EuclideanClusterComparator ()
: normals_ ()
, angular_threshold_ (0.0f)
Expand All @@ -220,34 +220,34 @@ namespace pcl
/** \brief Provide a pointer to the input normals.
* \param[in] normals the input normal cloud
*/
PCL_DEPRECATED_MESSAGE("EuclideadClusterComparator never actually used normals and angular threshold, this function has no effect on the behavior of the comparator. It is deprecated and will be removed in future releases.")
PCL_DEPRECATED("EuclideadClusterComparator never actually used normals and angular threshold, this function has no effect on the behavior of the comparator. It is deprecated and will be removed in future releases.")
inline void
setInputNormals (const PointCloudNConstPtr& normals) { normals_ = normals; }

/** \brief Get the input normals. */
PCL_DEPRECATED_MESSAGE("EuclideadClusterComparator never actually used normals and angular threshold, this function has no effect on the behavior of the comparator. It is deprecated and will be removed in future releases.")
PCL_DEPRECATED("EuclideadClusterComparator never actually used normals and angular threshold, this function has no effect on the behavior of the comparator. It is deprecated and will be removed in future releases.")
inline PointCloudNConstPtr
getInputNormals () const { return (normals_); }

/** \brief Set the tolerance in radians for difference in normal direction between neighboring points, to be considered part of the same plane.
* \param[in] angular_threshold the tolerance in radians
*/
PCL_DEPRECATED_MESSAGE("EuclideadClusterComparator never actually used normals and angular threshold, this function has no effect on the behavior of the comparator. It is deprecated and will be removed in future releases.")
PCL_DEPRECATED("EuclideadClusterComparator never actually used normals and angular threshold, this function has no effect on the behavior of the comparator. It is deprecated and will be removed in future releases.")
inline void
setAngularThreshold (float angular_threshold)
{
angular_threshold_ = std::cos (angular_threshold);
}

/** \brief Get the angular threshold in radians for difference in normal direction between neighboring points, to be considered part of the same plane. */
PCL_DEPRECATED_MESSAGE("EuclideadClusterComparator never actually used normals and angular threshold, this function has no effect on the behavior of the comparator. It is deprecated and will be removed in future releases.")
PCL_DEPRECATED("EuclideadClusterComparator never actually used normals and angular threshold, this function has no effect on the behavior of the comparator. It is deprecated and will be removed in future releases.")
inline float
getAngularThreshold () const { return (std::acos (angular_threshold_) ); }

/** \brief Set labels in the label cloud to exclude.
* \param[in] exclude_labels a vector of bools corresponding to whether or not a given label should be considered
*/
PCL_DEPRECATED_MESSAGE("use setExcludeLabels(const ExcludeLabelSetConstPtr &) instead")
PCL_DEPRECATED("use setExcludeLabels(const ExcludeLabelSetConstPtr &) instead")
void
setExcludeLabels (const std::vector<bool>& exclude_labels)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -285,7 +285,7 @@ namespace pcl
* \param [in] labels The labels produced by the initial segmentation
* \param [in] label_indices The list of indices corresponding to each label
*/
PCL_DEPRECATED_MESSAGE("centroids and covariances parameters are not used; they are deprecated and will be removed in future releases")
PCL_DEPRECATED("centroids and covariances parameters are not used; they are deprecated and will be removed in future releases")
void
refine (std::vector<ModelCoefficients>& model_coefficients,
std::vector<PointIndices>& inlier_indices,
Expand Down
Loading

0 comments on commit 6292eaa

Please sign in to comment.