#include <fuse_images.h>
|
virtual cv::Mat | fuseInputs (std::vector< cv::Mat > inputs) |
|
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 elements with the same timestamp. More...
|
|
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) |
|
virtual void | onInit () |
|
virtual void | subscribe () |
|
virtual void | unsubscribe () |
|
virtual bool | validateInput (const sensor_msgs::Image::ConstPtr &in, const int height_expected, const int width_expected, std::vector< cv::Mat > &inputs) |
|
|
bool | approximate_sync_ |
|
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. More...
|
|
bool | averaging_ |
|
std::string | encoding_ |
|
std::vector< boost::shared_ptr< message_filters::Subscriber< sensor_msgs::Image > > > | filters_ |
| A vector of message filters. More...
|
|
message_filters::PassThrough< sensor_msgs::Image > | nf_ |
| Null passthrough filter, used for pushing empty elements in the synchronizer. More...
|
|
ros::Publisher | pub_out_ |
|
int | queue_size_ |
|
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 at line 149 of file fuse_images.h.
◆ FuseRGBImages()
jsk_pcl_ros::FuseRGBImages::FuseRGBImages |
( |
| ) |
|
|
inline |
◆ fuseInputs()
cv::Mat jsk_pcl_ros::FuseRGBImages::fuseInputs |
( |
std::vector< cv::Mat > |
inputs | ) |
|
|
protectedvirtual |
The documentation for this class was generated from the following files: