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
2434TEST (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