Skip to content

Commit

Permalink
Rework of the deprecated macro from issue #537 and fixes to support t…
Browse files Browse the repository at this point in the history
…he new macro. Also a change to radius filter to comply with the deprecated constructor.
  • Loading branch information
erickulcyk committed Apr 18, 2014
1 parent 4157b33 commit 38a6f8d
Show file tree
Hide file tree
Showing 13 changed files with 83 additions and 60 deletions.
4 changes: 2 additions & 2 deletions common/include/pcl/common/pca.h
Original file line number Diff line number Diff line change
Expand Up @@ -98,8 +98,8 @@ namespace pcl
* X input m*n matrix (ie n vectors of R(m))
* basis_only flag to compute only the PCA basis
*/
PCL_DEPRECATED (PCA (const pcl::PointCloud<PointT>& X, bool basis_only = false),
"Use PCA (bool basis_only); setInputCloud (X.makeShared ()); instead");
PCL_DEPRECATED ("Use PCA (bool basis_only); setInputCloud (X.makeShared ()); instead")
PCA (const pcl::PointCloud<PointT>& X, bool basis_only = false);

/** Copy Constructor
* \param[in] pca PCA object
Expand Down
8 changes: 4 additions & 4 deletions common/include/pcl/pcl_macros.h
Original file line number Diff line number Diff line change
Expand Up @@ -301,21 +301,21 @@ log2f (float x)
#endif

#if (defined(__GNUC__) && PCL_LINEAR_VERSION(__GNUC__,__GNUC_MINOR__,__GNUC_PATCHLEVEL__) < PCL_LINEAR_VERSION(4,5,0) && ! defined(__clang__)) || defined(__INTEL_COMPILER)
#define PCL_DEPRECATED(func, message) func __attribute__ ((deprecated))
#define PCL_DEPRECATED(message) __attribute__ ((deprecated))
#endif

// gcc supports this starting from 4.5 : http://gcc.gnu.org/bugzilla/show_bug.cgi?id=43666
#if (defined(__GNUC__) && PCL_LINEAR_VERSION(__GNUC__,__GNUC_MINOR__,__GNUC_PATCHLEVEL__) >= PCL_LINEAR_VERSION(4,5,0)) || (defined(__clang__) && __has_extension(attribute_deprecated_with_message))
#define PCL_DEPRECATED(func, message) func __attribute__ ((deprecated(message)))
#define PCL_DEPRECATED(message) __attribute__ ((deprecated(message)))
#endif

#ifdef _MSC_VER
#define PCL_DEPRECATED(func, message) __declspec(deprecated(message)) func
#define PCL_DEPRECATED(message) __declspec(deprecated(message))
#endif

#ifndef PCL_DEPRECATED
#pragma message("WARNING: You need to implement PCL_DEPRECATED for this compiler")
#define PCL_DEPRECATED(func) func
#define PCL_DEPRECATED(message)
#endif


Expand Down
32 changes: 10 additions & 22 deletions common/include/pcl/ros/conversions.h
Original file line number Diff line number Diff line change
Expand Up @@ -63,12 +63,8 @@ namespace pcl
* \endcode
*/
template <typename PointT>
PCL_DEPRECATED (void fromROSMsg (
const pcl::PCLPointCloud2& msg, pcl::PointCloud<PointT>& cloud,
const MsgFieldMap& field_map),
"pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.");

template <typename PointT> void
PCL_DEPRECATED ("pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.")
void
fromROSMsg (const pcl::PCLPointCloud2& msg, pcl::PointCloud<PointT>& cloud,
const MsgFieldMap& field_map)
{
Expand All @@ -80,10 +76,8 @@ namespace pcl
* \param[out] cloud the resultant pcl::PointCloud<T>
*/
template<typename PointT>
PCL_DEPRECATED (void fromROSMsg (
const pcl::PCLPointCloud2& msg, pcl::PointCloud<PointT>& cloud),
"pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.");
template<typename PointT> void
PCL_DEPRECATED ("pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.")
void
fromROSMsg (const pcl::PCLPointCloud2& msg, pcl::PointCloud<PointT>& cloud)
{
fromPCLPointCloud2 (msg, cloud);
Expand All @@ -94,10 +88,8 @@ namespace pcl
* \param[out] msg the resultant PCLPointCloud2 binary blob
*/
template<typename PointT>
PCL_DEPRECATED (void toROSMsg (
const pcl::PointCloud<PointT>& cloud, pcl::PCLPointCloud2& msg),
"pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.");
template<typename PointT> void
PCL_DEPRECATED ("pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.")
void
toROSMsg (const pcl::PointCloud<PointT>& cloud, pcl::PCLPointCloud2& msg)
{
toPCLPointCloud2 (cloud, msg);
Expand All @@ -109,11 +101,9 @@ namespace pcl
* CloudT cloud type, CloudT should be akin to pcl::PointCloud<pcl::PointXYZRGBA>
* \note will throw std::runtime_error if there is a problem
*/
template<typename CloudT>
PCL_DEPRECATED (void toROSMsg (
const CloudT& cloud, pcl::PCLImage& msg),
"pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.");
template<typename CloudT> void
template<typename CloudT>
PCL_DEPRECATED ("pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.")
void
toROSMsg (const CloudT& cloud, pcl::PCLImage& msg)
{
toPCLPointCloud2 (cloud, msg);
Expand All @@ -124,10 +114,8 @@ namespace pcl
* \param msg the resultant pcl::PCLImage
* will throw std::runtime_error if there is a problem
*/
PCL_DEPRECATED (inline void toROSMsg (
const pcl::PCLPointCloud2& cloud, pcl::PCLImage& msg),
"pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.");
inline void
PCL_DEPRECATED ("pcl::fromROSMsg is deprecated, please use fromPCLPointCloud2 instead.")
toROSMsg (const pcl::PCLPointCloud2& cloud, pcl::PCLImage& msg)
{
toPCLPointCloud2 (cloud, msg);
Expand Down
2 changes: 2 additions & 0 deletions filters/include/pcl/filters/conditional_removal.h
Original file line number Diff line number Diff line change
Expand Up @@ -627,6 +627,8 @@ namespace pcl
* being removed by the filter
* \param extract_removed_indices extract filtered indices from indices vector
*/
PCL_DEPRECATED ("ConditionalRemoval(ConditionBasePtr condition, bool extract_removed_indices = false) is deprecated, "
"please use the setCondition (ConditionBasePtr condition) function instead.")
ConditionalRemoval (ConditionBasePtr condition, bool extract_removed_indices = false) :
Filter<PointT>::Filter (extract_removed_indices), capable_ (false), keep_organized_ (false), condition_ (),
user_filter_value_ (std::numeric_limits<float>::quiet_NaN ())
Expand Down
12 changes: 6 additions & 6 deletions io/include/pcl/io/png_io.h
Original file line number Diff line number Diff line change
Expand Up @@ -147,11 +147,11 @@ namespace pcl
* \ingroup io
*/
template <typename T>
PCL_DEPRECATED (void savePNGFile (const std::string& file_name, const pcl::PointCloud<T>& cloud),
PCL_DEPRECATED (
"pcl::io::savePNGFile<typename T> (file_name, cloud) is deprecated, please use a new generic "
"function pcl::io::savePNGFile (file_name, cloud, field_name) with \"rgb\" as the field name."
);
template <typename T> void
)
void
savePNGFile (const std::string& file_name, const pcl::PointCloud<T>& cloud)
{
std::vector<unsigned char> data(cloud.width * cloud.height * 3);
Expand All @@ -171,11 +171,11 @@ namespace pcl
* \ingroup io
* Warning: Converts to 16 bit (for png), labels using more than 16 bits will cause problems
*/
PCL_EXPORTS PCL_DEPRECATED (void savePNGFile (const std::string& file_name, const pcl::PointCloud<pcl::PointXYZL>& cloud),
PCL_EXPORTS PCL_DEPRECATED (
"pcl::io::savePNGFile (file_name, cloud) is deprecated, please use a new generic function "
"pcl::io::savePNGFile (file_name, cloud, field_name) with \"label\" as the field name."
);
PCL_EXPORTS void
)
void
savePNGFile (const std::string& file_name, const pcl::PointCloud<pcl::PointXYZL>& cloud);

/** \brief Saves the data from the specified field of the point cloud as image to PNG file.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -113,11 +113,14 @@ namespace pcl
*
* \param[in] cloud the input point cloud source
*/
PCL_DEPRECATED (void setInputCloud (const PointCloudSourceConstPtr &cloud), "[pcl::registration::CorrespondenceEstimationBase::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.");
PCL_DEPRECATED ("[pcl::registration::CorrespondenceEstimationBase::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.")
void
setInputCloud (const PointCloudSourceConstPtr &cloud);

/** \brief Get a pointer to the input point cloud dataset target. */
PCL_DEPRECATED (PointCloudSourceConstPtr const getInputCloud (),
"[pcl::registration::CorrespondenceEstimationBase::getInputCloud] getInputCloud is deprecated. Please use getInputSource instead.");
PCL_DEPRECATED ("[pcl::registration::CorrespondenceEstimationBase::getInputCloud] getInputCloud is deprecated. Please use getInputSource instead.")
PointCloudSourceConstPtr const
getInputCloud ();

/** \brief Provide a pointer to the input source
* (e.g., the point cloud that we want to align to the target)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -249,10 +249,14 @@ namespace pcl
* data!), used to compute the correspondence distance.
* \param[in] cloud a cloud containing XYZ data
*/
PCL_DEPRECATED (void setInputCloud (const PointCloudConstPtr &cloud), "[pcl::registration::DataContainer::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.");
PCL_DEPRECATED ("[pcl::registration::DataContainer::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.")
void
setInputCloud (const PointCloudConstPtr &cloud);

/** \brief Get a pointer to the input point cloud dataset target. */
PCL_DEPRECATED (PointCloudConstPtr const getInputCloud (), "[pcl::registration::DataContainer::getInputCloud] getInputCloud is deprecated. Please use getInputSource instead.");
PCL_DEPRECATED ("[pcl::registration::DataContainer::getInputCloud] getInputCloud is deprecated. Please use getInputSource instead.")
PointCloudConstPtr const
getInputCloud ();

/** \brief Provide a source point cloud dataset (must contain XYZ
* data!), used to compute the correspondence distance.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -100,11 +100,14 @@ namespace pcl
/** \brief Provide a source point cloud dataset (must contain XYZ data!)
* \param[in] cloud a cloud containing XYZ data
*/
PCL_DEPRECATED (virtual void setInputCloud (const PointCloudConstPtr &cloud),
"[pcl::registration::CorrespondenceRejectorSampleConsensus::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.");
PCL_DEPRECATED ("[pcl::registration::CorrespondenceRejectorSampleConsensus::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.")
virtual void
setInputCloud (const PointCloudConstPtr &cloud);

/** \brief Get a pointer to the input point cloud dataset target. */
PCL_DEPRECATED (PointCloudConstPtr const getInputCloud (), "[pcl::registration::CorrespondenceRejectorSampleConsensus::getInputCloud] getInputCloud is deprecated. Please use getInputSource instead.");
PCL_DEPRECATED ("[pcl::registration::CorrespondenceRejectorSampleConsensus::getInputCloud] getInputCloud is deprecated. Please use getInputSource instead.")
PointCloudConstPtr const
getInputCloud ();

/** \brief Provide a source point cloud dataset (must contain XYZ data!)
* \param[in] cloud a cloud containing XYZ data
Expand All @@ -122,7 +125,9 @@ namespace pcl
/** \brief Provide a target point cloud dataset (must contain XYZ data!)
* \param[in] cloud a cloud containing XYZ data
*/
PCL_DEPRECATED (virtual void setTargetCloud (const PointCloudConstPtr &cloud), "[pcl::registration::CorrespondenceRejectorSampleConsensus::setTargetCloud] setTargetCloud is deprecated. Please use setInputTarget instead.");
PCL_DEPRECATED ("[pcl::registration::CorrespondenceRejectorSampleConsensus::setTargetCloud] setTargetCloud is deprecated. Please use setInputTarget instead.")
virtual void
setTargetCloud (const PointCloudConstPtr &cloud);

/** \brief Provide a target point cloud dataset (must contain XYZ data!)
* \param[in] cloud a cloud containing XYZ data
Expand Down Expand Up @@ -174,12 +179,14 @@ namespace pcl
* \return Distance threshold in the same dimension as source and target data sets.
*/
inline double
getInlierThreshold() { return inlier_threshold_; };
getInlierThreshold () { return inlier_threshold_; };

/** \brief Set the maximum number of iterations.
* \param[in] max_iterations Maximum number if iterations to run
*/
PCL_DEPRECATED (void setMaxIterations (int max_iterations), "[pcl::registration::CorrespondenceRejectorSampleConsensus::setMaxIterations] setMaxIterations is deprecated. Please use setMaximumIterations instead.");
PCL_DEPRECATED ("[pcl::registration::CorrespondenceRejectorSampleConsensus::setMaxIterations] setMaxIterations is deprecated. Please use setMaximumIterations instead.")
void
setMaxIterations (int max_iterations);

/** \brief Set the maximum number of iterations.
* \param[in] max_iterations Maximum number if iterations to run
Expand All @@ -190,7 +197,9 @@ namespace pcl
/** \brief Get the maximum number of iterations.
* \return max_iterations Maximum number if iterations to run
*/
PCL_DEPRECATED (int getMaxIterations (), "[pcl::registration::CorrespondenceRejectorSampleConsensus::getMaxIterations] getMaxIterations is deprecated. Please use getMaximumIterations instead.");
PCL_DEPRECATED ("[pcl::registration::CorrespondenceRejectorSampleConsensus::getMaxIterations] getMaxIterations is deprecated. Please use getMaximumIterations instead.")
int
getMaxIterations ();

/** \brief Get the maximum number of iterations.
* \return max_iterations Maximum number if iterations to run
Expand Down
4 changes: 3 additions & 1 deletion registration/include/pcl/registration/gicp.h
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,9 @@ namespace pcl
/** \brief Provide a pointer to the input dataset
* \param cloud the const boost shared pointer to a PointCloud message
*/
PCL_DEPRECATED (void setInputCloud (const PointCloudSourceConstPtr &cloud), "[pcl::registration::GeneralizedIterativeClosestPoint::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.");
PCL_DEPRECATED ("[pcl::registration::GeneralizedIterativeClosestPoint::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.")
void
setInputCloud (const PointCloudSourceConstPtr &cloud);

/** \brief Provide a pointer to the input dataset
* \param cloud the const boost shared pointer to a PointCloud message
Expand Down
8 changes: 6 additions & 2 deletions registration/include/pcl/registration/registration.h
Original file line number Diff line number Diff line change
Expand Up @@ -178,10 +178,14 @@ namespace pcl
*
* \param[in] cloud the input point cloud source
*/
PCL_DEPRECATED (void setInputCloud (const PointCloudSourceConstPtr &cloud), "[pcl::registration::Registration::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.");
PCL_DEPRECATED ("[pcl::registration::Registration::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.")
void
setInputCloud (const PointCloudSourceConstPtr &cloud);

/** \brief Get a pointer to the input point cloud dataset target. */
PCL_DEPRECATED (PointCloudSourceConstPtr const getInputCloud (), "[pcl::registration::Registration::getInputCloud] getInputCloud is deprecated. Please use getInputSource instead.");
PCL_DEPRECATED ("[pcl::registration::Registration::getInputCloud] getInputCloud is deprecated. Please use getInputSource instead.")
PointCloudSourceConstPtr const
getInputCloud ();

/** \brief Provide a pointer to the input source
* (e.g., the point cloud that we want to align to the target)
Expand Down
6 changes: 4 additions & 2 deletions surface/include/pcl/surface/concave_hull.h
Original file line number Diff line number Diff line change
Expand Up @@ -134,8 +134,10 @@ namespace pcl
}

/** \brief Returns the dimensionality (2 or 3) of the calculated hull. */
PCL_DEPRECATED (int getDim () const, "[pcl::ConcaveHull::getDim] This method is deprecated. Please use getDimension () instead.");

PCL_DEPRECATED ("[pcl::ConcaveHull::getDim] This method is deprecated. Please use getDimension () instead.");
int
getDim () const;

/** \brief Returns the dimensionality (2 or 3) of the calculated hull. */
inline int
getDimension () const
Expand Down
3 changes: 2 additions & 1 deletion tools/radius_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,8 @@ compute (const Cloud::Ptr &input, Cloud::Ptr &output,
cond->addComparison (pcl::TfQuadraticXYZComparison<PointType>::ConstPtr (new pcl::TfQuadraticXYZComparison<PointType> (inside ? pcl::ComparisonOps::LT : pcl::ComparisonOps::GT, Eigen::Matrix3f::Identity (),
Eigen::Vector3f::Zero (), - radius * radius)));

pcl::ConditionalRemoval<PointType> condrem (cond);
pcl::ConditionalRemoval<PointType> condrem;
condrem.setCondition (cond);
condrem.setInputCloud (input);
condrem.setKeepOrganized (keep_organized);
condrem.filter (*output);
Expand Down
24 changes: 16 additions & 8 deletions visualization/include/pcl/visualization/pcl_visualizer.h
Original file line number Diff line number Diff line change
Expand Up @@ -278,9 +278,11 @@ namespace pcl
* \param[in] scale the scale of the axes (default: 1)
* \param[in] viewport the view port where the 3D axes should be added (default: all)
*/
PCL_DEPRECATED (void addCoordinateSystem (double scale, int viewport = 0),
PCL_DEPRECATED (
"addCoordinateSystem (scale, viewport) is deprecated, please use function "
"addCoordinateSystem (scale, id, viewport) with id a unique string identifier.");
"addCoordinateSystem (scale, id, viewport) with id a unique string identifier.")
void
addCoordinateSystem (double scale, int viewport = 0);

/** \brief Adds 3D axes describing a coordinate system to screen at 0,0,0.
* \param[in] scale the scale of the axes (default: 1)
Expand All @@ -297,9 +299,11 @@ namespace pcl
* \param[in] z the Z position of the axes
* \param[in] viewport the view port where the 3D axes should be added (default: all)
*/
PCL_DEPRECATED (void addCoordinateSystem (double scale, float x, float y, float z, int viewport = 0),
PCL_DEPRECATED (
"addCoordinateSystem (scale, x, y, z, viewport) is deprecated, please use function "
"addCoordinateSystem (scale, x, y, z, id, viewport) with id a unique string identifier.");
"addCoordinateSystem (scale, x, y, z, id, viewport) with id a unique string identifier.")
void
addCoordinateSystem (double scale, float x, float y, float z, int viewport = 0);

/** \brief Adds 3D axes describing a coordinate system to screen at x, y, z
* \param[in] scale the scale of the axes (default: 1)
Expand All @@ -318,9 +322,11 @@ namespace pcl
* \param[in] t transformation matrix
* \param[in] viewport the view port where the 3D axes should be added (default: all)
*/
PCL_DEPRECATED (void addCoordinateSystem (double scale, const Eigen::Affine3f& t, int viewport = 0),
PCL_DEPRECATED (
"addCoordinateSystem (scale, t, viewport) is deprecated, please use function "
"addCoordinateSystem (scale, t, id, viewport) with id a unique string identifier.");
"addCoordinateSystem (scale, t, id, viewport) with id a unique string identifier.")
void
addCoordinateSystem (double scale, const Eigen::Affine3f& t, int viewport = 0);

/** \brief Adds 3D axes describing a coordinate system to screen at x, y, z, Roll,Pitch,Yaw
*
Expand Down Expand Up @@ -360,9 +366,11 @@ namespace pcl
/** \brief Removes a previously added 3D axes (coordinate system)
* \param[in] viewport view port where the 3D axes should be removed from (default: all)
*/
PCL_DEPRECATED (bool removeCoordinateSystem (int viewport = 0),
PCL_DEPRECATED (
"removeCoordinateSystem (viewport) is deprecated, please use function "
"addCoordinateSystem (id, viewport) with id a unique string identifier.");
"addCoordinateSystem (id, viewport) with id a unique string identifier.")
bool
removeCoordinateSystem (int viewport = 0);

/** \brief Removes a previously added 3D axes (coordinate system)
* \param[in] id the coordinate system object id (default: reference)
Expand Down

0 comments on commit 38a6f8d

Please sign in to comment.