Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_pcl_ros::FuseImages Class Reference

#include <fuse_images.h>

Inheritance diagram for jsk_pcl_ros::FuseImages:
Inheritance graph
[legend]

Public Member Functions

 FuseImages (const std::string &name, const std::string &encoding)
 
virtual ~FuseImages ()
 

Protected Member Functions

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)
 

Protected Attributes

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_
 

Detailed Description

Definition at line 83 of file fuse_images.h.

Constructor & Destructor Documentation

◆ FuseImages()

jsk_pcl_ros::FuseImages::FuseImages ( const std::string name,
const std::string encoding 
)
inline

Definition at line 118 of file fuse_images.h.

◆ ~FuseImages()

jsk_pcl_ros::FuseImages::~FuseImages ( )
virtual

Definition at line 87 of file fuse_images.cpp.

Member Function Documentation

◆ fuseInputs()

virtual cv::Mat jsk_pcl_ros::FuseImages::fuseInputs ( std::vector< cv::Mat >  inputs)
inlineprotectedvirtual

Reimplemented in jsk_pcl_ros::FuseRGBImages, and jsk_pcl_ros::FuseDepthImages.

Definition at line 169 of file fuse_images.h.

◆ 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

Definition at line 279 of file fuse_images.cpp.

◆ onInit()

void jsk_pcl_ros::FuseImages::onInit ( )
protectedvirtual

Definition at line 80 of file fuse_images.cpp.

◆ subscribe()

void jsk_pcl_ros::FuseImages::subscribe ( )
protectedvirtual

Definition at line 99 of file fuse_images.cpp.

◆ unsubscribe()

void jsk_pcl_ros::FuseImages::unsubscribe ( )
protectedvirtual

Definition at line 245 of file fuse_images.cpp.

◆ 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

Definition at line 252 of file fuse_images.cpp.

Member Data Documentation

◆ approximate_sync_

bool jsk_pcl_ros::FuseImages::approximate_sync_
protected

Definition at line 130 of file fuse_images.h.

◆ async_

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> > > jsk_pcl_ros::FuseImages::async_
protected

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

Definition at line 132 of file fuse_images.h.

◆ encoding_

std::string jsk_pcl_ros::FuseImages::encoding_
protected

Definition at line 133 of file fuse_images.h.

◆ filters_

std::vector<boost::shared_ptr<message_filters::Subscriber<sensor_msgs::Image> > > jsk_pcl_ros::FuseImages::filters_
protected

A vector of message filters.

Definition at line 140 of file fuse_images.h.

◆ nf_

message_filters::PassThrough<sensor_msgs::Image> jsk_pcl_ros::FuseImages::nf_
protected

Null passthrough filter, used for pushing empty elements in the synchronizer.

Definition at line 137 of file fuse_images.h.

◆ pub_out_

ros::Publisher jsk_pcl_ros::FuseImages::pub_out_
protected

Definition at line 128 of file fuse_images.h.

◆ queue_size_

int jsk_pcl_ros::FuseImages::queue_size_
protected

Definition at line 131 of file fuse_images.h.

◆ sync_

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> > > jsk_pcl_ros::FuseImages::sync_
protected

Definition at line 150 of file fuse_images.h.


The documentation for this class was generated from the following files:


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:46