Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef JSK_PCL_ROS_FUSE_DEPTH_IMAGES_H_
00036 #define JSK_PCL_ROS_FUSE_DEPTH_IMAGES_H_
00037
00038 #include <vector>
00039
00040 #include <jsk_topic_tools/diagnostic_nodelet.h>
00041 #include <message_filters/pass_through.h>
00042 #include <message_filters/subscriber.h>
00043 #include <message_filters/synchronizer.h>
00044 #include <message_filters/sync_policies/approximate_time.h>
00045 #include <message_filters/time_synchronizer.h>
00046 #include <sensor_msgs/Image.h>
00047 #include <sensor_msgs/image_encodings.h>
00048
00049 namespace jsk_pcl_ros
00050 {
00051 class FuseImages: public jsk_topic_tools::DiagnosticNodelet
00052 {
00053 public:
00054 FuseImages(const std::string& name, const std::string& encoding):
00055 DiagnosticNodelet(name), encoding_(encoding) {}
00056 protected:
00057 virtual void onInit();
00058 virtual void subscribe();
00059 virtual void unsubscribe();
00060 virtual bool validateInput(const sensor_msgs::Image::ConstPtr& in,
00061 const int height_expected, const int width_expected, std::vector<cv::Mat>& inputs);
00062
00063 ros::Publisher pub_out_;
00064
00065 bool approximate_sync_;
00066 int queue_size_;
00067 bool averaging_;
00068 std::string encoding_;
00069
00072 message_filters::PassThrough<sensor_msgs::Image> nf_;
00073
00075 std::vector<boost::shared_ptr<message_filters::Subscriber<sensor_msgs::Image> > > filters_;
00076
00080 boost::shared_ptr<message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<
00081 sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image,
00082 sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image> > > async_;
00083 boost::shared_ptr<message_filters::Synchronizer<message_filters::sync_policies::ExactTime<
00084 sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image,
00085 sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image> > > sync_;
00086
00091 inline void
00092 input_callback (const sensor_msgs::Image::ConstPtr &input)
00093 {
00094 sensor_msgs::Image imgmsg;
00095 imgmsg.header.stamp = input->header.stamp;
00096 nf_.add(boost::make_shared<sensor_msgs::Image> (imgmsg));
00097 }
00098
00099 virtual void inputCb(const sensor_msgs::Image::ConstPtr &in1, const sensor_msgs::Image::ConstPtr &in2,
00100 const sensor_msgs::Image::ConstPtr &in3, const sensor_msgs::Image::ConstPtr &in4,
00101 const sensor_msgs::Image::ConstPtr &in5, const sensor_msgs::Image::ConstPtr &in6,
00102 const sensor_msgs::Image::ConstPtr &in7, const sensor_msgs::Image::ConstPtr &in8);
00103
00104 virtual cv::Mat fuseInputs(std::vector<cv::Mat> inputs) {};
00105 private:
00106 };
00107
00108 class FuseDepthImages: public FuseImages
00109 {
00110 public:
00111 FuseDepthImages(): FuseImages("FuseDepthImages", sensor_msgs::image_encodings::TYPE_32FC1) {};
00112 protected:
00113 virtual cv::Mat fuseInputs(std::vector<cv::Mat> inputs);
00114 };
00115
00116 class FuseRGBImages: public FuseImages
00117 {
00118 public:
00119 FuseRGBImages(): FuseImages("FuseRGBImages", sensor_msgs::image_encodings::RGB8) {};
00120 protected:
00121 virtual cv::Mat fuseInputs(std::vector<cv::Mat> inputs);
00122 };
00123
00124 }
00125
00126 #endif // JSK_PCL_ROS_FUSE_DEPTH_IMAGES_H_