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 #ifndef STOC_DRIVER_H
00033 #define STOC_DRIVER_H
00034 
00035 
00036 #include <sensor_msgs/PointCloud.h>
00037 #include <deprecated_msgs/ImageArray.h>
00038 #include <deprecated_msgs/Image.h>
00039 
00040 #include <stdexcept>
00041 #include <string>
00042 #include <SVS/svsclass.h>
00043 
00044 #include <opencv/cv.h>
00045 
00046 namespace stoc
00047 {
00049   
00050 #define DEF_EXCEPTION(name, parent) \
00051   class name  : public parent { \
00052   public: \
00053     name (const char* msg) : parent (msg) {} \
00054   }
00055   
00057   DEF_EXCEPTION(Exception, std::runtime_error);
00058 
00059   class STOC
00060   {
00061     public:
00062       STOC ();
00063       ~STOC ();
00064 
00065       int open ();
00066       int close ();
00067       void readData (sensor_msgs::PointCloud &cloud, deprecated_msgs::ImageArray &images);
00068       void readDataLeft (sensor_msgs::PointCloud &cloud, deprecated_msgs::Image &left_image);
00069 
00070       void sendInternalParameters ();
00071       void sendStereoParameters ();
00072       void readParametersFromFile (const char* parameter_file = NULL);
00073 
00074       std::string device_id_;
00075 
00076       
00077       int capture_type_, format_, channel_;
00078       bool swap_mode_;
00079       int color_mode_, color_alg_;
00080       
00081       
00082       int proc_mode_, rate_, frame_div_, size_w_, size_h_;
00083 
00084       bool rectification_;
00085       float z_max_;
00086 
00087       bool multiproc_en_;
00088       int cut_di_;
00089       
00090       void setNDisp       (int n) { ndisp_        = n; video_->SetNDisp (ndisp_); if (debug_) ROS_INFO ("[STOC] >> Number of disparities set to %d", ndisp_); }
00091       void setTexThresh   (int n) { tex_thresh_   = n; video_->SetThresh (tex_thresh_); if (debug_) ROS_INFO ("[STOC] >> Texture filter threshold set to %d", tex_thresh_); }
00092       void setUnique      (int n) { unique_       = n; video_->SetUnique (unique_); if (debug_) ROS_INFO ("[STOC] >> Uniqueness filter threshold set to %d", unique_); }
00093       void setCorrSize    (int n) { corrsize_     = n; video_->SetCorrsize (corrsize_); if (debug_) ROS_INFO ("[STOC] >> Correlation window size set to %d", corrsize_); }
00094       void setHoropter    (int n) { horopter_     = n; video_->SetHoropter (horopter_); if (debug_) ROS_INFO ("[STOC] >> Horopter (X-Offset) value set to %d", horopter_); }
00095       void setSpeckleSize (int n) { speckle_size_ = n; video_->SetSpeckleSize (speckle_size_); if (debug_) ROS_INFO ("[STOC] >> Minimum disparity region size set to %d", speckle_size_); }
00096       void setSpeckleDiff (int n) { speckle_diff_ = n; video_->SetSpeckleDiff (speckle_diff_); if (debug_) ROS_INFO ("[STOC] >> Disparity region neighbor diff to %d", speckle_diff_); }
00097     private:
00098 
00099       int speckle_diff_, speckle_size_, horopter_, corrsize_, unique_, tex_thresh_, ndisp_;
00100 
00101       
00102       svsVideoImages   *video_;
00103       svsStereoProcess *process_;
00104       svsMultiProcess  *multiproc_;
00105 
00106       bool debug_;
00107 
00108       
00109       CvMat *intrinsic_, *distortion_;
00110       void undistort (uint8_t *img, uint8_t *un_img, int width, int height);
00111   };
00112 
00113 };
00114 
00115 #endif
00116