Fawkes API  Fawkes Development Version
roi.h
1 
2 /***************************************************************************
3  * roi.h - Header for Region Of Interest (ROI) representation
4  *
5  * Generated: Tue Mai 03 19:46:44 2005
6  * Copyright 2005-2007 Tim Niemueller [www.niemueller.de]
7  *
8  ****************************************************************************/
9 
10 /* This program is free software; you can redistribute it and/or modify
11  * it under the terms of the GNU General Public License as published by
12  * the Free Software Foundation; either version 2 of the License, or
13  * (at your option) any later version. A runtime exception applies to
14  * this software (see LICENSE.GPL_WRE file mentioned below for details).
15  *
16  * This program is distributed in the hope that it will be useful,
17  * but WITHOUT ANY WARRANTY; without even the implied warranty of
18  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
19  * GNU Library General Public License for more details.
20  *
21  * Read the full text in the LICENSE.GPL_WRE file in the doc directory.
22  */
23 
24 #ifndef __FIREVISION_FVUTILS_ROI_H_
25 #define __FIREVISION_FVUTILS_ROI_H_
26 
27 #include <fvutils/base/types.h>
28 
29 namespace firevision {
30 #if 0 /* just to make Emacs auto-indent happy */
31 }
32 #endif
33 
34 /* The values of this enum-type have to be indexed subsequently,
35  beginning with 0. The last value has to be "H_SIZE = ...".
36  You may add further values at the end (but before H_SIZE!)
37  just continue the indexing properly.
38  NOTE: The indexing must be in correct order wrt the histograms
39  used in "genlut"
40  Do NOT change the order as this may invalidate already created
41  color maps.
42  */
43 /** Hint about object. */
44 typedef enum {
45  H_BALL = 0, /**< ball */
46  H_BACKGROUND = 1, /**< background */
47  H_ROBOT = 2, /**< robot */
48  H_FIELD = 3, /**< field */
49  H_GOAL_YELLOW = 4, /**< yellow goal */
50  H_GOAL_BLUE = 5, /**< blue goal */
51  H_LINE = 6, /**< line */
52  H_UNKNOWN = 7, /**< unknown */
53  H_ROBOT_OPP = 8, /**< opponents robot */
54  H_SIZE /**< size of enum (Has to be the last entry) */
55 } hint_t;
56 
57 
58 class ROI {
59  public:
60 
61  ROI();
62  ROI(const ROI &roi);
63  ROI(const ROI *roi);
64  ROI(unsigned int start_x, unsigned int start_y,
65  unsigned int width, unsigned int height,
66  unsigned int image_width, unsigned int image_height);
67 
69  void set_start(unsigned int x, unsigned int y);
70 
71  void set_width(unsigned int width);
72  unsigned int get_width() const;
73 
74  void set_height(unsigned int height);
75  unsigned int get_height() const;
76 
77  void set_image_width(unsigned int image_width);
78  unsigned int get_image_width() const;
79 
80  void set_image_height(unsigned int image_height);
81  unsigned int get_image_height() const;
82 
83  void set_line_step(unsigned int step);
84  unsigned int get_line_step() const;
85 
86  void set_pixel_step(unsigned int step);
87  unsigned int get_pixel_step() const;
88 
89  unsigned int get_hint() const;
90  void set_hint(unsigned int);
91 
92  bool contains(unsigned int x, unsigned int y);
93  ROI intersect(ROI const &roi) const;
94 
95  bool neighbours(unsigned int x, unsigned int y, unsigned int margin) const;
96  bool neighbours(ROI *roi, unsigned int margin) const;
97 
98  void extend(unsigned int x, unsigned int y);
99  ROI& operator+=(ROI &roi);
100  void grow(unsigned int margin);
101 
102 
103  bool operator<(const ROI &roi) const;
104  bool operator>(const ROI &roi) const;
105  bool operator==(const ROI &roi) const;
106  bool operator!=(const ROI &roi) const;
107  ROI& operator=(const ROI &roi);
108 
109  unsigned int get_num_hint_points() const;
110 
111 
112  unsigned char* get_roi_buffer_start(unsigned char *buffer) const;
113 
114  static ROI * full_image(unsigned int width, unsigned int height);
115 
116 
117  public: // Public for quick access
118  /** ROI start */
120  /** ROI width */
121  unsigned int width;
122  /** ROI height */
123  unsigned int height;
124  /** width of image that contains this ROI */
125  unsigned int image_width;
126  /** height of image that contains this ROI */
127  unsigned int image_height;
128  /** line step */
129  unsigned int line_step;
130  /** pixel step */
131  unsigned int pixel_step;
132  /** ROI hint */
133  unsigned int hint;
134 
135  /** ROI primary color */
136  color_t color;
137 
138  /** Minimum estimate of points in ROI that are attributed to the ROI hint */
139  unsigned int num_hint_points;
140 
141  private:
142  static ROI *roi_full_image;
143 
144 };
145 
146 } // end namespace firevision
147 
148 #endif
unsigned int get_height() const
Get height of ROI.
Definition: roi.cpp:177
unsigned int get_pixel_step() const
Get pixel step.
Definition: roi.cpp:267
unsigned int get_line_step() const
Get linestep.
Definition: roi.cpp:244
void set_height(unsigned int height)
Set height of ROI.
Definition: roi.cpp:167
unsigned int get_width() const
Get width of ROI.
Definition: roi.cpp:157
fawkes::upoint_t start
ROI start.
Definition: roi.h:119
ROI()
Constructor.
Definition: roi.cpp:51
void grow(unsigned int margin)
Grow this ROI by a given margin.
Definition: roi.cpp:419
bool neighbours(unsigned int x, unsigned int y, unsigned int margin) const
Check if this ROI neighbours a pixel.
Definition: roi.cpp:363
unsigned int get_image_height() const
Get full image height.
Definition: roi.cpp:221
unsigned int width
ROI width.
Definition: roi.h:121
ROI & operator+=(ROI &roi)
Merge two ROIs.
Definition: roi.cpp:455
void set_pixel_step(unsigned int step)
Set pixel step.
Definition: roi.cpp:256
Region of interest.
Definition: roi.h:58
bool operator!=(const ROI &roi) const
Check if this ROI does not mark the same region for the same object and an image of the same base siz...
Definition: roi.cpp:521
ROI & operator=(const ROI &roi)
Assign the given ROI data to this ROI.
Definition: roi.cpp:532
void set_image_height(unsigned int image_height)
Set full image height Set the height of the image that contains this ROI.
Definition: roi.cpp:210
unsigned int image_width
width of image that contains this ROI
Definition: roi.h:125
static ROI * full_image(unsigned int width, unsigned int height)
Get full image ROI for given size.
Definition: roi.cpp:597
unsigned int image_height
height of image that contains this ROI
Definition: roi.h:127
bool operator==(const ROI &roi) const
Check if this ROI marks the same region for the same object and an image of the same base size and st...
Definition: roi.cpp:498
void set_image_width(unsigned int image_width)
Set full image width.
Definition: roi.cpp:188
bool contains(unsigned int x, unsigned int y)
Check if this ROI contains the given coordinates.
Definition: roi.cpp:302
bool operator>(const ROI &roi) const
Check if this ROI contains more hint points than the given ROI.
Definition: roi.cpp:485
unsigned char * get_roi_buffer_start(unsigned char *buffer) const
Get ROI buffer start.
Definition: roi.cpp:556
Point with cartesian coordinates as unsigned integers.
Definition: types.h:34
void set_start(fawkes::upoint_t p)
Set upper left corner of ROI.
Definition: roi.cpp:124
unsigned int hint
ROI hint.
Definition: roi.h:133
unsigned int height
ROI height.
Definition: roi.h:123
void set_hint(unsigned int)
Set hint.
Definition: roi.cpp:290
ROI intersect(ROI const &roi) const
Intersect this ROI with another.
Definition: roi.cpp:323
void set_line_step(unsigned int step)
Set linestep.
Definition: roi.cpp:233
unsigned int line_step
line step
Definition: roi.h:129
unsigned int num_hint_points
Minimum estimate of points in ROI that are attributed to the ROI hint.
Definition: roi.h:139
void extend(unsigned int x, unsigned int y)
Extend ROI to include given pixel.
Definition: roi.cpp:403
unsigned int get_num_hint_points() const
Gives an estimate of the number of points in this ROI that are classified to the given hint It is: nu...
Definition: roi.cpp:580
unsigned int pixel_step
pixel step
Definition: roi.h:131
color_t color
ROI primary color.
Definition: roi.h:136
bool operator<(const ROI &roi) const
Check if this ROI contains less hint points than the given ROI.
Definition: roi.cpp:474
unsigned int get_hint() const
Get hint.
Definition: roi.cpp:279
unsigned int get_image_width() const
Get full image width.
Definition: roi.cpp:199
void set_width(unsigned int width)
Set width of ROI.
Definition: roi.cpp:147