Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove ROS1 headers from point_cloud.hpp #410

Merged
merged 1 commit into from
Apr 10, 2023
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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