Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage Class Reference

#include <mask_image_to_depth_considered_mask_image.h>

Inheritance diagram for jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage:
Inheritance graph
[legend]

Public Types

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::Image > ApproximateSyncPolicy
 
typedef jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImageConfig Config
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::Image > SyncPolicy
 

Public Member Functions

 MaskImageToDepthConsideredMaskImage ()
 
virtual ~MaskImageToDepthConsideredMaskImage ()
 

Protected Member Functions

virtual void configCallback (Config &config, uint32_t level)
 
virtual void extractmask (const sensor_msgs::PointCloud2::ConstPtr &point_cloud2_msg, const sensor_msgs::Image::ConstPtr &image_msg)
 
virtual void mask_region_callback (const sensor_msgs::Image::ConstPtr &msg)
 
virtual void onInit ()
 
virtual void subscribe ()
 
virtual void unsubscribe ()
 

Protected Attributes

ros::Publisher applypub_
 
bool approximate_sync_
 
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
 
int extract_num_
 
bool in_the_order_of_depth_
 
boost::mutex mutex_
 
ros::Publisher pub_
 
int queue_size_
 
int region_height_
 
double region_height_ratio_
 
int region_width_
 
double region_width_ratio_
 
int region_x_off_
 
double region_x_off_ratio_
 
int region_y_off_
 
double region_y_off_ratio_
 
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
 
ros::Subscriber sub_
 
message_filters::Subscriber< sensor_msgs::Image > sub_image_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
 
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
 
bool use_mask_region_
 
bool use_region_ratio_
 

Detailed Description

Definition at line 84 of file mask_image_to_depth_considered_mask_image.h.

Member Typedef Documentation

◆ ApproximateSyncPolicy

Definition at line 121 of file mask_image_to_depth_considered_mask_image.h.

◆ Config

typedef jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImageConfig jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::Config

Definition at line 125 of file mask_image_to_depth_considered_mask_image.h.

◆ SyncPolicy

Definition at line 124 of file mask_image_to_depth_considered_mask_image.h.

Constructor & Destructor Documentation

◆ MaskImageToDepthConsideredMaskImage()

jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::MaskImageToDepthConsideredMaskImage ( )
inline

Definition at line 127 of file mask_image_to_depth_considered_mask_image.h.

◆ ~MaskImageToDepthConsideredMaskImage()

jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::~MaskImageToDepthConsideredMaskImage ( )
virtual

Member Function Documentation

◆ configCallback()

void jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::configCallback ( Config config,
uint32_t  level 
)
protectedvirtual

◆ extractmask()

void jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::extractmask ( const sensor_msgs::PointCloud2::ConstPtr &  point_cloud2_msg,
const sensor_msgs::Image::ConstPtr &  image_msg 
)
protectedvirtual

◆ mask_region_callback()

void jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::mask_region_callback ( const sensor_msgs::Image::ConstPtr &  msg)
protectedvirtual

◆ onInit()

void jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::onInit ( )
protectedvirtual

◆ subscribe()

void jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::subscribe ( )
protectedvirtual

◆ unsubscribe()

void jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::unsubscribe ( )
protectedvirtual

Member Data Documentation

◆ applypub_

ros::Publisher jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::applypub_
protected

Definition at line 156 of file mask_image_to_depth_considered_mask_image.h.

◆ approximate_sync_

bool jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::approximate_sync_
protected

Definition at line 147 of file mask_image_to_depth_considered_mask_image.h.

◆ async_

boost::shared_ptr<message_filters::Synchronizer<ApproximateSyncPolicy> > jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::async_
protected

Definition at line 152 of file mask_image_to_depth_considered_mask_image.h.

◆ extract_num_

int jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::extract_num_
protected

Definition at line 149 of file mask_image_to_depth_considered_mask_image.h.

◆ in_the_order_of_depth_

bool jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::in_the_order_of_depth_
protected

Definition at line 168 of file mask_image_to_depth_considered_mask_image.h.

◆ mutex_

boost::mutex jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::mutex_
protected

Definition at line 150 of file mask_image_to_depth_considered_mask_image.h.

◆ pub_

ros::Publisher jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::pub_
protected

Definition at line 155 of file mask_image_to_depth_considered_mask_image.h.

◆ queue_size_

int jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::queue_size_
protected

Definition at line 148 of file mask_image_to_depth_considered_mask_image.h.

◆ region_height_

int jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::region_height_
protected

Definition at line 159 of file mask_image_to_depth_considered_mask_image.h.

◆ region_height_ratio_

double jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::region_height_ratio_
protected

Definition at line 163 of file mask_image_to_depth_considered_mask_image.h.

◆ region_width_

int jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::region_width_
protected

Definition at line 158 of file mask_image_to_depth_considered_mask_image.h.

◆ region_width_ratio_

double jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::region_width_ratio_
protected

Definition at line 162 of file mask_image_to_depth_considered_mask_image.h.

◆ region_x_off_

int jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::region_x_off_
protected

Definition at line 160 of file mask_image_to_depth_considered_mask_image.h.

◆ region_x_off_ratio_

double jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::region_x_off_ratio_
protected

Definition at line 164 of file mask_image_to_depth_considered_mask_image.h.

◆ region_y_off_

int jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::region_y_off_
protected

Definition at line 161 of file mask_image_to_depth_considered_mask_image.h.

◆ region_y_off_ratio_

double jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::region_y_off_ratio_
protected

Definition at line 165 of file mask_image_to_depth_considered_mask_image.h.

◆ srv_

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::srv_
protected

Definition at line 146 of file mask_image_to_depth_considered_mask_image.h.

◆ sub_

ros::Subscriber jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::sub_
protected

Definition at line 157 of file mask_image_to_depth_considered_mask_image.h.

◆ sub_image_

message_filters::Subscriber<sensor_msgs::Image> jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::sub_image_
protected

Definition at line 154 of file mask_image_to_depth_considered_mask_image.h.

◆ sub_input_

message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::sub_input_
protected

Definition at line 153 of file mask_image_to_depth_considered_mask_image.h.

◆ sync_

boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::sync_
protected

Definition at line 151 of file mask_image_to_depth_considered_mask_image.h.

◆ use_mask_region_

bool jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::use_mask_region_
protected

Definition at line 167 of file mask_image_to_depth_considered_mask_image.h.

◆ use_region_ratio_

bool jsk_pcl_ros_utils::MaskImageToDepthConsideredMaskImage::use_region_ratio_
protected

Definition at line 166 of file mask_image_to_depth_considered_mask_image.h.


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


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:44