00001 /** 00002 * @file GT2005ImageProcessor.h 00003 * 00004 * Definition of class GT2005ImageProcessor 00005 * 00006 * @author <a href="mailto:juengel@informatik.hu-berlin.de">Matthias Juengel</a> 00007 * @author <a href="mailto:roefer@tzi.de">Thomas Röfer</a> 00008 */ 00009 00010 #ifndef __GT2005ImageProcessor_h_ 00011 #define __GT2005ImageProcessor_h_ 00012 00013 //if defined, GuideDogRobotSpecialist will be used 00014 //#define OC_GUIDEDOG 00015 00016 #include "Modules/ImageProcessor/ImageProcessor.h" 00017 #include "Tools/Debugging/DebugDrawings.h" 00018 #include "Tools/Math/Geometry.h" 00019 #include "Tools/Debugging/DebugImages.h" 00020 #include "Tools/RingBuffer.h" 00021 #include "Modules/ImageProcessor/ImageProcessorTools/ColorCorrector.h" 00022 #include "GT2005ImageProcessorTools.h" 00023 #include "GT2005GoalRecognizer.h" 00024 #include "GT2005BallSpecialist.h" 00025 #include "GT2005BeaconDetector.h" 00026 #include "GT2005EdgeSpecialist.h" 00027 #include "GT2005PlayerSpecialist.h" 00028 #include "Tools/Actorics/RobotDimensions.h" 00029 #include "Tools/RobotConfiguration.h" 00030 #include "Tools/Math/Common.h" 00031 #include "GT2005Clustering.h" 00032 #include "GT2005LineFinder_DeterministicApproach.h" 00033 #include "GT2005CenterCircleFinder.h" 00034 00035 00036 #ifdef OC_GUIDEDOG 00037 #include "GuideDogRobotSpecialist.h" 00038 #endif //OC_GUIDEDOG 00039 00040 /** 00041 * @class GT2005ImageProcessor 00042 * 00043 * The lines image processor recognizes characteristic lines in the image. 00044 * Four types of lines are distinguished: 00045 * edges between the skyblue goal and the field, edges between the yellow goal 00046 * and the field, edges between the border and the field, and edges between the 00047 * field lines and the field. 00048 * 00049 * The module scans vertical and horizontal lines in the image from top to bottom 00050 * and from left to right. As the green of the field is very dark, all edges are 00051 * characterized by a big difference of the y-channel of adjacent pixels. An 00052 * increase in the y-channel followed by a decrease is an indication for an edge. 00053 * 00054 * The projection of the pixels on the field plane is used to determine their 00055 * relative position to the robot. 00056 * 00057 * @author <a href="mailto:juengel@informatik.hu-berlin.de">Matthias Juengel</a> 00058 * @author <a href="mailto:roefer@tzi.de">Thomas Röfer</a> 00059 */ 00060 class GT2005ImageProcessor : public ImageProcessor 00061 { 00062 public: 00063 /** 00064 * Constructor. 00065 * @param interfaces Collection of references to other objects, e.g. the current image, 00066 * required by this module. 00067 */ 00068 GT2005ImageProcessor(const ImageProcessorInterfaces& interfaces); 00069 00070 /** 00071 * Main method. Called on every captured image. 00072 */ 00073 virtual void execute(); 00074 00075 /** 00076 * Handles an incoming message 00077 * @param message The message 00078 */ 00079 virtual bool handleMessage(InMessage& message); 00080 00081 /** 00082 * Parameters for the scanning grid. 00083 * Only one in four scanlines run from the horizon to the bottom of the image. In between 00084 * of those, there are one medium and two short lines, so that the grid is more dense near 00085 * the horizon. 00086 * The parameter verticalScanlineSpacing specifies the distance between the vertical scan 00087 * lines. 00088 */ 00089 static const double verticalScanLineTopAboveHorizon; 00090 static const double verticalScanLineLength13; 00091 static const double verticalScanLineLength2; 00092 static const double verticalScanLineSpacing; 00093 00094 00095 private: // methods 00096 00097 /** 00098 * Calculates the vertical lines and calls scan(...) on each of them. The vertical lines 00099 * are more dense near the horizon, since objects are further away and hence smaller. 00100 */ 00101 void scanColumns(); 00102 00103 /** 00104 * Calculates the horizontal lines and calls scan 00105 */ 00106 void scanRows(); 00107 00108 /** 00109 * The function scans a line for varous things (??). 00110 * @param start The start point of the line. 00111 * @param end The end point of the line. 00112 * @param vertical The scanline is a vertical line (for specialist that differentiate 00113 * between vertical and horizontal scanlines). 00114 * @param noLines If true, don't look for field lines. 00115 * @param pixelsRelevantForGoals Number of pixels on the scanline (from the top) that 00116 * are relevant for the GoalRecognizer. 00117 */ 00118 void scan(const Vector2<int>& start, const Vector2<int>& end, 00119 bool vertical, bool noLines, int pixelsRelevantForGoal); 00120 00121 00122 private: 00123 static const double minAngleBetweenFlagAndGoal; 00124 double xFactor, /**< Factor to convert the pixel coordinate space to the anglular coordinate space. */ 00125 yFactor; /**< Factor to convert the pixel coordinate space to the anglular coordinate space. */ 00126 int yThreshold; /**< Brightness increase threshold. */ 00127 int vThreshold; /**< Brightness decrease threshold. */ 00128 int orangeCount, /**< Number of columns with ball points. */ 00129 noOrangeCount, /**< Number of columns without a ball point. */ 00130 noRedCount, /**< Number of columns without a red robot point. */ 00131 noBlueCount, /**< Number of columns without a blue robot point. */ 00132 noGoalCount, /**< Number of columns without a opponent goal seen. */ 00133 closestBottom; /**< Closest bottom point on the grid. */ 00134 Vector2<int> firstRed, /**< First red robot point in a cluster. */ 00135 closestRed, /**< Closest red robot point in a cluster. */ 00136 lastRed, /**< Last red robot point in a cluster. */ 00137 firstBlue, /**< First blue robot point in a cluster. */ 00138 closestBlue, /**< Closest blue robot point in a cluster. */ 00139 lastBlue, /**< Last blue robot point in a cluster. */ 00140 firstFlag, /**< First flag point in a cluster. */ 00141 lastFlag, /**< Last flag point in a cluster. */ 00142 lastRedMidPoint, /** Needed for debug drawings */ 00143 lastBlueMidPoint; /** Needed for debug drawings */ 00144 00145 00146 bool goalAtBorder; /**< Is the first goal point at the image border? */ 00147 00148 00149 /** Useful information about the current image that is calculated by the ImageProcessor 00150 object and may be used by the specialist (avoiding recalculation) like the horizon, 00151 etc. */ 00152 ImageInfo imageInfo; 00153 00154 00155 int longestBallRun; 00156 Vector2<int> ballCandidate; 00157 GT2005Clustering ballClustering; 00158 GT2005LineFinder_DeterministicApproach lineFinder; 00159 GT2005CenterCircleFinder circleFinder; 00160 00161 CameraMatrix cmTricot, /**< Camera matrix without tricot height. */ 00162 prevCmTricot; /**< The tricot matrix of the previous image. */ 00163 // prevCameraMatrix moved to ImageInfo! 00164 00165 ColorCorrector colorCorrector; /**< The color correction tool. */ 00166 00167 /** Goal specialists to recognize the goals (one for each color). */ 00168 GT2005GoalRecognizer goalSpecialistY, goalSpecialistB; 00169 00170 /** Other specialists. */ 00171 GT2005BeaconDetector beaconDetector; /**< The beacon detector */ 00172 GT2005BallSpecialist ballSpecialist; /**< The ball specialist. */ 00173 GT2005EdgeSpecialist edgeSpecialist; /**< The edge specialist. */ 00174 GT2005PlayerSpecialist playerSpecialist; /**< The player specialist. */ 00175 00176 #ifdef OC_GUIDEDOG 00177 GuideDogRobotSpecialist guideDogRobotSpecialist; 00178 #endif //OC_GUIDEDOG 00179 00180 00181 /** 00182 * The function calculates the distance to a point to horizon. 00183 * @param point The two dimenaional point in the camera image 00184 * @param distance The distance to horizon 00185 * @return Is below horizon 00186 */ 00187 00188 bool pixelBelowHorizon(Vector2<int> point, double &distance); 00189 00190 /** 00191 * The function clusters flag points. 00192 * @param flagType The type of the flag. 00193 * @param point The center of the pink area. 00194 */ 00195 //void clusterFlags(Flag::FlagType flagType, const Vector2<int>& point); 00196 00197 /** 00198 * The function filters the percepts, i.e. it removes potential misreadings. 00199 */ 00200 void filterPercepts(); 00201 00202 /** 00203 * The function filters the line-percepts, i.e. it removes potential misreadings, for the given line-type. 00204 */ 00205 void filterLinesPercept(LinesPercept& percept, int type, const Image& image); 00206 00207 /** 00208 * The function calculates the angle of an edge at an edge point. 00209 * @param angleInImage The angle in image coordinates to be determined. 00210 * @param angleOnField The angle in relative robot field coordinates to be determined. 00211 * @param pointInImage The edge point in image coordinates. 00212 * @param pointOnField The edge point in field coordinates. 00213 * @param scanAngle The angle of the scan line the point was found on. 00214 * @param pixelBuffer The pixels on the scan line around the edge point. 00215 * @param againstScanline The flag if bright to dark is detected against the direction of the scanline. 00216 * @param borderOrLine The flag if this edge belongs to a border or a line (white to green edge). 00217 * @param channel The channel the gradient is calculated in. 00218 * @return Whether the angle in field coordinates could be determined 00219 */ 00220 bool calcEdgeAngle( 00221 double& angleInImage, 00222 double& angleOnField, 00223 const Vector2<int>& pointInImage, 00224 const Vector2<int>& pointOnField, 00225 double scanAngle, 00226 const RingBuffer<const unsigned char*,7>& pixelBuffer, 00227 const bool againstScanline = false, 00228 const bool borderOrLine = true, 00229 int channel = 0); 00230 00231 /** 00232 * The function converts an address to pixel coordinates. 00233 * @param p An address in image.image. 00234 * @return The x- and y-coordinates of the corresponding pixel. 00235 */ 00236 Vector2<int> getCoords(const unsigned char* p) const 00237 { 00238 const int diff(p - &image.image[0][0][0]); 00239 return Vector2<int>(diff % cameraResolutionWidth_ERS7, diff / (cameraResolutionWidth_ERS7 * 6)); 00240 } 00241 00242 //!@name Helpers for grid drawing 00243 //!@{ 00244 const unsigned char* last; 00245 Drawings::Color lineColor; 00246 void plot(const unsigned char* p,Drawings::Color color); 00247 //!@} 00248 00249 double angleBetweenDirectionOfViewAndGround; 00250 00251 int numberOfScannedPixels; 00252 00253 Matrix2x2<double> rotation2x2; 00254 00255 DECLARE_DEBUG_IMAGE(imageProcessorPlayers); 00256 DECLARE_DEBUG_IMAGE(imageProcessorGeneral); 00257 DECLARE_DEBUG_COLOR_CLASS_IMAGE(segmentedImage1); 00258 DECLARE_DEBUG_IMAGE(imageProcessorBall); 00259 DECLARE_DEBUG_IMAGE(imageProcessorGradients); 00260 00261 N_DECLARE_DEBUG_IMAGE(colorCorrected); 00262 N_DECLARE_DEBUG_IMAGE(colorCorrectedAsJpeg); 00263 N_DECLARE_DEBUG_COLOR_CLASS_IMAGE(segmented); 00264 N_DECLARE_DEBUG_IMAGE(ball); 00265 N_DECLARE_DEBUG_IMAGE(edgeDetection); 00266 N_DECLARE_DEBUG_GRAY_SCALE_IMAGE(scanLines); 00267 }; 00268 00269 #endif// __GT2005ImageProcessor_h_
1.3.6