PSSources.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2010, ISR University of Coimbra.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the ISR University of Coimbra nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *
00035 * Author: Gonçalo Cabrita and Pedro Sousa on 02/15/2010
00036 *********************************************************************/
00037 #include <vector>
00038 #include <string>
00039 
00040 #define MIN_NUM_OF_POINTS       20
00041 
00042 namespace plumesim
00043 {
00051         typedef struct
00052         {
00053                 double px;
00054                 double py;
00055         
00056         } PSPoint2d;
00057 
00065         typedef struct
00066         {
00067                 double px;
00068                 double py;
00069                 double pz;
00070 
00071         } PSPoint3d;
00072 
00080         typedef struct
00081         {
00082                 PSPoint2d startPoint;
00083                 PSPoint2d endPoint;
00084         
00085         } PSRect;
00086 
00094         typedef struct
00095         {
00096                 double chemical;                // ??
00097                 double windSpeed;               // m/s
00098                 double windDirection;   // rad
00099         
00100         } PSOdorData;
00101 
00109         typedef struct
00110         {
00111                 PSPoint3d point;
00112                 PSOdorData odor;
00113         
00114         } PSFramePoint;
00115 
00116 
00123         class PSSource
00124         {
00125                 public:
00126                 
00128 
00131                 PSSource();
00133 
00136                 ~PSSource();
00137         
00146                 virtual int setup();
00155                 virtual int cleanup();
00156         
00157                 std::vector<PSPoint3d> plumePoints;             
00168                 virtual int generatePoints();
00179                 virtual int getChemicalReading(PSPoint3d * point, PSOdorData * odor_data);
00189                 bool ChangesOverTime();
00199                 bool IsPlaying();
00200                 
00201                 protected:
00202         
00211                 float drand();
00220                 double randomNormal();
00230                 int countPoints(PSPoint3d * center, double radius);
00231                 
00232                 bool changesOverTime;           
00233                 bool isPlaying;                         
00234         };
00235 
00236 
00243         class PSMeadering:public PSSource
00244         {
00245                 public:
00246                 
00253                 PSMeadering();
00255 
00258                 ~PSMeadering();
00259         
00268                 int setup();
00277                 int cleanup();
00278         
00288                 int generatePoints();
00299                 int getChemicalReading(PSPoint3d * point, PSOdorData * odor_data);
00300                 
00301                 // Preferences
00302                 PSPoint3d startPoint;                           
00303                 PSRect arenaRect;                                       
00304                 double releaseRate;                                     
00305                 double dispersionCoeficient;            
00306                 double radius;                                          
00307                 int maxPoints;                                          
00308                 int numOfPlumePoints;                           
00310                 private:
00311         
00322                 void linearInterpolation(PSPoint3d * points, int numOfPoints);
00323         };
00324 
00325 
00332         class PSGaussian:public PSSource
00333         {
00334                 public:
00335         
00342                 PSGaussian();
00344 
00347                 ~PSGaussian();
00348         
00357                 int setup();
00366                 int cleanup();
00367         
00377                 int generatePoints();
00388                 int getChemicalReading(PSPoint3d * point, PSOdorData * odor_data);
00389         
00390                 // Preferences
00391                 PSPoint3d startPoint;                           
00392                 PSRect arenaRect;                                       
00393                 double radius;                                          
00394                 double cellSize;                                        
00395                 int maxPointsPerCell;                           
00397                 double diffX;                                           
00398                 double diffY;                                           
00400                 private:
00401         
00402                 int t;                                                          
00404                 std::vector<PSFramePoint> frame;        
00405         };
00406 
00407 
00414         class PSLog:public PSSource
00415         {
00416                 public:
00417                 
00424                 PSLog();
00426 
00429                 ~PSLog();
00430         
00439                 int setup();
00448                 int cleanup();
00449         
00459                 int generatePoints();
00470                 int getChemicalReading(PSPoint3d * point, PSOdorData * odor_data);
00471                 
00472                 // Preferences
00473                 FILE * logFile;                         
00474                 std::string logFilePath;                
00476                 int period;                             
00477                 int numOfFrames;                        
00478                 int currentFrame;                       
00479                 double cellSize;                        
00480                 int maxPointsPerCell;                   
00482                 private:
00483         
00484                 std::vector<PSFramePoint> frame;        
00485         };
00486 
00487 
00494         class PSFluent:public PSSource
00495         {
00496                 public:
00497         
00504                 PSFluent();
00506 
00509                 ~PSFluent();
00510         
00519                 int setup();
00528                 int cleanup();
00529         
00539                 int generatePoints();
00550                 int getChemicalReading(PSPoint3d * point, PSOdorData * odor_data);
00551         
00552                 // Preferences
00553                 FILE * logFile;                         
00554                 std::string fileName;                   
00556                 int numOfFrames;                        
00557                 int currentFrame;                       
00558                 double cellSize;                        
00559                 int maxPointsPerCell;                   
00560                 double maxOdorValue;                    
00562                 private:
00563         
00564                 std::vector<PSFramePoint> frame;        
00565         };
00566 
00567 } // namespace
00568 
00569 // EOF


plumesim
Author(s): Gonçalo Cabrita and Pedro Sousa
autogenerated on Mon Jan 6 2014 11:27:16