36 #ifndef JSK_PCL_ROS_UTILS_POINTCLOUD_RELATIVE_FROM_POSE_STAMPED_H_ 37 #define JSK_PCL_ROS_UTILS_POINTCLOUD_RELATIVE_FROM_POSE_STAMPED_H_ 45 #include <sensor_msgs/PointCloud2.h> 46 #include <geometry_msgs/PoseStamped.h> 54 sensor_msgs::PointCloud2,
57 sensor_msgs::PointCloud2,
64 virtual void transform(
const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
65 const geometry_msgs::PoseStamped::ConstPtr& pose_msg);
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, geometry_msgs::PoseStamped > ApproximateSyncPolicy
virtual void transform(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_pose_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void unsubscribe()
PointCloudRelativeFromPoseStamped()
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, geometry_msgs::PoseStamped > SyncPolicy