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

#include <capture_stereo_synchronizer.h>

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

Public Types

typedef boost::shared_ptr< CaptureStereoSynchronizerPtr
 
typedef message_filters::sync_policies::ExactTime< geometry_msgs::PoseStamped, sensor_msgs::Image, pcl_msgs::PointIndices, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo, stereo_msgs::DisparityImage > SyncPolicy
 

Public Member Functions

 CaptureStereoSynchronizer ()
 
virtual ~CaptureStereoSynchronizer ()
 

Protected Member Functions

virtual bool checkNearPose (const geometry_msgs::Pose &new_pose)
 
virtual void onInit ()
 
virtual void republish (const geometry_msgs::PoseStamped::ConstPtr &pose, const sensor_msgs::Image::ConstPtr &mask, const PCLIndicesMsg::ConstPtr &mask_indices, const sensor_msgs::Image::ConstPtr &left_image, const sensor_msgs::CameraInfo::ConstPtr &left_cam_info, const sensor_msgs::CameraInfo::ConstPtr &right_cam_info, const stereo_msgs::DisparityImage::ConstPtr &disparity)
 
virtual void subscribe ()
 
virtual void unsubscribe ()
 

Protected Attributes

int counter_
 
std::vector< geometry_msgs::Poseposes_
 
double positional_bin_size_
 
ros::Publisher pub_count_
 
ros::Publisher pub_disparity_
 
ros::Publisher pub_left_cam_info_
 
ros::Publisher pub_left_image_
 
ros::Publisher pub_mask_
 
ros::Publisher pub_mask_indices_
 
ros::Publisher pub_pose_
 
ros::Publisher pub_right_cam_info_
 
double rotational_bin_size_
 
message_filters::Subscriber< stereo_msgs::DisparityImage > sub_disparity_
 
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_left_cam_info_
 
message_filters::Subscriber< sensor_msgs::Image > sub_left_image_
 
message_filters::Subscriber< sensor_msgs::Image > sub_mask_
 
message_filters::Subscriber< PCLIndicesMsgsub_mask_indices_
 
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_pose_
 
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_right_cam_info_
 
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
 

Detailed Description

Definition at line 89 of file capture_stereo_synchronizer.h.

Member Typedef Documentation

◆ Ptr

Definition at line 124 of file capture_stereo_synchronizer.h.

◆ SyncPolicy

typedef message_filters::sync_policies::ExactTime< geometry_msgs::PoseStamped, sensor_msgs::Image, pcl_msgs::PointIndices, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo, stereo_msgs::DisparityImage > jsk_pcl_ros::CaptureStereoSynchronizer::SyncPolicy

Definition at line 133 of file capture_stereo_synchronizer.h.

Constructor & Destructor Documentation

◆ CaptureStereoSynchronizer()

jsk_pcl_ros::CaptureStereoSynchronizer::CaptureStereoSynchronizer ( )
inline

Definition at line 134 of file capture_stereo_synchronizer.h.

◆ ~CaptureStereoSynchronizer()

jsk_pcl_ros::CaptureStereoSynchronizer::~CaptureStereoSynchronizer ( )
virtual

Definition at line 68 of file capture_stereo_synchronizer_nodelet.cpp.

Member Function Documentation

◆ checkNearPose()

bool jsk_pcl_ros::CaptureStereoSynchronizer::checkNearPose ( const geometry_msgs::Pose new_pose)
protectedvirtual

Definition at line 79 of file capture_stereo_synchronizer_nodelet.cpp.

◆ onInit()

void jsk_pcl_ros::CaptureStereoSynchronizer::onInit ( )
protectedvirtual

Definition at line 44 of file capture_stereo_synchronizer_nodelet.cpp.

◆ republish()

void jsk_pcl_ros::CaptureStereoSynchronizer::republish ( const geometry_msgs::PoseStamped::ConstPtr &  pose,
const sensor_msgs::Image::ConstPtr &  mask,
const PCLIndicesMsg::ConstPtr &  mask_indices,
const sensor_msgs::Image::ConstPtr &  left_image,
const sensor_msgs::CameraInfo::ConstPtr &  left_cam_info,
const sensor_msgs::CameraInfo::ConstPtr &  right_cam_info,
const stereo_msgs::DisparityImage::ConstPtr &  disparity 
)
protectedvirtual

Definition at line 140 of file capture_stereo_synchronizer_nodelet.cpp.

◆ subscribe()

void jsk_pcl_ros::CaptureStereoSynchronizer::subscribe ( )
protectedvirtual

Definition at line 101 of file capture_stereo_synchronizer_nodelet.cpp.

◆ unsubscribe()

void jsk_pcl_ros::CaptureStereoSynchronizer::unsubscribe ( )
protectedvirtual

Definition at line 129 of file capture_stereo_synchronizer_nodelet.cpp.

Member Data Documentation

◆ counter_

int jsk_pcl_ros::CaptureStereoSynchronizer::counter_
protected

Definition at line 161 of file capture_stereo_synchronizer.h.

◆ poses_

std::vector<geometry_msgs::Pose> jsk_pcl_ros::CaptureStereoSynchronizer::poses_
protected

Definition at line 178 of file capture_stereo_synchronizer.h.

◆ positional_bin_size_

double jsk_pcl_ros::CaptureStereoSynchronizer::positional_bin_size_
protected

Definition at line 183 of file capture_stereo_synchronizer.h.

◆ pub_count_

ros::Publisher jsk_pcl_ros::CaptureStereoSynchronizer::pub_count_
protected

Definition at line 162 of file capture_stereo_synchronizer.h.

◆ pub_disparity_

ros::Publisher jsk_pcl_ros::CaptureStereoSynchronizer::pub_disparity_
protected

Definition at line 169 of file capture_stereo_synchronizer.h.

◆ pub_left_cam_info_

ros::Publisher jsk_pcl_ros::CaptureStereoSynchronizer::pub_left_cam_info_
protected

Definition at line 167 of file capture_stereo_synchronizer.h.

◆ pub_left_image_

ros::Publisher jsk_pcl_ros::CaptureStereoSynchronizer::pub_left_image_
protected

Definition at line 166 of file capture_stereo_synchronizer.h.

◆ pub_mask_

ros::Publisher jsk_pcl_ros::CaptureStereoSynchronizer::pub_mask_
protected

Definition at line 164 of file capture_stereo_synchronizer.h.

◆ pub_mask_indices_

ros::Publisher jsk_pcl_ros::CaptureStereoSynchronizer::pub_mask_indices_
protected

Definition at line 165 of file capture_stereo_synchronizer.h.

◆ pub_pose_

ros::Publisher jsk_pcl_ros::CaptureStereoSynchronizer::pub_pose_
protected

Definition at line 163 of file capture_stereo_synchronizer.h.

◆ pub_right_cam_info_

ros::Publisher jsk_pcl_ros::CaptureStereoSynchronizer::pub_right_cam_info_
protected

Definition at line 168 of file capture_stereo_synchronizer.h.

◆ rotational_bin_size_

double jsk_pcl_ros::CaptureStereoSynchronizer::rotational_bin_size_
protected

Definition at line 182 of file capture_stereo_synchronizer.h.

◆ sub_disparity_

message_filters::Subscriber<stereo_msgs::DisparityImage> jsk_pcl_ros::CaptureStereoSynchronizer::sub_disparity_
protected

Definition at line 176 of file capture_stereo_synchronizer.h.

◆ sub_left_cam_info_

message_filters::Subscriber<sensor_msgs::CameraInfo> jsk_pcl_ros::CaptureStereoSynchronizer::sub_left_cam_info_
protected

Definition at line 174 of file capture_stereo_synchronizer.h.

◆ sub_left_image_

message_filters::Subscriber<sensor_msgs::Image> jsk_pcl_ros::CaptureStereoSynchronizer::sub_left_image_
protected

Definition at line 173 of file capture_stereo_synchronizer.h.

◆ sub_mask_

message_filters::Subscriber<sensor_msgs::Image> jsk_pcl_ros::CaptureStereoSynchronizer::sub_mask_
protected

Definition at line 171 of file capture_stereo_synchronizer.h.

◆ sub_mask_indices_

message_filters::Subscriber<PCLIndicesMsg> jsk_pcl_ros::CaptureStereoSynchronizer::sub_mask_indices_
protected

Definition at line 172 of file capture_stereo_synchronizer.h.

◆ sub_pose_

message_filters::Subscriber<geometry_msgs::PoseStamped> jsk_pcl_ros::CaptureStereoSynchronizer::sub_pose_
protected

Definition at line 170 of file capture_stereo_synchronizer.h.

◆ sub_right_cam_info_

message_filters::Subscriber<sensor_msgs::CameraInfo> jsk_pcl_ros::CaptureStereoSynchronizer::sub_right_cam_info_
protected

Definition at line 175 of file capture_stereo_synchronizer.h.

◆ sync_

boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::CaptureStereoSynchronizer::sync_
protected

Definition at line 177 of file capture_stereo_synchronizer.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:45