capture_stereo_synchronizer.h
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
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_pcl_ros/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, // pose of checker board
00063       sensor_msgs::Image,         // mask image
00064       pcl_msgs::PointIndices,     // mask indices
00065       sensor_msgs::Image,         // left image rect
00066       sensor_msgs::CameraInfo,    // left cmaera info
00067       sensor_msgs::CameraInfo,    // right camera info
00068       stereo_msgs::DisparityImage // stereo disparity
00069       > SyncPolicy;
00070     CaptureStereoSynchronizer(): DiagnosticNodelet("CaptureStereoSynchronizer") { }
00071   protected:
00073     // methods
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, // pose of checker board
00082       const sensor_msgs::Image::ConstPtr& mask,         // mask image
00083       const PCLIndicesMsg::ConstPtr& mask_indices, // mask indices
00084       const sensor_msgs::Image::ConstPtr& left_image, // left image rect
00085       const sensor_msgs::CameraInfo::ConstPtr& left_cam_info, // left cmaera info
00086       const sensor_msgs::CameraInfo::ConstPtr& right_cam_info, // right camera info
00087       const stereo_msgs::DisparityImage::ConstPtr& disparity // stereo disparity
00088       );
00089 
00090     // check is there near pose or not
00091     // if there is a near pose, return true
00092     virtual bool checkNearPose(
00093       const geometry_msgs::Pose& new_pose);
00094     
00096     // ROS variables
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     // Parameters
00119     double rotational_bin_size_;
00120     double positional_bin_size_;
00121   private:
00122   
00123   };
00124 }
00125 #endif


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:47