PSLog.cpp
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/23/2010
00036 *********************************************************************/
00037 #include <string.h>
00038 #include <stdio.h>
00039 #include <math.h>
00040 
00041 #include "PSSources.h"
00042 
00043 // *****************************************************************************
00044 // Constructor.
00045 plumesim::PSLog::PSLog()
00046 {
00047         this->maxPointsPerCell = 10;
00048         this->logFilePath = "log.txt";
00049 }
00050 
00051 // *****************************************************************************
00052 // Destructor.
00053 plumesim::PSLog::~PSLog()
00054 {
00055         // Clean up...
00056 }
00057 
00058 // *****************************************************************************
00059 // Setup routine.
00060 int plumesim::PSLog::setup()
00061 {
00062         if(!plumePoints.empty()) plumePoints.clear();
00063         if(!frame.empty()) frame.clear();
00064         
00065         // Open the file
00066         this->logFile = fopen(logFilePath.c_str(), "r");
00067         // Take out the settings...
00068         // period ppFrame nFrames cellSize maxOdor
00069         if( fscanf(this->logFile, "%d %d %lf\n", &this->period, &this->numOfFrames, &this->cellSize) == 0)
00070         {
00071                 return(-1);
00072         }
00073         
00074         if(this->numOfFrames > 1) this->changesOverTime = true;
00075         else this->changesOverTime = false;
00076         this->isPlaying = true;
00077         
00078         return(0);
00079 }
00080 
00081 // *****************************************************************************
00082 // Cleanup routine.
00083 int plumesim::PSLog::cleanup()
00084 {
00085         // Close the file
00086         fclose(logFile);
00087         // Clean up...
00088         plumePoints.clear();
00089         frame.clear();
00090         return 0;
00091 }
00092 
00093 // *****************************************************************************
00094 // Read points from the log file.
00095 int plumesim::PSLog::generatePoints()
00096 {
00097         int i, j;
00098         int pointsCount;
00099         int pointsInFrame;
00100         
00101         if( !feof(logFile) )
00102         {
00103                 if(!plumePoints.empty()) plumePoints.clear();
00104                 if(!frame.empty()) frame.clear();
00105 
00106                 // +t
00107                 fscanf(logFile, "+%d %d\n", &currentFrame, &pointsInFrame);
00108                 
00109                 for(i=0 ; i<pointsInFrame ; i++)
00110                 {
00111                         PSFramePoint pointFromFrame;
00112                         // x y z windSpeed windDirection chemical
00113                         //fscanf(logFile, "%lf,%lf,%lf,%lf,%lf,%lf\n", &pointFromFrame.point.px, &pointFromFrame.point.py, &pointFromFrame.point.pz,  &pointFromFrame.odor.windSpeed, &pointFromFrame.odor.windDirection, &pointFromFrame.odor.chemical);
00114                         fscanf(logFile, "%lf %lf %lf\n", &pointFromFrame.point.px, &pointFromFrame.point.py, &pointFromFrame.odor.chemical);
00115                         
00116                         this->frame.push_back(pointFromFrame);
00117                         
00118                         pointsCount = round(maxPointsPerCell * pointFromFrame.odor.chemical/100.0);
00119                         for(j=0 ; j<pointsCount ; j++)
00120                         {
00121                                 PSPoint3d point;
00122                                 point.px = pointFromFrame.point.px + cellSize * randomNormal();
00123                                 point.py = pointFromFrame.point.py + cellSize * randomNormal();
00124                                 // TODO: Complete for full 3D support!
00125                                 point.pz = 0.0;
00126                                 plumePoints.push_back(point);
00127                         }
00128                 }
00129         }
00130         else
00131         {
00132                 isPlaying = false;
00133         }
00134         return(0);
00135 }
00136 
00137 // *****************************************************************************
00138 // Sends the chemical reading for a given position.
00139 int plumesim::PSLog::getChemicalReading(PSPoint3d * point, PSOdorData * odor_data)
00140 {       
00141         double distance;
00142         double minDistance = cellSize;
00143         
00144         odor_data->chemical = 0.0;
00145         odor_data->windSpeed = 0.0;
00146         odor_data->windDirection = 0.0;
00147         
00148         PSFramePoint * framePoint;
00149         for(int i=0 ; i<this->frame.size() ; i++)
00150         {
00151                 framePoint = &this->frame[i];
00152                 
00153                 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));
00154                 if(distance < minDistance)
00155                 {
00156                         odor_data->chemical = framePoint->odor.chemical;
00157                         odor_data->windSpeed = framePoint->odor.windSpeed;
00158                         odor_data->windDirection = framePoint->odor.windDirection;
00159                         
00160                         minDistance = distance;
00161                 }
00162         }
00163         return(0);
00164 }
00165 
00166 // EOF
00167 


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