Skip to content

Commit

Permalink
Remove ROS1 headers from point_cloud.hpp (#410)
Browse files Browse the repository at this point in the history
  • Loading branch information
mvieth authored Apr 10, 2023
1 parent 6642b73 commit 3bb07c0
Showing 1 changed file with 2 additions and 3 deletions.
5 changes: 2 additions & 3 deletions pcl_ros/include/pcl_ros/point_cloud.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,6 @@
#define ROS_POINTER_COMPATIBILITY_IMPLEMENTED 0
#endif

#include <ros/ros.h>
#include <pcl/point_cloud.h>
#include <pcl/pcl_config.h> // for PCL_VERSION_COMPARE
#if PCL_VERSION_COMPARE(>=, 1, 11, 0)
Expand All @@ -60,14 +59,14 @@
#endif
#endif
#include <pcl_conversions/pcl_conversions.h>
#include <sensor_msgs/PointCloud2.h>
#include <string>
#include <utility>
#include <vector>
#if ROS_POINTER_COMPATIBILITY_IMPLEMENTED
#include <type_traits>
#include <memory>
#endif
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <boost/foreach.hpp> // for BOOST_FOREACH
#include <boost/mpl/size.hpp>
#include <boost/ref.hpp>
Expand Down Expand Up @@ -128,7 +127,7 @@ namespace ros
// In ROS 1.3.1+, we can specialize the functor used to create PointCloud<T> objects
// on the subscriber side. This allows us to generate the mapping between message
// data and object fields only once and reuse it.
#if ROS_VERSION_MINIMUM(1, 3, 1)
#if 0 // ROS_VERSION_MINIMUM(1, 3, 1)
template<typename T>
struct DefaultMessageCreator<pcl::PointCloud<T>>
{
Expand Down

0 comments on commit 3bb07c0

Please sign in to comment.