37 #ifndef JSK_PCL_ROS_UTILS_SUBTRACT_POINT_INDICES_H_ 38 #define JSK_PCL_ROS_UTILS_SUBTRACT_POINT_INDICES_H_ 70 const PCLIndicesMsg::ConstPtr&
src1,
71 const PCLIndicesMsg::ConstPtr&
src2);
message_filters::sync_policies::ExactTime< PCLIndicesMsg, PCLIndicesMsg > SyncPolicy
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > async_
message_filters::Subscriber< PCLIndicesMsg > sub_src2_
virtual void unsubscribe()
virtual void subtract(const PCLIndicesMsg::ConstPtr &src1, const PCLIndicesMsg::ConstPtr &src2)
message_filters::sync_policies::ApproximateTime< PCLIndicesMsg, PCLIndicesMsg > ASyncPolicy
pcl::PointIndices PCLIndicesMsg
message_filters::Subscriber< PCLIndicesMsg > sub_src1_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_