fuse_images.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Kentaro Wada and JSK Lab
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Kentaro Wada and JSK Lab nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #ifndef JSK_PCL_ROS_FUSE_DEPTH_IMAGES_H_
36 #define JSK_PCL_ROS_FUSE_DEPTH_IMAGES_H_
37 
38 #include <vector>
39 
40 #include <jsk_topic_tools/diagnostic_nodelet.h>
46 #include <sensor_msgs/Image.h>
48 
49 namespace jsk_pcl_ros
50 {
51  class FuseImages: public jsk_topic_tools::DiagnosticNodelet
52  {
53  public:
54  FuseImages(const std::string& name, const std::string& encoding):
55  DiagnosticNodelet(name), encoding_(encoding) {}
56  virtual ~FuseImages();
57  protected:
58  virtual void onInit();
59  virtual void subscribe();
60  virtual void unsubscribe();
61  virtual bool validateInput(const sensor_msgs::Image::ConstPtr& in,
62  const int height_expected, const int width_expected, std::vector<cv::Mat>& inputs);
63 
65 
66  bool approximate_sync_;
67  int queue_size_;
68  bool averaging_;
69  std::string encoding_;
70 
74 
76  std::vector<boost::shared_ptr<message_filters::Subscriber<sensor_msgs::Image> > > filters_;
77 
82  sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image,
83  sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image> > > async_;
85  sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image,
86  sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image> > > sync_;
87 
92  inline void
93  input_callback (const sensor_msgs::Image::ConstPtr &input)
94  {
95  sensor_msgs::Image imgmsg;
96  imgmsg.header.stamp = input->header.stamp;
97  nf_.add(boost::make_shared<sensor_msgs::Image> (imgmsg));
98  }
99 
100  virtual void inputCb(const sensor_msgs::Image::ConstPtr &in1, const sensor_msgs::Image::ConstPtr &in2,
101  const sensor_msgs::Image::ConstPtr &in3, const sensor_msgs::Image::ConstPtr &in4,
102  const sensor_msgs::Image::ConstPtr &in5, const sensor_msgs::Image::ConstPtr &in6,
103  const sensor_msgs::Image::ConstPtr &in7, const sensor_msgs::Image::ConstPtr &in8);
104 
105  virtual cv::Mat fuseInputs(std::vector<cv::Mat> inputs) {};
106  private:
107  };
108 
109  class FuseDepthImages: public FuseImages
110  {
111  public:
112  FuseDepthImages(): FuseImages("FuseDepthImages", sensor_msgs::image_encodings::TYPE_32FC1) {};
113  protected:
114  virtual cv::Mat fuseInputs(std::vector<cv::Mat> inputs);
115  };
116 
117  class FuseRGBImages: public FuseImages
118  {
119  public:
121  protected:
122  virtual cv::Mat fuseInputs(std::vector<cv::Mat> inputs);
123  };
124 
125 } // namespace jsk_pcl_ros
126 
127 #endif // JSK_PCL_ROS_FUSE_DEPTH_IMAGES_H_
jsk_pcl_ros::FuseImages::filters_
std::vector< boost::shared_ptr< message_filters::Subscriber< sensor_msgs::Image > > > filters_
A vector of message filters.
Definition: fuse_images.h:140
jsk_pcl_ros::FuseImages::onInit
virtual void onInit()
Definition: fuse_images.cpp:80
ros::Publisher
image_encodings.h
message_filters::Synchronizer
pass_through.h
boost::shared_ptr
jsk_pcl_ros::FuseDepthImages::FuseDepthImages
FuseDepthImages()
Definition: fuse_images.h:144
jsk_pcl_ros::FuseImages::nf_
message_filters::PassThrough< sensor_msgs::Image > nf_
Null passthrough filter, used for pushing empty elements in the synchronizer.
Definition: fuse_images.h:137
jsk_pcl_ros::FuseImages::approximate_sync_
bool approximate_sync_
Definition: fuse_images.h:130
jsk_pcl_ros::FuseImages::inputCb
virtual void inputCb(const sensor_msgs::Image::ConstPtr &in1, const sensor_msgs::Image::ConstPtr &in2, const sensor_msgs::Image::ConstPtr &in3, const sensor_msgs::Image::ConstPtr &in4, const sensor_msgs::Image::ConstPtr &in5, const sensor_msgs::Image::ConstPtr &in6, const sensor_msgs::Image::ConstPtr &in7, const sensor_msgs::Image::ConstPtr &in8)
Definition: fuse_images.cpp:279
jsk_pcl_ros::FuseImages::unsubscribe
virtual void unsubscribe()
Definition: fuse_images.cpp:245
jsk_pcl_ros::FuseImages::pub_out_
ros::Publisher pub_out_
Definition: fuse_images.h:128
time_synchronizer.h
jsk_pcl_ros::FuseImages::~FuseImages
virtual ~FuseImages()
Definition: fuse_images.cpp:87
sensor_msgs::image_encodings::RGB8
const std::string RGB8
jsk_pcl_ros::FuseImages::FuseImages
FuseImages(const std::string &name, const std::string &encoding)
Definition: fuse_images.h:118
jsk_pcl_ros::FuseImages::async_
boost::shared_ptr< message_filters::Synchronizer< message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image > > > async_
Synchronizer.
Definition: fuse_images.h:147
message_filters::sync_policies::ApproximateTime
jsk_pcl_ros::FuseDepthImages::fuseInputs
virtual cv::Mat fuseInputs(std::vector< cv::Mat > inputs)
Definition: fuse_images.cpp:301
jsk_pcl_ros::FuseImages::sync_
boost::shared_ptr< message_filters::Synchronizer< message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image > > > sync_
Definition: fuse_images.h:150
jsk_pcl_ros
Definition: add_color_from_image.h:51
name
std::string name
subscriber.h
jsk_pcl_ros::FuseImages::validateInput
virtual bool validateInput(const sensor_msgs::Image::ConstPtr &in, const int height_expected, const int width_expected, std::vector< cv::Mat > &inputs)
Definition: fuse_images.cpp:252
jsk_pcl_ros::FuseImages::encoding_
std::string encoding_
Definition: fuse_images.h:133
message_filters::PassThrough::add
void add(const EventType &evt)
jsk_pcl_ros::FuseImages::fuseInputs
virtual cv::Mat fuseInputs(std::vector< cv::Mat > inputs)
Definition: fuse_images.h:169
message_filters::PassThrough< sensor_msgs::Image >
TYPE_32FC1
const std::string TYPE_32FC1
jsk_pcl_ros::FuseImages::subscribe
virtual void subscribe()
Definition: fuse_images.cpp:99
jsk_pcl_ros::FuseImages::input_callback
void input_callback(const sensor_msgs::Image::ConstPtr &input)
Input point cloud callback. Because we want to use the same synchronizer object, we push back empty e...
Definition: fuse_images.h:157
jsk_pcl_ros::FuseImages::averaging_
bool averaging_
Definition: fuse_images.h:132
synchronizer.h
imgmsg
imgmsg
approximate_time.h
jsk_pcl_ros::FuseRGBImages::FuseRGBImages
FuseRGBImages()
Definition: fuse_images.h:152
depth_error_calibration.input
input
Definition: depth_error_calibration.py:43
encoding
std::string encoding
message_filters::sync_policies::ExactTime
jsk_pcl_ros::FuseImages::queue_size_
int queue_size_
Definition: fuse_images.h:131
sensor_msgs
jsk_pcl_ros::FuseRGBImages::fuseInputs
virtual cv::Mat fuseInputs(std::vector< cv::Mat > inputs)
Definition: fuse_images.cpp:329


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