create_calibs.h
Go to the documentation of this file.
00001 
00008 #include <iostream>
00009 
00010 #include <youbot_overhead_vision/markerCoords.h>
00011 #include <youbot_overhead_vision/CalibCameraImg.h>
00012 #include "image_calibration.h"
00013 #include "yaml-cpp/yaml.h"
00014 
00015 using namespace std;
00016 
00017 //Object Types 
00018 /*
00019  * L= Left  R = Right.  F = Front B = Back
00020  */
00021 
00022 #define PI 3.14159
00023 
00024 #define ZOOM_CONSTANT 4
00025 #define SCREEN_RESIZE 2
00026 
00027 bool mouseEvent;
00028 uint8_t clickedColorR;
00029 uint8_t clickedColorG;
00030 uint8_t clickedColorB;
00031 bool savePointToBothCameraFlag;
00032 int mouseX;
00033 int mouseY;
00034 
00035 //Marks if the user is selecting the room boundary box
00036 bool roomBoundaryModeFlag;
00037 vector<cv::Point> roomBoundaryPoints;
00038 
00039 //Zooming variables. Determine whether the image should be zoomed, and which quadrant should be zoomed.
00040 bool zoom;
00041 int zoomQuadX;
00042 int zoomQuadY;
00043 //These are used by the mouse event to determine the color pixel that was clicked on.  Must be outside the class.
00044 
00051 class createCalibs
00052 {
00053 public:
00054 
00055   //Determines how close to the calibrating colors a pixel must be to be considered that color.
00056   int calibAccuracy;
00057 
00058   //Marks when escape was pressed to escape the program.
00059   bool escPressed;
00060   /*
00061    * Determines if the simulation or real world is currently being used.
00062    */
00063   bool useSim;
00064 
00065   //Bool marks whether or not the image was paused
00066   bool imagePaused;
00067 
00068   //Marks which color is currently being calibrated 
00069   int calibratingColor;
00070 
00071   //Denotes which camera is currently shown
00072   int cameraShown;
00073 
00074   //Marks what level of calibration was toggled (No calib, white/colors, white/Black)
00075   int calibToggled;
00076 
00077   //The overlap between the two cameras in pixels
00078   int realCameraOverlap;
00079 
00080   //Marks if the raw images were read from cameras or gazebo.  Required to process images
00081   bool image1LoadedFlag;
00082   bool image2LoadedFlag;
00083 
00084   ros::Subscriber imgSub1;
00085   ros::Subscriber imgSub2;
00086   ros::Publisher pubImgCal; //Used for testing.  Allows for viewing calibrated image
00087 
00088   //Class that creates and manages the tree used for calibrating images.
00089   calibTree * calTree;
00090 
00091   int colors[5][3];
00092 
00093   //Stores the cal image
00094   cv_bridge::CvImagePtr output_Img1;
00095   cv_bridge::CvImagePtr output_Img2;
00096 
00097   //raw image updated by the image_raw subscriber
00098   cv_bridge::CvImagePtr raw_Img1;
00099   cv_bridge::CvImagePtr raw_Img2;
00100 
00101   //marks whether or not the image still has to be updated before being analyzed
00102   bool updatedImageFlag;
00103 
00104   int blurringFactor;
00105   int seq_num;
00106 
00107   /*
00108    *                                       Public Functions
00109    */
00110 
00114   createCalibs();
00115 
00119   ~createCalibs();
00120 
00124   void showImage();
00125 
00135   void getCalibration(int calibType, int calibR, int calibB, int calibG);
00136 
00142   void imageCallback1(const sensor_msgs::ImageConstPtr& image_msg);
00143 
00149   void imageCallback2(const sensor_msgs::ImageConstPtr& image_msg);
00150 
00156   void applyCalib(cv::Mat * image_msg, int camera);
00157 
00161   void saveCalibsToFiles();
00162 
00168   string convertInt(int number);
00169 
00170 private:
00171   //File paths for calibration files
00172   string filenames[5];
00173 
00174   string boundaryImgFilename;
00175 
00176 };
00177 
00186 void myMouseCallback(int event, int x, int y, int flags, void *param);


youbot_overhead_vision
Author(s): Fred Clinckemaillie, Maintained by David Kent
autogenerated on Thu Jan 2 2014 12:14:12