OfflineItemSearcher.cpp
Go to the documentation of this file.
00001 
00015 // World Item Search
00016 #include "world_item_search/OfflineItemSearcher.h"
00017 
00018 // ROS
00019 #include <ros/package.h>
00020 
00021 // Boost
00022 #include <boost/filesystem.hpp>
00023 
00024 // C++ Standard Library
00025 #include <fstream>
00026 
00027 using namespace std;
00028 using namespace rail::spatial_temporal_learning;
00029 
00030 OfflineItemSearcher::OfflineItemSearcher() : worldlib::remote::Node()
00031 {
00032   // location of the GeoLife files
00033   string geolife(ros::package::getPath("world_item_search") + "/geolife");
00034   private_node_.getParam("geolife", geolife);
00035   // open the Geolife files for model generation
00036   this->loadGeoLife(geolife);
00037   okay_ &= !geolife_.empty();
00038   if (!okay_)
00039   {
00040     ROS_ERROR("Unable to load any GeoLife PLT files in '%s'.", geolife.c_str());
00041   }
00042 
00043   // create the clients we need
00044   interactive_world_model_client_ = this->createInteractiveWorldModelClient();
00045   spatial_world_client_ = this->createSpatialWorldClient();
00046 
00047   // our default "room"
00048   world_.addRoom(worldlib::world::Room("default"));
00049   interactive_world_.addRoom(worldlib::world::Room("default"));
00050 
00051   // grab the interactive world models
00052   uint32_t task_id = worldlib::remote::InteractiveWorldModelClient::TASK_ID_PUT_AWAY_GENERAL;
00053   okay_ &= interactive_world_model_client_->getTaskModel(task_id, interactive_world_task_model_);
00054   interactive_world_task_model_.getUniqueItems(interactive_world_.getItems());
00055   interactive_world_task_model_.getUniqueSurfaces(interactive_world_.getRoom(0).getSurfaces());
00056 
00057   // initialize the objects we have in our "world"
00058   world_.addItem(worldlib::world::Item("spoon"));
00059   world_.addItem(worldlib::world::Item("fork"));
00060   world_.addItem(worldlib::world::Item("bowl"));
00061   world_.addItem(worldlib::world::Item("keys"));
00062   world_.getRoom(0).addSurface(worldlib::world::Surface("Coffee Table"));
00063   world_.getRoom(0).addSurface(worldlib::world::Surface("Sink Unit"));
00064   world_.getRoom(0).addSurface(worldlib::world::Surface("Dining Table with Chairs"));
00065   world_.getRoom(0).addSurface(worldlib::world::Surface("Dresser"));
00066 
00067   // attempt to connect to the spatial world database
00068   okay_ &= spatial_world_client_->connect();
00069 
00070   // set when samples are drawn
00071   min_lat_ = numeric_limits<double>::infinity();
00072   max_lat_ = -numeric_limits<double>::infinity();
00073   min_lng_ = numeric_limits<double>::infinity();
00074   max_lng_ = -numeric_limits<double>::infinity();
00075 
00076   if (okay_)
00077   {
00078     ROS_INFO("Offline Item Searcher Initialized");
00079   }
00080 }
00081 
00082 OfflineItemSearcher::~OfflineItemSearcher()
00083 {
00084   // clean up clients
00085   delete interactive_world_model_client_;
00086   delete spatial_world_client_;
00087 }
00088 
00089 void OfflineItemSearcher::loadGeoLife(const std::string &directory)
00090 {
00091   // use Boost to search the directory
00092   boost::filesystem::path path(directory.c_str());
00093   if (boost::filesystem::exists(path))
00094   {
00095     // the order is not defined, so we will sort a list instead
00096     vector<string> files;
00097     for (boost::filesystem::directory_iterator itr(path); itr != boost::filesystem::directory_iterator(); ++itr)
00098     {
00099       // check for a .plt file
00100       if (itr->path().extension().string() == ".plt")
00101       {
00102         files.push_back(itr->path().string());
00103       }
00104     }
00105     std::sort(files.begin(), files.end());
00106     for (size_t i = 0; i < files.size(); i++)
00107     {
00108       // open the file and read each line
00109       ifstream myfile(files[i].c_str());
00110       string line;
00111       uint32_t line_count = 0;
00112       while (std::getline(myfile, line))
00113       {
00114         // first 6 lines don't contain data
00115         if (++line_count > 6)
00116         {
00117           // split the line based on ','
00118           GeoLifeEntry entry;
00119           stringstream ss(line);
00120           string token;
00121           uint32_t token_count = 0;
00122           while (std::getline(ss, token, ',') && ++token_count <= 5)
00123           {
00124             if (token_count == 1)
00125             {
00126               double latitude = boost::lexical_cast<double>(token);
00127               entry.setLatitude(latitude);
00128             }
00129             if (token_count == 2)
00130             {
00131               double longitude = boost::lexical_cast<double>(token);
00132               entry.setLongitude(longitude);
00133             }
00134             else if (token_count == 5)
00135             {
00136               // date is "days since 12/30/1899" -- concert to posix time (move to 1/1/1970 then convert to seconds)
00137               double days = boost::lexical_cast<double>(token) - 25569;
00138               ros::Time time(round(days * 86400));
00139               entry.setTime(time);
00140             }
00141           }
00142           geolife_.push_back(entry);
00143         }
00144       }
00145     }
00146   }
00147 }
00148 
00149 void OfflineItemSearcher::run()
00150 {
00151   cout << "=== Begining Simulated Item Search Experiments ===" << endl;
00152 
00153   // run the GeoLife experiment
00154   this->runGeoLifeExperiment();
00155 
00156   cout << "=== Simulated Item Search Experiments Finished ===" << endl;
00157 
00158 }
00159 
00160 void OfflineItemSearcher::runGeoLifeExperiment()
00161 {
00162   cout << endl << "=== Start GeoLife Experiment ===" << endl;
00163 
00164   // generate random points from the first 3/4 of the data points from a uniform distribution
00165   int observation_pool_size = round((geolife_.size() * (3.0 / 4.0)));
00166   int verification_pool_size = geolife_.size() - observation_pool_size;
00167   boost::uniform_int<> observation_dist(0, observation_pool_size - 1);
00168   boost::uniform_int<> verification_dist(observation_pool_size, geolife_.size() - 1);
00169   boost::variate_generator<boost::mt19937, boost::uniform_int<> > observation_generator(random_, observation_dist);
00170   boost::variate_generator<boost::mt19937, boost::uniform_int<> > verification_generator(random_, verification_dist);
00171 
00172   // generate 20% of observations (will need to order)
00173   vector<int> rand_observations;
00174   int num_observations = round(0.2 * observation_pool_size);
00175   cout << "  Generating " << num_observations << " random indices out of " << observation_pool_size
00176   << " for observations... " << flush;
00177   while (rand_observations.size() < num_observations)
00178   {
00179     // get a random unique number
00180     int generated;
00181     do
00182     {
00183       generated = observation_generator();
00184     } while (std::find(rand_observations.begin(), rand_observations.end(), generated) != rand_observations.end());
00185     rand_observations.push_back(generated);
00186   }
00187   std::sort(rand_observations.begin(), rand_observations.end());
00188   cout << "done." << endl;
00189 
00190   // generate 20% of verification points
00191   vector<int> rand_verification;
00192   int num_verifications = round(0.2 * verification_pool_size);
00193   cout << "  Generating " << num_verifications << " random indices out of " << verification_pool_size
00194   << " for verification... " << flush;
00195   while (rand_verification.size() < num_verifications)
00196   {
00197     // get a random unique number
00198     int generated;
00199     do
00200     {
00201       generated = verification_generator();
00202     } while (std::find(rand_verification.begin(), rand_verification.end(), generated) != rand_verification.end());
00203     rand_verification.push_back(generated);
00204   }
00205   cout << "done." << endl;
00206 
00207   // determine the new min-max values
00208   cout << "  Finding bounding region... " << flush;
00209   for (size_t i = 0; i < rand_observations.size(); i++)
00210   {
00211     min_lat_ = min(min_lat_, geolife_[rand_observations[i]].getLatitude());
00212     max_lat_ = max(max_lat_, geolife_[rand_observations[i]].getLatitude());
00213     min_lng_ = min(min_lng_, geolife_[rand_observations[i]].getLongitude());
00214     max_lng_ = max(max_lng_, geolife_[rand_observations[i]].getLongitude());
00215   }
00216   for (size_t i = 0; i < rand_verification.size(); i++)
00217   {
00218     min_lat_ = min(min_lat_, geolife_[rand_verification[i]].getLatitude());
00219     max_lat_ = max(max_lat_, geolife_[rand_verification[i]].getLatitude());
00220     min_lng_ = min(min_lng_, geolife_[rand_verification[i]].getLongitude());
00221     max_lng_ = max(max_lng_, geolife_[rand_verification[i]].getLongitude());
00222   }
00223   cout << "[" << min_lat_ << ", " << max_lat_ << "] x [" << min_lng_ << ", " << max_lng_ << "]" << endl;
00224 
00225   // create and store the observations
00226   cout << "  Inserting samples into the spatial world database... " << flush;
00227   // clear the initial database
00228   spatial_world_client_->clearAllEntities();
00229   worldlib::world::Observation observation(worldlib::world::Item("Person"));
00230   // internal counter of where things where
00231   map<string, uint32_t> surface_counts;
00232   for (size_t i = 0; i < rand_observations.size(); i++)
00233   {
00234     const GeoLifeEntry &entry = geolife_[rand_observations[i]];
00235     const string surface_name = this->getGeoLifeSurface(entry.getLatitude(), entry.getLongitude());
00236 
00237     // update the counter
00238     surface_counts[surface_name]++;
00239 
00240     // only add observations when there are changes (dramatic speedup)
00241     if (observation.getSurface().getName() != surface_name)
00242     {
00243       // if the last surface name is empty, it means it was the first entry
00244       if (!observation.getSurface().getName().empty())
00245       {
00246         // add the last seen and mark it as removed
00247         const GeoLifeEntry &prev = geolife_[rand_observations[i - 1]];
00248         observation.setTime(prev.getTime());
00249         spatial_world_client_->addObservation(observation);
00250         spatial_world_client_->markObservationsAsRemoved(observation.getItem(), observation.getSurface(),
00251                                                          entry.getTime());
00252       }
00253       // add the new observation
00254       observation.getSurface().setName(surface_name);
00255       observation.setTime(entry.getTime());
00256       spatial_world_client_->addObservation(observation);
00257     }
00258   }
00259   cout << "done." << endl;
00260 
00261   // load each model
00262   cout << "  Loading initial persistence models... " << flush;
00263   // load the surface we have models for
00264   vector<string> surfaces;
00265   spatial_world_client_->getUniqueSurfaceNames(surfaces);
00266   // store in a map
00267   map<string, worldlib::model::PersistenceModel> models;
00268   for (int i = 0; i < surfaces.size(); i++)
00269   {
00270     const worldlib::world::Surface surface(surfaces[i]);
00271     models[surface.getName()] = spatial_world_client_->getPersistenceModel(observation.getItem(), surface);
00272   }
00273   cout << "done." << endl;
00274 
00275   // check the accuracy of the model
00276   cout << "  Running accuarcy test... " << endl;
00277   size_t model_correct = 0, most_freq_correct = 0, greedy_correct = 0, random_correct = 0;
00278   // get the most frequent surface
00279   uint32_t best_freq_count = 0;
00280   string most_freq_guess;
00281   for (size_t i = 0; i < surfaces.size(); i++)
00282   {
00283     if (surface_counts[surfaces[i]] > best_freq_count)
00284     {
00285       best_freq_count = surface_counts[surfaces[i]];
00286       most_freq_guess = surfaces[i];
00287     }
00288   }
00289   // used for random guess
00290   boost::uniform_int<> random_surface_dist(0, surfaces.size() - 1);
00291   boost::variate_generator<boost::mt19937, boost::uniform_int<> > random_surface(random_, random_surface_dist);
00292   for (int i = 0; i < rand_verification.size(); i++)
00293   {
00294     // get the ground truth of where the "item" is located
00295     const GeoLifeEntry &entry = geolife_[rand_verification[i]];
00296     const string ground_truth_name = this->getGeoLifeSurface(entry.getLatitude(), entry.getLongitude());
00297 
00298     // check for the best guess by our model
00299     double model_best_p = -numeric_limits<double>::infinity();
00300     string model_guess_name;
00301     for (int j = 0; j < surfaces.size(); j++)
00302     {
00303       const worldlib::model::PersistenceModel &model = models[surfaces[j]];
00304       double p = model.getProbabilityItemStillExists(entry.getTime());
00305       if (p > model_best_p)
00306       {
00307         model_guess_name = model.getSurface().getName();
00308         model_best_p = p;
00309       }
00310     }
00311 
00312     // randomly guess
00313     string random_guess_name = surfaces[random_surface()];
00314 
00315     // greedy last seen
00316     const GeoLifeEntry &greedy_entry = geolife_[(i == 0) ? rand_observations.back() : rand_verification[i - 1]];
00317     string greedy_guess_name = this->getGeoLifeSurface(greedy_entry.getLatitude(), greedy_entry.getLongitude());
00318 
00319     // check if we matches
00320     if (model_guess_name == ground_truth_name)
00321     {
00322       model_correct++;
00323     }
00324     if (most_freq_guess == ground_truth_name)
00325     {
00326       most_freq_correct++;
00327     }
00328     if (greedy_guess_name == ground_truth_name)
00329     {
00330       greedy_correct++;
00331     }
00332     if (random_guess_name == ground_truth_name)
00333     {
00334       random_correct++;
00335     }
00336 
00337     // update the observed time
00338     models[ground_truth_name].setLastSeen(entry.getTime());
00339   }
00340 
00341   double model_percentage = (((double) model_correct) / rand_verification.size()) * 100.0;
00342   cout << "         Model Rate: ";
00343   cout << model_percentage << "% (" << model_correct << "/" << rand_verification.size() << ")" << endl;
00344   double most_freq_percentage = (((double) most_freq_correct) / rand_verification.size()) * 100.0;
00345   cout << "    Most Freq. Rate: ";
00346   cout << most_freq_percentage << "% (" << most_freq_correct << "/" << rand_verification.size() << ")" << endl;
00347   double greedy_percentage = (((double) greedy_correct) / rand_verification.size()) * 100.0;
00348   cout << "        Greedy Rate: ";
00349   cout << greedy_percentage << "% (" << greedy_correct << "/" << rand_verification.size() << ")" << endl;
00350   double random_percentage = (((double) random_correct) / rand_verification.size()) * 100.0;
00351   cout << "        Random Rate: ";
00352   cout << random_percentage << "% (" << random_correct << "/" << rand_verification.size() << ")" << endl;
00353 
00354   cout << "=== End GeoLife Experiment ===" << endl << endl;
00355 }
00356 
00357 string OfflineItemSearcher::getGeoLifeSurface(const double latitude, const double longitude) const
00358 {
00359   double row_size = (max_lng_ - min_lng_) / NUM_GEOLIFE_ROWS;
00360   double col_size = (max_lat_ - min_lat_) / NUM_GEOLIFE_COLUMNS;
00361 
00362   int row = (int) ((longitude - min_lng_) / row_size);
00363   int col = (int) ((latitude - min_lat_) / col_size);
00364   stringstream ss;
00365   ss << row << "-" << col;
00366   return ss.str();
00367 }
00368 
00369 void OfflineItemSearcher::printItemList(const vector<worldlib::world::Item> &items) const
00370 {
00371   cout << "[";
00372   for (size_t i = 0; i < items.size(); i++)
00373   {
00374     cout << items[i].getName();
00375     (i < items.size() - 1) ? cout << ", " : cout << "";
00376   }
00377   cout << "]" << endl;
00378 }
00379 
00380 void OfflineItemSearcher::printSurfaceList(const vector<worldlib::world::Surface> &surfaces) const
00381 {
00382   cout << "[";
00383   for (size_t i = 0; i < surfaces.size(); i++)
00384   {
00385     cout << surfaces[i].getName();
00386     (i < surfaces.size() - 1) ? cout << ", " : cout << "";
00387   }
00388   cout << "]" << endl;
00389 }


world_item_search
Author(s): Russell Toris
autogenerated on Fri Feb 12 2016 00:24:30