pointcloud_relative_from_pose_stamped.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #ifndef JSK_PCL_ROS_UTILS_POINTCLOUD_RELATIVE_FROM_POSE_STAMPED_H_
37 #define JSK_PCL_ROS_UTILS_POINTCLOUD_RELATIVE_FROM_POSE_STAMPED_H_
38 
39 #include <jsk_topic_tools/diagnostic_nodelet.h>
45 #include <sensor_msgs/PointCloud2.h>
46 #include <geometry_msgs/PoseStamped.h>
47 
48 namespace jsk_pcl_ros_utils
49 {
50  class PointCloudRelativeFromPoseStamped: public jsk_topic_tools::DiagnosticNodelet
51  {
52  public:
54  sensor_msgs::PointCloud2,
55  geometry_msgs::PoseStamped > SyncPolicy;
57  sensor_msgs::PointCloud2,
58  geometry_msgs::PoseStamped > ApproximateSyncPolicy;
59  PointCloudRelativeFromPoseStamped(): DiagnosticNodelet("PointCloudRelativeFromPoseStamped") {}
61  protected:
62  virtual void onInit();
63  virtual void subscribe();
64  virtual void unsubscribe();
65  virtual void transform(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
66  const geometry_msgs::PoseStamped::ConstPtr& pose_msg);
67 
73  bool approximate_sync_;
74  private:
75  };
76 }
77 
78 #endif
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
ros::Publisher
jsk_pcl_ros_utils::PointCloudRelativeFromPoseStamped::async_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
Definition: pointcloud_relative_from_pose_stamped.h:136
jsk_pcl_ros_utils::PointCloudRelativeFromPoseStamped::onInit
virtual void onInit()
Definition: pointcloud_relative_from_pose_stamped_nodelet.cpp:46
boost::shared_ptr
jsk_pcl_ros_utils::PointCloudRelativeFromPoseStamped::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, geometry_msgs::PoseStamped > SyncPolicy
Definition: pointcloud_relative_from_pose_stamped.h:119
jsk_pcl_ros_utils::PointCloudRelativeFromPoseStamped::transform
virtual void transform(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
Definition: pointcloud_relative_from_pose_stamped_nodelet.cpp:87
time_synchronizer.h
jsk_pcl_ros_utils::PointCloudRelativeFromPoseStamped::PointCloudRelativeFromPoseStamped
PointCloudRelativeFromPoseStamped()
Definition: pointcloud_relative_from_pose_stamped.h:123
jsk_pcl_ros_utils::PointCloudRelativeFromPoseStamped::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: pointcloud_relative_from_pose_stamped.h:135
message_filters::Subscriber< sensor_msgs::PointCloud2 >
message_filters::sync_policies::ApproximateTime
jsk_pcl_ros_utils::PointCloudRelativeFromPoseStamped::unsubscribe
virtual void unsubscribe()
Definition: pointcloud_relative_from_pose_stamped_nodelet.cpp:81
subscriber.h
jsk_pcl_ros_utils::PointCloudRelativeFromPoseStamped::pub_
ros::Publisher pub_
Definition: pointcloud_relative_from_pose_stamped.h:132
jsk_pcl_ros_utils::PointCloudRelativeFromPoseStamped::subscribe
virtual void subscribe()
Definition: pointcloud_relative_from_pose_stamped_nodelet.cpp:66
exact_time.h
jsk_pcl_ros_utils::PointCloudRelativeFromPoseStamped::~PointCloudRelativeFromPoseStamped
virtual ~PointCloudRelativeFromPoseStamped()
Definition: pointcloud_relative_from_pose_stamped_nodelet.cpp:54
jsk_pcl_ros_utils::PointCloudRelativeFromPoseStamped::sub_pose_
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_pose_
Definition: pointcloud_relative_from_pose_stamped.h:134
jsk_pcl_ros_utils::PointCloudRelativeFromPoseStamped::ApproximateSyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, geometry_msgs::PoseStamped > ApproximateSyncPolicy
Definition: pointcloud_relative_from_pose_stamped.h:122
synchronizer.h
approximate_time.h
jsk_pcl_ros_utils::PointCloudRelativeFromPoseStamped::approximate_sync_
bool approximate_sync_
Definition: pointcloud_relative_from_pose_stamped.h:137
message_filters::sync_policies::ExactTime
jsk_pcl_ros_utils::PointCloudRelativeFromPoseStamped::sub_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
Definition: pointcloud_relative_from_pose_stamped.h:133


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43