#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 83 of file fuse_images.h.
◆ FuseImages()
◆ ~FuseImages()
jsk_pcl_ros::FuseImages::~FuseImages |
( |
| ) |
|
|
virtual |
◆ fuseInputs()
virtual cv::Mat jsk_pcl_ros::FuseImages::fuseInputs |
( |
std::vector< cv::Mat > |
inputs | ) |
|
|
inlineprotectedvirtual |
◆ input_callback()
void jsk_pcl_ros::FuseImages::input_callback |
( |
const sensor_msgs::Image::ConstPtr & |
input | ) |
|
|
inlineprotected |
Input point cloud callback. Because we want to use the same synchronizer object, we push back empty elements with the same timestamp.
Definition at line 157 of file fuse_images.h.
◆ inputCb()
void jsk_pcl_ros::FuseImages::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 |
|
) |
| |
|
protectedvirtual |
◆ onInit()
void jsk_pcl_ros::FuseImages::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ subscribe()
void jsk_pcl_ros::FuseImages::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
void jsk_pcl_ros::FuseImages::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ validateInput()
bool jsk_pcl_ros::FuseImages::validateInput |
( |
const sensor_msgs::Image::ConstPtr & |
in, |
|
|
const int |
height_expected, |
|
|
const int |
width_expected, |
|
|
std::vector< cv::Mat > & |
inputs |
|
) |
| |
|
protectedvirtual |
◆ approximate_sync_
bool jsk_pcl_ros::FuseImages::approximate_sync_ |
|
protected |
◆ async_
Synchronizer.
- Note
- This will most likely be rewritten soon using the DynamicTimeSynchronizer.
Definition at line 147 of file fuse_images.h.
◆ averaging_
bool jsk_pcl_ros::FuseImages::averaging_ |
|
protected |
◆ encoding_
◆ filters_
◆ nf_
Null passthrough filter, used for pushing empty elements in the synchronizer.
Definition at line 137 of file fuse_images.h.
◆ pub_out_
◆ queue_size_
int jsk_pcl_ros::FuseImages::queue_size_ |
|
protected |
◆ sync_
The documentation for this class was generated from the following files: