Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #ifndef JSK_PCL_ROS_CAPTURE_STEREO_SYNCHRONIZER_H_
00037 #define JSK_PCL_ROS_CAPTURE_STEREO_SYNCHRONIZER_H_
00038
00039
00040
00041
00042 #include <ros/ros.h>
00043 #include <message_filters/subscriber.h>
00044 #include <message_filters/time_synchronizer.h>
00045 #include <message_filters/synchronizer.h>
00046 #include <jsk_topic_tools/diagnostic_nodelet.h>
00047
00048 #include <sensor_msgs/Image.h>
00049 #include <sensor_msgs/CameraInfo.h>
00050 #include <stereo_msgs/DisparityImage.h>
00051 #include <geometry_msgs/PoseStamped.h>
00052 #include <pcl_msgs/PointIndices.h>
00053 #include "jsk_recognition_utils/pcl_conversion_util.h"
00054
00055 namespace jsk_pcl_ros
00056 {
00057 class CaptureStereoSynchronizer: public jsk_topic_tools::DiagnosticNodelet
00058 {
00059 public:
00060 typedef boost::shared_ptr<CaptureStereoSynchronizer> Ptr;
00061 typedef message_filters::sync_policies::ExactTime<
00062 geometry_msgs::PoseStamped,
00063 sensor_msgs::Image,
00064 pcl_msgs::PointIndices,
00065 sensor_msgs::Image,
00066 sensor_msgs::CameraInfo,
00067 sensor_msgs::CameraInfo,
00068 stereo_msgs::DisparityImage
00069 > SyncPolicy;
00070 CaptureStereoSynchronizer(): DiagnosticNodelet("CaptureStereoSynchronizer") { }
00071 protected:
00073
00075 virtual void onInit();
00076 virtual void subscribe();
00077 virtual void unsubscribe();
00078 virtual void updateDiagnostic(
00079 diagnostic_updater::DiagnosticStatusWrapper &stat);
00080 virtual void republish(
00081 const geometry_msgs::PoseStamped::ConstPtr& pose,
00082 const sensor_msgs::Image::ConstPtr& mask,
00083 const PCLIndicesMsg::ConstPtr& mask_indices,
00084 const sensor_msgs::Image::ConstPtr& left_image,
00085 const sensor_msgs::CameraInfo::ConstPtr& left_cam_info,
00086 const sensor_msgs::CameraInfo::ConstPtr& right_cam_info,
00087 const stereo_msgs::DisparityImage::ConstPtr& disparity
00088 );
00089
00090
00091
00092 virtual bool checkNearPose(
00093 const geometry_msgs::Pose& new_pose);
00094
00096
00098 int counter_;
00099 ros::Publisher pub_count_;
00100 ros::Publisher pub_pose_;
00101 ros::Publisher pub_mask_;
00102 ros::Publisher pub_mask_indices_;
00103 ros::Publisher pub_left_image_;
00104 ros::Publisher pub_left_cam_info_;
00105 ros::Publisher pub_right_cam_info_;
00106 ros::Publisher pub_disparity_;
00107 message_filters::Subscriber<geometry_msgs::PoseStamped> sub_pose_;
00108 message_filters::Subscriber<sensor_msgs::Image> sub_mask_;
00109 message_filters::Subscriber<PCLIndicesMsg> sub_mask_indices_;
00110 message_filters::Subscriber<sensor_msgs::Image> sub_left_image_;
00111 message_filters::Subscriber<sensor_msgs::CameraInfo> sub_left_cam_info_;
00112 message_filters::Subscriber<sensor_msgs::CameraInfo> sub_right_cam_info_;
00113 message_filters::Subscriber<stereo_msgs::DisparityImage> sub_disparity_;
00114 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00115 std::vector<geometry_msgs::Pose> poses_;
00117
00119 double rotational_bin_size_;
00120 double positional_bin_size_;
00121 private:
00122
00123 };
00124 }
00125 #endif