#include <capture_stereo_synchronizer.h>
Public Types | |
typedef boost::shared_ptr < CaptureStereoSynchronizer > | Ptr |
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 () | |
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::Pose > | poses_ |
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 < PCLIndicesMsg > | sub_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_ |
Definition at line 57 of file capture_stereo_synchronizer.h.
typedef boost::shared_ptr<CaptureStereoSynchronizer> jsk_pcl_ros::CaptureStereoSynchronizer::Ptr |
Definition at line 60 of file capture_stereo_synchronizer.h.
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 69 of file capture_stereo_synchronizer.h.
Definition at line 70 of file capture_stereo_synchronizer.h.
bool jsk_pcl_ros::CaptureStereoSynchronizer::checkNearPose | ( | const geometry_msgs::Pose & | new_pose | ) | [protected, virtual] |
Definition at line 68 of file capture_stereo_synchronizer_nodelet.cpp.
void jsk_pcl_ros::CaptureStereoSynchronizer::onInit | ( | void | ) | [protected, virtual] |
Definition at line 44 of file capture_stereo_synchronizer_nodelet.cpp.
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 | ||
) | [protected, virtual] |
Definition at line 129 of file capture_stereo_synchronizer_nodelet.cpp.
void jsk_pcl_ros::CaptureStereoSynchronizer::subscribe | ( | ) | [protected, virtual] |
Definition at line 90 of file capture_stereo_synchronizer_nodelet.cpp.
void jsk_pcl_ros::CaptureStereoSynchronizer::unsubscribe | ( | ) | [protected, virtual] |
Definition at line 118 of file capture_stereo_synchronizer_nodelet.cpp.
int jsk_pcl_ros::CaptureStereoSynchronizer::counter_ [protected] |
Definition at line 96 of file capture_stereo_synchronizer.h.
Definition at line 113 of file capture_stereo_synchronizer.h.
double jsk_pcl_ros::CaptureStereoSynchronizer::positional_bin_size_ [protected] |
Definition at line 118 of file capture_stereo_synchronizer.h.
Definition at line 97 of file capture_stereo_synchronizer.h.
Definition at line 104 of file capture_stereo_synchronizer.h.
Definition at line 102 of file capture_stereo_synchronizer.h.
Definition at line 101 of file capture_stereo_synchronizer.h.
Definition at line 99 of file capture_stereo_synchronizer.h.
Definition at line 100 of file capture_stereo_synchronizer.h.
Definition at line 98 of file capture_stereo_synchronizer.h.
Definition at line 103 of file capture_stereo_synchronizer.h.
double jsk_pcl_ros::CaptureStereoSynchronizer::rotational_bin_size_ [protected] |
Definition at line 117 of file capture_stereo_synchronizer.h.
message_filters::Subscriber<stereo_msgs::DisparityImage> jsk_pcl_ros::CaptureStereoSynchronizer::sub_disparity_ [protected] |
Definition at line 111 of file capture_stereo_synchronizer.h.
message_filters::Subscriber<sensor_msgs::CameraInfo> jsk_pcl_ros::CaptureStereoSynchronizer::sub_left_cam_info_ [protected] |
Definition at line 109 of file capture_stereo_synchronizer.h.
message_filters::Subscriber<sensor_msgs::Image> jsk_pcl_ros::CaptureStereoSynchronizer::sub_left_image_ [protected] |
Definition at line 108 of file capture_stereo_synchronizer.h.
message_filters::Subscriber<sensor_msgs::Image> jsk_pcl_ros::CaptureStereoSynchronizer::sub_mask_ [protected] |
Definition at line 106 of file capture_stereo_synchronizer.h.
message_filters::Subscriber<PCLIndicesMsg> jsk_pcl_ros::CaptureStereoSynchronizer::sub_mask_indices_ [protected] |
Definition at line 107 of file capture_stereo_synchronizer.h.
message_filters::Subscriber<geometry_msgs::PoseStamped> jsk_pcl_ros::CaptureStereoSynchronizer::sub_pose_ [protected] |
Definition at line 105 of file capture_stereo_synchronizer.h.
message_filters::Subscriber<sensor_msgs::CameraInfo> jsk_pcl_ros::CaptureStereoSynchronizer::sub_right_cam_info_ [protected] |
Definition at line 110 of file capture_stereo_synchronizer.h.
boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::CaptureStereoSynchronizer::sync_ [protected] |
Definition at line 112 of file capture_stereo_synchronizer.h.