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)
 
- Public Member Functions inherited from jsk_topic_tools::DiagnosticNodelet
 DiagnosticNodelet (const std::string &name)
 
- Public Member Functions inherited from jsk_topic_tools::ConnectionBasedNodelet
 ConnectionBasedNodelet ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

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 Member Functions inherited from jsk_topic_tools::DiagnosticNodelet
virtual void updateDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat)
 
- Protected Member Functions inherited from jsk_topic_tools::ConnectionBasedNodelet
ros::Publisher advertise (ros::NodeHandle &nh, std::string topic, int queue_size)
 
image_transport::CameraPublisher advertiseCamera (ros::NodeHandle &nh, image_transport::ImageTransport &it, const std::string &topic, int queue_size)
 
image_transport::CameraPublisher advertiseCamera (ros::NodeHandle &nh, const std::string &topic, int queue_size)
 
image_transport::Publisher advertiseImage (ros::NodeHandle &nh, image_transport::ImageTransport &it, const std::string &topic, int queue_size)
 
image_transport::Publisher advertiseImage (ros::NodeHandle &nh, const std::string &topic, int queue_size)
 
virtual void cameraConnectionBaseCallback ()
 
virtual void cameraConnectionCallback (const image_transport::SingleSubscriberPublisher &pub)
 
virtual void cameraInfoConnectionCallback (const ros::SingleSubscriberPublisher &pub)
 
virtual void connectionCallback (const ros::SingleSubscriberPublisher &pub)
 
virtual void imageConnectionCallback (const image_transport::SingleSubscriberPublisher &pub)
 
virtual bool isSubscribed ()
 
virtual void onInitPostProcess ()
 
virtual void warnNeverSubscribedCallback (const ros::WallTimerEvent &event)
 
virtual void warnOnInitPostProcessCalledCallback (const ros::WallTimerEvent &event)
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::stringgetName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

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_
 
- Protected Attributes inherited from jsk_topic_tools::DiagnosticNodelet
TimeredDiagnosticUpdater::Ptr diagnostic_updater_
 
const std::string name_
 
jsk_topic_tools::VitalChecker::Ptr vital_checker_
 
- Protected Attributes inherited from jsk_topic_tools::ConnectionBasedNodelet
bool always_subscribe_
 
std::vector< image_transport::CameraPublishercamera_publishers_
 
boost::mutex connection_mutex_
 
ConnectionStatus connection_status_
 
bool ever_subscribed_
 
std::vector< image_transport::Publisherimage_publishers_
 
boost::shared_ptr< ros::NodeHandlenh_
 
bool on_init_post_process_called_
 
boost::shared_ptr< ros::NodeHandlepnh_
 
std::vector< ros::Publisherpublishers_
 
bool subscribed_
 
ros::WallTimer timer_warn_never_subscribed_
 
ros::WallTimer timer_warn_on_init_post_process_called_
 
bool verbose_connection_
 

Additional Inherited Members

- Public Types inherited from jsk_topic_tools::DiagnosticNodelet
typedef boost::shared_ptr< DiagnosticNodeletPtr
 

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)
inlineprotectedvirtual

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)
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 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 
)
protectedvirtual

Definition at line 235 of file fuse_images.cpp.

void jsk_pcl_ros::FuseImages::onInit ( void  )
protectedvirtual

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 48 of file fuse_images.cpp.

void jsk_pcl_ros::FuseImages::subscribe ( )
protectedvirtual

Implements jsk_topic_tools::ConnectionBasedNodelet.

Definition at line 55 of file fuse_images.cpp.

void jsk_pcl_ros::FuseImages::unsubscribe ( )
protectedvirtual

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 
)
protectedvirtual

Definition at line 208 of file fuse_images.cpp.

Member Data Documentation

bool jsk_pcl_ros::FuseImages::approximate_sync_
protected

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.

bool jsk_pcl_ros::FuseImages::averaging_
protected

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.

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

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

Definition at line 63 of file fuse_images.h.

int jsk_pcl_ros::FuseImages::queue_size_
protected

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 Mon May 3 2021 03:03:47