Public Member Functions | Protected Member Functions | Protected Attributes
resized_image_transport::ImageProcessing Class Reference

#include <image_processing_nodelet.h>

Inheritance diagram for resized_image_transport::ImageProcessing:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 ImageProcessing ()
 ~ImageProcessing ()

Protected Member Functions

void callback (const sensor_msgs::ImageConstPtr &img, const sensor_msgs::CameraInfoConstPtr &info)
void image_cb (const sensor_msgs::ImageConstPtr &img)
void image_nonsync_cb (const sensor_msgs::ImageConstPtr &img)
void info_cb (const sensor_msgs::CameraInfoConstPtr &info)
void initNodeHandle ()
void initParams ()
void initPublishersAndSubscribers ()
void initReconfigure ()
void onInit ()
virtual void process (const sensor_msgs::ImageConstPtr &src_img, const sensor_msgs::CameraInfoConstPtr &src_info, sensor_msgs::ImagePtr &dst_img, sensor_msgs::CameraInfo &dst_info)=0
void snapshot_msg_cb (const std_msgs::EmptyConstPtr msg)
bool snapshot_srv_cb (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
virtual void updateDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat)

Protected Attributes

ros::Subscriber camera_info_sub_
image_transport::CameraPublisher cp_
image_transport::CameraSubscriber cs_
jsk_topic_tools::TimeredDiagnosticUpdater::Ptr diagnostic_updater_
int dst_height_
int dst_width_
ros::Publisher height_scale_pub_
image_transport::Subscriber image_nonsync_sub_
ros::Publisher image_pub_
ros::Subscriber image_sub_
jsk_topic_tools::VitalChecker::Ptr image_vital_
boost::circular_buffer< double > in_bytes
boost::circular_buffer< double > in_times
sensor_msgs::CameraInfoConstPtr info_msg_
jsk_topic_tools::VitalChecker::Ptr info_vital_
image_transport::ImageTransportit_
ros::Time last_publish_time_
ros::Time last_rosinfo_time_
ros::Time last_subscribe_time_
int max_queue_size_
boost::mutex mutex_
ros::NodeHandle nh
boost::circular_buffer< double > out_bytes
boost::circular_buffer< double > out_times
ros::Duration period_
ros::NodeHandle pnh
bool publish_once_
double resize_x_
double resize_y_
ros::ServiceServer srv_
ros::Subscriber sub_
bool use_bytes_
bool use_camera_info_
bool use_camera_subscriber_
bool use_messages_
bool use_snapshot_
bool verbose_
ros::Publisher width_scale_pub_

Detailed Description

Definition at line 29 of file image_processing_nodelet.h.


Constructor & Destructor Documentation

Definition at line 84 of file image_processing_nodelet.h.

Definition at line 90 of file image_processing_nodelet.h.


Member Function Documentation

void resized_image_transport::ImageProcessing::callback ( const sensor_msgs::ImageConstPtr &  img,
const sensor_msgs::CameraInfoConstPtr &  info 
) [protected]

Definition at line 233 of file image_processing_nodelet.cpp.

void resized_image_transport::ImageProcessing::image_cb ( const sensor_msgs::ImageConstPtr &  img) [protected]

Definition at line 228 of file image_processing_nodelet.cpp.

void resized_image_transport::ImageProcessing::image_nonsync_cb ( const sensor_msgs::ImageConstPtr &  img) [protected]

Definition at line 129 of file image_processing_nodelet.cpp.

void resized_image_transport::ImageProcessing::info_cb ( const sensor_msgs::CameraInfoConstPtr &  info) [protected]

Definition at line 123 of file image_processing_nodelet.cpp.

Definition at line 15 of file image_processing_nodelet.cpp.

Definition at line 50 of file image_processing_nodelet.cpp.

void resized_image_transport::ImageProcessing::onInit ( ) [protected, virtual]
virtual void resized_image_transport::ImageProcessing::process ( const sensor_msgs::ImageConstPtr &  src_img,
const sensor_msgs::CameraInfoConstPtr &  src_info,
sensor_msgs::ImagePtr &  dst_img,
sensor_msgs::CameraInfo &  dst_info 
) [protected, pure virtual]
void resized_image_transport::ImageProcessing::snapshot_msg_cb ( const std_msgs::EmptyConstPtr  msg) [protected]

Definition at line 110 of file image_processing_nodelet.cpp.

bool resized_image_transport::ImageProcessing::snapshot_srv_cb ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
) [protected]

Definition at line 115 of file image_processing_nodelet.cpp.

Definition at line 141 of file image_processing_nodelet.cpp.


Member Data Documentation

Definition at line 46 of file image_processing_nodelet.h.

Definition at line 38 of file image_processing_nodelet.h.

Definition at line 37 of file image_processing_nodelet.h.

Definition at line 73 of file image_processing_nodelet.h.

Definition at line 53 of file image_processing_nodelet.h.

Definition at line 53 of file image_processing_nodelet.h.

Definition at line 48 of file image_processing_nodelet.h.

Definition at line 45 of file image_processing_nodelet.h.

Definition at line 43 of file image_processing_nodelet.h.

Definition at line 44 of file image_processing_nodelet.h.

Definition at line 71 of file image_processing_nodelet.h.

boost::circular_buffer<double> resized_image_transport::ImageProcessing::in_bytes [protected]

Definition at line 68 of file image_processing_nodelet.h.

boost::circular_buffer<double> resized_image_transport::ImageProcessing::in_times [protected]

Definition at line 66 of file image_processing_nodelet.h.

sensor_msgs::CameraInfoConstPtr resized_image_transport::ImageProcessing::info_msg_ [protected]

Definition at line 50 of file image_processing_nodelet.h.

Definition at line 72 of file image_processing_nodelet.h.

Definition at line 39 of file image_processing_nodelet.h.

Definition at line 62 of file image_processing_nodelet.h.

Definition at line 62 of file image_processing_nodelet.h.

Definition at line 62 of file image_processing_nodelet.h.

Definition at line 54 of file image_processing_nodelet.h.

Definition at line 64 of file image_processing_nodelet.h.

Definition at line 33 of file image_processing_nodelet.h.

boost::circular_buffer<double> resized_image_transport::ImageProcessing::out_bytes [protected]

Definition at line 69 of file image_processing_nodelet.h.

boost::circular_buffer<double> resized_image_transport::ImageProcessing::out_times [protected]

Definition at line 67 of file image_processing_nodelet.h.

Definition at line 63 of file image_processing_nodelet.h.

Definition at line 34 of file image_processing_nodelet.h.

Definition at line 57 of file image_processing_nodelet.h.

Definition at line 52 of file image_processing_nodelet.h.

Definition at line 52 of file image_processing_nodelet.h.

Definition at line 40 of file image_processing_nodelet.h.

Reimplemented in resized_image_transport::ImageResizer.

Definition at line 41 of file image_processing_nodelet.h.

Definition at line 59 of file image_processing_nodelet.h.

Definition at line 60 of file image_processing_nodelet.h.

Definition at line 55 of file image_processing_nodelet.h.

Definition at line 58 of file image_processing_nodelet.h.

Definition at line 56 of file image_processing_nodelet.h.

Definition at line 61 of file image_processing_nodelet.h.

Definition at line 47 of file image_processing_nodelet.h.


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


resized_image_transport
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:39