SRCalibratedLib.h
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <ros/names.h>
00003 
00004 #include <sensor_msgs/CameraInfo.h>
00005 #include <sensor_msgs/PointCloud.h>
00006 
00007 #include <opencv/cv.h>
00008 #include <cv_bridge/CvBridge.h>
00009 
00010 class SRCalibratedLib {
00011 private:
00012   sensor_msgs::CameraInfo info_depth_;
00013   IplImage *ipl_depth_;
00014   float *map_x, *map_y, *map_z;
00015   int srheight, srwidth;
00016   CvMat *cam_matrix, *dist_coeff;
00017 
00018 protected:
00019   void
00020   makeConvertMap ();
00021 
00022   void
00023   convert3DPos (sensor_msgs::PointCloud &pts);
00024 
00025 public:
00026   // parameters
00027   double max_range;
00028   double depth_scale;
00029   bool short_range;
00030   int intensity_threshold, confidence_threshold;
00031 
00032   bool use_smooth;
00033   int smooth_size;
00034   double smooth_depth,smooth_space;
00035 
00036   bool use_filter;
00037   double edge1, edge2;
00038   int dilate_times;
00039 
00040   SRCalibratedLib ();
00041 
00042   inline int
00043   width ()
00044   {
00045     return srwidth;
00046   }
00047 
00048   inline int
00049   height ()
00050   {
00051     return srheight;
00052   }
00053 
00054   void
00055   setRengeImg (const sensor_msgs::ImageConstPtr &img_conf,
00056                const sensor_msgs::ImageConstPtr &img_intent,
00057                const sensor_msgs::ImageConstPtr &img_depth,
00058                const sensor_msgs::CameraInfoConstPtr &info);
00059 
00060   void
00061   calc3DPoints (sensor_msgs::PointCloud &pts_);
00062 };
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


cr_capture
Author(s): youhei kakiuchi, JSK
autogenerated on Sun Mar 24 2013 02:36:21