point_indices_to_mask_image.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, 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 
37 #ifndef JSK_PCL_ROS_UTILS_POINT_INDICES_TO_MASK_IMAGE_H_
38 #define JSK_PCL_ROS_UTILS_POINT_INDICES_TO_MASK_IMAGE_H_
39 
40 #include <jsk_topic_tools/diagnostic_nodelet.h>
41 #include <sensor_msgs/Image.h>
47 
48 namespace jsk_pcl_ros_utils
49 {
50  class PointIndicesToMaskImage: public jsk_topic_tools::DiagnosticNodelet
51  {
52  public:
55  sensor_msgs::Image > ApproximateSyncPolicy;
58  sensor_msgs::Image > SyncPolicy;
59 
60  PointIndicesToMaskImage(): DiagnosticNodelet("PointIndicesToMaskImage") { }
61  virtual ~PointIndicesToMaskImage();
62  protected:
64  // methods
66  virtual void onInit();
67  virtual void subscribe();
68  virtual void unsubscribe();
69  virtual void convertAndPublish(
70  const PCLIndicesMsg::ConstPtr& indices_msg,
71  const int width,
72  const int height);
73  virtual void mask(
74  const PCLIndicesMsg::ConstPtr& indices_msg);
75  virtual void mask(
76  const PCLIndicesMsg::ConstPtr& indices_msg,
77  const sensor_msgs::Image::ConstPtr& image_msg);
78 
80  // ROS variables
83  int queue_size_;
84  bool static_image_size_;
85  int width_;
86  int height_;
93  private:
94 
95  };
96 }
97 
98 #endif
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
jsk_pcl_ros_utils::PointIndicesToMaskImage::PointIndicesToMaskImage
PointIndicesToMaskImage()
Definition: point_indices_to_mask_image.h:124
ros::Publisher
jsk_pcl_ros_utils::PointIndicesToMaskImage::ApproximateSyncPolicy
message_filters::sync_policies::ApproximateTime< PCLIndicesMsg, sensor_msgs::Image > ApproximateSyncPolicy
Definition: point_indices_to_mask_image.h:119
boost::shared_ptr
jsk_pcl_ros_utils::PointIndicesToMaskImage::static_image_size_
bool static_image_size_
Definition: point_indices_to_mask_image.h:148
jsk_pcl_ros_utils::PointIndicesToMaskImage::mask
virtual void mask(const PCLIndicesMsg::ConstPtr &indices_msg)
Definition: point_indices_to_mask_image_nodelet.cpp:119
jsk_pcl_ros_utils::PointIndicesToMaskImage::convertAndPublish
virtual void convertAndPublish(const PCLIndicesMsg::ConstPtr &indices_msg, const int width, const int height)
Definition: point_indices_to_mask_image_nodelet.cpp:97
PCLIndicesMsg
pcl::PointIndices PCLIndicesMsg
jsk_pcl_ros_utils::PointIndicesToMaskImage::height_
int height_
Definition: point_indices_to_mask_image.h:150
jsk_pcl_ros_utils::PointIndicesToMaskImage::sub_image_
message_filters::Subscriber< sensor_msgs::Image > sub_image_
Definition: point_indices_to_mask_image.h:155
jsk_pcl_ros_utils::PointIndicesToMaskImage::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: point_indices_to_mask_image.h:151
time_synchronizer.h
jsk_pcl_ros_utils::PointIndicesToMaskImage::unsubscribe
virtual void unsubscribe()
Definition: point_indices_to_mask_image_nodelet.cpp:89
jsk_pcl_ros_utils::PointIndicesToMaskImage::sub_input_static_
ros::Subscriber sub_input_static_
Definition: point_indices_to_mask_image.h:153
message_filters::Subscriber< PCLIndicesMsg >
jsk_pcl_ros_utils::PointIndicesToMaskImage::queue_size_
int queue_size_
Definition: point_indices_to_mask_image.h:147
message_filters::sync_policies::ApproximateTime
subscriber.h
jsk_pcl_ros_utils::PointIndicesToMaskImage::sub_input_
message_filters::Subscriber< PCLIndicesMsg > sub_input_
Definition: point_indices_to_mask_image.h:154
jsk_pcl_ros_utils::PointIndicesToMaskImage::width_
int width_
Definition: point_indices_to_mask_image.h:149
jsk_pcl_ros_utils::PointIndicesToMaskImage::pub_
ros::Publisher pub_
Definition: point_indices_to_mask_image.h:156
pcl_conversion_util.h
jsk_pcl_ros_utils::PointIndicesToMaskImage::~PointIndicesToMaskImage
virtual ~PointIndicesToMaskImage()
Definition: point_indices_to_mask_image_nodelet.cpp:53
sample_camera_info_and_pointcloud_publisher.width
width
Definition: sample_camera_info_and_pointcloud_publisher.py:16
sample_camera_info_and_pointcloud_publisher.height
height
Definition: sample_camera_info_and_pointcloud_publisher.py:15
jsk_pcl_ros_utils::PointIndicesToMaskImage::SyncPolicy
message_filters::sync_policies::ExactTime< PCLIndicesMsg, sensor_msgs::Image > SyncPolicy
Definition: point_indices_to_mask_image.h:122
synchronizer.h
approximate_time.h
jsk_pcl_ros_utils::PointIndicesToMaskImage::approximate_sync_
bool approximate_sync_
Definition: point_indices_to_mask_image.h:146
jsk_pcl_ros_utils::PointIndicesToMaskImage::subscribe
virtual void subscribe()
Definition: point_indices_to_mask_image_nodelet.cpp:65
message_filters::sync_policies::ExactTime
jsk_pcl_ros_utils::PointIndicesToMaskImage::onInit
virtual void onInit()
Definition: point_indices_to_mask_image_nodelet.cpp:43
ros::Subscriber
jsk_pcl_ros_utils::PointIndicesToMaskImage::async_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
Definition: point_indices_to_mask_image.h:152


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