From b30ed13005098011836f8194f6a1a0221bf82240 Mon Sep 17 00:00:00 2001 From: Tully Foote Date: Fri, 17 Apr 2020 11:07:29 -0700 Subject: [PATCH] Deprecate PointCloud message and APIs using it (#107) * Deprecate PointCloud message and APIs using it Signed-off-by: Tully Foote --- .../sensor_msgs/point_cloud_conversion.hpp | 12 +++++++ sensor_msgs/msg/PointCloud.msg | 3 ++ .../test/test_pointcloud_conversion.cpp | 35 +++++++++++++++++++ 3 files changed, 50 insertions(+) diff --git a/sensor_msgs/include/sensor_msgs/point_cloud_conversion.hpp b/sensor_msgs/include/sensor_msgs/point_cloud_conversion.hpp index 6a08fa8a..628e040b 100644 --- a/sensor_msgs/include/sensor_msgs/point_cloud_conversion.hpp +++ b/sensor_msgs/include/sensor_msgs/point_cloud_conversion.hpp @@ -42,6 +42,16 @@ #include +#ifndef SENSOR_MSGS_SKIP_WARNING +# define POINT_CLOUD_DEPRECATION_MESSAGE \ + "PointCloud is deprecated in Foxy for PointCloud2. This whole header will be removed." +# ifdef _MSC_VER +# pragma message(POINT_CLOUD_DEPRECATION_MESSAGE) +# else +# warning POINT_CLOUD_DEPRECATION_MESSAGE +# endif +#endif + /** * \brief Convert between the old (sensor_msgs::msg::PointCloud) and the new (sensor_msgs::msg::PointCloud2) format. * \author Radu Bogdan Rusu @@ -71,6 +81,7 @@ static inline int getPointCloud2FieldIndex( * \param input the message in the sensor_msgs::msg::PointCloud format * \param output the resultant message in the sensor_msgs::msg::PointCloud2 format */ +[[deprecated("PointCloud is deprecated as of Foxy in favor of sensor_msgs/PointCloud2.")]] static inline bool convertPointCloudToPointCloud2( const sensor_msgs::msg::PointCloud & input, sensor_msgs::msg::PointCloud2 & output) @@ -125,6 +136,7 @@ static inline bool convertPointCloudToPointCloud2( * \param input the message in the sensor_msgs::msg::PointCloud2 format * \param output the resultant message in the sensor_msgs::msg::PointCloud format */ +[[deprecated("PointCloud is deprecated as of Foxy if favor of sensor_msgs/PointCloud2.")]] static inline bool convertPointCloud2ToPointCloud( const sensor_msgs::msg::PointCloud2 & input, sensor_msgs::msg::PointCloud & output) diff --git a/sensor_msgs/msg/PointCloud.msg b/sensor_msgs/msg/PointCloud.msg index 969cdd97..a07d4504 100644 --- a/sensor_msgs/msg/PointCloud.msg +++ b/sensor_msgs/msg/PointCloud.msg @@ -1,3 +1,6 @@ +## THIS MESSAGE IS DEPRECATED AS OF FOXY +## Please use sensor_msgs/PointCloud2 + # This message holds a collection of 3d points, plus optional additional # information about each point. diff --git a/sensor_msgs/test/test_pointcloud_conversion.cpp b/sensor_msgs/test/test_pointcloud_conversion.cpp index 5745d4c1..58b97c7f 100644 --- a/sensor_msgs/test/test_pointcloud_conversion.cpp +++ b/sensor_msgs/test/test_pointcloud_conversion.cpp @@ -18,7 +18,17 @@ #include "sensor_msgs/msg/point_cloud.hpp" #include "sensor_msgs/msg/point_cloud2.hpp" +#define SENSOR_MSGS_SKIP_WARNING + +// #warning suppression +// Not working due to preprocessor ignoring pragmas in g++ +// https://gcc.gnu.org/bugzilla/show_bug.cgi?id=53431 +// Clang doesn't support suppressing -Wcpp probably like above. +// And I can't find any windows way to suppress it either. + #include "sensor_msgs/point_cloud_conversion.hpp" +#undef SENSOR_MSGS_SKIP_WARNING + #include "sensor_msgs/point_field_conversion.hpp" TEST(sensor_msgs, PointCloudConversion) @@ -49,7 +59,20 @@ TEST(sensor_msgs, PointCloudConversion) // Convert to PointCloud2 sensor_msgs::msg::PointCloud2 cloud2; + +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable : 4996) +#else +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif auto ret_cc2 = sensor_msgs::convertPointCloudToPointCloud2(cloud, cloud2); +#ifdef _MSC_VER +#pragma warning(pop) +#else +#pragma GCC diagnostic pop +#endif ASSERT_TRUE(ret_cc2); EXPECT_EQ(1u, cloud2.height); @@ -68,7 +91,19 @@ TEST(sensor_msgs, PointCloudConversion) // Convert back to PointCloud sensor_msgs::msg::PointCloud cloud3; +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable : 4996) +#else +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif auto ret_c2c = sensor_msgs::convertPointCloud2ToPointCloud(cloud2, cloud3); +#ifdef _MSC_VER +#pragma warning(pop) +#else +#pragma GCC diagnostic pop +#endif ASSERT_TRUE(ret_c2c); EXPECT_EQ(cloud3.points.size(), 100u); EXPECT_EQ(cloud3.channels.size(), 2u);