Go to the documentation of this file.
36 #ifndef JSK_PCL_ROS_CAPTURE_STEREO_SYNCHRONIZER_H_
37 #define JSK_PCL_ROS_CAPTURE_STEREO_SYNCHRONIZER_H_
46 #include <jsk_topic_tools/diagnostic_nodelet.h>
48 #include <sensor_msgs/Image.h>
49 #include <sensor_msgs/CameraInfo.h>
50 #include <stereo_msgs/DisparityImage.h>
51 #include <geometry_msgs/PoseStamped.h>
52 #include <pcl_msgs/PointIndices.h>
57 class CaptureStereoSynchronizer:
public jsk_topic_tools::DiagnosticNodelet
62 geometry_msgs::PoseStamped,
64 pcl_msgs::PointIndices,
66 sensor_msgs::CameraInfo,
67 sensor_msgs::CameraInfo,
68 stereo_msgs::DisparityImage
80 const geometry_msgs::PoseStamped::ConstPtr& pose,
81 const sensor_msgs::Image::ConstPtr& mask,
82 const PCLIndicesMsg::ConstPtr& mask_indices,
83 const sensor_msgs::Image::ConstPtr& left_image,
84 const sensor_msgs::CameraInfo::ConstPtr& left_cam_info,
85 const sensor_msgs::CameraInfo::ConstPtr& right_cam_info,
86 const stereo_msgs::DisparityImage::ConstPtr& disparity
92 const geometry_msgs::Pose& new_pose);
114 std::vector<geometry_msgs::Pose>
poses_;
ros::Publisher pub_disparity_
ros::Publisher pub_right_cam_info_
message_filters::Subscriber< sensor_msgs::Image > sub_mask_
message_filters::Subscriber< PCLIndicesMsg > sub_mask_indices_
ros::Publisher pub_left_cam_info_
ros::Publisher pub_count_
double positional_bin_size_
message_filters::Subscriber< stereo_msgs::DisparityImage > sub_disparity_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_right_cam_info_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
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
virtual bool checkNearPose(const geometry_msgs::Pose &new_pose)
CaptureStereoSynchronizer()
virtual void unsubscribe()
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_left_cam_info_
boost::shared_ptr< CaptureStereoSynchronizer > Ptr
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)
std::vector< geometry_msgs::Pose > poses_
virtual ~CaptureStereoSynchronizer()
double rotational_bin_size_
message_filters::Subscriber< sensor_msgs::Image > sub_left_image_
ros::Publisher pub_left_image_
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_pose_
ros::Publisher pub_mask_indices_
jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:44