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
00033
00034
00035
00036
00037 #include <string.h>
00038 #include <stdio.h>
00039 #include <math.h>
00040
00041 #include "PSSources.h"
00042
00043
00044
00045 plumesim::PSFluent::PSFluent()
00046 {
00047 this->maxPointsPerCell = 10;
00048 this->fileName = "fluentlog";
00049 this->numOfFrames = 1;
00050 this->cellSize = 0.1;
00051 this->maxOdorValue = 1.0;
00052 }
00053
00054
00055
00056 plumesim::PSFluent::~PSFluent()
00057 {
00058
00059 }
00060
00061
00062
00063 int plumesim::PSFluent::setup()
00064 {
00065 if(!plumePoints.empty()) plumePoints.clear();
00066 if(!frame.empty()) frame.clear();
00067
00068 if(this->numOfFrames > 1) this->changesOverTime = true;
00069 else this->changesOverTime = false;
00070
00071 this->isPlaying = true;
00072
00073 this->currentFrame = 1;
00074
00075 return 0;
00076 }
00077
00078
00079
00080 int plumesim::PSFluent::cleanup()
00081 {
00082 plumePoints.clear();
00083 frame.clear();
00084 return 0;
00085 }
00086
00087
00088
00089 int plumesim::PSFluent::generatePoints()
00090 {
00091 if(currentFrame > numOfFrames)
00092 {
00093 isPlaying = false;
00094 return(0);
00095 }
00096
00097 int i, j;
00098 int pointsCount;
00099
00100 if(!plumePoints.empty()) plumePoints.clear();
00101 if(!frame.empty()) frame.clear();
00102
00103 char logFileName[128];
00104 char logFileNum[8];
00105 strcpy(logFileName, fileName.c_str());
00106 sprintf(logFileNum, "%03d", currentFrame);
00107 strncat(logFileName, logFileNum, strlen(logFileNum));
00108
00109 logFile = fopen(logFileName, "r");
00110 if(logFile == NULL) return(-1);
00111
00112 char dummy[64];
00113 fgets(dummy, 64, logFile);
00114
00115 while( !feof(logFile) )
00116 {
00117 PSFramePoint pointFromFrame;
00118 pointFromFrame.point.pz = 0.0;
00119
00120 fscanf(logFile, "%d,%lf,%lf,%lf\n", &i, &pointFromFrame.point.px, &pointFromFrame.point.py, &pointFromFrame.odor.chemical);
00121 pointFromFrame.odor.chemical = 100.0*pointFromFrame.odor.chemical/maxOdorValue;
00122
00123 frame.push_back(pointFromFrame);
00124
00125 pointsCount = round(maxPointsPerCell * pointFromFrame.odor.chemical/100.0);
00126 for(j=0 ; j<pointsCount ; j++)
00127 {
00128 PSPoint3d point;
00129 point.px = pointFromFrame.point.px + cellSize * randomNormal();
00130 point.py = pointFromFrame.point.py + cellSize * randomNormal();
00131
00132 point.pz = 0.0;
00133 plumePoints.push_back(point);
00134 }
00135 }
00136 currentFrame++;
00137
00138
00139 fclose(logFile);
00140
00141 return(0);
00142 }
00143
00144
00145
00146 int plumesim::PSFluent::getChemicalReading(PSPoint3d * point, PSOdorData * odor_data)
00147 {
00148 double distance;
00149 double minDistance = cellSize;
00150
00151 odor_data->chemical = 0.0;
00152 odor_data->windSpeed = 0.0;
00153 odor_data->windDirection = 0.0;
00154
00155 PSFramePoint * framePoint;
00156 for(int i=0 ; i<this->frame.size() ; i++)
00157 {
00158 framePoint = &this->frame[i];
00159
00160 distance = sqrt((point->px - framePoint->point.px)*(point->px - framePoint->point.px) + (point->py - framePoint->point.py)*(point->py - framePoint->point.py) + (point->pz - framePoint->point.pz)*(point->pz - framePoint->point.pz));
00161 if(distance < minDistance)
00162 {
00163 odor_data->chemical = framePoint->odor.chemical;
00164 odor_data->windSpeed = framePoint->odor.windSpeed;
00165 odor_data->windDirection = framePoint->odor.windDirection;
00166
00167 minDistance = distance;
00168 }
00169 }
00170 return(0);
00171 }
00172
00173
00174