39 #include <opencv2/opencv.hpp> 50 DiagnosticNodelet::onInit();
51 pub_out_ = advertise<sensor_msgs::Image>(*
pnh_,
"output", 1);
62 if (!
pnh_->getParam(
"input_topics", input_topics))
69 NODELET_ERROR(
"Invalid type of '~input_topics' is specified. String array is expected.");
80 sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image,
81 sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image> >(
queue_size_));
86 sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image,
87 sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image> > (
queue_size_));
91 ROS_INFO(
"Subscribing to %d topics user given topics as inputs:", input_topics.
size());
92 for (
size_t i = 0; i < input_topics.
size (); i++)
102 if (input_topics.
size() == 2)
113 else if (input_topics.
size() == 3)
124 else if (input_topics.
size() == 4)
135 else if (input_topics.
size() == 5)
146 else if (input_topics.
size() == 6)
159 else if (input_topics.
size() == 7)
172 else if (input_topics.
size() == 8)
187 NODELET_ERROR(
"Invalid number of topics is specified: %d. It must be > 1 and <= 8.", input_topics.
size());
203 for (
size_t i = 0; i <
filters_.size(); i++) {
209 const sensor_msgs::Image::ConstPtr& in,
210 const int height_expected,
211 const int width_expected,
212 std::vector<cv::Mat>& inputs)
214 if (in->height == 0 && in->width == 0)
219 if (in->height != height_expected || in->width != width_expected)
222 height_expected, width_expected);
228 encoding_.c_str(), in->encoding.c_str());
236 const sensor_msgs::Image::ConstPtr& in1,
const sensor_msgs::Image::ConstPtr& in2,
237 const sensor_msgs::Image::ConstPtr& in3,
const sensor_msgs::Image::ConstPtr& in4,
238 const sensor_msgs::Image::ConstPtr& in5,
const sensor_msgs::Image::ConstPtr& in6,
239 const sensor_msgs::Image::ConstPtr& in7,
const sensor_msgs::Image::ConstPtr& in8)
242 int width = in1->width;
243 std::vector<cv::Mat> inputs;
260 out.setTo(std::numeric_limits<float>::quiet_NaN());
261 for (
size_t j = 0; j < inputs[0].rows; j++)
263 for (
size_t i = 0; i < inputs[0].cols; i++)
266 float value_fused = 0;
267 for (
size_t k = 0; k < inputs.size(); k++)
269 float value = inputs[k].at<
float>(j, i);
270 if (!std::isnan(value))
272 value_fused += value;
278 out.at<
float>(j, i) = value_fused / n_fused;
288 out.setTo(cv::Scalar(0, 0, 0));
289 for (
size_t j = 0; j < inputs[0].rows; j++)
291 for (
size_t i = 0; i < inputs[0].cols; i++)
294 cv::Vec3b value_fused(0, 0, 0);
295 for (
size_t k = 0; k < inputs.size(); k++)
297 cv::Vec3b
value = inputs[k].at<cv::Vec3b>(j, i);
298 if (value[0] != 0 || value[1] != 0 || value[2] != 0)
304 value_fused += value;
310 out.at<cv::Vec3b>(j, i) = value_fused / n_fused;
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
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)
#define NODELET_ERROR(...)
virtual void unsubscribe()
void publish(const boost::shared_ptr< M > &message) const
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...
#define NODELET_ERROR_THROTTLE(rate,...)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::FuseDepthImages, nodelet::Nodelet)
Type const & getType() const
virtual cv::Mat fuseInputs(std::vector< cv::Mat > inputs)
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)
int getCvType(const std::string &encoding)
std::vector< boost::shared_ptr< message_filters::Subscriber< sensor_msgs::Image > > > filters_
A vector of message filters.
#define ROS_INFO_STREAM(args)
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_
sensor_msgs::ImagePtr toImageMsg() const
virtual cv::Mat fuseInputs(std::vector< cv::Mat > inputs)