rgbd_image_proc.h
Go to the documentation of this file.
00001 
00024 #ifndef CCNY_RGBD_RGBD_IMAGE_PROC_H
00025 #define CCNY_RGBD_RGBD_IMAGE_PROC_H
00026 
00027 #include <ros/ros.h>
00028 #include <boost/filesystem.hpp>
00029 #include <opencv2/opencv.hpp>
00030 #include <pcl/point_cloud.h>
00031 #include <pcl_ros/point_cloud.h>
00032 #include <dynamic_reconfigure/server.h>
00033 #include <rgbdtools/rgbdtools.h>
00034 
00035 #include "ccny_rgbd/types.h"
00036 #include "ccny_rgbd/util.h"
00037 #include "ccny_rgbd/RGBDImageProcConfig.h"
00038 
00039 namespace ccny_rgbd {
00040 
00055 class RGBDImageProc 
00056 {
00057   typedef RGBDImageProcConfig ProcConfig;
00058   typedef dynamic_reconfigure::Server<ProcConfig> ProcConfigServer;
00059   
00060   public:
00061 
00066     RGBDImageProc(
00067       const ros::NodeHandle& nh, 
00068       const ros::NodeHandle& nh_private);
00069     
00072     virtual ~RGBDImageProc();
00073 
00081     void RGBDCallback(const ImageMsg::ConstPtr& rgb_msg,
00082                       const ImageMsg::ConstPtr& depth_msg,
00083                       const CameraInfoMsg::ConstPtr& rgb_info_msg,
00084                       const CameraInfoMsg::ConstPtr& depth_info_msg);
00085 
00086   private:
00087 
00088     ros::NodeHandle nh_;          
00089     ros::NodeHandle nh_private_;  
00090 
00091     boost::shared_ptr<RGBDSynchronizer4> sync_; 
00092        
00093     ImageTransport rgb_image_transport_;    
00094     ImageTransport depth_image_transport_;  
00095     
00096     ImageSubFilter sub_rgb_;   
00097     ImageSubFilter sub_depth_; 
00098 
00099     CameraInfoSubFilter sub_rgb_info_;   
00100     CameraInfoSubFilter sub_depth_info_; 
00101     
00102     ImagePublisher rgb_publisher_;      
00103     ImagePublisher depth_publisher_;    
00104     ros::Publisher info_publisher_;     
00105     ros::Publisher cloud_publisher_;    
00106     
00107     ProcConfigServer config_server_;    
00108     
00109     // parameters
00110     
00111     int queue_size_;          
00112     
00113     std::string calib_path_;  
00114     bool verbose_;             
00115     bool unwarp_;             
00116     bool publish_cloud_;      
00117     
00121     double scale_;             
00122     
00126     std::string calib_extr_filename_;
00127     
00131     std::string calib_warp_filename_;
00132    
00133     // **** state variables
00134     
00135     bool initialized_;      
00136     boost::mutex mutex_;    
00137     
00138     // **** calibration
00139     
00144     int fit_mode_;        
00145     
00146     cv::Size size_in_; 
00147     
00149     cv::Mat coeff_0_, coeff_1_, coeff_2_;   
00150     
00154     cv::Mat coeff_0_rect_, coeff_1_rect_, coeff_2_rect_;  
00155     
00157     cv::Mat ir2rgb_;    
00158    
00160     cv::Mat intr_rect_rgb_, intr_rect_depth_;  
00161     
00163     CameraInfoMsg rgb_rect_info_msg_;   
00164     
00166     CameraInfoMsg depth_rect_info_msg_; 
00167     
00169     cv::Mat map_rgb_1_,   map_rgb_2_;
00170     
00172     cv::Mat map_depth_1_, map_depth_2_;
00173     
00180     void initMaps(
00181       const CameraInfoMsg::ConstPtr& rgb_info_msg,
00182       const CameraInfoMsg::ConstPtr& depth_info_msg);
00183     
00187     bool loadCalibration();   
00188     
00191     bool loadUnwarpCalibration();
00192 
00195     void reconfigCallback(ProcConfig& config, uint32_t level);
00196 };
00197 
00198 } //namespace ccny_rgbd
00199 
00200 #endif // CCNY_RGBD_RGBD_IMAGE_PROC_H
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


ccny_rgbd
Author(s): Ivan Dryanovski
autogenerated on Tue Aug 27 2013 10:34:02