Skip to content

Commit

Permalink
Deprecate PointCloud message and APIs using it (#107)
Browse files Browse the repository at this point in the history
* Deprecate PointCloud message and APIs using it

Signed-off-by: Tully Foote <[email protected]>
  • Loading branch information
tfoote authored Apr 17, 2020
1 parent c994200 commit b30ed13
Show file tree
Hide file tree
Showing 3 changed files with 50 additions and 0 deletions.
12 changes: 12 additions & 0 deletions sensor_msgs/include/sensor_msgs/point_cloud_conversion.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,16 @@

#include <string>

#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
Expand Down Expand Up @@ -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)
Expand Down Expand Up @@ -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)
Expand Down
3 changes: 3 additions & 0 deletions sensor_msgs/msg/PointCloud.msg
Original file line number Diff line number Diff line change
@@ -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.

Expand Down
35 changes: 35 additions & 0 deletions sensor_msgs/test/test_pointcloud_conversion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down Expand Up @@ -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);
Expand All @@ -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);
Expand Down

0 comments on commit b30ed13

Please sign in to comment.