camerasensors.h
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 #ifndef __CAMERASENSORS_H
00026 #define __CAMERASENSORS_H
00027
00028 #include "camerasensor.h"
00029 #include <selforg/controller_misc.h>
00030
00031 namespace lpzrobots {
00032
00033
00034
00035
00036
00037 class DirectCameraSensor : public CameraSensor {
00038 public:
00039
00040
00041
00042
00043
00044
00045
00046 DirectCameraSensor(int minValue=-256, int maxValue=256)
00047 : minValue(minValue), maxValue(maxValue) {
00048 }
00049
00050
00051 virtual ~DirectCameraSensor(){
00052 delete[] data;
00053 }
00054
00055 virtual void intern_init(){
00056 assert(camera->isInitialized());
00057 const osg::Image* img = camera->getImage();
00058 assert(img && img->getPixelFormat()==GL_LUMINANCE && img->getDataType()==GL_UNSIGNED_BYTE);
00059 num = img->s() * img->t();
00060 data = new sensor[num];
00061 };
00062
00063
00064
00065 virtual bool sense(const GlobalData& globaldata){
00066 const osg::Image* img = camera->getImage();
00067 const unsigned char* pixel = img->data();
00068 if(img->s() * img->t() < num) return false;
00069 int center = (maxValue+minValue)/2;
00070 for(int k=0; k< num; k++){
00071 data[k]=(pixel[k]-center)*2.0/double(maxValue-minValue);
00072 }
00073 return true;
00074 }
00075
00076 virtual int getSensorNumber() const {
00077 return num;
00078 };
00079
00080
00081 virtual int get(sensor* sensors, int length) const {
00082 assert(length>=num);
00083 memcpy(sensors, data, num * sizeof(sensor));
00084 return num;
00085 }
00086
00087
00088 protected:
00089 int num;
00090 int minValue;
00091 int maxValue;
00092 sensor* data;
00093 };
00094
00095 struct PositionCameraSensorConf {
00096 typedef short Values;
00097
00098
00099 Values values ;
00100
00101 Sensor::Dimensions dims ;
00102
00103
00104 double sizeExponent;
00105
00106 double factorSizeChange;
00107
00108 double clipsize ;
00109
00110 double border ;
00111 };
00112
00113
00114
00115
00116
00117
00118
00119 class PositionCameraSensor : public CameraSensor {
00120 public:
00121
00122
00123 enum ValueTypes { None = 0, Position = 1, Size = 2, SizeChange = 4 };
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133 PositionCameraSensor(PositionCameraSensorConf conf = getDefaultConf())
00134 : conf(conf), oldsize(0) {
00135 num = (bool(conf.dims & X) + bool(conf.dims & Y))* bool(conf.values & Position) +
00136 bool(conf.values & Size) + bool(conf.values & SizeChange);
00137 }
00138
00139 static PositionCameraSensorConf getDefaultConf(){
00140 PositionCameraSensorConf c;
00141 c.values = Position;
00142 c.dims = XY;
00143 c.factorSizeChange = 10.0;
00144 c.sizeExponent = 1;
00145 c.clipsize = 1.5;
00146 c.border = 0;
00147 return c;
00148 }
00149
00150 virtual ~PositionCameraSensor(){
00151 if(data) delete[] data;
00152 }
00153
00154 virtual void intern_init(){
00155 assert(camera->isInitialized());
00156
00157 data = new sensor[num];
00158 memset(data,0,sizeof(sensor)*num);
00159
00160 const osg::Image* img = camera->getImage();
00161 img=img;
00162 assert(img && img->getPixelFormat()==GL_LUMINANCE &&
00163 img->getDataType()==GL_UNSIGNED_BYTE);
00164 };
00165
00166
00167
00168 virtual bool sense(const GlobalData& globaldata){
00169 const osg::Image* img = camera->getImage();
00170 double x;
00171 double y;
00172 double size;
00173 calcImgCOG(img, x, y, size);
00174 int k=0;
00175 return processAndFillData(x, y, size, k );
00176 }
00177
00178 virtual int getSensorNumber() const {
00179 return num;
00180 };
00181
00182
00183 virtual int get(sensor* sensors, int length) const {
00184 assert(length>=num);
00185 memcpy(sensors, data, num * sizeof(sensor));
00186 return num;
00187 }
00188
00189 protected:
00190
00191
00192 virtual bool processAndFillData(double& x, double& y, double& size, int& k){
00193 int kstart = k;
00194 if(conf.sizeExponent!=1)
00195 size = pow(size,conf.sizeExponent);
00196
00197 if(conf.values & Position){
00198 if(conf.dims & X) data[k++] = x;
00199 if(conf.dims & Y) data[k++] = y;
00200 }
00201 double sizeChange = (size - oldsize)*conf.factorSizeChange;
00202 oldsize = size;
00203
00204
00205 if(conf.border>0){
00206 if((x==0 && y==0) || ((conf.dims & X) && (fabs(x) > (1-conf.border))) ||
00207 ((conf.dims & Y) && (fabs(y) > (1-conf.border))) ){
00208 size=0;
00209 sizeChange=0;
00210 }
00211 }
00212 if(conf.values & Size) data[k++] = size;
00213 if(conf.values & SizeChange) data[k++] = sizeChange;
00214
00215
00216 if(conf.clipsize!=0){
00217 for(int i=kstart; i<k; i++){
00218 data[i] = clip(data[i],-conf.clipsize,conf.clipsize);
00219 }
00220 }
00221 return true;
00222 }
00223
00224
00225
00226
00227
00228 static bool calcImgCOG(const osg::Image* img, double& x, double& y, double& size,
00229 int threshold = 1){
00230 int w = img->s();
00231 int h = img->t();
00232 double centerX = w/2.0;
00233 double centerY = h/2.0;
00234 if(threshold<1) threshold = 1;
00235 x = y = 0;
00236 double sum= 0;
00237 for(int r=0; r< h; r++){
00238 const unsigned char* row = img->data(0, r);
00239 double pY = ((double)r-centerY);
00240 for(int c=0; c < w; c++){
00241 sum += row[c];
00242 x += row[c] * ((double)c-centerX);
00243 y += row[c] * pY;
00244 }
00245 }
00246 if(sum<threshold){
00247 x = y = size = 0;
00248 return false;
00249 }else{
00250 x /= sum * centerX;
00251 y /= sum * centerY;
00252
00253 size = double(sum) / (w*h) / 128;
00254 return true;
00255 }
00256 }
00257
00258
00259 protected:
00260 PositionCameraSensorConf conf;
00261 int num;
00262 sensor* data;
00263 double oldsize;
00264 };
00265
00266
00267 struct MotionCameraSensorConf : public PositionCameraSensorConf{
00268
00269 int avg ;
00270
00271 double factorMotion ;
00272
00273 bool window ;
00274
00275 };
00276
00277
00278
00279
00280
00281
00282
00283 class MotionCameraSensor : public PositionCameraSensor {
00284 public:
00285
00286
00287
00288
00289
00290
00291
00292 MotionCameraSensor(const MotionCameraSensorConf& mconf = getDefaultConf())
00293 : PositionCameraSensor(mconf), mconf(mconf),
00294 last(false), lastX(0), lastY(0)
00295 {
00296 if(this->mconf.avg<1) this->mconf.avg=1;
00297 lambda = 1/(double)this->mconf.avg;
00298 num += bool(this->mconf.dims & X) + bool(this->mconf.dims & Y);
00299 }
00300
00301 static MotionCameraSensorConf getDefaultConf(){
00302 MotionCameraSensorConf c;
00303 c.avg = 2;
00304 c.values = None;
00305 c.dims = X;
00306 c.factorSizeChange = 10.0;
00307 c.sizeExponent = 1;
00308 c.clipsize = 1.5;
00309 c.border = 0;
00310 c.factorMotion = 5.0;
00311 c.window = true;
00312 return c;
00313 }
00314
00315 virtual ~MotionCameraSensor(){
00316 }
00317
00318
00319 virtual bool sense(const GlobalData& globaldata){
00320 const osg::Image* img = camera->getImage();
00321 double x;
00322 double y;
00323 double size;
00324 bool success = calcImgCOG(img, x, y, size);
00325 int k=0;
00326
00327 if(last && success && fabs(x - lastX) < 0.4 && fabs(y - lastY) < 0.4){
00328 if(mconf.dims & X) {
00329 data[k] = lambda*(x - lastX)*mconf.factorMotion* (mconf.window ? windowfunc(x) : 1)
00330 + (1- lambda)*data[k];
00331 k++;
00332 }
00333 if(mconf.dims & Y) {
00334 data[k] = lambda*(y - lastY)*mconf.factorMotion* (mconf.window ? windowfunc(y) : 1)
00335 + (1- lambda)*data[k]; k++;
00336 }
00337
00338 if(conf.clipsize!=0){
00339 for(int i=0; i<k; i++){
00340 data[i] = clip(data[i],-mconf.clipsize,mconf.clipsize);
00341 }
00342 }
00343 }else{
00344 if(mconf.dims & X) data[k++]=0;
00345 if(mconf.dims & Y) data[k++]=0;
00346 }
00347 lastX = x;
00348 lastY = y;
00349 last = success;
00350
00351 return processAndFillData(x,y,size,k);
00352 }
00353
00354
00355 double windowfunc(double x){
00356 if(x>-0.5 && x<0.5) return 1.0;
00357 if(x<= -0.5) return 2+ 2*x;
00358 else return 2- 2*x;
00359 }
00360
00361 protected:
00362 MotionCameraSensorConf mconf;
00363 double lambda;
00364 bool last;
00365 double lastX;
00366 double lastY;
00367
00368 };
00369
00370 }
00371
00372 #endif