depth_image_creator.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 #ifndef JSK_PCL_ROS_IMAGE_CREATOR_H_
37 #define JSK_PCL_ROS_IMAGE_CREATOR_H_
38 
39 #include <pcl_ros/pcl_nodelet.h>
40 #include <pcl_ros/transforms.h>
41 
43 #include <dynamic_reconfigure/server.h>
44 
45 #include <pcl/range_image/range_image_planar.h>
46 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 )
47 #include <pcl/common/transforms.h>
48 #else
49 #include <pcl/common/transform.h>
50 #endif
51 
52 #include <sensor_msgs/Image.h>
53 #include <sensor_msgs/CameraInfo.h>
54 #include <sensor_msgs/PointCloud2.h>
56 #include <stereo_msgs/DisparityImage.h>
57 
58 #include <opencv2/opencv.hpp>
59 
60 #include <std_srvs/Empty.h>
61 #include <boost/thread/mutex.hpp>
62 
63 #include <jsk_topic_tools/connection_based_nodelet.h>
65 
66 namespace jsk_pcl_ros
67 {
68  class DepthImageCreator : public jsk_topic_tools::ConnectionBasedNodelet
69  {
70  protected:
80 
81  sensor_msgs::PointCloud2ConstPtr points_ptr_;
82 
87  bool use_service;
88  bool use_asynchronous;
89  bool use_approximate;
90  bool organize_cloud_;
91  int info_throttle_;
92  int info_counter_;
93  int max_queue_size_;
98  double scale_depth;
99  double tf_duration_;
100  float fill_value;
101  typedef pcl::PointXYZRGB Point;
102  typedef pcl::PointCloud< Point > PointCloud;
103 
104  void onInit();
105 
106  bool service_cb (std_srvs::Empty::Request &req,
107  std_srvs::Empty::Response &res);
108 
109  void callback_sync(const sensor_msgs::CameraInfoConstPtr& info,
110  const sensor_msgs::PointCloud2ConstPtr& pcloud2);
111 
112  void callback_cloud(const sensor_msgs::PointCloud2ConstPtr& pcloud2);
113 
114  void callback_info(const sensor_msgs::CameraInfoConstPtr& info);
115 
116  void publish_points(const sensor_msgs::CameraInfoConstPtr& info,
117  const sensor_msgs::PointCloud2ConstPtr& pcloud2);
118 
119  void subscribe();
120  void unsubscribe();
121  public:
122  virtual ~DepthImageCreator();
123  };
124 }
125 
126 #endif
127 
jsk_pcl_ros::DepthImageCreator::subscribe
void subscribe()
Definition: depth_image_creator_nodelet.cpp:121
jsk_pcl_ros::DepthImageCreator::callback_cloud
void callback_cloud(const sensor_msgs::PointCloud2ConstPtr &pcloud2)
Definition: depth_image_creator_nodelet.cpp:177
jsk_pcl_ros::DepthImageCreator::pub_cloud_
ros::Publisher pub_cloud_
Definition: depth_image_creator.h:141
jsk_pcl_ros::DepthImageCreator::callback_sync
void callback_sync(const sensor_msgs::CameraInfoConstPtr &info, const sensor_msgs::PointCloud2ConstPtr &pcloud2)
Definition: depth_image_creator_nodelet.cpp:171
jsk_pcl_ros::DepthImageCreator::sub_as_cloud_
ros::Subscriber sub_as_cloud_
Definition: depth_image_creator.h:138
jsk_pcl_ros::DepthImageCreator::sync_inputs_a_
boost::shared_ptr< message_filters::Synchronizer< message_filters::sync_policies::ApproximateTime< sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 > > > sync_inputs_a_
Definition: depth_image_creator.h:148
ros::Publisher
image_encodings.h
jsk_pcl_ros::DepthImageCreator::fixed_transform
tf::StampedTransform fixed_transform
Definition: depth_image_creator.h:160
boost::shared_ptr
jsk_pcl_ros::DepthImageCreator::points_ptr_
sensor_msgs::PointCloud2ConstPtr points_ptr_
Definition: depth_image_creator.h:145
jsk_pcl_ros::DepthImageCreator::organize_cloud_
bool organize_cloud_
Definition: depth_image_creator.h:154
jsk_pcl_ros::DepthImageCreator::use_fixed_transform
bool use_fixed_transform
Definition: depth_image_creator.h:150
jsk_pcl_ros::DepthImageCreator::publish_points
void publish_points(const sensor_msgs::CameraInfoConstPtr &info, const sensor_msgs::PointCloud2ConstPtr &pcloud2)
Definition: depth_image_creator_nodelet.cpp:196
tf_listener_singleton.h
tf::StampedTransform
jsk_pcl_ros::DepthImageCreator::pub_disp_image_
ros::Publisher pub_disp_image_
Definition: depth_image_creator.h:142
jsk_pcl_ros::DepthImageCreator::onInit
void onInit()
Definition: depth_image_creator_nodelet.cpp:44
transforms.h
message_filters::Subscriber< sensor_msgs::CameraInfo >
ros::ServiceServer
jsk_pcl_ros::DepthImageCreator::use_approximate
bool use_approximate
Definition: depth_image_creator.h:153
class_list_macros.h
pcl_nodelet.h
jsk_pcl_ros::DepthImageCreator::service_
ros::ServiceServer service_
Definition: depth_image_creator.h:143
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::DepthImageCreator::pub_image_
ros::Publisher pub_image_
Definition: depth_image_creator.h:140
jsk_pcl_ros::DepthImageCreator::sub_info_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_
Definition: depth_image_creator.h:135
jsk_pcl_ros::DepthImageCreator::Point
pcl::PointXYZRGB Point
Definition: depth_image_creator.h:165
jsk_pcl_ros::DepthImageCreator::mutex_points
boost::mutex mutex_points
Definition: depth_image_creator.h:149
jsk_pcl_ros::DepthImageCreator::max_queue_size_
int max_queue_size_
Definition: depth_image_creator.h:157
jsk_pcl_ros::DepthImageCreator::service_cb
bool service_cb(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: depth_image_creator_nodelet.cpp:166
jsk_pcl_ros::DepthImageCreator::tf_duration_
double tf_duration_
Definition: depth_image_creator.h:163
jsk_pcl_ros::DepthImageCreator::info_counter_
int info_counter_
Definition: depth_image_creator.h:156
jsk_pcl_ros::DepthImageCreator::info_throttle_
int info_throttle_
Definition: depth_image_creator.h:155
jsk_pcl_ros::DepthImageCreator::~DepthImageCreator
virtual ~DepthImageCreator()
Definition: depth_image_creator_nodelet.cpp:109
jsk_pcl_ros::DepthImageCreator::callback_info
void callback_info(const sensor_msgs::CameraInfoConstPtr &info)
Definition: depth_image_creator_nodelet.cpp:183
jsk_pcl_ros::DepthImageCreator::PointCloud
pcl::PointCloud< Point > PointCloud
Definition: depth_image_creator.h:166
tf::TransformListener
jsk_pcl_ros::DepthImageCreator::fill_value
float fill_value
Definition: depth_image_creator.h:164
jsk_pcl_ros::DepthImageCreator::use_asynchronous
bool use_asynchronous
Definition: depth_image_creator.h:152
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::DepthImageCreator::pub_depth_
ros::Publisher pub_depth_
Definition: depth_image_creator.h:139
jsk_pcl_ros::DepthImageCreator::max_pub_queue_size_
int max_pub_queue_size_
Definition: depth_image_creator.h:158
jsk_pcl_ros::DepthImageCreator::unsubscribe
void unsubscribe()
Definition: depth_image_creator_nodelet.cpp:150
jsk_pcl_ros::DepthImageCreator::sub_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
Definition: depth_image_creator.h:136
jsk_pcl_ros::DepthImageCreator::scale_depth
double scale_depth
Definition: depth_image_creator.h:162
jsk_pcl_ros::DepthImageCreator::use_service
bool use_service
Definition: depth_image_creator.h:151
sample_pointcloud_localization_client.req
req
Definition: sample_pointcloud_localization_client.py:15
jsk_pcl_ros::DepthImageCreator::sync_inputs_e_
boost::shared_ptr< message_filters::Synchronizer< message_filters::sync_policies::ExactTime< sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 > > > sync_inputs_e_
Definition: depth_image_creator.h:147
jsk_pcl_ros::DepthImageCreator::max_sub_queue_size_
int max_sub_queue_size_
Definition: depth_image_creator.h:159
sample_empty_service_caller.res
res
Definition: sample_empty_service_caller.py:14
jsk_pcl_ros::DepthImageCreator::tf_listener_
tf::TransformListener * tf_listener_
Definition: depth_image_creator.h:161
ros::Subscriber
jsk_pcl_ros::DepthImageCreator::sub_as_info_
ros::Subscriber sub_as_info_
Definition: depth_image_creator.h:137


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:44