37 #ifndef JSK_PCL_ROS_POINTCLOUD_MOVEIT_FILTER_H_
38 #define JSK_PCL_ROS_POINTCLOUD_MOVEIT_FILTER_H_
43 #include <sensor_msgs/PointCloud2.h>
44 #include <moveit/version.h>
49 #include <pcl/point_types.h>
50 #include <pcl/point_cloud.h>
52 #include <pcl/filters/extract_indices.h>
54 #if (ROS_VERSION_MINIMUM(1,14,0) || MOVEIT_VERSION_MAJOR >= 1) // melodic or MoveIt 1.0
64 class PointCloudMoveitFilter:
81 #
if (ROS_VERSION_MINIMUM(1,14,0) || MOVEIT_VERSION_MAJOR >= 1)
82 Eigen::Isometry3d &transform)
const;
86 template <
typename Po
intT>
88 const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
100 #if (ROS_VERSION_MINIMUM(1,14,0) || MOVEIT_VERSION_MAJOR >= 1) // melodic or MoveIt 1.0
102 cloud_msg->header.frame_id,
103 cloud_msg->header.stamp),
107 cloud_msg->header.frame_id,
108 cloud_msg->header.stamp,
115 <<
ex.what() <<
"; quitting callback");
125 typename pcl::PointCloud<PointT>::Ptr
cloud;
126 cloud.reset(
new pcl::PointCloud<PointT>());
127 pcl::PointCloud<pcl::PointXYZ> xyz_cloud;
130 const tf::Vector3 &sensor_origin_tf = map_H_sensor.
getOrigin();
132 sensor_origin_tf.getX(),
133 sensor_origin_tf.getY(),
134 sensor_origin_tf.getZ());
135 Eigen::Vector3d sensor_origin_eigen(
136 sensor_origin_tf.getX(),
137 sensor_origin_tf.getY(),
138 sensor_origin_tf.getZ());
140 cloud_msg->header.stamp))
143 1,
"Transform cache was not updated. Self-filtering may fail.");
147 #if (MOVEIT_VERSION_MAJOR == 0 and MOVEIT_VERSION_MINOR < 6)
148 shape_mask_->maskContainment(xyz_cloud, sensor_origin_eigen, 0.0,
150 #else // from moveit 0.6 (indigo), PCL dependency is removed
151 shape_mask_->maskContainment(*cloud_msg, sensor_origin_eigen, 0.0,
154 typename pcl::PointCloud<PointT>::Ptr
155 filtered_cloud (
new pcl::PointCloud<PointT>);
156 pcl::PointIndices::Ptr indices (
new pcl::PointIndices);
158 for (
size_t i = 0;
i <
mask_.size();
i++) {
160 indices->indices.push_back(i);
163 pcl::ExtractIndices<PointT>
ex;
164 ex.setInputCloud(cloud);
165 ex.setIndices(indices);
167 ex.filter(*filtered_cloud);
168 sensor_msgs::PointCloud2 ros_cloud;
170 ros_cloud.header = cloud_msg->header;
179 #if (ROS_VERSION_MINIMUM(1,14,0) || MOVEIT_VERSION_MAJOR >= 1) // melodic and MoveIt 1.0
180 std::shared_ptr<tf2_ros::Buffer>
tf_;
193 #if (ROS_VERSION_MINIMUM(1,14,0) || MOVEIT_VERSION_MAJOR >= 1) // melodic or MoveIt 1.0
199 boost::scoped_ptr<point_containment_filter::ShapeMask>
shape_mask_;
200 std::vector<int>
mask_;