Public Member Functions | Protected Member Functions | Protected Attributes
jsk_pcl_ros::FuseImages Class Reference

#include <fuse_images.h>

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

List of all members.

Public Member Functions

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

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.
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.
bool averaging_
std::string encoding_
std::vector< boost::shared_ptr
< message_filters::Subscriber
< sensor_msgs::Image > > > 
filters_
 A vector of message filters.
message_filters::PassThrough
< sensor_msgs::Image > 
nf_
 Null passthrough filter, used for pushing empty elements in the synchronizer.
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 51 of file fuse_images.h.


Constructor & Destructor Documentation

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

Definition at line 54 of file fuse_images.h.


Member Function Documentation

virtual cv::Mat jsk_pcl_ros::FuseImages::fuseInputs ( std::vector< cv::Mat >  inputs) [inline, protected, virtual]

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

Definition at line 104 of file fuse_images.h.

void jsk_pcl_ros::FuseImages::input_callback ( const sensor_msgs::Image::ConstPtr &  input) [inline, protected]

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 92 of file fuse_images.h.

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 
) [protected, virtual]

Definition at line 235 of file fuse_images.cpp.

void jsk_pcl_ros::FuseImages::onInit ( void  ) [protected, virtual]

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 48 of file fuse_images.cpp.

void jsk_pcl_ros::FuseImages::subscribe ( ) [protected, virtual]

Implements jsk_topic_tools::ConnectionBasedNodelet.

Definition at line 55 of file fuse_images.cpp.

void jsk_pcl_ros::FuseImages::unsubscribe ( ) [protected, virtual]

Implements jsk_topic_tools::ConnectionBasedNodelet.

Definition at line 201 of file fuse_images.cpp.

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 
) [protected, virtual]

Definition at line 208 of file fuse_images.cpp.


Member Data Documentation

Definition at line 65 of file fuse_images.h.

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 82 of file fuse_images.h.

Definition at line 67 of file fuse_images.h.

std::string jsk_pcl_ros::FuseImages::encoding_ [protected]

Definition at line 68 of file fuse_images.h.

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 75 of file fuse_images.h.

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

Definition at line 72 of file fuse_images.h.

Definition at line 63 of file fuse_images.h.

Definition at line 66 of file fuse_images.h.

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 85 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 Sun Oct 8 2017 02:43:51