35 #ifndef JSK_PCL_ROS_FUSE_DEPTH_IMAGES_H_
36 #define JSK_PCL_ROS_FUSE_DEPTH_IMAGES_H_
40 #include <jsk_topic_tools/diagnostic_nodelet.h>
46 #include <sensor_msgs/Image.h>
51 class FuseImages:
public jsk_topic_tools::DiagnosticNodelet
54 FuseImages(
const std::string& name,
const std::string& encoding):
61 virtual bool validateInput(
const sensor_msgs::Image::ConstPtr& in,
62 const int height_expected,
const int width_expected, std::vector<cv::Mat>& inputs);
76 std::vector<boost::shared_ptr<message_filters::Subscriber<sensor_msgs::Image> > >
filters_;
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_;
97 nf_.
add(boost::make_shared<sensor_msgs::Image> (
imgmsg));
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);
105 virtual cv::Mat
fuseInputs(std::vector<cv::Mat> inputs) {};
109 class FuseDepthImages:
public FuseImages
114 virtual cv::Mat
fuseInputs(std::vector<cv::Mat> inputs);
117 class FuseRGBImages:
public FuseImages
122 virtual cv::Mat
fuseInputs(std::vector<cv::Mat> inputs);
127 #endif // JSK_PCL_ROS_FUSE_DEPTH_IMAGES_H_