35 #ifndef JSK_PCL_ROS_FUSE_DEPTH_IMAGES_H_ 36 #define JSK_PCL_ROS_FUSE_DEPTH_IMAGES_H_ 46 #include <sensor_msgs/Image.h> 54 FuseImages(
const std::string& name,
const std::string& encoding):
60 virtual bool validateInput(
const sensor_msgs::Image::ConstPtr& in,
61 const int height_expected,
const int width_expected, std::vector<cv::Mat>& inputs);
75 std::vector<boost::shared_ptr<message_filters::Subscriber<sensor_msgs::Image> > >
filters_;
81 sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image,
82 sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image> > >
async_;
84 sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image,
85 sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image> > >
sync_;
95 imgmsg.header.stamp = input->header.stamp;
96 nf_.
add(boost::make_shared<sensor_msgs::Image> (imgmsg));
99 virtual void inputCb(
const sensor_msgs::Image::ConstPtr &in1,
const sensor_msgs::Image::ConstPtr &in2,
100 const sensor_msgs::Image::ConstPtr &in3,
const sensor_msgs::Image::ConstPtr &in4,
101 const sensor_msgs::Image::ConstPtr &in5,
const sensor_msgs::Image::ConstPtr &in6,
102 const sensor_msgs::Image::ConstPtr &in7,
const sensor_msgs::Image::ConstPtr &in8);
113 virtual cv::Mat
fuseInputs(std::vector<cv::Mat> inputs);
121 virtual cv::Mat
fuseInputs(std::vector<cv::Mat> inputs);
126 #endif // JSK_PCL_ROS_FUSE_DEPTH_IMAGES_H_
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.
virtual bool validateInput(const sensor_msgs::Image::ConstPtr &in, const int height_expected, const int width_expected, std::vector< cv::Mat > &inputs)
virtual void unsubscribe()
FuseImages(const std::string &name, const std::string &encoding)
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...
const std::string TYPE_32FC1
virtual cv::Mat fuseInputs(std::vector< cv::Mat > inputs)
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)
std::vector< boost::shared_ptr< message_filters::Subscriber< sensor_msgs::Image > > > filters_
A vector of message filters.
void add(const MConstPtr &msg)
message_filters::PassThrough< sensor_msgs::Image > nf_
Null passthrough filter, used for pushing empty elements in the synchronizer.
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_