Skip to content

Commit 7893bce

Browse files
committed
Deprecate PointCloud message and APIs using it
Signed-off-by: Tully Foote <tfoote@osrfoundation.org>
1 parent c994200 commit 7893bce

File tree

3 files changed

+50
-0
lines changed

3 files changed

+50
-0
lines changed

‎sensor_msgs/include/sensor_msgs/point_cloud_conversion.hpp‎

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,16 @@
4242

4343
#include <string>
4444

45+
#ifndef SENSOR_MSGS_SKIP_WARNING
46+
# define POINT_CLOUD_DEPRECATION_MESSAGE \
47+
"PointCloud is deprecated in Foxy for PointCloud2. This whole header will be removed."
48+
# ifdef _MSC_VER
49+
# pragma message(POINT_CLOUD_DEPRECATION_MESSAGE)
50+
# else
51+
# warning POINT_CLOUD_DEPRECATION_MESSAGE
52+
# endif
53+
#endif
54+
4555
/**
4656
* \brief Convert between the old (sensor_msgs::msg::PointCloud) and the new (sensor_msgs::msg::PointCloud2) format.
4757
* \author Radu Bogdan Rusu
@@ -71,6 +81,7 @@ static inline int getPointCloud2FieldIndex(
7181
* \param input the message in the sensor_msgs::msg::PointCloud format
7282
* \param output the resultant message in the sensor_msgs::msg::PointCloud2 format
7383
*/
84+
[[deprecated("PointCloud is deprecated as of Foxy in favor of sensor_msgs/PointCloud2.")]]
7485
static inline bool convertPointCloudToPointCloud2(
7586
const sensor_msgs::msg::PointCloud & input,
7687
sensor_msgs::msg::PointCloud2 & output)
@@ -125,6 +136,7 @@ static inline bool convertPointCloudToPointCloud2(
125136
* \param input the message in the sensor_msgs::msg::PointCloud2 format
126137
* \param output the resultant message in the sensor_msgs::msg::PointCloud format
127138
*/
139+
[[deprecated("PointCloud is deprecated as of Foxy if favor of sensor_msgs/PointCloud2.")]]
128140
static inline bool convertPointCloud2ToPointCloud(
129141
const sensor_msgs::msg::PointCloud2 & input,
130142
sensor_msgs::msg::PointCloud & output)

‎sensor_msgs/msg/PointCloud.msg‎

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,6 @@
1+
## THIS MESSAGE IS DEPRECATED AS OF FOXY
2+
## Please use sensor_msgs/PointCloud2
3+
14
# This message holds a collection of 3d points, plus optional additional
25
# information about each point.
36

‎sensor_msgs/test/test_pointcloud_conversion.cpp‎

Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,17 @@
1818
#include "sensor_msgs/msg/point_cloud.hpp"
1919
#include "sensor_msgs/msg/point_cloud2.hpp"
2020

21+
#define SENSOR_MSGS_SKIP_WARNING
22+
23+
// #warning suppression
24+
// Not working due to preprocessor ignoring pragmas in g++
25+
// https://gcc.gnu.org/bugzilla/show_bug.cgi?id=53431
26+
// Clang doesn't support suppressing -Wcpp probably like above.
27+
// And I can't find any windows way to suppress it either.
28+
2129
#include "sensor_msgs/point_cloud_conversion.hpp"
30+
#undef SENSOR_MSGS_SKIP_WARNING
31+
2232
#include "sensor_msgs/point_field_conversion.hpp"
2333

2434
TEST(sensor_msgs, PointCloudConversion)
@@ -49,7 +59,20 @@ TEST(sensor_msgs, PointCloudConversion)
4959

5060
// Convert to PointCloud2
5161
sensor_msgs::msg::PointCloud2 cloud2;
62+
63+
#ifdef _MSC_VER
64+
#pragma warning(push)
65+
#pragma warning(disable : 4996 )
66+
#else
67+
#pragma GCC diagnostic push
68+
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
69+
#endif
5270
auto ret_cc2 = sensor_msgs::convertPointCloudToPointCloud2(cloud, cloud2);
71+
#ifdef _MSC_VER
72+
#pragma warning(pop)
73+
#else
74+
#pragma GCC diagnostic pop
75+
#endif
5376
ASSERT_TRUE(ret_cc2);
5477

5578
EXPECT_EQ(1u, cloud2.height);
@@ -68,7 +91,19 @@ TEST(sensor_msgs, PointCloudConversion)
6891

6992
// Convert back to PointCloud
7093
sensor_msgs::msg::PointCloud cloud3;
94+
#ifdef _MSC_VER
95+
#pragma warning(push)
96+
#pragma warning(disable : 4996 )
97+
#else
98+
#pragma GCC diagnostic push
99+
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
100+
#endif
71101
auto ret_c2c = sensor_msgs::convertPointCloud2ToPointCloud(cloud2, cloud3);
102+
#ifdef _MSC_VER
103+
#pragma warning(pop)
104+
#else
105+
#pragma GCC diagnostic pop
106+
#endif
72107
ASSERT_TRUE(ret_c2c);
73108
EXPECT_EQ(cloud3.points.size(), 100u);
74109
EXPECT_EQ(cloud3.channels.size(), 2u);

0 commit comments

Comments
 (0)